20 size_t queue_size,
bool latch =
false);
42 const std::string& pcl_topic,
size_t queue_size,
bool latch =
false);
49 const std::string& pcl_topic,
size_t queue_size,
79 void(*fp)(
const sensor_msgs::ImageConstPtr&,
80 const sensor_msgs::CameraInfoConstPtr&,
81 const sensor_msgs::ImageConstPtr&,
82 const sensor_msgs::CameraInfoConstPtr&),
87 transport_hints_rgb, transport_hints_depth);
96 void(T::*fp)(
const sensor_msgs::ImageConstPtr&,
97 const sensor_msgs::CameraInfoConstPtr&,
98 const sensor_msgs::ImageConstPtr&,
99 const sensor_msgs::CameraInfoConstPtr&), T* obj,
103 return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, queue_size, boost::bind(fp, obj, _1, _2, _3, _4),
ros::VoidPtr(),
104 transport_hints_rgb, transport_hints_depth);
113 void(T::*fp)(
const sensor_msgs::ImageConstPtr&,
114 const sensor_msgs::CameraInfoConstPtr&,
115 const sensor_msgs::ImageConstPtr&,
116 const sensor_msgs::CameraInfoConstPtr&),
121 return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, queue_size, boost::bind(fp, obj.get(), _1, _2, _3, _4), obj,
122 transport_hints_rgb, transport_hints_depth);
135 const std::string& pcl_topic,
size_t queue_size,
146 const std::string& pcl_topic,
size_t queue_size,
147 void(*fp)(
const sensor_msgs::ImageConstPtr&,
148 const sensor_msgs::CameraInfoConstPtr&,
149 const sensor_msgs::ImageConstPtr&,
150 const sensor_msgs::CameraInfoConstPtr&,
151 const sensor_msgs::PointCloud2ConstPtr&),
157 transport_hints_rgb, transport_hints_depth, transport_hints_pcl);
166 const std::string& pcl_topic,
size_t queue_size,
167 void(T::*fp)(
const sensor_msgs::ImageConstPtr&,
168 const sensor_msgs::CameraInfoConstPtr&,
169 const sensor_msgs::ImageConstPtr&,
170 const sensor_msgs::CameraInfoConstPtr&,
171 const sensor_msgs::PointCloud2ConstPtr&), T* obj,
176 return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, pcl_topic, queue_size, boost::bind(fp, obj, _1, _2, _3, _4, _5),
ros::VoidPtr(),
177 transport_hints_rgb, transport_hints_depth, transport_hints_pcl);
186 const std::string& pcl_topic,
size_t queue_size,
187 void(T::*fp)(
const sensor_msgs::ImageConstPtr&,
188 const sensor_msgs::CameraInfoConstPtr&,
189 const sensor_msgs::ImageConstPtr&,
190 const sensor_msgs::CameraInfoConstPtr&,
191 const sensor_msgs::PointCloud2ConstPtr&),
197 return subscribeRgbdCamera(rgb_base_topic, depth_base_topic, pcl_topic, queue_size, boost::bind(fp, obj.get(), _1, _2, _3, _4, _5), obj,
198 transport_hints_rgb, transport_hints_depth, transport_hints_pcl);