39 #include <sensor_msgs/CameraInfo.h> 40 #include <nav_msgs/Odometry.h> 75 private_nh.
param(
"queue_size", queueSize, queueSize);
80 image_sub_.subscribe(rgb_it, rgb_nh.
resolveName(
"image_in"), 1, hintsRgb);
81 image_depth_sub_.subscribe(depth_it, depth_nh.
resolveName(
"image_in"), 1, hintsDepth);
82 info_sub_.subscribe(rgb_nh,
"camera_info_in", 1);
91 void callback(
const sensor_msgs::ImageConstPtr& image,
92 const sensor_msgs::ImageConstPtr& imageDepth,
93 const sensor_msgs::CameraInfoConstPtr& camInfo,
94 const nav_msgs::OdometryConstPtr & odom)
message_filters::Subscriber< nav_msgs::Odometry > odom_sub_
message_filters::Subscriber< sensor_msgs::CameraInfo > info_sub_
void publish(const boost::shared_ptr< M > &message) const
image_transport::SubscriberFilter image_depth_sub_
std::string resolveName(const std::string &name, bool remap=true) const
virtual ~DataOdomSyncNodelet()
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Publisher imageDepthPub_
image_transport::Publisher imagePub_
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &camInfo, const nav_msgs::OdometryConstPtr &odom)
void publish(const sensor_msgs::Image &message) const
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, nav_msgs::Odometry > MySyncPolicy
message_filters::Synchronizer< MySyncPolicy > * sync_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
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)
image_transport::SubscriberFilter image_sub_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)