OdometryROS.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 
29 
30 #include <sensor_msgs/Image.h>
32 #include <sensor_msgs/PointCloud2.h>
33 #include <nav_msgs/Odometry.h>
34 
36 
37 #include <cv_bridge/cv_bridge.h>
38 
41 #include <rtabmap/core/util3d.h>
43 #include <rtabmap/core/Memory.h>
44 #include <rtabmap/core/Signature.h>
46 #include "rtabmap_ros/OdomInfo.h"
49 #include "rtabmap/utilite/UStl.h"
50 #include "rtabmap/utilite/UFile.h"
51 #include "rtabmap/utilite/UMath.h"
52 
53 #define BAD_COVARIANCE 9999
54 
55 using namespace rtabmap;
56 
57 namespace rtabmap_ros {
58 
59 OdometryROS::OdometryROS(bool stereoParams, bool visParams, bool icpParams) :
60  odometry_(0),
61  warningThread_(0),
62  callbackCalled_(false),
63  frameId_("base_link"),
64  odomFrameId_("odom"),
65  groundTruthFrameId_(""),
66  groundTruthBaseFrameId_(""),
67  guessFrameId_(""),
68  guessMinTranslation_(0.0),
69  guessMinRotation_(0.0),
70  guessMinTime_(0.0),
71  publishTf_(true),
72  waitForTransform_(true),
73  waitForTransformDuration_(0.1), // 100 ms
74  publishNullWhenLost_(true),
75  paused_(false),
76  resetCountdown_(0),
77  resetCurrentCount_(0),
78  stereoParams_(stereoParams),
79  visParams_(visParams),
80  icpParams_(icpParams),
81  previousStamp_(0.0),
82  expectedUpdateRate_(0.0),
83  maxUpdateRate_(0.0),
84  minUpdateRate_(0.0),
85  odomStrategy_(Parameters::defaultOdomStrategy()),
86  waitIMUToinit_(false),
87  imuProcessed_(false)
88 {
89 
90 }
91 
93 {
94  if(warningThread_)
95  {
97  warningThread_->join();
98  delete warningThread_;
99  }
100 
101  delete odometry_;
102 }
103 
105 {
108 
109  odomPub_ = nh.advertise<nav_msgs::Odometry>("odom", 1);
110  odomInfoPub_ = nh.advertise<rtabmap_ros::OdomInfo>("odom_info", 1);
111  odomInfoLitePub_ = nh.advertise<rtabmap_ros::OdomInfo>("odom_info_lite", 1);
112  odomLocalMap_ = nh.advertise<sensor_msgs::PointCloud2>("odom_local_map", 1);
113  odomLocalScanMap_ = nh.advertise<sensor_msgs::PointCloud2>("odom_local_scan_map", 1);
114  odomLastFrame_ = nh.advertise<sensor_msgs::PointCloud2>("odom_last_frame", 1);
115  odomRgbdImagePub_ = nh.advertise<rtabmap_ros::RGBDImage>("odom_rgbd_image", 1);
116 
117  Transform initialPose = Transform::getIdentity();
118  std::string initialPoseStr;
119  std::string configPath;
120  pnh.param("frame_id", frameId_, frameId_);
121  pnh.param("odom_frame_id", odomFrameId_, odomFrameId_);
122  pnh.param("publish_tf", publishTf_, publishTf_);
123  if(pnh.hasParam("tf_prefix"))
124  {
125  NODELET_ERROR("tf_prefix parameter has been removed, use directly odom_frame_id and frame_id parameters.");
126  }
127  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
128  pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
129  pnh.param("initial_pose", initialPoseStr, initialPoseStr); // "x y z roll pitch yaw"
130  pnh.param("ground_truth_frame_id", groundTruthFrameId_, groundTruthFrameId_);
131  pnh.param("ground_truth_base_frame_id", groundTruthBaseFrameId_, frameId_);
132  pnh.param("config_path", configPath, configPath);
133  pnh.param("publish_null_when_lost", publishNullWhenLost_, publishNullWhenLost_);
134  if(pnh.hasParam("guess_from_tf"))
135  {
136  if(!pnh.hasParam("guess_frame_id"))
137  {
138  NODELET_ERROR("Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
139  }
140  else
141  {
142  NODELET_WARN("Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
143  }
144  }
145  pnh.param("guess_frame_id", guessFrameId_, guessFrameId_); // odometry guess frame
146  pnh.param("guess_min_translation", guessMinTranslation_, guessMinTranslation_);
147  pnh.param("guess_min_rotation", guessMinRotation_, guessMinRotation_);
148  pnh.param("guess_min_time", guessMinTime_, guessMinTime_);
149 
150  pnh.param("expected_update_rate", expectedUpdateRate_, expectedUpdateRate_); // expected sensor rate
151  pnh.param("max_update_rate", maxUpdateRate_, maxUpdateRate_);
152  pnh.param("min_update_rate", minUpdateRate_, minUpdateRate_);
153 
154  pnh.param("wait_imu_to_init", waitIMUToinit_, waitIMUToinit_);
155 
156  int eventLevel = ULogger::kFatal;
157  pnh.param("log_to_rosout_level", eventLevel, eventLevel);
158  UASSERT(eventLevel >= ULogger::kDebug && eventLevel <= ULogger::kFatal);
160 
161  if(publishTf_ && !guessFrameId_.empty() && guessFrameId_.compare(odomFrameId_) == 0)
162  {
163  NODELET_WARN( "\"publish_tf\" and \"guess_frame_id\" cannot be used "
164  "at the same time if \"guess_frame_id\" and \"odom_frame_id\" "
165  "are the same frame (value=\"%s\"). \"guess_frame_id\" is disabled.", odomFrameId_.c_str());
166  guessFrameId_.clear();
167  }
168  NODELET_INFO("Odometry: frame_id = %s", frameId_.c_str());
169  NODELET_INFO("Odometry: odom_frame_id = %s", odomFrameId_.c_str());
170  NODELET_INFO("Odometry: publish_tf = %s", publishTf_?"true":"false");
171  NODELET_INFO("Odometry: wait_for_transform = %s", waitForTransform_?"true":"false");
172  NODELET_INFO("Odometry: wait_for_transform_duration = %f", waitForTransformDuration_);
173  NODELET_INFO("Odometry: log_to_rosout_level = %d", eventLevel);
174  NODELET_INFO("Odometry: initial_pose = %s", initialPose.prettyPrint().c_str());
175  NODELET_INFO("Odometry: ground_truth_frame_id = %s", groundTruthFrameId_.c_str());
176  NODELET_INFO("Odometry: ground_truth_base_frame_id = %s", groundTruthBaseFrameId_.c_str());
177  NODELET_INFO("Odometry: config_path = %s", configPath.c_str());
178  NODELET_INFO("Odometry: publish_null_when_lost = %s", publishNullWhenLost_?"true":"false");
179  NODELET_INFO("Odometry: guess_frame_id = %s", guessFrameId_.c_str());
180  NODELET_INFO("Odometry: guess_min_translation = %f", guessMinTranslation_);
181  NODELET_INFO("Odometry: guess_min_rotation = %f", guessMinRotation_);
182  NODELET_INFO("Odometry: guess_min_time = %f", guessMinTime_);
183  NODELET_INFO("Odometry: expected_update_rate = %f Hz", expectedUpdateRate_);
184  NODELET_INFO("Odometry: max_update_rate = %f Hz", maxUpdateRate_);
185  NODELET_INFO("Odometry: min_update_rate = %f Hz", minUpdateRate_);
186  NODELET_INFO("Odometry: wait_imu_to_init = %s", waitIMUToinit_?"true":"false");
187 
188  configPath = uReplaceChar(configPath, '~', UDirectory::homeDir());
189  if(configPath.size() && configPath.at(0) != '/')
190  {
191  configPath = UDirectory::currentDir(true) + configPath;
192  }
193 
194  if(initialPoseStr.size())
195  {
196  std::vector<std::string> values = uListToVector(uSplit(initialPoseStr, ' '));
197  if(values.size() == 6)
198  {
199  initialPose = Transform(
200  uStr2Float(values[0]), uStr2Float(values[1]), uStr2Float(values[2]),
201  uStr2Float(values[3]), uStr2Float(values[4]), uStr2Float(values[5]));
202  }
203  else
204  {
205  NODELET_ERROR( "Wrong initial_pose format: %s (should be \"x y z roll pitch yaw\" with angle in radians). "
206  "Identity will be used...", initialPoseStr.c_str());
207  }
208  }
209 
210 
211  //parameters
212  ROS_INFO("Odometry: stereoParams_=%d visParams_=%d icpParams_=%d", stereoParams_?1:0, visParams_?1:0, icpParams_?1:0);
213  parameters_ = Parameters::getDefaultOdometryParameters(stereoParams_, visParams_, icpParams_);
214  if(icpParams_)
215  {
216  if(!visParams_)
217  {
218  uInsert(parameters_, ParametersPair(Parameters::kRegStrategy(), "1"));
219  }
220  else
221  {
222  uInsert(parameters_, ParametersPair(Parameters::kRegStrategy(), "2"));
223  }
224  }
225  parameters_.insert(*Parameters::getDefaultParameters().find(Parameters::kRtabmapImagesAlreadyRectified()));
226  if(!configPath.empty())
227  {
228  if(UFile::exists(configPath.c_str()))
229  {
230  NODELET_INFO( "Odometry: Loading parameters from %s", configPath.c_str());
231  rtabmap::ParametersMap allParameters;
232  Parameters::readINI(configPath.c_str(), allParameters);
233  // only update odometry parameters
234  for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
235  {
236  ParametersMap::iterator jter = allParameters.find(iter->first);
237  if(jter!=allParameters.end())
238  {
239  iter->second = jter->second;
240  }
241  }
242  }
243  else
244  {
245  NODELET_ERROR( "Config file \"%s\" not found!", configPath.c_str());
246  }
247  }
248  for(rtabmap::ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
249  {
250  std::string vStr;
251  bool vBool;
252  int vInt;
253  double vDouble;
254  if(pnh.getParam(iter->first, vStr))
255  {
256  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
257  iter->second = vStr;
258  }
259  else if(pnh.getParam(iter->first, vBool))
260  {
261  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
262  iter->second = uBool2Str(vBool);
263  }
264  else if(pnh.getParam(iter->first, vDouble))
265  {
266  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble, 6).c_str());
267  iter->second = uNumber2Str(vDouble, 6);
268  }
269  else if(pnh.getParam(iter->first, vInt))
270  {
271  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
272  iter->second = uNumber2Str(vInt);
273  }
274 
275  if(iter->first.compare(Parameters::kVisMinInliers()) == 0 && atoi(iter->second.c_str()) < 8)
276  {
277  NODELET_WARN( "Parameter min_inliers must be >= 8, setting to 8...");
278  iter->second = uNumber2Str(8);
279  }
280  }
281 
282  std::vector<std::string> argList = getMyArgv();
283  char ** argv = new char*[argList.size()];
284  for(unsigned int i=0; i<argList.size(); ++i)
285  {
286  argv[i] = &argList[i].at(0);
287  }
288 
290  delete [] argv;
291  for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
292  {
293  rtabmap::ParametersMap::iterator jter = parameters_.find(iter->first);
294  if(jter!=parameters_.end())
295  {
296  NODELET_INFO( "Update odometry parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
297  jter->second = iter->second;
298  }
299  else
300  {
301  NODELET_INFO( "Odometry: Ignored parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
302  }
303  }
304 
305  // Backward compatibility
306  for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=Parameters::getRemovedParameters().begin();
307  iter!=Parameters::getRemovedParameters().end();
308  ++iter)
309  {
310  std::string vStr;
311  if(pnh.getParam(iter->first, vStr))
312  {
313  if(!iter->second.second.empty() && parameters_.find(iter->second.second)!=parameters_.end())
314  {
315  NODELET_WARN("Rtabmap: Parameter name changed: \"%s\" -> \"%s\". The new parameter is already used with value \"%s\", ignoring the old one with value \"%s\".",
316  iter->first.c_str(), iter->second.second.c_str(), parameters_.find(iter->second.second)->second.c_str(), vStr.c_str());
317  }
318  else if(iter->second.first && parameters_.find(iter->second.second) != parameters_.end())
319  {
320  // can be migrated
321  parameters_.at(iter->second.second)= vStr;
322  NODELET_WARN( "Odometry: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
323  iter->first.c_str(), iter->second.second.c_str(), vStr.c_str());
324  }
325  else
326  {
327  if(iter->second.second.empty())
328  {
329  NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore!",
330  iter->first.c_str());
331  }
332  else
333  {
334  NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
335  iter->first.c_str(), iter->second.second.c_str());
336  }
337  }
338  }
339  }
340 
341  // set private parameters
342  for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
343  {
344  pnh.setParam(iter->first, iter->second);
345  }
346 
347  Parameters::parse(parameters_, Parameters::kOdomResetCountdown(), resetCountdown_);
348  parameters_.at(Parameters::kOdomResetCountdown()) = "0"; // use modified reset countdown here
349 
351 
352  odometry_ = Odometry::create(parameters_);
353  if(!initialPose.isIdentity())
354  {
355  odometry_->reset(initialPose);
356  }
357 
358  resetSrv_ = nh.advertiseService("reset_odom", &OdometryROS::reset, this);
359  resetToPoseSrv_ = nh.advertiseService("reset_odom_to_pose", &OdometryROS::resetToPose, this);
360  pauseSrv_ = nh.advertiseService("pause_odom", &OdometryROS::pause, this);
361  resumeSrv_ = nh.advertiseService("resume_odom", &OdometryROS::resume, this);
362 
363  setLogDebugSrv_ = pnh.advertiseService("log_debug", &OdometryROS::setLogDebug, this);
364  setLogInfoSrv_ = pnh.advertiseService("log_info", &OdometryROS::setLogInfo, this);
365  setLogWarnSrv_ = pnh.advertiseService("log_warning", &OdometryROS::setLogWarn, this);
366  setLogErrorSrv_ = pnh.advertiseService("log_error", &OdometryROS::setLogError, this);
367 
368  odomStrategy_ = 0;
369  Parameters::parse(this->parameters(), Parameters::kOdomStrategy(), odomStrategy_);
370  if(waitIMUToinit_)
371  {
372  int queueSize = 10;
373  pnh.param("queue_size", queueSize, queueSize);
374  imuSub_ = nh.subscribe("imu", queueSize*5, &OdometryROS::callbackIMU, this);
375  NODELET_INFO("odometry: Subscribing to IMU topic %s", imuSub_.getTopic().c_str());
376  }
377 
378  onOdomInit();
379 }
380 
381 void OdometryROS::startWarningThread(const std::string & subscribedTopicsMsg, bool approxSync)
382 {
383  warningThread_ = new boost::thread(boost::bind(&OdometryROS::warningLoop, this, subscribedTopicsMsg, approxSync));
384  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
385 }
386 
387 void OdometryROS::warningLoop(const std::string & subscribedTopicsMsg, bool approxSync)
388 {
389  ros::Duration r(5.0);
390  while(!callbackCalled_)
391  {
392  r.sleep();
393  if(!callbackCalled_)
394  {
395  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
396  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
397  "header are set. %s%s",
398  getName().c_str(),
399  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
400  "topics should have all the exact timestamp for the callback to be called.",
401  subscribedTopicsMsg.c_str());
402  }
403  }
404 }
405 
407 {
408  if(odometry_)
409  {
410  return odometry_->getVelocityGuess();
411  }
412  return rtabmap::Transform();
413 }
414 
415 void OdometryROS::callbackIMU(const sensor_msgs::ImuConstPtr& msg)
416 {
417  if(!this->isPaused())
418  {
419  double stamp = msg->header.stamp.toSec();
421  if(this->frameId().compare(msg->header.frame_id) != 0)
422  {
423  localTransform = getTransform(this->frameId(), msg->header.frame_id, msg->header.stamp, this->tfListener(), this->waitForTransformDuration());
424  }
425  if(localTransform.isNull())
426  {
427  ROS_ERROR("Could not transform IMU msg from frame \"%s\" to frame \"%s\", TF not available at time %f",
428  msg->header.frame_id.c_str(), this->frameId().c_str(), stamp);
429  return;
430  }
431 
432  IMU imu(cv::Vec4d(msg->orientation.x, msg->orientation.y, msg->orientation.z, msg->orientation.w),
433  cv::Mat(3,3,CV_64FC1,(void*)msg->orientation_covariance.data()).clone(),
434  cv::Vec3d(msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z),
435  cv::Mat(3,3,CV_64FC1,(void*)msg->angular_velocity_covariance.data()).clone(),
436  cv::Vec3d(msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z),
437  cv::Mat(3,3,CV_64FC1,(void*)msg->linear_acceleration_covariance.data()).clone(),
438  localTransform);
439 
440  imus_.insert(std::make_pair(stamp, imu));
441 
442  if(bufferedData_.first.isValid() && stamp > bufferedData_.first.stamp())
443  {
444  SensorData data = bufferedData_.first;
445  bufferedData_.first = SensorData();
446  processData(data, bufferedData_.second);
447  }
448 
449  if(imus_.size() > 1000)
450  {
451  imus_.erase(imus_.begin());
452  }
453  }
454 }
455 
456 void OdometryROS::processData(SensorData & data, const std_msgs::Header & header)
457 {
459  {
460  NODELET_WARN("odometry: waiting imu (%s) to initialize orientation (wait_imu_to_init=true)", imuSub_.getTopic().c_str());
461  return;
462  }
463 
464  if(waitIMUToinit_ && (imus_.empty() || imus_.rbegin()->first < header.stamp.toSec()))
465  {
466  //NODELET_WARN("No imu received with higher stamp than last image (%f)! Buffering this image until we get more imu msgs...", stamp.toSec());
467 
468  // keep in cache to process later when we will receive imu msgs
469  if(bufferedData_.first.isValid())
470  {
471  NODELET_ERROR("Overwriting previous data! Make sure IMU is "
472  "published faster than data rate. (last image stamp "
473  "buffered=%f and new one is %f, last imu stamp received=%f)",
474  bufferedData_.first.stamp(), data.stamp(), imus_.empty()?0:imus_.rbegin()->first);
475  }
476  bufferedData_.first = data;
477  bufferedData_.second = header;
478  return;
479  }
480  // process all imu data up to current image stamp (or just after so that underlying odom approach can do interpolation of imu at image stamp)
481  std::map<double, rtabmap::IMU>::iterator iterEnd = imus_.lower_bound(header.stamp.toSec());
482  if(iterEnd!= imus_.end())
483  {
484  ++iterEnd;
485  }
486  for(std::map<double, rtabmap::IMU>::iterator iter=imus_.begin(); iter!=iterEnd;)
487  {
488  //NODELET_WARN("img callback: process imu %f", iter->first);
489  SensorData dataIMU(iter->second, 0, iter->first);
490  odometry_->process(dataIMU);
491  imus_.erase(iter++);
492  imuProcessed_ = true;
493  }
494 
495  //NODELET_WARN("img callback: process image %f", stamp.toSec());
496 
497  Transform groundTruth;
498  if(!data.imageRaw().empty() || !data.laserScanRaw().isEmpty())
499  {
500  if(previousStamp_>0.0 && previousStamp_ >= header.stamp.toSec())
501  {
502  NODELET_WARN("Odometry: Detected not valid consecutive stamps (previous=%fs new=%fs). "
503  "New stamp should be always greater than previous stamp. This new data is ignored.",
504  previousStamp_, header.stamp.toSec());
505  return;
506  }
507  else if(maxUpdateRate_ > 0 &&
508  previousStamp_ > 0 &&
509  (header.stamp.toSec()-previousStamp_+(expectedUpdateRate_ > 0?1.0/expectedUpdateRate_:0)) < 1.0/maxUpdateRate_)
510  {
511  // throttling
512  return;
513  }
514  else if(maxUpdateRate_ == 0 &&
515  expectedUpdateRate_ > 0 &&
516  previousStamp_ > 0 &&
517  (header.stamp.toSec()-previousStamp_) < 1.0/expectedUpdateRate_)
518  {
519  NODELET_WARN("Odometry: Aborting odometry update, higher frame rate detected (%f Hz) than the expected one (%f Hz). (stamps: previous=%fs new=%fs)",
520  1.0/(header.stamp.toSec()-previousStamp_), expectedUpdateRate_, previousStamp_, header.stamp.toSec());
521  return;
522  }
523 
524  if(!groundTruthFrameId_.empty())
525  {
526  groundTruth = getTransform(groundTruthFrameId_, groundTruthBaseFrameId_, header.stamp, this->tfListener(), this->waitForTransformDuration());
527 
528  if(!data.imageRaw().empty() || !data.laserScanRaw().isEmpty())
529  {
530  // Use only XYZ to handle the case odometry was previously initialized with IMU,
531  // we assume that the ground truth contains also a real initial orientation
532  float x,y,z;
533  odometry_->getPose().getTranslation(x, y, z);
534  if(x==0.0f && y==0.0f && z==0.0f)
535  {
536  // sync with the first value of the ground truth
537  if(groundTruth.isNull())
538  {
539  NODELET_WARN("Ground truth frames \"%s\" -> \"%s\" are set but failed to "
540  "get them, odometry won't be initialized with ground truth.",
542  }
543  else
544  {
545  NODELET_INFO( "Initializing odometry pose to %s (from \"%s\" -> \"%s\")",
546  groundTruth.prettyPrint().c_str(),
547  groundTruthFrameId_.c_str(),
548  groundTruthBaseFrameId_.c_str());
549  odometry_->reset(groundTruth);
550  }
551  }
552  }
553  }
554  }
555 
556 
557  Transform guessCurrentPose;
558  if(!guessFrameId_.empty())
559  {
560  guessCurrentPose = getTransform(guessFrameId_, frameId_, header.stamp, this->tfListener(), this->waitForTransformDuration());
561 
562  Transform previousPose = guessPreviousPose_;
564  {
565  previousPose = guessCurrentPose;
566  if(!guessCurrentPose.isNull() && odometry_->getPose().isIdentity())
567  {
568  ROS_INFO("Odometry: init pose with guess %s", guessCurrentPose.prettyPrint().c_str());
569  odometry_->reset(guessCurrentPose);
570  }
571  }
572 
573  if(!previousPose.isNull() && !guessCurrentPose.isNull())
574  {
575  if(guess_.isNull())
576  {
577  guess_ = previousPose.inverse() * guessCurrentPose;
578  }
579  else
580  {
581  guess_ = guess_ * previousPose.inverse() * guessCurrentPose;
582  }
584  {
585  float x,y,z,roll,pitch,yaw;
586  guess_.getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
587  if((guessMinTranslation_ <= 0.0 || uMax3(fabs(x), fabs(y), fabs(z)) < guessMinTranslation_) &&
588  (guessMinRotation_ <= 0.0 || uMax3(fabs(roll), fabs(pitch), fabs(yaw)) < guessMinRotation_) &&
589  (guessMinTime_ <= 0.0 || (previousStamp_>0.0 && header.stamp.toSec()-previousStamp_ < guessMinTime_)))
590  {
591  // Ignore odometry update, we didn't move enough
592  if(publishTf_)
593  {
594  geometry_msgs::TransformStamped correctionMsg;
595  correctionMsg.child_frame_id = guessFrameId_;
596  correctionMsg.header.frame_id = odomFrameId_;
597  correctionMsg.header.stamp = header.stamp;
598  Transform correction = odometry_->getPose() * guess_ * guessCurrentPose.inverse();
599  rtabmap_ros::transformToGeometryMsg(correction, correctionMsg.transform);
600  tfBroadcaster_.sendTransform(correctionMsg);
601  }
602  guessPreviousPose_ = guessCurrentPose;
603  return;
604  }
605  }
606  guessPreviousPose_ = guessCurrentPose;
607  }
608  else
609  {
610  NODELET_ERROR("\"guess_frame_id\" is set, but guess cannot be computed between frames \"%s\" -> \"%s\". Aborting odometry update...", guessFrameId_.c_str(), frameId_.c_str());
611  return;
612  }
613  }
614 
615  bool tooOldPreviousData = minUpdateRate_ > 0 && previousStamp_ > 0 && (header.stamp.toSec()-previousStamp_) > 1.0/minUpdateRate_;
616 
617  // process data
620  if(!groundTruth.isNull())
621  {
622  data.setGroundTruth(groundTruth);
623  }
624  rtabmap::Transform pose;
625  if(!tooOldPreviousData)
626  {
627  pose = odometry_->process(data, guess_, &info);
628  }
629  if(!pose.isNull())
630  {
631  guess_.setNull();
633 
634  //*********************
635  // Update odometry
636  //*********************
638  poseMsg.child_frame_id = frameId_;
639  poseMsg.header.frame_id = odomFrameId_;
640  poseMsg.header.stamp = header.stamp;
641  rtabmap_ros::transformToGeometryMsg(pose, poseMsg.transform);
642 
643  if(publishTf_)
644  {
645  if(!guessFrameId_.empty())
646  {
647  //publish correction of actual odometry so we have /odom -> /odom_guess -> /base_link
648  geometry_msgs::TransformStamped correctionMsg;
649  correctionMsg.child_frame_id = guessFrameId_;
650  correctionMsg.header.frame_id = odomFrameId_;
651  correctionMsg.header.stamp = header.stamp;
652  Transform correction = pose * guessCurrentPose.inverse();
653  rtabmap_ros::transformToGeometryMsg(correction, correctionMsg.transform);
654  tfBroadcaster_.sendTransform(correctionMsg);
655  }
656  else
657  {
658  tfBroadcaster_.sendTransform(poseMsg);
659  }
660  }
661 
663  {
664  //next, we'll publish the odometry message over ROS
665  nav_msgs::Odometry odom;
666  odom.header.stamp = header.stamp; // use corresponding time stamp to image
667  odom.header.frame_id = odomFrameId_;
668  odom.child_frame_id = frameId_;
669 
670  //set the position
671  odom.pose.pose.position.x = poseMsg.transform.translation.x;
672  odom.pose.pose.position.y = poseMsg.transform.translation.y;
673  odom.pose.pose.position.z = poseMsg.transform.translation.z;
674  odom.pose.pose.orientation = poseMsg.transform.rotation;
675 
676  //set covariance
677  // libviso2 uses approximately vel variance * 2
678  odom.pose.covariance.at(0) = info.reg.covariance.at<double>(0,0)*2; // xx
679  odom.pose.covariance.at(7) = info.reg.covariance.at<double>(1,1)*2; // yy
680  odom.pose.covariance.at(14) = info.reg.covariance.at<double>(2,2)*2; // zz
681  odom.pose.covariance.at(21) = info.reg.covariance.at<double>(3,3)*2; // rr
682  odom.pose.covariance.at(28) = info.reg.covariance.at<double>(4,4)*2; // pp
683  odom.pose.covariance.at(35) = info.reg.covariance.at<double>(5,5)*2; // yawyaw
684 
685  //set velocity
686  bool setTwist = !odometry_->getVelocityGuess().isNull();
687  if(setTwist)
688  {
689  float x,y,z,roll,pitch,yaw;
691  odom.twist.twist.linear.x = x;
692  odom.twist.twist.linear.y = y;
693  odom.twist.twist.linear.z = z;
694  odom.twist.twist.angular.x = roll;
695  odom.twist.twist.angular.y = pitch;
696  odom.twist.twist.angular.z = yaw;
697  }
698 
699  odom.twist.covariance.at(0) = setTwist?info.reg.covariance.at<double>(0,0):BAD_COVARIANCE; // xx
700  odom.twist.covariance.at(7) = setTwist?info.reg.covariance.at<double>(1,1):BAD_COVARIANCE; // yy
701  odom.twist.covariance.at(14) = setTwist?info.reg.covariance.at<double>(2,2):BAD_COVARIANCE; // zz
702  odom.twist.covariance.at(21) = setTwist?info.reg.covariance.at<double>(3,3):BAD_COVARIANCE; // rr
703  odom.twist.covariance.at(28) = setTwist?info.reg.covariance.at<double>(4,4):BAD_COVARIANCE; // pp
704  odom.twist.covariance.at(35) = setTwist?info.reg.covariance.at<double>(5,5):BAD_COVARIANCE; // yawyaw
705 
706  //publish the message
707  if(setTwist || publishNullWhenLost_)
708  {
709  odomPub_.publish(odom);
710  }
711  }
712 
713  // local map / reference frame
714  if(odomLocalMap_.getNumSubscribers() && !info.localMap.empty())
715  {
716  pcl::PointCloud<pcl::PointXYZRGB> cloud;
717  for(std::map<int, cv::Point3f>::const_iterator iter=info.localMap.begin(); iter!=info.localMap.end(); ++iter)
718  {
719  bool inlier = info.words.find(iter->first) != info.words.end();
720  pcl::PointXYZRGB pt;
721  pt.r = inlier?0:255;
722  pt.g = 255;
723  pt.x = iter->second.x;
724  pt.y = iter->second.y;
725  pt.z = iter->second.z;
726  cloud.push_back(pt);
727  }
728  sensor_msgs::PointCloud2 cloudMsg;
729  pcl::toROSMsg(cloud, cloudMsg);
730  cloudMsg.header.stamp = header.stamp; // use corresponding time stamp to image
731  cloudMsg.header.frame_id = odomFrameId_;
732  odomLocalMap_.publish(cloudMsg);
733  }
734 
736  {
737  // check which type of Odometry is using
738  if(odometry_->getType() == Odometry::kTypeF2M) // If it's Frame to Map Odometry
739  {
740  const std::vector<cv::Point3f> & words3 = ((OdometryF2M*)odometry_)->getLastFrame().getWords3();
741  if(words3.size())
742  {
743  pcl::PointCloud<pcl::PointXYZ> cloud;
744  for(std::vector<cv::Point3f>::const_iterator iter=words3.begin(); iter!=words3.end(); ++iter)
745  {
746  // transform to odom frame
747  cv::Point3f pt = util3d::transformPoint(*iter, pose);
748  cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
749  }
750 
751  sensor_msgs::PointCloud2 cloudMsg;
752  pcl::toROSMsg(cloud, cloudMsg);
753  cloudMsg.header.stamp = header.stamp; // use corresponding time stamp to image
754  cloudMsg.header.frame_id = odomFrameId_;
755  odomLastFrame_.publish(cloudMsg);
756  }
757  }
758  else if(odometry_->getType() == Odometry::kTypeF2F) // if Using Frame to Frame Odometry
759  {
760  const Signature & refFrame = ((OdometryF2F*)odometry_)->getRefFrame();
761 
762  if(refFrame.getWords3().size())
763  {
764  pcl::PointCloud<pcl::PointXYZ> cloud;
765  for(std::vector<cv::Point3f>::const_iterator iter=refFrame.getWords3().begin(); iter!=refFrame.getWords3().end(); ++iter)
766  {
767  // transform to odom frame
768  cv::Point3f pt = util3d::transformPoint(*iter, pose);
769  cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
770  }
771  sensor_msgs::PointCloud2 cloudMsg;
772  pcl::toROSMsg(cloud, cloudMsg);
773  cloudMsg.header.stamp = header.stamp; // use corresponding time stamp to image
774  cloudMsg.header.frame_id = odomFrameId_;
775  odomLastFrame_.publish(cloudMsg);
776  }
777  }
778  }
779 
781  {
782  sensor_msgs::PointCloud2 cloudMsg;
783  if(info.localScanMap.hasNormals() && info.localScanMap.hasIntensity())
784  {
785  pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloud = util3d::laserScanToPointCloudINormal(info.localScanMap, info.localScanMap.localTransform());
786  pcl::toROSMsg(*cloud, cloudMsg);
787  }
788  else if(info.localScanMap.hasNormals())
789  {
790  pcl::PointCloud<pcl::PointNormal>::Ptr cloud = util3d::laserScanToPointCloudNormal(info.localScanMap, info.localScanMap.localTransform());
791  pcl::toROSMsg(*cloud, cloudMsg);
792  }
793  else if(info.localScanMap.hasIntensity())
794  {
795  pcl::PointCloud<pcl::PointXYZI>::Ptr cloud = util3d::laserScanToPointCloudI(info.localScanMap, info.localScanMap.localTransform());
796  pcl::toROSMsg(*cloud, cloudMsg);
797  }
798  else
799  {
800  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::laserScanToPointCloud(info.localScanMap, info.localScanMap.localTransform());
801  pcl::toROSMsg(*cloud, cloudMsg);
802  }
803 
804  cloudMsg.header.stamp = header.stamp; // use corresponding time stamp to image
805  cloudMsg.header.frame_id = odomFrameId_;
806  odomLocalScanMap_.publish(cloudMsg);
807  }
808  }
809  else if(data.imageRaw().empty() && data.laserScanRaw().isEmpty() && !data.imu().empty())
810  {
811  return;
812  }
813  else // pose is null / lost
814  {
816  {
817  //NODELET_WARN( "Odometry lost!");
818 
819  //send null pose to notify that odometry is lost
820  nav_msgs::Odometry odom;
821  odom.header.stamp = header.stamp; // use corresponding time stamp to image
822  odom.header.frame_id = odomFrameId_;
823  odom.child_frame_id = frameId_;
824  odom.pose.covariance.at(0) = BAD_COVARIANCE; // xx
825  odom.pose.covariance.at(7) = BAD_COVARIANCE; // yy
826  odom.pose.covariance.at(14) = BAD_COVARIANCE; // zz
827  odom.pose.covariance.at(21) = BAD_COVARIANCE; // rr
828  odom.pose.covariance.at(28) = BAD_COVARIANCE; // pp
829  odom.pose.covariance.at(35) = BAD_COVARIANCE; // yawyaw
830  odom.twist.covariance.at(0) = BAD_COVARIANCE; // xx
831  odom.twist.covariance.at(7) = BAD_COVARIANCE; // yy
832  odom.twist.covariance.at(14) = BAD_COVARIANCE; // zz
833  odom.twist.covariance.at(21) = BAD_COVARIANCE; // rr
834  odom.twist.covariance.at(28) = BAD_COVARIANCE; // pp
835  odom.twist.covariance.at(35) = BAD_COVARIANCE; // yawyaw
836 
837  //publish the message
838  odomPub_.publish(odom);
839  }
840 
841  // Publish the Tf correction using guess pose directly so that TF tree is not broken when vo is lost
842  if(publishTf_ && !guess_.isNull())
843  {
844  geometry_msgs::TransformStamped correctionMsg;
845  correctionMsg.child_frame_id = guessFrameId_;
846  correctionMsg.header.frame_id = odomFrameId_;
847  correctionMsg.header.stamp = header.stamp;
848  Transform correction = odometry_->getPose() * guess_ * guessCurrentPose.inverse();
849  rtabmap_ros::transformToGeometryMsg(correction, correctionMsg.transform);
850  tfBroadcaster_.sendTransform(correctionMsg);
851  }
852  }
853 
854  if(pose.isNull() && (resetCurrentCount_ > 0 || tooOldPreviousData))
855  {
856  if(tooOldPreviousData)
857  {
858  NODELET_WARN( "Odometry lost! Odometry will be reset because last update "
859  "is %fs too old (>%fs, min_update_rate = %f Hz). Previous data stamp is %f while new data stamp is %f.",
860  header.stamp.toSec() - previousStamp_, 1.0/minUpdateRate_, minUpdateRate_, previousStamp_, header.stamp.toSec());
861  }
862  else
863  {
864  NODELET_WARN( "Odometry lost! Odometry will be reset after next %d consecutive unsuccessful odometry updates...", resetCurrentCount_);
866  }
867 
868  if(resetCurrentCount_ == 0 || tooOldPreviousData)
869  {
870  if(!guess_.isNull())
871  {
872  NODELET_WARN( "Odometry automatically reset based on latest guess available from TF (%s->%s, moved %s since got lost)!",
873  guessFrameId_.c_str(), frameId_.c_str(), guess_.prettyPrint().c_str());
875  guess_.setNull();
876  }
877  else
878  {
879  // Check TF to see if sensor fusion is used (e.g., the output of robot_localization)
880  Transform tfPose = getTransform(odomFrameId_, frameId_, header.stamp, this->tfListener(), this->waitForTransformDuration());
881  if(tfPose.isNull())
882  {
883  NODELET_WARN( "Odometry automatically reset to latest computed pose!");
885  }
886  else
887  {
888  NODELET_WARN( "Odometry automatically reset to latest odometry pose available from TF (%s->%s)!",
889  odomFrameId_.c_str(), frameId_.c_str());
890  odometry_->reset(tfPose);
891  }
892  }
893  }
894  }
895 
897  {
898  rtabmap_ros::OdomInfo infoMsg;
899  odomInfoToROS(info, infoMsg, odomInfoPub_.getNumSubscribers()==0);
900  infoMsg.header.stamp = header.stamp; // use corresponding time stamp to image
901  infoMsg.header.frame_id = odomFrameId_;
903  odomInfoPub_.publish(infoMsg);
904  }
905 
907  {
908  infoMsg.wordInliers.clear();
909  infoMsg.wordMatches.clear();
910  infoMsg.wordsKeys.clear();
911  infoMsg.wordsValues.clear();
912  infoMsg.refCorners.clear();
913  infoMsg.newCorners.clear();
914  infoMsg.cornerInliers.clear();
915  infoMsg.localMapKeys.clear();
916  infoMsg.localMapValues.clear();
917  infoMsg.localScanMap = sensor_msgs::PointCloud2();
918  odomInfoLitePub_.publish(infoMsg);
919  }
920  }
921 
922  if(!data.imageRaw().empty() && odomRgbdImagePub_.getNumSubscribers())
923  {
924  if(!header.frame_id.empty())
925  {
926  rtabmap_ros::RGBDImage msg;
927  rtabmap_ros::rgbdImageToROS(data, msg, header.frame_id);
928  msg.header = header; // use corresponding time stamp to image
930  }
931  else
932  {
933  ROS_WARN("Sensor frame not set, cannot convert SensorData to RGBDImage");
934  }
935  }
936 
937  postProcessData(data, header);
938 
939  if(!data.imageRaw().empty() || !data.laserScanRaw().isEmpty())
940  {
941  if(visParams_)
942  {
943  if(icpParams_)
944  {
945  NODELET_INFO( "Odom: quality=%d, ratio=%f, std dev=%fm|%frad, update time=%fs", info.reg.inliers, info.reg.icpInliersRatio, pose.isNull()?0.0f:std::sqrt(info.reg.covariance.at<double>(0,0)), pose.isNull()?0.0f:std::sqrt(info.reg.covariance.at<double>(5,5)), (ros::WallTime::now()-time).toSec());
946  }
947  else
948  {
949  NODELET_INFO( "Odom: quality=%d, std dev=%fm|%frad, update time=%fs", info.reg.inliers, pose.isNull()?0.0f:std::sqrt(info.reg.covariance.at<double>(0,0)), pose.isNull()?0.0f:std::sqrt(info.reg.covariance.at<double>(5,5)), (ros::WallTime::now()-time).toSec());
950  }
951  }
952  else // if(icpParams_)
953  {
954  NODELET_INFO( "Odom: ratio=%f, std dev=%fm|%frad, update time=%fs", info.reg.icpInliersRatio, pose.isNull()?0.0f:std::sqrt(info.reg.covariance.at<double>(0,0)), pose.isNull()?0.0f:std::sqrt(info.reg.covariance.at<double>(5,5)), (ros::WallTime::now()-time).toSec());
955  }
956  previousStamp_ = header.stamp.toSec();
957  }
958 }
959 
960 bool OdometryROS::reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
961 {
962  NODELET_INFO( "visual_odometry: reset odom!");
963  reset();
964  return true;
965 }
966 
967 bool OdometryROS::resetToPose(rtabmap_ros::ResetPose::Request& req, rtabmap_ros::ResetPose::Response&)
968 {
969  Transform pose(req.x, req.y, req.z, req.roll, req.pitch, req.yaw);
970  NODELET_INFO( "visual_odometry: reset odom to pose %s!", pose.prettyPrint().c_str());
971  reset(pose);
972  return true;
973 }
974 
975 void OdometryROS::reset(const Transform & pose)
976 {
977  odometry_->reset(pose);
978  guess_.setNull();
980  previousStamp_ = 0.0;
982  imuProcessed_ = false;
983  bufferedData_.first= SensorData();
984  imus_.clear();
985  this->flushCallbacks();
986 }
987 
988 bool OdometryROS::pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
989 {
990  if(paused_)
991  {
992  NODELET_WARN( "Odometry: Already paused!");
993  }
994  else
995  {
996  paused_ = true;
997  NODELET_INFO( "Odometry: paused!");
998  }
999  return true;
1000 }
1001 
1002 bool OdometryROS::resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1003 {
1004  if(!paused_)
1005  {
1006  NODELET_WARN( "Odometry: Already running!");
1007  }
1008  else
1009  {
1010  paused_ = false;
1011  NODELET_INFO( "Odometry: resumed!");
1012  }
1013  return true;
1014 }
1015 
1016 bool OdometryROS::setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1017 {
1018  NODELET_INFO( "visual_odometry: Set log level to Debug");
1020  return true;
1021 }
1022 bool OdometryROS::setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1023 {
1024  NODELET_INFO( "visual_odometry: Set log level to Info");
1026  return true;
1027 }
1028 bool OdometryROS::setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1029 {
1030  NODELET_INFO( "visual_odometry: Set log level to Warning");
1032  return true;
1033 }
1034 bool OdometryROS::setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1035 {
1036  NODELET_INFO( "visual_odometry: Set log level to Error");
1038  return true;
1039 }
1040 
1041 
1042 }
std::string groundTruthBaseFrameId_
Definition: OdometryROS.h:108
static std::string homeDir()
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
std::pair< rtabmap::SensorData, std_msgs::Header > bufferedData_
Definition: OdometryROS.h:154
ros::Publisher odomRgbdImagePub_
Definition: OdometryROS.h:125
std::string getTopic() const
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
f
x
std::string uReplaceChar(const std::string &str, char before, char after)
std::vector< double > values
virtual void reset(const Transform &initialPose=Transform::getIdentity())
unsigned int framesProcessed() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition: OdometryROS.h:134
std::map< int, cv::Point3f > localMap
std::pair< std::string, std::string > ParametersPair
virtual void updateParameters(rtabmap::ParametersMap &parameters)
Definition: OdometryROS.h:94
static Transform getIdentity()
ros::NodeHandle & getNodeHandle() const
const std::string & frameId() const
Definition: OdometryROS.h:73
boost::thread * warningThread_
Definition: OdometryROS.h:101
ros::Publisher odomLocalScanMap_
Definition: OdometryROS.h:123
data
void odomInfoToROS(const rtabmap::OdometryInfo &info, rtabmap_ros::OdomInfo &msg, bool ignoreData=false)
void callbackIMU(const sensor_msgs::ImuConstPtr &msg)
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
ros::ServiceServer setLogInfoSrv_
Definition: OdometryROS.h:131
#define BAD_COVARIANCE
Definition: OdometryROS.cpp:53
bool pause(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
std::map< std::string, std::string > ParametersMap
const std::vector< cv::Point3f > & getWords3() const
virtual void postProcessData(const rtabmap::SensorData &data, const std_msgs::Header &header) const
Definition: OdometryROS.h:88
virtual Odometry::Type getType()=0
std::string groundTruthFrameId_
Definition: OdometryROS.h:107
ros::NodeHandle & getPrivateNodeHandle() const
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
ros::ServiceServer setLogDebugSrv_
Definition: OdometryROS.h:130
bool isEmpty() const
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
static void setLevel(ULogger::Level level)
#define ROS_WARN(...)
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
std::string uBool2Str(bool boolean)
Transform process(SensorData &data, OdometryInfo *info=0)
bool setLogWarn(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
virtual void onOdomInit()=0
ros::Publisher odomPub_
Definition: OdometryROS.h:119
#define UASSERT(condition)
std::list< std::string > uSplit(const std::string &str, char separator=' ')
const std::string & getName() const
ros::ServiceServer setLogWarnSrv_
Definition: OdometryROS.h:132
static std::string currentDir(bool trailingSeparator=false)
bool hasNormals() const
std::string uNumber2Str(unsigned int number)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define true
void publish(const boost::shared_ptr< M > &message) const
T uMax3(const T &a, const T &b, const T &c)
ros::ServiceServer resetToPoseSrv_
Definition: OdometryROS.h:127
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
uint16_t x
void rgbdImageToROS(const rtabmap::SensorData &data, rtabmap_ros::RGBDImage &msg, const std::string &sensorFrameId)
bool resume(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
const Transform & getVelocityGuess() const
rtabmap::ParametersMap parameters_
Definition: OdometryROS.h:117
double waitForTransformDuration() const
Definition: OdometryROS.h:85
const cv::Mat & imageRaw() const
ros::ServiceServer setLogErrorSrv_
Definition: OdometryROS.h:133
bool setLogError(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
std::string prettyPrint() const
void startWarningThread(const std::string &subscribedTopicsMsg, bool approxSync)
static void setEventLevel(ULogger::Level eventSentLevel)
virtual void flushCallbacks()=0
ros::ServiceServer resetSrv_
Definition: OdometryROS.h:126
std::map< double, rtabmap::IMU > imus_
Definition: OdometryROS.h:153
ros::Subscriber imuSub_
Definition: OdometryROS.h:136
ros::ServiceServer pauseSrv_
Definition: OdometryROS.h:128
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer resumeSrv_
Definition: OdometryROS.h:129
rtabmap::Transform velocityGuess() const
ros::Publisher odomLocalMap_
Definition: OdometryROS.h:122
void sendTransform(const geometry_msgs::TransformStamped &transform)
rtabmap::Transform guessPreviousPose_
Definition: OdometryROS.h:145
bool hasParam(const std::string &key) const
bool isNull() const
const V_string & getMyArgv() const
#define false
std::vector< V > uListToVector(const std::list< V > &list)
#define NODELET_INFO(...)
bool setLogInfo(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool reset(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
const LaserScan & laserScanRaw() const
std::multimap< int, cv::KeyPoint > words
static WallTime now()
bool empty() const
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
bool exists()
rtabmap::Odometry * odometry_
Definition: OdometryROS.h:100
ros::Publisher odomInfoPub_
Definition: OdometryROS.h:120
void getTranslation(float &x, float &y, float &z) const
argv
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
double stamp() const
rtabmap::Transform guess_
Definition: OdometryROS.h:144
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
float uStr2Float(const std::string &str)
bool find(const std::vector< unsigned int > &l, unsigned int n)
void processData(rtabmap::SensorData &data, const std_msgs::Header &header)
bool hasIntensity() const
RegistrationInfo reg
void setGroundTruth(const Transform &pose)
ros::Publisher odomInfoLitePub_
Definition: OdometryROS.h:121
bool sleep() const
bool resetToPose(rtabmap_ros::ResetPose::Request &, rtabmap_ros::ResetPose::Response &)
const rtabmap::ParametersMap & parameters() const
Definition: OdometryROS.h:76
const Transform & getPose() const
uint32_t getNumSubscribers() const
const IMU & imu() const
r
#define ROS_ERROR(...)
ros::Publisher odomLastFrame_
Definition: OdometryROS.h:124
Transform localTransform() const
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool isIdentity() const
Transform inverse() const
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40