Class CommonDataSubscriber

Class Documentation

class CommonDataSubscriber

Public Functions

RTABMAP_SYNC_PUBLIC CommonDataSubscriber(rclcpp::Node &node, bool gui)
virtual ~CommonDataSubscriber()
inline bool isSubscribedToDepth() const
inline bool isSubscribedToStereo() const
inline bool isSubscribedToRGB() const
inline bool isSubscribedToOdom() const
inline bool isSubscribedToRGBD() const
inline bool isSubscribedToScan2d() const
inline bool isSubscribedToScan3d() const
inline bool isSubscribedToOdomInfo() const
inline bool isDataSubscribed() const
inline int rgbdCameras() const
inline int getQueueSize() const
inline bool isApproxSync() const
inline const std::string &name() const

Protected Functions

void setupCallbacks(rclcpp::Node &node)
virtual void commonMultiCameraCallback(const nav_msgs::msg::Odometry::ConstSharedPtr &odomMsg, const rtabmap_msgs::msg::UserData::ConstSharedPtr &userDataMsg, const std::vector<cv_bridge::CvImageConstPtr> &imageMsgs, const std::vector<cv_bridge::CvImageConstPtr> &depthMsgs, const std::vector<sensor_msgs::msg::CameraInfo> &cameraInfoMsgs, const std::vector<sensor_msgs::msg::CameraInfo> &depthCameraInfoMsgs, const sensor_msgs::msg::LaserScan &scanMsg, const sensor_msgs::msg::PointCloud2 &scan3dMsg, const rtabmap_msgs::msg::OdomInfo::ConstSharedPtr &odomInfoMsg, const std::vector<rtabmap_msgs::msg::GlobalDescriptor> &globalDescriptorMsgs = std::vector<rtabmap_msgs::msg::GlobalDescriptor>(), const std::vector<std::vector<rtabmap_msgs::msg::KeyPoint>> &localKeyPoints = std::vector<std::vector<rtabmap_msgs::msg::KeyPoint>>(), const std::vector<std::vector<rtabmap_msgs::msg::Point3f>> &localPoints3d = std::vector<std::vector<rtabmap_msgs::msg::Point3f>>(), const std::vector<cv::Mat> &localDescriptors = std::vector<cv::Mat>()) = 0
virtual void commonLaserScanCallback(const nav_msgs::msg::Odometry::ConstSharedPtr &odomMsg, const rtabmap_msgs::msg::UserData::ConstSharedPtr &userDataMsg, const sensor_msgs::msg::LaserScan &scanMsg, const sensor_msgs::msg::PointCloud2 &scan3dMsg, const rtabmap_msgs::msg::OdomInfo::ConstSharedPtr &odomInfoMsg, const rtabmap_msgs::msg::GlobalDescriptor &globalDescriptor = rtabmap_msgs::msg::GlobalDescriptor()) = 0
virtual void commonOdomCallback(const nav_msgs::msg::Odometry::ConstSharedPtr &odomMsg, const rtabmap_msgs::msg::UserData::ConstSharedPtr &userDataMsg, const rtabmap_msgs::msg::OdomInfo::ConstSharedPtr &odomInfoMsg) = 0
void commonSingleCameraCallback(const nav_msgs::msg::Odometry::ConstSharedPtr &odomMsg, const rtabmap_msgs::msg::UserData::ConstSharedPtr &userDataMsg, const cv_bridge::CvImageConstPtr &imageMsg, const cv_bridge::CvImageConstPtr &depthMsg, const sensor_msgs::msg::CameraInfo &rgbCameraInfoMsg, const sensor_msgs::msg::CameraInfo &depthCameraInfoMsg, const sensor_msgs::msg::LaserScan &scanMsg, const sensor_msgs::msg::PointCloud2 &scan3dMsg, const rtabmap_msgs::msg::OdomInfo::ConstSharedPtr &odomInfoMsg, const std::vector<rtabmap_msgs::msg::GlobalDescriptor> &globalDescriptorMsgs = std::vector<rtabmap_msgs::msg::GlobalDescriptor>(), const std::vector<rtabmap_msgs::msg::KeyPoint> &localKeyPoints = std::vector<rtabmap_msgs::msg::KeyPoint>(), const std::vector<rtabmap_msgs::msg::Point3f> &localPoints3d = std::vector<rtabmap_msgs::msg::Point3f>(), const cv::Mat &localDescriptors = cv::Mat())

Protected Attributes

std::string subscribedTopicsMsg_
int queueSize_
rmw_qos_reliability_policy_t qosOdom_
rmw_qos_reliability_policy_t qosImage_
rmw_qos_reliability_policy_t qosCameraInfo_
rmw_qos_reliability_policy_t qosScan_
rmw_qos_reliability_policy_t qosUserData_