39 #include <sensor_msgs/CameraInfo.h> 90 bool approxSync =
false;
91 pnh.
param(
"approx_sync", approxSync, approxSync);
92 pnh.
param(
"rate", rate_, rate_);
93 pnh.
param(
"queue_size", queueSize, queueSize);
98 NODELET_INFO(
"Approximate time sync = %s", approxSync?
"true":
"false");
122 void callback(
const sensor_msgs::ImageConstPtr& imageLeft,
123 const sensor_msgs::ImageConstPtr& imageRight,
124 const sensor_msgs::CameraInfoConstPtr& camInfoLeft,
125 const sensor_msgs::CameraInfoConstPtr& camInfoRight)
147 out.
header = imagePtr->header;
163 out.
header = imagePtr->header;
177 sensor_msgs::CameraInfo info = *camInfoLeft;
202 sensor_msgs::CameraInfo info = *camInfoRight;
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
ros::Publisher infoRightPub_
void publish(const boost::shared_ptr< M > &message) const
image_transport::Publisher imageLeftPub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
image_transport::SubscriberFilter imageRight_
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
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_
uint32_t getNumSubscribers() const
void callback(const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &camInfoLeft, const sensor_msgs::CameraInfoConstPtr &camInfoRight)
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const sensor_msgs::Image &message) const
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
ros::Publisher infoLeftPub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
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()
#define NODELET_DEBUG(...)
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
sensor_msgs::ImagePtr toImageMsg() const