|
Swarm-SLAM
1.0.0
C-SLAM Framework
|
#include <rclcpp/rclcpp.hpp>#include <cv_bridge/cv_bridge.h>#include <chrono>#include <sensor_msgs/msg/image.hpp>#include <sensor_msgs/msg/point_cloud2.hpp>#include <sensor_msgs/point_cloud2_iterator.hpp>#include <rtabmap/core/SensorData.h>#include <image_geometry/pinhole_camera_model.h>#include <cslam_common_interfaces/msg/keyframe_odom.hpp>#include <deque>#include <functional>#include <thread>#include <memory>#include <rtabmap_conversions/MsgConversion.h>#include "cslam/front_end/utils/depth_traits.h"Go to the source code of this file.
Namespaces | |
| cslam | |
Functions | |
| sensor_msgs::msg::PointCloud2 | cslam::create_colored_pointcloud (const std::shared_ptr< rtabmap::SensorData > &sensor_data, const std_msgs::msg::Header &header) |
| Create a colored pointcloud message. More... | |
| template<typename T > | |
| void | cslam::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. More... | |
| void | cslam::add_rgb_to_pointcloud (const std::shared_ptr< rtabmap::SensorData > &sensor_data, sensor_msgs::msg::PointCloud2::SharedPtr &cloud_msg) |
| Add color to pointcloud. More... | |