1 #ifndef _VISUALIZATION_UTILS_H_
2 #define _VISUALIZATION_UTILS_H_
4 #include <rclcpp/rclcpp.hpp>
6 #include <cv_bridge/cv_bridge.h>
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>
21 #include <rtabmap_conversions/MsgConversion.h>
33 sensor_msgs::msg::PointCloud2
create_colored_pointcloud(
const std::shared_ptr<rtabmap::SensorData> &sensor_data,
const std_msgs::msg::Header &header);
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);
58 const std::shared_ptr<rtabmap::SensorData> &sensor_data,
59 sensor_msgs::msg::PointCloud2::SharedPtr &cloud_msg);
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.