Swarm-SLAM  1.0.0
C-SLAM Framework
visualization_utils.h
Go to the documentation of this file.
1 #ifndef _VISUALIZATION_UTILS_H_
2 #define _VISUALIZATION_UTILS_H_
3 
4 #include <rclcpp/rclcpp.hpp>
5 
6 #include <cv_bridge/cv_bridge.h>
7 
8 #include <chrono>
9 #include <sensor_msgs/msg/image.hpp>
10 #include <sensor_msgs/msg/point_cloud2.hpp>
11 #include <sensor_msgs/point_cloud2_iterator.hpp>
12 #include <rtabmap/core/SensorData.h>
13 #include <image_geometry/pinhole_camera_model.h>
14 #include <cslam_common_interfaces/msg/keyframe_odom.hpp>
15 #include <deque>
16 #include <functional>
17 #include <thread>
18 
19 #include <memory>
20 
21 #include <rtabmap_conversions/MsgConversion.h>
23 
24 namespace cslam
25 {
33  sensor_msgs::msg::PointCloud2 create_colored_pointcloud(const std::shared_ptr<rtabmap::SensorData> &sensor_data, const std_msgs::msg::Header &header);
34 
44  template <typename T>
46  const std::shared_ptr<rtabmap::SensorData> &sensor_data,
47  sensor_msgs::msg::PointCloud2::SharedPtr &cloud_msg,
48  const image_geometry::PinholeCameraModel &model,
49  double range_max = 0.0);
50 
58  const std::shared_ptr<rtabmap::SensorData> &sensor_data,
59  sensor_msgs::msg::PointCloud2::SharedPtr &cloud_msg);
60 
61 } // namespace cslam
62 #endif
Definition: __init__.py:1
void depth_image_to_pointcloud(const std::shared_ptr< rtabmap::SensorData > &sensor_data, sensor_msgs::msg::PointCloud2::SharedPtr &cloud_msg, const image_geometry::PinholeCameraModel &model, double range_max=0.0)
Convert depth image to pointcloud.
sensor_msgs::msg::PointCloud2 create_colored_pointcloud(const std::shared_ptr< rtabmap::SensorData > &sensor_data, const std_msgs::msg::Header &header)
Create a colored pointcloud message.
void add_rgb_to_pointcloud(const std::shared_ptr< rtabmap::SensorData > &sensor_data, sensor_msgs::msg::PointCloud2::SharedPtr &cloud_msg)
Add color to pointcloud.