40 #include <sensor_msgs/CameraInfo.h> 91 bool approxSync =
true;
92 if(private_nh.
getParam(
"max_rate", rate_))
96 private_nh.
param(
"rate", rate_, rate_);
97 private_nh.
param(
"queue_size", queueSize, queueSize);
98 private_nh.
param(
"approx_sync", approxSync, approxSync);
103 NODELET_INFO(
"Approximate time sync = %s", approxSync?
"true":
"false");
125 void callback(
const sensor_msgs::ImageConstPtr& image,
126 const sensor_msgs::ImageConstPtr& imageDepth,
127 const sensor_msgs::CameraInfoConstPtr& camInfo)
149 out.
header = imagePtr->header;
165 out.
header = imagePtr->header;
179 sensor_msgs::CameraInfo info = *camInfo;
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
image_transport::Publisher imagePub_
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::Synchronizer< MyExactSyncPolicy > * exactSync_
message_filters::Subscriber< sensor_msgs::CameraInfo > info_sub_
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
virtual ~DataThrottleNodelet()
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &camInfo)
void publish(const sensor_msgs::Image &message) const
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
image_transport::SubscriberFilter image_sub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncPolicy
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
image_transport::Publisher imageDepthPub_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
image_transport::SubscriberFilter image_depth_sub_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
#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)
bool getParam(const std::string &key, std::string &s) const
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const