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>
47 #include "rtabmap_msgs/OdomInfo.h"
50 #include "rtabmap/utilite/UStl.h"
51 #include "rtabmap/utilite/UFile.h"
52 #include "rtabmap/utilite/UMath.h"
53 
54 #define BAD_COVARIANCE 9999
55 
56 using namespace rtabmap;
57 
58 namespace rtabmap_odom {
59 
60 OdometryROS::OdometryROS(bool stereoParams, bool visParams, bool icpParams) :
61  odometry_(0),
62  frameId_("base_link"),
63  odomFrameId_("odom"),
64  groundTruthFrameId_(""),
65  groundTruthBaseFrameId_(""),
66  guessFrameId_(""),
67  guessMinTranslation_(0.0),
68  guessMinRotation_(0.0),
69  guessMinTime_(0.0),
70  publishTf_(true),
71  waitForTransform_(true),
72  waitForTransformDuration_(0.1), // 100 ms
73  publishNullWhenLost_(true),
74  publishCompressedSensorData_(false),
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  compressionImgFormat_(".jpg"),
86  compressionParallelized_(true),
87  odomStrategy_(Parameters::defaultOdomStrategy()),
88  waitIMUToinit_(false),
89  imuProcessed_(false)
90 {
91 
92 }
93 
95 {
96  this->join(true);
97  delete odometry_;
98 }
99 
101 {
104 
105  odomPub_ = nh.advertise<nav_msgs::Odometry>("odom", 1);
106  odomInfoPub_ = nh.advertise<rtabmap_msgs::OdomInfo>("odom_info", 1);
107  odomInfoLitePub_ = nh.advertise<rtabmap_msgs::OdomInfo>("odom_info_lite", 1);
108  odomLocalMap_ = nh.advertise<sensor_msgs::PointCloud2>("odom_local_map", 1);
109  odomLocalScanMap_ = nh.advertise<sensor_msgs::PointCloud2>("odom_local_scan_map", 1);
110  odomLastFrame_ = nh.advertise<sensor_msgs::PointCloud2>("odom_last_frame", 1);
111  odomRgbdImagePub_ = nh.advertise<rtabmap_msgs::RGBDImage>("odom_rgbd_image", 1);
112  odomSensorDataPub_ = nh.advertise<rtabmap_msgs::SensorData>("odom_sensor_data/raw", 1);
113  odomSensorDataFeaturesPub_ = nh.advertise<rtabmap_msgs::SensorData>("odom_sensor_data/features", 1);
114  odomSensorDataCompressedPub_ = nh.advertise<rtabmap_msgs::SensorData>("odom_sensor_data/compressed", 1);
115 
116  Transform initialPose = Transform::getIdentity();
117  std::string initialPoseStr;
118  std::string configPath;
119  pnh.param("frame_id", frameId_, frameId_);
120  pnh.param("odom_frame_id", odomFrameId_, odomFrameId_);
121  pnh.param("publish_tf", publishTf_, publishTf_);
122  if(pnh.hasParam("tf_prefix"))
123  {
124  NODELET_ERROR("tf_prefix parameter has been removed, use directly odom_frame_id and frame_id parameters.");
125  }
126  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
127  pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
128  pnh.param("initial_pose", initialPoseStr, initialPoseStr); // "x y z roll pitch yaw"
129  pnh.param("ground_truth_frame_id", groundTruthFrameId_, groundTruthFrameId_);
130  pnh.param("ground_truth_base_frame_id", groundTruthBaseFrameId_, frameId_);
131  pnh.param("config_path", configPath, configPath);
132  pnh.param("publish_null_when_lost", publishNullWhenLost_, publishNullWhenLost_);
133  if(pnh.hasParam("guess_from_tf"))
134  {
135  if(!pnh.hasParam("guess_frame_id"))
136  {
137  NODELET_ERROR("Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
138  }
139  else
140  {
141  NODELET_WARN("Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
142  }
143  }
144  pnh.param("guess_frame_id", guessFrameId_, guessFrameId_); // odometry guess frame
145  pnh.param("guess_min_translation", guessMinTranslation_, guessMinTranslation_);
146  pnh.param("guess_min_rotation", guessMinRotation_, guessMinRotation_);
147  pnh.param("guess_min_time", guessMinTime_, guessMinTime_);
148 
149  pnh.param("expected_update_rate", expectedUpdateRate_, expectedUpdateRate_); // expected sensor rate
150  pnh.param("max_update_rate", maxUpdateRate_, maxUpdateRate_);
151  pnh.param("min_update_rate", minUpdateRate_, minUpdateRate_);
152 
153  pnh.param("sensor_data_compression_format", compressionImgFormat_, compressionImgFormat_);
154  pnh.param("sensor_data_parallel_compression", compressionParallelized_, compressionParallelized_);
155 
156  pnh.param("wait_imu_to_init", waitIMUToinit_, waitIMUToinit_);
157 
158  int eventLevel = ULogger::kFatal;
159  pnh.param("log_to_rosout_level", eventLevel, eventLevel);
160  UASSERT(eventLevel >= ULogger::kDebug && eventLevel <= ULogger::kFatal);
162 
163  if(publishTf_ && !guessFrameId_.empty() && guessFrameId_.compare(odomFrameId_) == 0)
164  {
165  NODELET_WARN( "\"publish_tf\" and \"guess_frame_id\" cannot be used "
166  "at the same time if \"guess_frame_id\" and \"odom_frame_id\" "
167  "are the same frame (value=\"%s\"). \"guess_frame_id\" is disabled.", odomFrameId_.c_str());
168  guessFrameId_.clear();
169  }
170  NODELET_INFO("Odometry: frame_id = %s", frameId_.c_str());
171  NODELET_INFO("Odometry: odom_frame_id = %s", odomFrameId_.c_str());
172  NODELET_INFO("Odometry: publish_tf = %s", publishTf_?"true":"false");
173  NODELET_INFO("Odometry: wait_for_transform = %s", waitForTransform_?"true":"false");
174  NODELET_INFO("Odometry: wait_for_transform_duration = %f", waitForTransformDuration_);
175  NODELET_INFO("Odometry: log_to_rosout_level = %d", eventLevel);
176  NODELET_INFO("Odometry: initial_pose = %s", initialPose.prettyPrint().c_str());
177  NODELET_INFO("Odometry: ground_truth_frame_id = %s", groundTruthFrameId_.c_str());
178  NODELET_INFO("Odometry: ground_truth_base_frame_id = %s", groundTruthBaseFrameId_.c_str());
179  NODELET_INFO("Odometry: config_path = %s", configPath.c_str());
180  NODELET_INFO("Odometry: publish_null_when_lost = %s", publishNullWhenLost_?"true":"false");
181  NODELET_INFO("Odometry: publish_compressed_sensor_data = %s", publishCompressedSensorData_?"true":"false");
182  NODELET_INFO("Odometry: guess_frame_id = %s", guessFrameId_.c_str());
183  NODELET_INFO("Odometry: guess_min_translation = %f", guessMinTranslation_);
184  NODELET_INFO("Odometry: guess_min_rotation = %f", guessMinRotation_);
185  NODELET_INFO("Odometry: guess_min_time = %f", guessMinTime_);
186  NODELET_INFO("Odometry: expected_update_rate = %f Hz", expectedUpdateRate_);
187  NODELET_INFO("Odometry: max_update_rate = %f Hz", maxUpdateRate_);
188  NODELET_INFO("Odometry: min_update_rate = %f Hz", minUpdateRate_);
189  NODELET_INFO("Odometry: wait_imu_to_init = %s", waitIMUToinit_?"true":"false");
190  NODELET_INFO("Odometry: sensor_data_compression_format = %s", compressionImgFormat_.c_str());
191  NODELET_INFO("Odometry: sensor_data_parallel_compression = %s", compressionParallelized_?"true":"false");
192 
193  configPath = uReplaceChar(configPath, '~', UDirectory::homeDir());
194  if(configPath.size() && configPath.at(0) != '/')
195  {
196  configPath = UDirectory::currentDir(true) + configPath;
197  }
198 
199  if(initialPoseStr.size())
200  {
201  std::vector<std::string> values = uListToVector(uSplit(initialPoseStr, ' '));
202  if(values.size() == 6)
203  {
204  initialPose = Transform(
207  }
208  else
209  {
210  NODELET_ERROR( "Wrong initial_pose format: %s (should be \"x y z roll pitch yaw\" with angle in radians). "
211  "Identity will be used...", initialPoseStr.c_str());
212  }
213  }
214 
215 
216  //parameters
217  ROS_INFO("Odometry: stereoParams_=%d visParams_=%d icpParams_=%d", stereoParams_?1:0, visParams_?1:0, icpParams_?1:0);
218  parameters_ = Parameters::getDefaultOdometryParameters(stereoParams_, visParams_, icpParams_);
219  if(icpParams_)
220  {
221  if(!visParams_)
222  {
223  uInsert(parameters_, ParametersPair(Parameters::kRegStrategy(), "1"));
224  }
225  else
226  {
227  uInsert(parameters_, ParametersPair(Parameters::kRegStrategy(), "2"));
228  }
229  }
230  parameters_.insert(*Parameters::getDefaultParameters().find(Parameters::kRtabmapImagesAlreadyRectified()));
231  if(!configPath.empty())
232  {
233  if(UFile::exists(configPath.c_str()))
234  {
235  NODELET_INFO( "Odometry: Loading parameters from %s", configPath.c_str());
236  rtabmap::ParametersMap allParameters;
237  Parameters::readINI(configPath.c_str(), allParameters);
238  // only update odometry parameters
239  for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
240  {
241  ParametersMap::iterator jter = allParameters.find(iter->first);
242  if(jter!=allParameters.end())
243  {
244  iter->second = jter->second;
245  }
246  }
247  }
248  else
249  {
250  NODELET_ERROR( "Config file \"%s\" not found!", configPath.c_str());
251  }
252  }
253  for(rtabmap::ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
254  {
255  std::string vStr;
256  bool vBool;
257  int vInt;
258  double vDouble;
259  if(pnh.getParam(iter->first, vStr))
260  {
261  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
262  iter->second = vStr;
263  }
264  else if(pnh.getParam(iter->first, vBool))
265  {
266  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
267  iter->second = uBool2Str(vBool);
268  }
269  else if(pnh.getParam(iter->first, vDouble))
270  {
271  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble, 6).c_str());
272  iter->second = uNumber2Str(vDouble, 6);
273  }
274  else if(pnh.getParam(iter->first, vInt))
275  {
276  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
277  iter->second = uNumber2Str(vInt);
278  }
279 
280  if(iter->first.compare(Parameters::kVisMinInliers()) == 0 && atoi(iter->second.c_str()) < 8)
281  {
282  NODELET_WARN( "Parameter min_inliers must be >= 8, setting to 8...");
283  iter->second = uNumber2Str(8);
284  }
285  }
286 
287  std::vector<std::string> argList = getMyArgv();
288  char ** argv = new char*[argList.size()];
289  for(unsigned int i=0; i<argList.size(); ++i)
290  {
291  argv[i] = &argList[i].at(0);
292  }
293 
295  delete [] argv;
296  for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
297  {
298  rtabmap::ParametersMap::iterator jter = parameters_.find(iter->first);
299  if(jter!=parameters_.end())
300  {
301  NODELET_INFO( "Update odometry parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
302  jter->second = iter->second;
303  }
304  else
305  {
306  NODELET_INFO( "Odometry: Ignored parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
307  }
308  }
309 
310  // Backward compatibility
311  for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=Parameters::getRemovedParameters().begin();
312  iter!=Parameters::getRemovedParameters().end();
313  ++iter)
314  {
315  std::string vStr;
316  if(pnh.getParam(iter->first, vStr))
317  {
318  if(!iter->second.second.empty() && parameters_.find(iter->second.second)!=parameters_.end())
319  {
320  NODELET_WARN("Rtabmap: Parameter name changed: \"%s\" -> \"%s\". The new parameter is already used with value \"%s\", ignoring the old one with value \"%s\".",
321  iter->first.c_str(), iter->second.second.c_str(), parameters_.find(iter->second.second)->second.c_str(), vStr.c_str());
322  }
323  else if(iter->second.first && parameters_.find(iter->second.second) != parameters_.end())
324  {
325  // can be migrated
326  parameters_.at(iter->second.second)= vStr;
327  NODELET_WARN( "Odometry: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
328  iter->first.c_str(), iter->second.second.c_str(), vStr.c_str());
329  }
330  else
331  {
332  if(iter->second.second.empty())
333  {
334  NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore!",
335  iter->first.c_str());
336  }
337  else
338  {
339  NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
340  iter->first.c_str(), iter->second.second.c_str());
341  }
342  }
343  }
344  }
345 
346  // set private parameters
347  for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
348  {
349  pnh.setParam(iter->first, iter->second);
350  }
351 
352  Parameters::parse(parameters_, Parameters::kOdomResetCountdown(), resetCountdown_);
353  parameters_.at(Parameters::kOdomResetCountdown()) = "0"; // use modified reset countdown here
354 
356 
357  odometry_ = Odometry::create(parameters_);
358  if(!initialPose.isIdentity())
359  {
360  odometry_->reset(initialPose);
361  }
362 
363  resetSrv_ = nh.advertiseService("reset_odom", &OdometryROS::reset, this);
364  resetToPoseSrv_ = nh.advertiseService("reset_odom_to_pose", &OdometryROS::resetToPose, this);
365  pauseSrv_ = nh.advertiseService("pause_odom", &OdometryROS::pause, this);
366  resumeSrv_ = nh.advertiseService("resume_odom", &OdometryROS::resume, this);
367 
368  setLogDebugSrv_ = pnh.advertiseService("log_debug", &OdometryROS::setLogDebug, this);
369  setLogInfoSrv_ = pnh.advertiseService("log_info", &OdometryROS::setLogInfo, this);
370  setLogWarnSrv_ = pnh.advertiseService("log_warning", &OdometryROS::setLogWarn, this);
371  setLogErrorSrv_ = pnh.advertiseService("log_error", &OdometryROS::setLogError, this);
372 
373  odomStrategy_ = 0;
374  Parameters::parse(this->parameters(), Parameters::kOdomStrategy(), odomStrategy_);
375  if(waitIMUToinit_)
376  {
377  int queueSize = 10;
378  pnh.param("queue_size", queueSize, queueSize);
379  imuSub_ = nh.subscribe("imu", queueSize*5, &OdometryROS::callbackIMU, this);
380  NODELET_INFO("odometry: Subscribing to IMU topic %s", imuSub_.getTopic().c_str());
381  }
382 
383  this->start();
384 
385  onOdomInit();
386 }
387 
388 void OdometryROS::initDiagnosticMsg(const std::string & subscribedTopicsMsg, bool approxSync, const std::string & subscribedTopic)
389 {
390  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
392  std::vector<diagnostic_updater::DiagnosticTask*> tasks;
393  tasks.push_back(&statusDiagnostic_);
394  syncDiagnostic_->init(subscribedTopic,
395  uFormat("%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  tasks);
403 }
404 
406 {
407  if(odometry_)
408  {
409  return odometry_->getVelocityGuess();
410  }
411  return rtabmap::Transform();
412 }
413 
414 void OdometryROS::callbackIMU(const sensor_msgs::ImuConstPtr& msg)
415 {
416  if(!this->isPaused())
417  {
418  double stamp = msg->header.stamp.toSec();
420  if(this->frameId().compare(msg->header.frame_id) != 0)
421  {
422  localTransform = rtabmap_conversions::getTransform(this->frameId(), msg->header.frame_id, msg->header.stamp, this->tfListener(), this->waitForTransformDuration());
423  }
424  if(localTransform.isNull())
425  {
426  ROS_ERROR("Could not transform IMU msg from frame \"%s\" to frame \"%s\", TF not available at time %f",
427  msg->header.frame_id.c_str(), this->frameId().c_str(), stamp);
428  return;
429  }
430 
431  IMU imu(cv::Vec4d(msg->orientation.x, msg->orientation.y, msg->orientation.z, msg->orientation.w),
432  cv::Mat(3,3,CV_64FC1,(void*)msg->orientation_covariance.data()).clone(),
433  cv::Vec3d(msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z),
434  cv::Mat(3,3,CV_64FC1,(void*)msg->angular_velocity_covariance.data()).clone(),
435  cv::Vec3d(msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z),
436  cv::Mat(3,3,CV_64FC1,(void*)msg->linear_acceleration_covariance.data()).clone(),
437  localTransform);
438 
439  {
441 
442  imus_.insert(std::make_pair(stamp, imu));
443  if(imus_.size() > 1000)
444  {
445  NODELET_WARN("Dropping imu data!");
446  imus_.erase(imus_.begin());
447  }
448  }
449  if(dataMutex_.lockTry() == 0)
450  {
451  if(bufferedDataToProcess_ && dataHeaderToProcess_.stamp.toSec() <= stamp)
452  {
453  bufferedDataToProcess_ = false;
455  }
456  dataMutex_.unlock();
457  }
458  }
459 }
460 
461 void OdometryROS::processData(SensorData & data, const std_msgs::Header & header)
462 {
463  //NODELET_WARN("Received image: %f delay=%f", data.stamp(), (ros::Time::now() - header.stamp).toSec());
464  if(dataMutex_.lockTry() == 0)
465  {
467  NODELET_ERROR("We didn't receive IMU newer than previous image (%f) and we just received a new image (%f). The previous image is dropped!",
468  dataHeaderToProcess_.stamp.toSec(), header.stamp.toSec());
469  }
472  bufferedDataToProcess_ = false;
474  dataMutex_.unlock();
475  }
476  else
477  {
478  NODELET_DEBUG("Dropping image/scan data");
479  }
480 }
481 
483 {
484  // in case we were waiting, unblock thread
486 }
487 
489 {
491 
492  if(!this->isRunning())
493  {
494  // thread killed
495  return;
496  }
497 
498  UScopeMutex lock(dataMutex_);
499 
500  // aliases
502  std_msgs::Header & header = dataHeaderToProcess_;
503 
504  std::vector<std::pair<double, IMU> > imus;
505  {
507 
509  {
510  NODELET_WARN("odometry: waiting imu (%s) to initialize orientation (wait_imu_to_init=true)", imuSub_.getTopic().c_str());
511  return;
512  }
513 
514  if(waitIMUToinit_ && (imus_.empty() || imus_.rbegin()->first < header.stamp.toSec()))
515  {
516  NODELET_WARN("Make sure IMU is published faster than data rate! (last image stamp=%f and last imu stamp received=%f). Buffering the image until an imu with same or greater stamp is received.",
517  data.stamp(), imus_.empty()?0:imus_.rbegin()->first);
518  bufferedDataToProcess_ = true;
519  return;
520  }
521  // 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)
522  std::map<double, rtabmap::IMU>::iterator iterEnd = imus_.lower_bound(header.stamp.toSec());
523  if(iterEnd!= imus_.end())
524  {
525  ++iterEnd;
526  }
527  for(std::map<double, rtabmap::IMU>::iterator iter=imus_.begin(); iter!=iterEnd;)
528  {
529  imus.push_back(*iter);
530  imus_.erase(iter++);
531  }
532  }
533 
534  for(size_t i=0; i<imus.size(); ++i)
535  {
536  SensorData dataIMU(imus[i].second, 0, imus[i].first);
537  odometry_->process(dataIMU);
538  imuProcessed_ = true;
539  }
540 
541  //NODELET_WARN("img callback: process image %f", stamp.toSec());
542 
543  Transform groundTruth;
544  if(!data.imageRaw().empty() || !data.laserScanRaw().isEmpty())
545  {
546  if(previousStamp_>0.0 && previousStamp_ >= header.stamp.toSec())
547  {
548  NODELET_WARN("Odometry: Detected not valid consecutive stamps (previous=%fs new=%fs). "
549  "New stamp should be always greater than previous stamp. This new data is ignored.",
550  previousStamp_, header.stamp.toSec());
551  return;
552  }
553  else if(maxUpdateRate_ > 0 &&
554  previousStamp_ > 0 &&
556  {
557  // throttling
558  return;
559  }
560  else if(maxUpdateRate_ == 0 &&
561  expectedUpdateRate_ > 0 &&
562  previousStamp_ > 0 &&
563  (header.stamp.toSec()-previousStamp_) < 1.0/expectedUpdateRate_)
564  {
565  NODELET_WARN("Odometry: Aborting odometry update, higher frame rate detected (%f Hz) than the expected one (%f Hz). (stamps: previous=%fs new=%fs)",
566  1.0/(header.stamp.toSec()-previousStamp_), expectedUpdateRate_, previousStamp_, header.stamp.toSec());
567  return;
568  }
569 
570  if(!groundTruthFrameId_.empty())
571  {
572  groundTruth = rtabmap_conversions::getTransform(groundTruthFrameId_, groundTruthBaseFrameId_, header.stamp, this->tfListener(), this->waitForTransformDuration());
573 
574  if(!data.imageRaw().empty() || !data.laserScanRaw().isEmpty())
575  {
576  // Use only XYZ to handle the case odometry was previously initialized with IMU,
577  // we assume that the ground truth contains also a real initial orientation
578  float x,y,z;
580  if(x==0.0f && y==0.0f && z==0.0f)
581  {
582  // sync with the first value of the ground truth
583  if(groundTruth.isNull())
584  {
585  NODELET_WARN("Ground truth frames \"%s\" -> \"%s\" are set but failed to "
586  "get them, odometry won't be initialized with ground truth.",
588  }
589  else
590  {
591  NODELET_INFO( "Initializing odometry pose to %s (from \"%s\" -> \"%s\")",
592  groundTruth.prettyPrint().c_str(),
593  groundTruthFrameId_.c_str(),
594  groundTruthBaseFrameId_.c_str());
595  odometry_->reset(groundTruth);
596  }
597  }
598  }
599  }
600  }
601 
602 
603  Transform guessCurrentPose;
604  if(!guessFrameId_.empty())
605  {
606  guessCurrentPose = rtabmap_conversions::getTransform(guessFrameId_, frameId_, header.stamp, this->tfListener(), this->waitForTransformDuration());
607 
608  Transform previousPose = guessPreviousPose_;
610  {
611  previousPose = guessCurrentPose;
612  if(!guessCurrentPose.isNull() && odometry_->getPose().isIdentity())
613  {
614  ROS_INFO("Odometry: init pose with guess %s", guessCurrentPose.prettyPrint().c_str());
615  odometry_->reset(guessCurrentPose);
616  }
617  }
618 
619  if(!previousPose.isNull() && !guessCurrentPose.isNull())
620  {
621  if(guess_.isNull())
622  {
623  guess_ = previousPose.inverse() * guessCurrentPose;
624  }
625  else
626  {
627  guess_ = guess_ * previousPose.inverse() * guessCurrentPose;
628  }
630  {
631  float x,y,z,roll,pitch,yaw;
633  if((guessMinTranslation_ <= 0.0 || uMax3(fabs(x), fabs(y), fabs(z)) < guessMinTranslation_) &&
635  (guessMinTime_ <= 0.0 || (previousStamp_>0.0 && header.stamp.toSec()-previousStamp_ < guessMinTime_)))
636  {
637  // Ignore odometry update, we didn't move enough
638  if(publishTf_)
639  {
640  geometry_msgs::TransformStamped correctionMsg;
641  correctionMsg.child_frame_id = guessFrameId_;
642  correctionMsg.header.frame_id = odomFrameId_;
643  correctionMsg.header.stamp = header.stamp;
644  Transform correction = odometry_->getPose() * guess_ * guessCurrentPose.inverse();
645  rtabmap_conversions::transformToGeometryMsg(correction, correctionMsg.transform);
646  tfBroadcaster_.sendTransform(correctionMsg);
647  }
648  guessPreviousPose_ = guessCurrentPose;
649  return;
650  }
651  }
652  guessPreviousPose_ = guessCurrentPose;
653  }
654  else
655  {
656  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());
657  return;
658  }
659  }
660 
661  bool tooOldPreviousData = minUpdateRate_ > 0 && previousStamp_ > 0 && (header.stamp.toSec()-previousStamp_) > 1.0/minUpdateRate_;
662 
663  // process data
666  if(!groundTruth.isNull())
667  {
668  data.setGroundTruth(groundTruth);
669  }
670  rtabmap::Transform pose;
671  if(!tooOldPreviousData)
672  {
673  pose = odometry_->process(data, guess_, &info);
674  }
675  if(!pose.isNull())
676  {
677  guess_.setNull();
679 
680  //*********************
681  // Update odometry
682  //*********************
683  geometry_msgs::TransformStamped poseMsg;
684  poseMsg.child_frame_id = frameId_;
685  poseMsg.header.frame_id = odomFrameId_;
686  poseMsg.header.stamp = header.stamp;
687  rtabmap_conversions::transformToGeometryMsg(pose, poseMsg.transform);
688 
689  if(publishTf_)
690  {
691  if(!guessFrameId_.empty())
692  {
693  //publish correction of actual odometry so we have /odom -> /odom_guess -> /base_link
694  geometry_msgs::TransformStamped correctionMsg;
695  correctionMsg.child_frame_id = guessFrameId_;
696  correctionMsg.header.frame_id = odomFrameId_;
697  correctionMsg.header.stamp = header.stamp;
698  Transform correction = pose * guessCurrentPose.inverse();
699  rtabmap_conversions::transformToGeometryMsg(correction, correctionMsg.transform);
700  tfBroadcaster_.sendTransform(correctionMsg);
701  }
702  else
703  {
704  tfBroadcaster_.sendTransform(poseMsg);
705  }
706  }
707 
709  {
710  //next, we'll publish the odometry message over ROS
711  nav_msgs::Odometry odom;
712  odom.header.stamp = header.stamp; // use corresponding time stamp to image
713  odom.header.frame_id = odomFrameId_;
714  odom.child_frame_id = frameId_;
715 
716  //set the position
717  odom.pose.pose.position.x = poseMsg.transform.translation.x;
718  odom.pose.pose.position.y = poseMsg.transform.translation.y;
719  odom.pose.pose.position.z = poseMsg.transform.translation.z;
720  odom.pose.pose.orientation = poseMsg.transform.rotation;
721 
722  //set covariance
723  // libviso2 uses approximately vel variance * 2
724  odom.pose.covariance.at(0) = info.reg.covariance.at<double>(0,0)*2; // xx
725  odom.pose.covariance.at(7) = info.reg.covariance.at<double>(1,1)*2; // yy
726  odom.pose.covariance.at(14) = info.reg.covariance.at<double>(2,2)*2; // zz
727  odom.pose.covariance.at(21) = info.reg.covariance.at<double>(3,3)*2; // rr
728  odom.pose.covariance.at(28) = info.reg.covariance.at<double>(4,4)*2; // pp
729  odom.pose.covariance.at(35) = info.reg.covariance.at<double>(5,5)*2; // yawyaw
730 
731  //set velocity
732  bool setTwist = !odometry_->getVelocityGuess().isNull();
733  if(setTwist)
734  {
735  float x,y,z,roll,pitch,yaw;
737  odom.twist.twist.linear.x = x;
738  odom.twist.twist.linear.y = y;
739  odom.twist.twist.linear.z = z;
740  odom.twist.twist.angular.x = roll;
741  odom.twist.twist.angular.y = pitch;
742  odom.twist.twist.angular.z = yaw;
743  }
744 
745  odom.twist.covariance.at(0) = setTwist?info.reg.covariance.at<double>(0,0):BAD_COVARIANCE; // xx
746  odom.twist.covariance.at(7) = setTwist?info.reg.covariance.at<double>(1,1):BAD_COVARIANCE; // yy
747  odom.twist.covariance.at(14) = setTwist?info.reg.covariance.at<double>(2,2):BAD_COVARIANCE; // zz
748  odom.twist.covariance.at(21) = setTwist?info.reg.covariance.at<double>(3,3):BAD_COVARIANCE; // rr
749  odom.twist.covariance.at(28) = setTwist?info.reg.covariance.at<double>(4,4):BAD_COVARIANCE; // pp
750  odom.twist.covariance.at(35) = setTwist?info.reg.covariance.at<double>(5,5):BAD_COVARIANCE; // yawyaw
751 
752  //publish the message
753  if(setTwist || publishNullWhenLost_)
754  {
755  odomPub_.publish(odom);
756  }
757  }
758 
759  // local map / reference frame
760  if(odomLocalMap_.getNumSubscribers() && !info.localMap.empty())
761  {
762  pcl::PointCloud<pcl::PointXYZRGB> cloud;
763  for(std::map<int, cv::Point3f>::const_iterator iter=info.localMap.begin(); iter!=info.localMap.end(); ++iter)
764  {
765  bool inlier = info.words.find(iter->first) != info.words.end();
766  pcl::PointXYZRGB pt;
767  pt.r = inlier?0:255;
768  pt.g = 255;
769  pt.x = iter->second.x;
770  pt.y = iter->second.y;
771  pt.z = iter->second.z;
772  cloud.push_back(pt);
773  }
774  sensor_msgs::PointCloud2 cloudMsg;
775  pcl::toROSMsg(cloud, cloudMsg);
776  cloudMsg.header.stamp = header.stamp; // use corresponding time stamp to image
777  cloudMsg.header.frame_id = odomFrameId_;
778  odomLocalMap_.publish(cloudMsg);
779  }
780 
782  {
783  // check which type of Odometry is using
784  if(odometry_->getType() == Odometry::kTypeF2M) // If it's Frame to Map Odometry
785  {
786  const std::vector<cv::Point3f> & words3 = ((OdometryF2M*)odometry_)->getLastFrame().getWords3();
787  if(words3.size())
788  {
789  pcl::PointCloud<pcl::PointXYZ> cloud;
790  for(std::vector<cv::Point3f>::const_iterator iter=words3.begin(); iter!=words3.end(); ++iter)
791  {
792  // transform to odom frame
793  cv::Point3f pt = util3d::transformPoint(*iter, pose);
794  cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
795  }
796 
797  sensor_msgs::PointCloud2 cloudMsg;
798  pcl::toROSMsg(cloud, cloudMsg);
799  cloudMsg.header.stamp = header.stamp; // use corresponding time stamp to image
800  cloudMsg.header.frame_id = odomFrameId_;
801  odomLastFrame_.publish(cloudMsg);
802  }
803  }
804  else if(odometry_->getType() == Odometry::kTypeF2F) // if Using Frame to Frame Odometry
805  {
806  const Signature & refFrame = ((OdometryF2F*)odometry_)->getRefFrame();
807 
808  if(refFrame.getWords3().size())
809  {
810  pcl::PointCloud<pcl::PointXYZ> cloud;
811  for(std::vector<cv::Point3f>::const_iterator iter=refFrame.getWords3().begin(); iter!=refFrame.getWords3().end(); ++iter)
812  {
813  // transform to odom frame
814  cv::Point3f pt = util3d::transformPoint(*iter, pose);
815  cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
816  }
817  sensor_msgs::PointCloud2 cloudMsg;
818  pcl::toROSMsg(cloud, cloudMsg);
819  cloudMsg.header.stamp = header.stamp; // use corresponding time stamp to image
820  cloudMsg.header.frame_id = odomFrameId_;
821  odomLastFrame_.publish(cloudMsg);
822  }
823  }
824  }
825 
826  if(odomLocalScanMap_.getNumSubscribers() && !info.localScanMap.isEmpty())
827  {
828  sensor_msgs::PointCloud2 cloudMsg;
829  if(info.localScanMap.hasNormals() && info.localScanMap.hasIntensity())
830  {
831  pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloud = util3d::laserScanToPointCloudINormal(info.localScanMap, info.localScanMap.localTransform());
832  pcl::toROSMsg(*cloud, cloudMsg);
833  }
834  else if(info.localScanMap.hasNormals())
835  {
836  pcl::PointCloud<pcl::PointNormal>::Ptr cloud = util3d::laserScanToPointCloudNormal(info.localScanMap, info.localScanMap.localTransform());
837  pcl::toROSMsg(*cloud, cloudMsg);
838  }
839  else if(info.localScanMap.hasIntensity())
840  {
841  pcl::PointCloud<pcl::PointXYZI>::Ptr cloud = util3d::laserScanToPointCloudI(info.localScanMap, info.localScanMap.localTransform());
842  pcl::toROSMsg(*cloud, cloudMsg);
843  }
844  else
845  {
846  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::laserScanToPointCloud(info.localScanMap, info.localScanMap.localTransform());
847  pcl::toROSMsg(*cloud, cloudMsg);
848  }
849 
850  cloudMsg.header.stamp = header.stamp; // use corresponding time stamp to image
851  cloudMsg.header.frame_id = odomFrameId_;
852  odomLocalScanMap_.publish(cloudMsg);
853  }
854  }
855  else if(data.imageRaw().empty() && data.laserScanRaw().isEmpty() && !data.imu().empty())
856  {
857  return;
858  }
859  else // pose is null / lost
860  {
862  {
863  //NODELET_WARN( "Odometry lost!");
864 
865  //send null pose to notify that odometry is lost
866  nav_msgs::Odometry odom;
867  odom.header.stamp = header.stamp; // use corresponding time stamp to image
868  odom.header.frame_id = odomFrameId_;
869  odom.child_frame_id = frameId_;
870  odom.pose.covariance.at(0) = BAD_COVARIANCE; // xx
871  odom.pose.covariance.at(7) = BAD_COVARIANCE; // yy
872  odom.pose.covariance.at(14) = BAD_COVARIANCE; // zz
873  odom.pose.covariance.at(21) = BAD_COVARIANCE; // rr
874  odom.pose.covariance.at(28) = BAD_COVARIANCE; // pp
875  odom.pose.covariance.at(35) = BAD_COVARIANCE; // yawyaw
876  odom.twist.covariance.at(0) = BAD_COVARIANCE; // xx
877  odom.twist.covariance.at(7) = BAD_COVARIANCE; // yy
878  odom.twist.covariance.at(14) = BAD_COVARIANCE; // zz
879  odom.twist.covariance.at(21) = BAD_COVARIANCE; // rr
880  odom.twist.covariance.at(28) = BAD_COVARIANCE; // pp
881  odom.twist.covariance.at(35) = BAD_COVARIANCE; // yawyaw
882 
883  //publish the message
884  odomPub_.publish(odom);
885  }
886 
887  // Publish the Tf correction using guess pose directly so that TF tree is not broken when vo is lost
888  if(publishTf_ && !guess_.isNull())
889  {
890  geometry_msgs::TransformStamped correctionMsg;
891  correctionMsg.child_frame_id = guessFrameId_;
892  correctionMsg.header.frame_id = odomFrameId_;
893  correctionMsg.header.stamp = header.stamp;
894  Transform correction = odometry_->getPose() * guess_ * guessCurrentPose.inverse();
895  rtabmap_conversions::transformToGeometryMsg(correction, correctionMsg.transform);
896  tfBroadcaster_.sendTransform(correctionMsg);
897  }
898  }
899 
900  if(pose.isNull() && (resetCurrentCount_ > 0 || tooOldPreviousData))
901  {
902  if(tooOldPreviousData)
903  {
904  NODELET_WARN( "Odometry lost! Odometry will be reset because last update "
905  "is %fs too old (>%fs, min_update_rate = %f Hz). Previous data stamp is %f while new data stamp is %f.",
906  header.stamp.toSec() - previousStamp_, 1.0/minUpdateRate_, minUpdateRate_, previousStamp_, header.stamp.toSec());
907  }
908  else if(--resetCurrentCount_>0)
909  {
910  NODELET_WARN( "Odometry lost! Odometry will be reset after next %d consecutive unsuccessful odometry updates...", resetCurrentCount_);
911  }
912 
913  if(resetCurrentCount_ == 0 || tooOldPreviousData)
914  {
915  if(!guess_.isNull())
916  {
917  NODELET_WARN( "Odometry automatically reset based on latest guess available from TF (%s->%s, moved %s since got lost)!",
918  guessFrameId_.c_str(), frameId_.c_str(), guess_.prettyPrint().c_str());
920  guess_.setNull();
921  }
922  else
923  {
924  // Check TF to see if sensor fusion is used (e.g., the output of robot_localization)
925  Transform tfPose = rtabmap_conversions::getTransform(odomFrameId_, frameId_, header.stamp, this->tfListener(), this->waitForTransformDuration());
926  if(tfPose.isNull())
927  {
928  NODELET_WARN( "Odometry automatically reset to latest computed pose!");
930  }
931  else
932  {
933  NODELET_WARN( "Odometry automatically reset to latest odometry pose available from TF (%s->%s)!",
934  odomFrameId_.c_str(), frameId_.c_str());
935  odometry_->reset(tfPose);
936  }
937  }
938  // Keep resetting if the odometry cannot initialize in next updates (e.g., lack of features).
939  // This will make sure we keep updating to latest guess pose.
940  if(resetCurrentCount_ == 0) {
942  }
943  }
944  }
945 
947  {
948  rtabmap_msgs::OdomInfo infoMsg;
950  infoMsg.header.stamp = header.stamp; // use corresponding time stamp to image
951  infoMsg.header.frame_id = odomFrameId_;
953  odomInfoPub_.publish(infoMsg);
954  }
955 
957  {
958  infoMsg.wordInliers.clear();
959  infoMsg.wordMatches.clear();
960  infoMsg.wordsKeys.clear();
961  infoMsg.wordsValues.clear();
962  infoMsg.refCorners.clear();
963  infoMsg.newCorners.clear();
964  infoMsg.cornerInliers.clear();
965  infoMsg.localMapKeys.clear();
966  infoMsg.localMapValues.clear();
967  infoMsg.localScanMap = sensor_msgs::PointCloud2();
968  odomInfoLitePub_.publish(infoMsg);
969  }
970  }
971 
973 
974  if(!data.imageRaw().empty() && odomRgbdImagePub_.getNumSubscribers())
975  {
976  if(!header.frame_id.empty())
977  {
978  rtabmap_msgs::RGBDImage msg;
980  msg.header = header; // use corresponding time stamp to image
982  }
983  else
984  {
985  ROS_WARN("Sensor frame not set, cannot convert SensorData to RGBDImage");
986  }
987  }
988 
990  {
991  rtabmap_msgs::SensorData msg;
993  msg.header.stamp = header.stamp; // use corresponding time stamp to image
995  {
997  }
999  {
1000  // remove data
1001  msg.left = sensor_msgs::Image();
1002  msg.right = sensor_msgs::Image();
1003  msg.laser_scan = sensor_msgs::PointCloud2();
1004  msg.grid_ground.clear();
1005  msg.grid_obstacles.clear();
1006  msg.grid_empty_cells.clear();
1008  }
1009  }
1011  {
1012  cv::Mat compressedImage;
1013  cv::Mat compressedDepth;
1014  cv::Mat compressedScan;
1016  {
1018  rtabmap::CompressionThread ctDepth(data.depthOrRightRaw(), data.depthOrRightRaw().type() == CV_32FC1 || data.depthOrRightRaw().type() == CV_16UC1?std::string(".png"):compressionImgFormat_);
1019  rtabmap::CompressionThread ctLaserScan(data.laserScanRaw().data());
1020  if(!data.imageRaw().empty())
1021  {
1022  ctImage.start();
1023  }
1024  if(!data.depthOrRightRaw().empty())
1025  {
1026  ctDepth.start();
1027  }
1028  if(!data.laserScanRaw().isEmpty())
1029  {
1030  ctLaserScan.start();
1031  }
1032  ctImage.join();
1033  ctDepth.join();
1034  ctLaserScan.join();
1035 
1036  compressedImage = ctImage.getCompressedData();
1037  compressedDepth = ctDepth.getCompressedData();
1038  compressedScan = ctLaserScan.getCompressedData();
1039  }
1040  else
1041  {
1042  compressedImage = compressImage2(data.imageRaw(), compressionImgFormat_);
1043  compressedDepth = compressImage2(data.depthOrRightRaw(), data.depthOrRightRaw().type() == CV_32FC1 || data.depthOrRightRaw().type() == CV_16UC1?std::string(".png"):compressionImgFormat_);
1044  compressedScan = compressData2(data.laserScanRaw().data());
1045  }
1046  if(!compressedImage.empty() && !data.stereoCameraModels().empty())
1047  {
1048  data.setStereoImage(compressedImage, compressedDepth, data.stereoCameraModels(), false);
1049  }
1050  else if(!compressedImage.empty() && !data.cameraModels().empty())
1051  {
1052  data.setRGBDImage(compressedImage, compressedDepth, data.cameraModels(), false);
1053  }
1054  if(!compressedScan.empty())
1055  {
1056  data.setLaserScan(data.laserScanRaw().angleIncrement() == 0.0f?
1057  LaserScan(compressedScan,
1058  data.laserScanRaw().maxPoints(),
1059  data.laserScanRaw().rangeMax(),
1060  data.laserScanRaw().format(),
1061  data.laserScanRaw().localTransform()):
1062  LaserScan(compressedScan,
1063  data.laserScanRaw().format(),
1064  data.laserScanRaw().rangeMin(),
1065  data.laserScanRaw().rangeMax(),
1066  data.laserScanRaw().angleMin(),
1067  data.laserScanRaw().angleMax(),
1068  data.laserScanRaw().angleIncrement(),
1069  data.laserScanRaw().localTransform()), false);
1070  }
1071  rtabmap_msgs::SensorData msg;
1073  msg.header.stamp = header.stamp; // use corresponding time stamp to image
1075  }
1076 
1077  double delay = (ros::Time::now() - header.stamp).toSec();
1078  if(visParams_)
1079  {
1080  if(icpParams_)
1081  {
1082  NODELET_INFO( "Odom: quality=%d, ratio=%f, std dev=%fm|%frad, update time=%fs, delay=%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(), delay);
1083  }
1084  else
1085  {
1086  NODELET_INFO( "Odom: quality=%d, std dev=%fm|%frad, update time=%fs, delay=%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(), delay);
1087  }
1088  }
1089  else // if(icpParams_)
1090  {
1091  NODELET_INFO( "Odom: ratio=%f, std dev=%fm|%frad, update time=%fs, delay=%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(), delay);
1092  }
1093 
1095  if(syncDiagnostic_.get())
1096  {
1097  double curentRate = 1.0/(ros::WallTime::now()-time).toSec();
1098  syncDiagnostic_->tick(header.stamp,
1101  previousStamp_ == 0.0 || header.stamp.toSec() - previousStamp_ > 1.0/curentRate?0:curentRate);
1102  }
1103 
1104  previousStamp_ = header.stamp.toSec();
1105 }
1106 
1107 bool OdometryROS::reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1108 {
1109  NODELET_INFO( "visual_odometry: reset odom!");
1110  reset();
1111  return true;
1112 }
1113 
1114 bool OdometryROS::resetToPose(rtabmap_msgs::ResetPose::Request& req, rtabmap_msgs::ResetPose::Response&)
1115 {
1116  Transform pose(req.x, req.y, req.z, req.roll, req.pitch, req.yaw);
1117  NODELET_INFO( "visual_odometry: reset odom to pose %s!", pose.prettyPrint().c_str());
1118  reset(pose);
1119  return true;
1120 }
1121 
1122 void OdometryROS::reset(const Transform & pose)
1123 {
1124  UScopeMutex lock(dataMutex_);
1125  odometry_->reset(pose);
1126  guess_.setNull();
1128  previousStamp_ = 0.0;
1130  imuProcessed_ = false;
1132  dataHeaderToProcess_ = std_msgs::Header();
1133  bufferedDataToProcess_ = false;
1134  imuMutex_.lock();
1135  imus_.clear();
1136  imuMutex_.unlock();
1137  this->flushCallbacks();
1138 }
1139 
1140 bool OdometryROS::pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1141 {
1142  if(paused_)
1143  {
1144  NODELET_WARN( "Odometry: Already paused!");
1145  }
1146  else
1147  {
1148  paused_ = true;
1149  NODELET_INFO( "Odometry: paused!");
1150  }
1151  return true;
1152 }
1153 
1154 bool OdometryROS::resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1155 {
1156  if(!paused_)
1157  {
1158  NODELET_WARN( "Odometry: Already running!");
1159  }
1160  else
1161  {
1162  paused_ = false;
1163  NODELET_INFO( "Odometry: resumed!");
1164  }
1165  return true;
1166 }
1167 
1168 bool OdometryROS::setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1169 {
1170  NODELET_INFO( "visual_odometry: Set log level to Debug");
1172  return true;
1173 }
1174 bool OdometryROS::setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1175 {
1176  NODELET_INFO( "visual_odometry: Set log level to Info");
1178  return true;
1179 }
1180 bool OdometryROS::setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1181 {
1182  NODELET_INFO( "visual_odometry: Set log level to Warning");
1184  return true;
1185 }
1186 bool OdometryROS::setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1187 {
1188  NODELET_INFO( "visual_odometry: Set log level to Error");
1190  return true;
1191 }
1192 
1194  diagnostic_updater::DiagnosticTask("Odom status"),
1195  lost_(false),
1196  dataReceived_(false)
1197 {}
1198 
1200 {
1201  dataReceived_ = true;
1202  lost_ = isLost;
1203 }
1204 
1206 {
1207  if(!dataReceived_)
1208  {
1209  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No data received!");
1210  }
1211  else if(lost_)
1212  {
1213  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Lost!");
1214  }
1215  else
1216  {
1217  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Tracking.");
1218  }
1219 }
1220 
1221 }
rtabmap::SensorData
ParametersPair
std::pair< std::string, std::string > ParametersPair
rtabmap::OdometryF2F
rtabmap_odom
Definition: OdometryROS.h:57
rtabmap_odom::OdometryROS::resumeSrv_
ros::ServiceServer resumeSrv_
Definition: OdometryROS.h:136
UMutex::lock
int lock() const
rtabmap_odom::OdometryROS::processData
void processData(rtabmap::SensorData &data, const std_msgs::Header &header)
Definition: OdometryROS.cpp:461
compare
bool compare
rtabmap_odom::OdometryROS::odometry_
rtabmap::Odometry * odometry_
Definition: OdometryROS.h:105
rtabmap_odom::OdometryROS::dataMutex_
UMutex dataMutex_
Definition: OdometryROS.h:147
rtabmap_odom::OdometryROS::publishCompressedSensorData_
bool publishCompressedSensorData_
Definition: OdometryROS.h:120
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
USemaphore::acquire
bool acquire(int n=1, int ms=0)
rtabmap_odom::OdometryROS::imuProcessed_
bool imuProcessed_
Definition: OdometryROS.h:169
rtabmap_odom::OdometryROS::imus_
std::map< double, rtabmap::IMU > imus_
Definition: OdometryROS.h:170
NODELET_ERROR
#define NODELET_ERROR(...)
rtabmap_odom::OdometryROS::groundTruthBaseFrameId_
std::string groundTruthBaseFrameId_
Definition: OdometryROS.h:111
rtabmap_odom::OdometryROS::statusDiagnostic_
OdomStatusTask statusDiagnostic_
Definition: OdometryROS.h:184
rtabmap_odom::OdometryROS::stereoParams_
bool stereoParams_
Definition: OdometryROS.h:156
msg
msg
rtabmap_odom::OdometryROS::resume
bool resume(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1154
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
yaw
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
image_encodings.h
rtabmap_odom::OdometryROS::odomPub_
ros::Publisher odomPub_
Definition: OdometryROS.h:123
rtabmap_odom::OdometryROS::visParams_
bool visParams_
Definition: OdometryROS.h:157
ULogger::kError
kError
gtsam::Values::size
size_t size() const
rtabmap_conversions::getTransform
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
rtabmap_odom::OdometryROS::OdomStatusTask::run
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: OdometryROS.cpp:1205
UMutex::unlock
int unlock() const
rtabmap::Parameters::parseArguments
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
rtabmap_odom::OdometryROS::odomInfoLitePub_
ros::Publisher odomInfoLitePub_
Definition: OdometryROS.h:125
rtabmap_odom::OdometryROS::waitIMUToinit_
bool waitIMUToinit_
Definition: OdometryROS.h:168
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
rtabmap_odom::OdometryROS::velocityGuess
rtabmap::Transform velocityGuess() const
Definition: OdometryROS.cpp:405
uFormat
std::string uFormat(const char *fmt,...)
rtabmap_odom::OdometryROS::odomSensorDataFeaturesPub_
ros::Publisher odomSensorDataFeaturesPub_
Definition: OdometryROS.h:131
rtabmap::Transform::getIdentity
static Transform getIdentity()
this
this
rtabmap_sync::SyncDiagnostic
rtabmap::CompressionThread::getCompressedData
const cv::Mat & getCompressedData() const
Compression.h
ULogger::setLevel
static void setLevel(ULogger::Level level)
rtabmap_odom::OdometryROS::odomLocalMap_
ros::Publisher odomLocalMap_
Definition: OdometryROS.h:126
rtabmap_odom::OdometryROS::imuSub_
ros::Subscriber imuSub_
Definition: OdometryROS.h:143
UThread::join
void join(bool killFirst=false)
rtabmap_odom::OdometryROS::maxUpdateRate_
double maxUpdateRate_
Definition: OdometryROS.h:163
ros::Subscriber::getTopic
std::string getTopic() const
ULogger::kDebug
kDebug
UStl.h
NODELET_WARN
#define NODELET_WARN(...)
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
y
Matrix3f y
rtabmap_odom::OdometryROS::initDiagnosticMsg
void initDiagnosticMsg(const std::string &subscribedTopicsMsg, bool approxSync, const std::string &subscribedTopic="")
Definition: OdometryROS.cpp:388
UMutex::lockTry
int lockTry() const
true
#define true
rtabmap_odom::OdometryROS::onInit
virtual void onInit()
Definition: OdometryROS.cpp:100
rtabmap_odom::OdometryROS::imuMutex_
UMutex imuMutex_
Definition: OdometryROS.h:146
rtabmap::Transform::setNull
void setNull()
rtabmap_odom::OdometryROS::OdomStatusTask::OdomStatusTask
OdomStatusTask()
Definition: OdometryROS.cpp:1193
rtabmap::LaserScan
uListToVector
std::vector< V > uListToVector(const std::list< V > &list)
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
nodelet::Nodelet::getMyArgv
const V_string & getMyArgv() const
f
Vector3 f(-6, 1, 0.5)
rtabmap_odom::OdometryROS::dataHeaderToProcess_
std_msgs::Header dataHeaderToProcess_
Definition: OdometryROS.h:150
rtabmap_odom::OdometryROS::publishNullWhenLost_
bool publishNullWhenLost_
Definition: OdometryROS.h:119
uNumber2Str
std::string uNumber2Str(double number, int precision, bool fixed)
rtabmap_odom::OdometryROS::guessPreviousPose_
rtabmap::Transform guessPreviousPose_
Definition: OdometryROS.h:160
rtabmap::Transform::isNull
bool isNull() const
rtabmap_odom::OdometryROS::callbackIMU
void callbackIMU(const sensor_msgs::ImuConstPtr &msg)
Definition: OdometryROS.cpp:414
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)
OdometryF2F.h
data
data
rtabmap::Transform::getTranslationAndEulerAngles
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
fabs
Real fabs(const Real &a)
UDirectory::homeDir
static std::string homeDir()
rtabmap::Odometry::getType
virtual Odometry::Type getType()=0
rtabmap_odom::OdometryROS::odomFrameId_
std::string odomFrameId_
Definition: OdometryROS.h:109
rtabmap::Odometry::getPose
const Transform & getPose() const
rtabmap_odom::OdometryROS::pause
bool pause(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1140
uReplaceChar
std::string uReplaceChar(const std::string &str, char before, char after)
rtabmap_conversions::odomInfoToROS
void odomInfoToROS(const rtabmap::OdometryInfo &info, rtabmap_msgs::OdomInfo &msg, bool ignoreData=false)
BAD_COVARIANCE
#define BAD_COVARIANCE
Definition: OdometryROS.cpp:54
rtabmap_odom::OdometryROS::compressionImgFormat_
std::string compressionImgFormat_
Definition: OdometryROS.h:165
rtabmap_odom::OdometryROS::waitForTransform_
bool waitForTransform_
Definition: OdometryROS.h:117
rtabmap::IMU
rtabmap_odom::OdometryROS::parameters_
rtabmap::ParametersMap parameters_
Definition: OdometryROS.h:121
UDirectory::currentDir
static std::string currentDir(bool trailingSeparator=false)
OdometryF2M.h
ULogger::setEventLevel
static void setEventLevel(ULogger::Level eventSentLevel)
rtabmap_odom::OdometryROS::compressionParallelized_
bool compressionParallelized_
Definition: OdometryROS.h:166
uBool2Str
std::string uBool2Str(bool boolean)
rtabmap::Transform::prettyPrint
std::string prettyPrint() const
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
UScopeMutex
rtabmap_odom::OdometryROS::guessMinTime_
double guessMinTime_
Definition: OdometryROS.h:115
rtabmap_odom::OdometryROS::flushCallbacks
virtual void flushCallbacks()=0
rtabmap_odom::OdometryROS::syncDiagnostic_
std::unique_ptr< rtabmap_sync::SyncDiagnostic > syncDiagnostic_
Definition: OdometryROS.h:185
uInsert
void uInsert(std::map< K, V > &map, const std::map< K, V > &items)
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
rtabmap_odom::OdometryROS::odomSensorDataCompressedPub_
ros::Publisher odomSensorDataCompressedPub_
Definition: OdometryROS.h:132
sqrt
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
uMax3
T uMax3(const T &a, const T &b, const T &c)
rtabmap_odom::OdometryROS::odomStrategy_
int odomStrategy_
Definition: OdometryROS.h:167
diagnostic_updater
ros::WallTime::now
static WallTime now()
first
constexpr int first(int i)
rtabmap::CompressionThread
ULogger::kWarning
kWarning
rtabmap_odom::OdometryROS::minUpdateRate_
double minUpdateRate_
Definition: OdometryROS.h:164
rtabmap::Signature::getWords3
const std::vector< cv::Point3f > & getWords3() const
rtabmap_odom::OdometryROS::icpParams_
bool icpParams_
Definition: OdometryROS.h:158
rtabmap_odom::OdometryROS::odomSensorDataPub_
ros::Publisher odomSensorDataPub_
Definition: OdometryROS.h:130
rtabmap_odom::OdometryROS::resetSrv_
ros::ServiceServer resetSrv_
Definition: OdometryROS.h:133
ULogger::kInfo
kInfo
rtabmap_odom::OdometryROS::expectedUpdateRate_
double expectedUpdateRate_
Definition: OdometryROS.h:162
rtabmap::Odometry::reset
virtual void reset(const Transform &initialPose=Transform::getIdentity())
rtabmap_odom::OdometryROS::mainLoop
virtual void mainLoop()
Definition: OdometryROS.cpp:488
info
else if n * info
rtabmap_odom::OdometryROS::dataReady_
USemaphore dataReady_
Definition: OdometryROS.h:148
rtabmap_odom::OdometryROS::resetCurrentCount_
int resetCurrentCount_
Definition: OdometryROS.h:155
rtabmap::Odometry::getVelocityGuess
const Transform & getVelocityGuess() const
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
UASSERT
#define UASSERT(condition)
argv
argv
ROS_WARN
#define ROS_WARN(...)
z
z
rtabmap_odom::OdometryROS::setLogWarn
bool setLogWarn(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1180
rtabmap_conversions::sensorDataToROS
void sensorDataToROS(const rtabmap::SensorData &signature, rtabmap_msgs::SensorData &msg, const std::string &frameId="base_link", bool copyRawData=false)
x
x
m
Matrix3f m
UThread::start
void start()
rtabmap_odom::OdometryROS::parameters
const rtabmap::ParametersMap & parameters() const
Definition: OdometryROS.h:80
rtabmap_odom::OdometryROS::guessMinRotation_
double guessMinRotation_
Definition: OdometryROS.h:114
rtabmap::Odometry::framesProcessed
unsigned int framesProcessed() const
rtabmap::Odometry::process
Transform process(SensorData &data, const Transform &guess, OdometryInfo *info=0)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
rtabmap::Parameters
time
#define time
ros::WallTime
pitch
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
rtabmap::OdometryF2M
rtabmap::Transform::inverse
Transform inverse() const
compressData2
cv::Mat RTABMAP_CORE_EXPORT compressData2(const cv::Mat &data)
rtabmap_odom::OdometryROS::setLogErrorSrv_
ros::ServiceServer setLogErrorSrv_
Definition: OdometryROS.h:140
rtabmap_odom::OdometryROS::~OdometryROS
virtual ~OdometryROS()
Definition: OdometryROS.cpp:94
NODELET_INFO
#define NODELET_INFO(...)
rtabmap_odom::OdometryROS::paused_
bool paused_
Definition: OdometryROS.h:153
rtabmap::Transform
USemaphore::release
void release(int n=1)
rtabmap_odom::OdometryROS::odomLastFrame_
ros::Publisher odomLastFrame_
Definition: OdometryROS.h:128
uSplit
std::list< std::string > uSplit(const std::string &str, char separator=' ')
rtabmap_odom::OdometryROS::resetCountdown_
int resetCountdown_
Definition: OdometryROS.h:154
values
leaf::MyValues values
UFile.h
rtabmap_odom::OdometryROS::odomInfoPub_
ros::Publisher odomInfoPub_
Definition: OdometryROS.h:124
iter
iterator iter(handle obj)
rtabmap::Transform::isIdentity
bool isIdentity() const
c_str
const char * c_str(Args &&...args)
cv_bridge.h
rtabmap_odom::OdometryROS::odomLocalScanMap_
ros::Publisher odomLocalScanMap_
Definition: OdometryROS.h:127
ROS_ERROR
#define ROS_ERROR(...)
rtabmap_odom::OdometryROS::setLogInfo
bool setLogInfo(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1174
rtabmap_conversions::transformToGeometryMsg
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
rtabmap_odom::OdometryROS::setLogError
bool setLogError(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1186
rtabmap_odom::OdometryROS::publishTf_
bool publishTf_
Definition: OdometryROS.h:116
rtabmap::Transform::getTranslation
void getTranslation(float &x, float &y, float &z) const
rtabmap_odom::OdometryROS::guess_
rtabmap::Transform guess_
Definition: OdometryROS.h:159
nodelet::Nodelet::getName
const std::string & getName() const
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rtabmap_odom::OdometryROS::tfBroadcaster_
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition: OdometryROS.h:141
rtabmap::OdometryInfo
diagnostic_updater::DiagnosticStatusWrapper
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
rtabmap_odom::OdometryROS::previousStamp_
double previousStamp_
Definition: OdometryROS.h:161
rtabmap_odom::OdometryROS::bufferedDataToProcess_
bool bufferedDataToProcess_
Definition: OdometryROS.h:151
scan_step::second
@ second
rtabmap_odom::OdometryROS::onOdomInit
virtual void onOdomInit()=0
ULogger.h
ULogger::kFatal
kFatal
Signature.h
rtabmap_odom::OdometryROS::reset
bool reset(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1107
UThread::isRunning
bool isRunning() const
rtabmap_odom::OdometryROS::odomRgbdImagePub_
ros::Publisher odomRgbdImagePub_
Definition: OdometryROS.h:129
ULogger::Level
Level
rtabmap_odom::OdometryROS::guessFrameId_
std::string guessFrameId_
Definition: OdometryROS.h:112
rtabmap_odom::OdometryROS::isPaused
bool isPaused() const
Definition: OdometryROS.h:81
rtabmap_odom::OdometryROS::setLogDebug
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1168
false
#define false
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
rtabmap_odom::OdometryROS::pauseSrv_
ros::ServiceServer pauseSrv_
Definition: OdometryROS.h:135
header
const std::string header
Memory.h
uStr2Float
float uStr2Float(const std::string &str)
ROS_INFO
#define ROS_INFO(...)
UConversion.h
OdometryROS.h
MsgConversion.h
rtabmap
rtabmap_conversions::rgbdImageToROS
void rgbdImageToROS(const rtabmap::SensorData &data, rtabmap_msgs::RGBDImage &msg, const std::string &sensorFrameId)
UFile::exists
bool exists()
util3d_transforms.h
rtabmap_odom::OdometryROS::postProcessData
virtual void postProcessData(const rtabmap::SensorData &data, const std_msgs::Header &header) const
Definition: OdometryROS.h:91
rtabmap_odom::OdometryROS::updateParameters
virtual void updateParameters(rtabmap::ParametersMap &parameters)
Definition: OdometryROS.h:96
compressImage2
cv::Mat RTABMAP_CORE_EXPORT compressImage2(const cv::Mat &image, const std::string &format=".png")
rtabmap_odom::OdometryROS::setLogInfoSrv_
ros::ServiceServer setLogInfoSrv_
Definition: OdometryROS.h:138
rtabmap_odom::OdometryROS::setLogDebugSrv_
ros::ServiceServer setLogDebugSrv_
Definition: OdometryROS.h:137
i
int i
rtabmap_odom::OdometryROS::frameId_
std::string frameId_
Definition: OdometryROS.h:108
rtabmap_odom::OdometryROS::groundTruthFrameId_
std::string groundTruthFrameId_
Definition: OdometryROS.h:110
rtabmap_odom::OdometryROS::waitForTransformDuration_
double waitForTransformDuration_
Definition: OdometryROS.h:118
util3d.h
roll
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
UMath.h
ros::NodeHandle
rtabmap::Signature
rtabmap_odom::OdometryROS::OdomStatusTask::setStatus
void setStatus(bool isLost)
Definition: OdometryROS.cpp:1199
rtabmap_odom::OdometryROS::resetToPoseSrv_
ros::ServiceServer resetToPoseSrv_
Definition: OdometryROS.h:134
rtabmap_odom::OdometryROS::resetToPose
bool resetToPose(rtabmap_msgs::ResetPose::Request &, rtabmap_msgs::ResetPose::Response &)
Definition: OdometryROS.cpp:1114
NODELET_DEBUG
#define NODELET_DEBUG(...)
rtabmap_odom::OdometryROS::setLogWarnSrv_
ros::ServiceServer setLogWarnSrv_
Definition: OdometryROS.h:139
ros::Time::now
static Time now()
rtabmap_odom::OdometryROS::mainLoopKill
virtual void mainLoopKill()
Definition: OdometryROS.cpp:482
rtabmap_odom::OdometryROS::frameId
const std::string & frameId() const
Definition: OdometryROS.h:77
pcl_conversions.h
rtabmap_odom::OdometryROS::dataToProcess_
rtabmap::SensorData dataToProcess_
Definition: OdometryROS.h:149
rtabmap_odom::OdometryROS::guessMinTranslation_
double guessMinTranslation_
Definition: OdometryROS.h:113


rtabmap_odom
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:42:24