22 #include "sensor_msgs/PointCloud2.h" 23 #include <sensor_msgs/Image.h> 24 #include <sensor_msgs/CameraInfo.h> 97 void callback(
const tPointCloud::ConstPtr& rgb_cloud,
98 const tImage::ConstPtr& rgb_image,
99 const tCameraInfo::ConstPtr& rgb_caminfo
sensor_msgs::PointCloud2 tPointCloud
ros::Publisher cloud_pub_
sensor_msgs::CameraInfo tCameraInfo
ros::NodeHandle & getNodeHandle() const
message_filters::Subscriber< tImage > rgb_image_sub_
message_filters::Subscriber< tCameraInfo > rgb_caminfo_sub_
ros::Publisher rgb_caminfo_pub_
ros::NodeHandle & getPrivateNodeHandle() const
message_filters::sync_policies::ApproximateTime< tPointCloud, tImage, tCameraInfo > tSyncPolicy
void callback(const tPointCloud::ConstPtr &rgb_cloud, const tImage::ConstPtr &rgb_image, const tCameraInfo::ConstPtr &rgb_caminfo)
void publish(const boost::shared_ptr< M > &message) const
void connectCB(const ros::SingleSubscriberPublisher &pub)
bool getParam(const std::string &key, std::string &s) const
void disconnectCB(const ros::SingleSubscriberPublisher &pub)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int sub_counter_
message_filters::Subscriber< tPointCloud > cloud_sub_
sensor_msgs::Image tImage
message_filters::Synchronizer< tSyncPolicy > sync_
ros::Publisher rgb_image_pub_
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::Subscriber< tImage > depth_image_sub_
message_filters::Subscriber< tPointCloud > rgb_cloud_sub_
ros::Publisher depth_image_pub_
#define NODELET_DEBUG(...)
PLUGINLIB_EXPORT_CLASS(cob_cam3d_throttle::Cam3DThrottle, nodelet::Nodelet)
ros::Publisher rgb_cloud_pub_