36 callbackCalled_(
false),
37 subscribedToDepth_(!gui),
38 subscribedToStereo_(
false),
39 subscribedToRGBD_(
false),
40 subscribedToScan2d_(
false),
41 subscribedToScan3d_(
false),
42 subscribedToOdomInfo_(
false),
216 bool subscribeScan2d =
false;
217 bool subscribeScan3d =
false;
218 bool subscribeOdomInfo =
false;
219 bool subscribeUserData =
false;
225 if(pnh.
getParam(
"subscribe_laserScan", subscribeScan2d) && subscribeScan2d)
227 ROS_WARN(
"rtabmap: \"subscribe_laserScan\" parameter is deprecated, use \"subscribe_scan\" instead. The scan topic is still subscribed.");
229 pnh.
param(
"subscribe_scan", subscribeScan2d, subscribeScan2d);
230 pnh.
param(
"subscribe_scan_cloud", subscribeScan3d, subscribeScan3d);
233 pnh.
param(
"subscribe_odom_info", subscribeOdomInfo, subscribeOdomInfo);
234 pnh.
param(
"subscribe_user_data", subscribeUserData, subscribeUserData);
237 ROS_WARN(
"rtabmap: Parameters subscribe_depth and subscribe_stereo cannot be true at the same time. Parameter subscribe_depth is set to false.");
242 ROS_WARN(
"rtabmap: Parameters subscribe_depth and subscribe_rgbd cannot be true at the same time. Parameter subscribe_depth is set to false.");
247 ROS_WARN(
"rtabmap: Parameters subscribe_stereo and subscribe_rgbd cannot be true at the same time. Parameter subscribe_stereo is set to false.");
250 if(subscribeScan2d && subscribeScan3d)
252 ROS_WARN(
"rtabmap: Parameters subscribe_scan and subscribe_scan_cloud cannot be true at the same time. Parameter subscribe_scan_cloud is set to false.");
253 subscribeScan3d =
false;
255 if(subscribeScan2d || subscribeScan3d)
259 ROS_WARN(
"When subscribing to laser scan, you should subscribe to depth, stereo or rgbd too. Subscribing to depth by default...");
268 std::string odomFrameId;
269 pnh.
getParam(
"odom_frame_id", odomFrameId);
270 pnh.
param(
"rgbd_cameras", rgbdCameras, rgbdCameras);
273 ROS_ERROR(
"\"depth_cameras\" parameter doesn't exist anymore. It is replaced by \"rgbd_cameras\" used when \"subscribe_rgbd\" is true.");
278 ROS_WARN(
"Parameter \"stereo_approx_sync\" has been renamed " 279 "to \"approx_sync\"! Your value is still copied to " 280 "corresponding parameter.");
297 bool subscribeOdom = odomFrameId.empty();
336 else if(rgbdCameras == 3)
349 else if(rgbdCameras == 2)
559 for(
unsigned int i=0; i<
rgbdSubs_.size(); ++i)
574 ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are " 575 "published (\"$ rostopic hz my_topic\") and the timestamps in their " 576 "header are set. If topics are coming from different computers, make sure " 577 "the clocks of the computers are synchronized (\"ntpdate\"). %s%s",
580 uFormat(
"If topics are not published at the same rate, you could increase \"queue_size\" parameter (current=%d).",
queueSize_).c_str():
581 "Parameter \"approx_sync\" is false, which means that input topics should have all the exact timestamp for the callback to be called.",
588 const nav_msgs::OdometryConstPtr & odomMsg,
589 const rtabmap_ros::UserDataConstPtr & userDataMsg,
592 const sensor_msgs::CameraInfo & rgbCameraInfoMsg,
593 const sensor_msgs::CameraInfo & depthCameraInfoMsg,
594 const sensor_msgs::LaserScanConstPtr& scanMsg,
595 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
596 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
600 if(depthMsg.get() == 0 ||
605 std::vector<cv_bridge::CvImageConstPtr> imageMsgs;
606 std::vector<cv_bridge::CvImageConstPtr> depthMsgs;
607 std::vector<sensor_msgs::CameraInfo> cameraInfoMsgs;
610 imageMsgs.push_back(imageMsg);
614 depthMsgs.push_back(depthMsg);
616 cameraInfoMsgs.push_back(rgbCameraInfoMsg);
617 commonDepthCallback(odomMsg, userDataMsg, imageMsgs, depthMsgs, cameraInfoMsgs, scanMsg, scan3dMsg, odomInfoMsg);
621 commonStereoCallback(odomMsg, userDataMsg, imageMsg, depthMsg, rgbCameraInfoMsg, depthCameraInfoMsg, scanMsg, scan3dMsg, odomInfoMsg);
CommonDataSubscriber(bool gui)
std::string uFormat(const char *fmt,...)
void commonSingleDepthCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const cv_bridge::CvImageConstPtr &imageMsg, const cv_bridge::CvImageConstPtr &depthMsg, const sensor_msgs::CameraInfo &rgbCameraInfoMsg, const sensor_msgs::CameraInfo &depthCameraInfoMsg, const sensor_msgs::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)
void setupRGBD2Callbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
virtual ~CommonDataSubscriber()
virtual void commonDepthCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const sensor_msgs::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)=0
void setupRGBD3Callbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
void setupRGBD4Callbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
void setupRGBDCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
void setupCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string TYPE_32FC1
const std::string TYPE_16UC1
boost::thread * warningThread_
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::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &scan3dMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)=0
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
std::string subscribedTopicsMsg_
void setupStereoCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeOdomInfo, int queueSize, bool approxSync)
std::vector< message_filters::Subscriber< rtabmap_ros::RGBDImage > * > rgbdSubs_
void setupDepthCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeUserData, bool subscribeScan2d, bool subscribeScan3d, bool subscribeOdomInfo, int queueSize, bool approxSync)
#define SYNC_INIT(PREFIX)