Swarm-SLAM  1.0.0
C-SLAM Framework
stereo_handler.h
Go to the documentation of this file.
1 #ifndef _STEREOHANDLER_H_
2 #define _STEREOHANDLER_H_
3 
5 
6 namespace cslam
7 {
8 
9  class StereoHandler : public RGBDHandler
10  {
11  public:
17  StereoHandler(std::shared_ptr<rclcpp::Node> &node);
19 
29  void stereo_callback(
30  const sensor_msgs::msg::Image::ConstSharedPtr image_rect_left,
31  const sensor_msgs::msg::Image::ConstSharedPtr image_rect_right,
32  const sensor_msgs::msg::CameraInfo::ConstSharedPtr camera_info_left,
33  const sensor_msgs::msg::CameraInfo::ConstSharedPtr camera_info_right,
34  const nav_msgs::msg::Odometry::ConstSharedPtr odom);
35 
43  const std::shared_ptr<cslam_common_interfaces::msg::LocalImageDescriptors> msg,
44  rtabmap::SensorData &sensor_data);
45 
51  virtual void send_visualization(const std::pair<std::shared_ptr<rtabmap::SensorData>, std::shared_ptr<const nav_msgs::msg::Odometry>> &keypoints_data);
52 
53  private:
54  image_transport::SubscriberFilter sub_image_rect_left_;
55  image_transport::SubscriberFilter sub_image_rect_right_;
56  message_filters::Subscriber<sensor_msgs::msg::CameraInfo> sub_camera_info_left_;
57  message_filters::Subscriber<sensor_msgs::msg::CameraInfo> sub_camera_info_right_;
58  typedef message_filters::sync_policies::ApproximateTime<
59  sensor_msgs::msg::Image, sensor_msgs::msg::Image,
60  sensor_msgs::msg::CameraInfo, sensor_msgs::msg::CameraInfo,
61  nav_msgs::msg::Odometry>
62  StereoSyncPolicy;
63  message_filters::Synchronizer<StereoSyncPolicy> *stereo_sync_policy_;
64  };
65 } // namespace cslam
66 #endif
void stereo_callback(const sensor_msgs::msg::Image::ConstSharedPtr image_rect_left, const sensor_msgs::msg::Image::ConstSharedPtr image_rect_right, const sensor_msgs::msg::CameraInfo::ConstSharedPtr camera_info_left, const sensor_msgs::msg::CameraInfo::ConstSharedPtr camera_info_right, const nav_msgs::msg::Odometry::ConstSharedPtr odom)
Callback receiving sync data from camera.
virtual void local_descriptors_msg_to_sensor_data(const std::shared_ptr< cslam_common_interfaces::msg::LocalImageDescriptors > msg, rtabmap::SensorData &sensor_data)
converts descriptors to sensore data
StereoHandler(std::shared_ptr< rclcpp::Node > &node)
Initialization of parameters and ROS 2 objects.
virtual void send_visualization(const std::pair< std::shared_ptr< rtabmap::SensorData >, std::shared_ptr< const nav_msgs::msg::Odometry >> &keypoints_data)
Send keypoints for visualizations.
Definition: __init__.py:1