rgbdx_sync.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
30 #include <nodelet/nodelet.h>
31 
35 
36 #include <boost/thread.hpp>
37 
38 #include "rtabmap_msgs/RGBDImages.h"
40 
41 namespace rtabmap_sync
42 {
43 
45 {
46 public:
48  SYNC_INIT(rgbd2),
49  SYNC_INIT(rgbd3),
50  SYNC_INIT(rgbd4),
51  SYNC_INIT(rgbd5),
52  SYNC_INIT(rgbd6),
53  SYNC_INIT(rgbd7),
54  SYNC_INIT(rgbd8)
55  {}
56 
57  virtual ~RGBDXSync()
58  {
59  SYNC_DEL(rgbd2);
60  SYNC_DEL(rgbd3);
61  SYNC_DEL(rgbd4);
62  SYNC_DEL(rgbd5);
63  SYNC_DEL(rgbd6);
64  SYNC_DEL(rgbd7);
65  SYNC_DEL(rgbd8);
66 
67  for(size_t i=0; i<rgbdSubs_.size(); ++i)
68  {
69  delete rgbdSubs_[i];
70  }
71  }
72 
73 private:
74 
75  virtual void onInit()
76  {
79 
80  int queueSize = 1;
81  int syncQueueSize = 10;
82  bool approxSync = true;
83  int rgbdCameras = 2;
84  double approxSyncMaxInterval = 0.0;
85  pnh.param("approx_sync", approxSync, approxSync);
86  pnh.param("approx_sync_max_interval", approxSyncMaxInterval, approxSyncMaxInterval);
87  pnh.param("topic_queue_size", queueSize, queueSize);
88  if(pnh.hasParam("queue_size") && !pnh.hasParam("sync_queue_size"))
89  {
90  pnh.param("queue_size", syncQueueSize, syncQueueSize);
91  ROS_WARN("Parameter \"queue_size\" has been renamed "
92  "to \"sync_queue_size\" and will be removed "
93  "in future versions! The value (%d) is still copied to "
94  "\"sync_queue_size\".", syncQueueSize);
95  }
96  else
97  {
98  pnh.param("sync_queue_size", syncQueueSize, syncQueueSize);
99  }
100  pnh.param("rgbd_cameras", rgbdCameras, rgbdCameras);
101 
102  NODELET_INFO("%s: approx_sync = %s", getName().c_str(), approxSync?"true":"false");
103  if(approxSync)
104  NODELET_INFO("%s: approx_sync_max_interval = %f", getName().c_str(), approxSyncMaxInterval);
105  NODELET_INFO("%s: topic_queue_size = %d", getName().c_str(), queueSize);
106  NODELET_INFO("%s: queue_size = %d", getName().c_str(), syncQueueSize);
107  NODELET_INFO("%s: rgbd_cameras = %d", getName().c_str(), rgbdCameras);
108 
109  rgbdImagesPub_ = nh.advertise<rtabmap_msgs::RGBDImages>("rgbd_images", 1);
110 
111  ROS_ASSERT(rgbdCameras>=2 && rgbdCameras<=8);
112 
113  rgbdSubs_.resize(rgbdCameras);
114  for(int i=0; i<rgbdCameras; ++i)
115  {
117  rgbdSubs_[i]->subscribe(nh, uFormat("rgbd_image%d", i), queueSize);
118  }
119 
120  std::string name_ = this->getName();
121  std::string subscribedTopicsMsg_;
122  if(rgbdCameras==2)
123  {
124  SYNC_DECL2(RGBDXSync, rgbd2, approxSync, syncQueueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]));
125  if(approxSync && approxSyncMaxInterval>0.0)
126  {
127  rgbd2ApproximateSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
128  }
129  }
130  else if(rgbdCameras==3)
131  {
132  SYNC_DECL3(RGBDXSync, rgbd3, approxSync, syncQueueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]));
133  if(approxSync && approxSyncMaxInterval>0.0)
134  {
135  rgbd3ApproximateSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
136  }
137  }
138  else if(rgbdCameras==4)
139  {
140  SYNC_DECL4(RGBDXSync, rgbd4, approxSync, syncQueueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]));
141  if(approxSync && approxSyncMaxInterval>0.0)
142  {
143  rgbd4ApproximateSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
144  }
145  }
146  else if(rgbdCameras==5)
147  {
148  SYNC_DECL5(RGBDXSync, rgbd5, approxSync, syncQueueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]));
149  if(approxSync && approxSyncMaxInterval>0.0)
150  {
151  rgbd5ApproximateSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
152  }
153  }
154  else if(rgbdCameras==6)
155  {
156  SYNC_DECL6(RGBDXSync, rgbd6, approxSync, syncQueueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), (*rgbdSubs_[5]));
157  if(approxSync && approxSyncMaxInterval>0.0)
158  {
159  rgbd6ApproximateSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
160  }
161  }
162  else if(rgbdCameras==7)
163  {
164  SYNC_DECL7(RGBDXSync, rgbd7, approxSync, syncQueueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), (*rgbdSubs_[5]), (*rgbdSubs_[6]));
165  if(approxSync && approxSyncMaxInterval>0.0)
166  {
167  rgbd7ApproximateSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
168  }
169  }
170  else if(rgbdCameras==8)
171  {
172  SYNC_DECL8(RGBDXSync, rgbd8, approxSync, syncQueueSize, (*rgbdSubs_[0]), (*rgbdSubs_[1]), (*rgbdSubs_[2]), (*rgbdSubs_[3]), (*rgbdSubs_[4]), (*rgbdSubs_[5]), (*rgbdSubs_[6]), (*rgbdSubs_[7]));
173  if(approxSync && approxSyncMaxInterval>0.0)
174  {
175  rgbd8ApproximateSync_->setMaxIntervalDuration(ros::Duration(approxSyncMaxInterval));
176  }
177  }
178 
179  std::string subscribedTopicsMsg = uFormat("%s%s", subscribedTopicsMsg_.c_str(),
180  approxSync&&approxSyncMaxInterval!=0.0?uFormat(" (approx sync max interval=%fs)", approxSyncMaxInterval).c_str():"");
181  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
182 
183  // Setup diagnostic
184  syncDiagnostic_.reset(new SyncDiagnostic(nh, pnh, getName()));
185  syncDiagnostic_->init("",
186  uFormat("%s: Did not receive data since 5 seconds! Make sure the input topics are "
187  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
188  "header are set. %s%s",
189  getName().c_str(),
190  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
191  "topics should have all the exact timestamp for the callback to be called.",
192  subscribedTopicsMsg.c_str()));
193  }
194 
195  DATA_SYNCS2(rgbd2, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
196  DATA_SYNCS3(rgbd3, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
197  DATA_SYNCS4(rgbd4, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
198  DATA_SYNCS5(rgbd5, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
199  DATA_SYNCS6(rgbd6, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
200  DATA_SYNCS7(rgbd7, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
201  DATA_SYNCS8(rgbd8, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage);
202 
203 private:
205 
206  std::vector<message_filters::Subscriber<rtabmap_msgs::RGBDImage>*> rgbdSubs_;
207 
208  std::unique_ptr<SyncDiagnostic> syncDiagnostic_;
209 };
210 
211 void RGBDXSync::rgbd2Callback(
212  const rtabmap_msgs::RGBDImageConstPtr& image0,
213  const rtabmap_msgs::RGBDImageConstPtr& image1)
214 {
215  syncDiagnostic_->tick(image0->header.stamp);
216 
217  rtabmap_msgs::RGBDImages output;
218  output.header = image0->header;
219  output.rgbd_images.resize(2);
220  output.rgbd_images[0]=(*image0);
221  output.rgbd_images[1]=(*image1);
222  rgbdImagesPub_.publish(output);
223 }
224 
225 void RGBDXSync::rgbd3Callback(
226  const rtabmap_msgs::RGBDImageConstPtr& image0,
227  const rtabmap_msgs::RGBDImageConstPtr& image1,
228  const rtabmap_msgs::RGBDImageConstPtr& image2)
229 {
230  syncDiagnostic_->tick(image0->header.stamp);
231  rtabmap_msgs::RGBDImages output;
232  output.header = image0->header;
233  output.rgbd_images.resize(3);
234  output.rgbd_images[0]=(*image0);
235  output.rgbd_images[1]=(*image1);
236  output.rgbd_images[2]=(*image2);
237  rgbdImagesPub_.publish(output);
238 }
239 
240 void RGBDXSync::rgbd4Callback(
241  const rtabmap_msgs::RGBDImageConstPtr& image0,
242  const rtabmap_msgs::RGBDImageConstPtr& image1,
243  const rtabmap_msgs::RGBDImageConstPtr& image2,
244  const rtabmap_msgs::RGBDImageConstPtr& image3)
245 {
246  syncDiagnostic_->tick(image0->header.stamp);
247  rtabmap_msgs::RGBDImages output;
248  output.header = image0->header;
249  output.rgbd_images.resize(4);
250  output.rgbd_images[0]=(*image0);
251  output.rgbd_images[1]=(*image1);
252  output.rgbd_images[2]=(*image2);
253  output.rgbd_images[3]=(*image3);
254  rgbdImagesPub_.publish(output);
255 }
256 
257 void RGBDXSync::rgbd5Callback(
258  const rtabmap_msgs::RGBDImageConstPtr& image0,
259  const rtabmap_msgs::RGBDImageConstPtr& image1,
260  const rtabmap_msgs::RGBDImageConstPtr& image2,
261  const rtabmap_msgs::RGBDImageConstPtr& image3,
262  const rtabmap_msgs::RGBDImageConstPtr& image4)
263 {
264  syncDiagnostic_->tick(image0->header.stamp);
265  rtabmap_msgs::RGBDImages output;
266  output.header = image0->header;
267  output.rgbd_images.resize(5);
268  output.rgbd_images[0]=(*image0);
269  output.rgbd_images[1]=(*image1);
270  output.rgbd_images[2]=(*image2);
271  output.rgbd_images[3]=(*image3);
272  output.rgbd_images[4]=(*image4);
273  rgbdImagesPub_.publish(output);
274 }
275 
276 void RGBDXSync::rgbd6Callback(
277  const rtabmap_msgs::RGBDImageConstPtr& image0,
278  const rtabmap_msgs::RGBDImageConstPtr& image1,
279  const rtabmap_msgs::RGBDImageConstPtr& image2,
280  const rtabmap_msgs::RGBDImageConstPtr& image3,
281  const rtabmap_msgs::RGBDImageConstPtr& image4,
282  const rtabmap_msgs::RGBDImageConstPtr& image5)
283 {
284  syncDiagnostic_->tick(image0->header.stamp);
285  rtabmap_msgs::RGBDImages output;
286  output.header = image0->header;
287  output.rgbd_images.resize(6);
288  output.rgbd_images[0]=(*image0);
289  output.rgbd_images[1]=(*image1);
290  output.rgbd_images[2]=(*image2);
291  output.rgbd_images[3]=(*image3);
292  output.rgbd_images[4]=(*image4);
293  output.rgbd_images[5]=(*image5);
294  rgbdImagesPub_.publish(output);
295 }
296 
297 void RGBDXSync::rgbd7Callback(
298  const rtabmap_msgs::RGBDImageConstPtr& image0,
299  const rtabmap_msgs::RGBDImageConstPtr& image1,
300  const rtabmap_msgs::RGBDImageConstPtr& image2,
301  const rtabmap_msgs::RGBDImageConstPtr& image3,
302  const rtabmap_msgs::RGBDImageConstPtr& image4,
303  const rtabmap_msgs::RGBDImageConstPtr& image5,
304  const rtabmap_msgs::RGBDImageConstPtr& image6)
305 {
306  syncDiagnostic_->tick(image0->header.stamp);
307  rtabmap_msgs::RGBDImages output;
308  output.header = image0->header;
309  output.rgbd_images.resize(7);
310  output.rgbd_images[0]=(*image0);
311  output.rgbd_images[1]=(*image1);
312  output.rgbd_images[2]=(*image2);
313  output.rgbd_images[3]=(*image3);
314  output.rgbd_images[4]=(*image4);
315  output.rgbd_images[5]=(*image5);
316  output.rgbd_images[6]=(*image6);
317  rgbdImagesPub_.publish(output);
318 }
319 
320 void RGBDXSync::rgbd8Callback(
321  const rtabmap_msgs::RGBDImageConstPtr& image0,
322  const rtabmap_msgs::RGBDImageConstPtr& image1,
323  const rtabmap_msgs::RGBDImageConstPtr& image2,
324  const rtabmap_msgs::RGBDImageConstPtr& image3,
325  const rtabmap_msgs::RGBDImageConstPtr& image4,
326  const rtabmap_msgs::RGBDImageConstPtr& image5,
327  const rtabmap_msgs::RGBDImageConstPtr& image6,
328  const rtabmap_msgs::RGBDImageConstPtr& image7)
329 {
330  syncDiagnostic_->tick(image0->header.stamp);
331  rtabmap_msgs::RGBDImages output;
332  output.header = image0->header;
333  output.rgbd_images.resize(8);
334  output.rgbd_images[0]=(*image0);
335  output.rgbd_images[1]=(*image1);
336  output.rgbd_images[2]=(*image2);
337  output.rgbd_images[3]=(*image3);
338  output.rgbd_images[4]=(*image4);
339  output.rgbd_images[5]=(*image5);
340  output.rgbd_images[6]=(*image6);
341  output.rgbd_images[7]=(*image7);
342  rgbdImagesPub_.publish(output);
343 }
344 
346 }
347 
SYNC_DECL6
#define SYNC_DECL6(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5)
Definition: CommonDataSubscriberDefines.h:190
SYNC_DEL
#define SYNC_DEL(PREFIX)
Definition: CommonDataSubscriberDefines.h:103
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
SYNC_DECL2
#define SYNC_DECL2(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
Definition: CommonDataSubscriberDefines.h:108
rtabmap_sync
Definition: CommonDataSubscriber.h:59
SYNC_DECL8
#define SYNC_DECL8(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6, SUB7)
Definition: CommonDataSubscriberDefines.h:237
uFormat
std::string uFormat(const char *fmt,...)
ros.h
rtabmap_sync::SyncDiagnostic
Definition: SyncDiagnostic.h:13
name_
std::string name_
SYNC_DECL3
#define SYNC_DECL3(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
Definition: CommonDataSubscriberDefines.h:127
rtabmap_sync::RGBDXSync::RGBDXSync
RGBDXSync()
Definition: rgbdx_sync.cpp:47
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
CommonDataSubscriber.h
message_filters::Subscriber
rtabmap_sync::RGBDXSync::DATA_SYNCS2
DATA_SYNCS2(rgbd2, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage)
rtabmap_sync::RGBDXSync
Definition: rgbdx_sync.cpp:44
rtabmap_sync::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_sync::RgbSync, nodelet::Nodelet)
rtabmap_sync::RGBDXSync::~RGBDXSync
virtual ~RGBDXSync()
Definition: rgbdx_sync.cpp:57
rtabmap_sync::RGBDXSync::DATA_SYNCS7
DATA_SYNCS7(rgbd7, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage)
subscriber.h
rtabmap_sync::RGBDXSync::rgbdSubs_
std::vector< message_filters::Subscriber< rtabmap_msgs::RGBDImage > * > rgbdSubs_
Definition: rgbdx_sync.cpp:206
rtabmap_sync::RGBDXSync::onInit
virtual void onInit()
Definition: rgbdx_sync.cpp:75
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
rtabmap_sync::RGBDXSync::DATA_SYNCS4
DATA_SYNCS4(rgbd4, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage)
rtabmap_sync::RGBDXSync::DATA_SYNCS3
DATA_SYNCS3(rgbd3, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage)
SYNC_DECL5
#define SYNC_DECL5(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4)
Definition: CommonDataSubscriberDefines.h:168
exact_time.h
rtabmap_sync::RGBDXSync::syncDiagnostic_
std::unique_ptr< SyncDiagnostic > syncDiagnostic_
Definition: rgbdx_sync.cpp:208
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
rtabmap_sync::RGBDXSync::DATA_SYNCS6
DATA_SYNCS6(rgbd6, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage)
nodelet.h
c_str
const char * c_str(Args &&...args)
class_list_macros.hpp
SYNC_DECL4
#define SYNC_DECL4(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3)
Definition: CommonDataSubscriberDefines.h:147
nodelet::Nodelet::getName
const std::string & getName() const
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rtabmap_sync::RGBDXSync::DATA_SYNCS8
DATA_SYNCS8(rgbd8, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage)
approximate_time.h
ROS_ASSERT
#define ROS_ASSERT(cond)
SYNC_INIT
#define SYNC_INIT(PREFIX)
Definition: CommonDataSubscriberDefines.h:98
ros::Duration
i
int i
rtabmap_sync::RGBDXSync::rgbdImagesPub_
ros::Publisher rgbdImagesPub_
Definition: rgbdx_sync.cpp:204
ros::NodeHandle
SYNC_DECL7
#define SYNC_DECL7(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2, SUB3, SUB4, SUB5, SUB6)
Definition: CommonDataSubscriberDefines.h:213
rtabmap_sync::RGBDXSync::DATA_SYNCS5
DATA_SYNCS5(rgbd5, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage, rtabmap_msgs::RGBDImage)


rtabmap_sync
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:39:12