33 void CommonDataSubscriber::stereoCallback(
34 const sensor_msgs::ImageConstPtr& leftImageMsg,
35 const sensor_msgs::ImageConstPtr& rightImageMsg,
36 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
37 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg)
40 nav_msgs::OdometryConstPtr odomMsg;
41 rtabmap_ros::UserDataConstPtr userDataMsg;
42 sensor_msgs::LaserScan scanMsg;
43 sensor_msgs::PointCloud2 scan3dMsg;
44 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
47 void CommonDataSubscriber::stereoInfoCallback(
48 const sensor_msgs::ImageConstPtr& leftImageMsg,
49 const sensor_msgs::ImageConstPtr& rightImageMsg,
50 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
51 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
52 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
55 nav_msgs::OdometryConstPtr odomMsg;
56 rtabmap_ros::UserDataConstPtr userDataMsg;
57 sensor_msgs::LaserScan scan2dMsg;
58 sensor_msgs::PointCloud2 scan3dMsg;
63 void CommonDataSubscriber::stereoOdomCallback(
64 const nav_msgs::OdometryConstPtr & odomMsg,
65 const sensor_msgs::ImageConstPtr& leftImageMsg,
66 const sensor_msgs::ImageConstPtr& rightImageMsg,
67 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
68 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg)
71 rtabmap_ros::UserDataConstPtr userDataMsg;
72 sensor_msgs::LaserScan scanMsg;
73 sensor_msgs::PointCloud2 scan3dMsg;
74 rtabmap_ros::OdomInfoConstPtr odomInfoMsg;
77 void CommonDataSubscriber::stereoOdomInfoCallback(
78 const nav_msgs::OdometryConstPtr & odomMsg,
79 const sensor_msgs::ImageConstPtr& leftImageMsg,
80 const sensor_msgs::ImageConstPtr& rightImageMsg,
81 const sensor_msgs::CameraInfoConstPtr& leftCamInfoMsg,
82 const sensor_msgs::CameraInfoConstPtr& rightCamInfoMsg,
83 const rtabmap_ros::OdomInfoConstPtr & odomInfoMsg)
86 rtabmap_ros::UserDataConstPtr userDataMsg;
87 sensor_msgs::LaserScan scan2dMsg;
88 sensor_msgs::PointCloud2 scan3dMsg;
96 bool subscribeOdomInfo,
120 if(subscribeOdomInfo)
133 if(subscribeOdomInfo)
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define SYNC_DECL5(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
std::string resolveName(const std::string &name, bool remap=true) const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
bool subscribedToOdomInfo_
#define SYNC_DECL6(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
virtual void commonStereoCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const cv_bridge::CvImageConstPtr &leftImageMsg, const cv_bridge::CvImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfo &leftCamInfoMsg, const sensor_msgs::CameraInfo &rightCamInfoMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_ros::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_ros::GlobalDescriptor >(), const std::vector< rtabmap_ros::KeyPoint > &localKeyPoints=std::vector< rtabmap_ros::KeyPoint >(), const std::vector< rtabmap_ros::Point3f > &localPoints3d=std::vector< rtabmap_ros::Point3f >(), const cv::Mat &localDescriptors=cv::Mat())=0
#define SYNC_DECL4(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
image_transport::SubscriberFilter imageRectLeft_
image_transport::SubscriberFilter imageRectRight_
void setupStereoCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeOdomInfo, int queueSize, bool approxSync)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_