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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19