39 #include <sensor_msgs/CameraInfo.h> 90 bool approxSync =
false;
91 double approxSyncMaxInterval = 0.0;
92 pnh.
param(
"approx_sync", approxSync, approxSync);
93 pnh.
param(
"approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
94 pnh.
param(
"rate", rate_, rate_);
95 pnh.
param(
"queue_size", queueSize, queueSize);
100 NODELET_INFO(
"approx_sync = %s", approxSync?
"true":
"false");
102 NODELET_INFO(
"approx_sync_max_interval = %f", approxSyncMaxInterval);
107 if(approxSyncMaxInterval>0.0)
128 void callback(
const sensor_msgs::ImageConstPtr& imageLeft,
129 const sensor_msgs::ImageConstPtr& imageRight,
130 const sensor_msgs::CameraInfoConstPtr& camInfoLeft,
131 const sensor_msgs::CameraInfoConstPtr& camInfoRight)
147 double leftStamp = imageLeft->header.stamp.toSec();
148 double rightStamp = imageRight->header.stamp.toSec();
149 double leftInfoStamp = camInfoLeft->header.stamp.toSec();
150 double rightInfoStamp = camInfoRight->header.stamp.toSec();
156 sensor_msgs::CameraInfo info = *camInfoLeft;
181 sensor_msgs::CameraInfo info = *camInfoRight;
210 out.
header = imagePtr->header;
226 out.
header = imagePtr->header;
237 if( leftStamp != imageLeft->header.stamp.toSec() ||
238 rightStamp != imageRight->header.stamp.toSec())
240 NODELET_ERROR(
"Input stamps changed between the beginning and the end of the callback! Make " 241 "sure the node publishing the topics doesn't override the same data after publishing them. A " 242 "solution is to use this node within another nodelet manager. Stamps: " 243 "left%f->%f right=%f->%f",
244 leftStamp, imageLeft->header.stamp.toSec(),
245 rightStamp, imageRight->header.stamp.toSec());
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
ros::Publisher infoRightPub_
image_transport::Publisher imageLeftPub_
uint32_t getNumSubscribers() const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
image_transport::SubscriberFilter imageRight_
ros::NodeHandle & getNodeHandle() const
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getPrivateNodeHandle() const
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncPolicy
image_transport::SubscriberFilter imageLeft_
image_transport::Publisher imageRightPub_
void callback(const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &camInfoLeft, const sensor_msgs::CameraInfoConstPtr &camInfoRight)
sensor_msgs::ImagePtr toImageMsg() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
ros::Publisher infoLeftPub_
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publish(const sensor_msgs::Image &message) const
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#define NODELET_INFO(...)
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)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncPolicy
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
virtual ~StereoThrottleNodelet()
uint32_t getNumSubscribers() const
#define NODELET_DEBUG(...)
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_