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 
39 #include <rtabmap/core/Rtabmap.h>
42 #include <rtabmap/core/util3d.h>
44 #include <rtabmap/core/Memory.h>
45 #include <rtabmap/core/Signature.h>
47 #include "rtabmap_ros/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_ros {
59 
60 OdometryROS::OdometryROS(bool stereoParams, bool visParams, bool icpParams) :
61  odometry_(0),
62  warningThread_(0),
63  callbackCalled_(false),
64  frameId_("base_link"),
65  odomFrameId_("odom"),
66  groundTruthFrameId_(""),
67  groundTruthBaseFrameId_(""),
68  guessFrameId_(""),
69  guessMinTranslation_(0.0),
70  guessMinRotation_(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  guessStamp_(0.0)
82 {
83 
84 }
85 
87 {
88  if(warningThread_)
89  {
91  warningThread_->join();
92  delete warningThread_;
93  }
95  if(pnh.ok())
96  {
97  for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
98  {
99  pnh.deleteParam(iter->first);
100  }
101  }
102 
103  delete odometry_;
104 }
105 
107 {
110 
111  odomPub_ = nh.advertise<nav_msgs::Odometry>("odom", 1);
112  odomInfoPub_ = nh.advertise<rtabmap_ros::OdomInfo>("odom_info", 1);
113  odomLocalMap_ = nh.advertise<sensor_msgs::PointCloud2>("odom_local_map", 1);
114  odomLocalScanMap_ = nh.advertise<sensor_msgs::PointCloud2>("odom_local_scan_map", 1);
115  odomLastFrame_ = nh.advertise<sensor_msgs::PointCloud2>("odom_last_frame", 1);
116 
117  Transform initialPose = Transform::getIdentity();
118  std::string initialPoseStr;
119  std::string configPath;
120  pnh.param("frame_id", frameId_, frameId_);
121  pnh.param("odom_frame_id", odomFrameId_, odomFrameId_);
122  pnh.param("publish_tf", publishTf_, publishTf_);
123  if(pnh.hasParam("tf_prefix"))
124  {
125  NODELET_ERROR("tf_prefix parameter has been removed, use directly odom_frame_id and frame_id parameters.");
126  }
127  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
128  pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
129  pnh.param("initial_pose", initialPoseStr, initialPoseStr); // "x y z roll pitch yaw"
130  pnh.param("ground_truth_frame_id", groundTruthFrameId_, groundTruthFrameId_);
131  pnh.param("ground_truth_base_frame_id", groundTruthBaseFrameId_, frameId_);
132  pnh.param("config_path", configPath, configPath);
133  pnh.param("publish_null_when_lost", publishNullWhenLost_, publishNullWhenLost_);
134  if(pnh.hasParam("guess_from_tf"))
135  {
136  if(!pnh.hasParam("guess_frame_id"))
137  {
138  NODELET_ERROR("Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
139  }
140  else
141  {
142  NODELET_WARN("Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
143  }
144  }
145  pnh.param("guess_frame_id", guessFrameId_, guessFrameId_); // odometry guess frame
146  pnh.param("guess_min_translation", guessMinTranslation_, guessMinTranslation_);
147  pnh.param("guess_min_rotation", guessMinRotation_, guessMinRotation_);
148 
149  if(publishTf_ && !guessFrameId_.empty() && guessFrameId_.compare(odomFrameId_) == 0)
150  {
151  NODELET_WARN( "\"publish_tf\" and \"guess_frame_id\" cannot be used "
152  "at the same time if \"guess_frame_id\" and \"odom_frame_id\" "
153  "are the same frame (value=\"%s\"). \"guess_frame_id\" is disabled.", odomFrameId_.c_str());
154  guessFrameId_.clear();
155  }
156  NODELET_INFO("Odometry: frame_id = %s", frameId_.c_str());
157  NODELET_INFO("Odometry: odom_frame_id = %s", odomFrameId_.c_str());
158  NODELET_INFO("Odometry: publish_tf = %s", publishTf_?"true":"false");
159  NODELET_INFO("Odometry: wait_for_transform = %s", waitForTransform_?"true":"false");
160  NODELET_INFO("Odometry: wait_for_transform_duration = %f", waitForTransformDuration_);
161  NODELET_INFO("Odometry: initial_pose = %s", initialPose.prettyPrint().c_str());
162  NODELET_INFO("Odometry: ground_truth_frame_id = %s", groundTruthFrameId_.c_str());
163  NODELET_INFO("Odometry: ground_truth_base_frame_id = %s", groundTruthBaseFrameId_.c_str());
164  NODELET_INFO("Odometry: config_path = %s", configPath.c_str());
165  NODELET_INFO("Odometry: publish_null_when_lost = %s", publishNullWhenLost_?"true":"false");
166  NODELET_INFO("Odometry: guess_frame_id = %s", guessFrameId_.c_str());
167  NODELET_INFO("Odometry: guess_min_translation = %f", guessMinTranslation_);
168  NODELET_INFO("Odometry: guess_min_rotation = %f", guessMinRotation_);
169 
170  configPath = uReplaceChar(configPath, '~', UDirectory::homeDir());
171  if(configPath.size() && configPath.at(0) != '/')
172  {
173  configPath = UDirectory::currentDir(true) + configPath;
174  }
175 
176  if(initialPoseStr.size())
177  {
178  std::vector<std::string> values = uListToVector(uSplit(initialPoseStr, ' '));
179  if(values.size() == 6)
180  {
181  initialPose = Transform(
182  uStr2Float(values[0]), uStr2Float(values[1]), uStr2Float(values[2]),
183  uStr2Float(values[3]), uStr2Float(values[4]), uStr2Float(values[5]));
184  }
185  else
186  {
187  NODELET_ERROR( "Wrong initial_pose format: %s (should be \"x y z roll pitch yaw\" with angle in radians). "
188  "Identity will be used...", initialPoseStr.c_str());
189  }
190  }
191 
192 
193  //parameters
194  parameters_ = Parameters::getDefaultOdometryParameters(stereoParams_, visParams_, icpParams_);
195  parameters_.insert(*Parameters::getDefaultParameters().find(Parameters::kRtabmapImagesAlreadyRectified()));
196  if(!configPath.empty())
197  {
198  if(UFile::exists(configPath.c_str()))
199  {
200  NODELET_INFO( "Odometry: Loading parameters from %s", configPath.c_str());
201  rtabmap::ParametersMap allParameters;
202  Parameters::readINI(configPath.c_str(), allParameters);
203  // only update odometry parameters
204  for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
205  {
206  ParametersMap::iterator jter = allParameters.find(iter->first);
207  if(jter!=allParameters.end())
208  {
209  iter->second = jter->second;
210  }
211  }
212  }
213  else
214  {
215  NODELET_ERROR( "Config file \"%s\" not found!", configPath.c_str());
216  }
217  }
218  for(rtabmap::ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
219  {
220  std::string vStr;
221  bool vBool;
222  int vInt;
223  double vDouble;
224  if(pnh.getParam(iter->first, vStr))
225  {
226  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
227  iter->second = vStr;
228  }
229  else if(pnh.getParam(iter->first, vBool))
230  {
231  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
232  iter->second = uBool2Str(vBool);
233  }
234  else if(pnh.getParam(iter->first, vDouble))
235  {
236  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble).c_str());
237  iter->second = uNumber2Str(vDouble);
238  }
239  else if(pnh.getParam(iter->first, vInt))
240  {
241  NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
242  iter->second = uNumber2Str(vInt);
243  }
244 
245  if(iter->first.compare(Parameters::kVisMinInliers()) == 0 && atoi(iter->second.c_str()) < 8)
246  {
247  NODELET_WARN( "Parameter min_inliers must be >= 8, setting to 8...");
248  iter->second = uNumber2Str(8);
249  }
250  }
251 
252  std::vector<std::string> argList = getMyArgv();
253  char * argv[argList.size()];
254  for(unsigned int i=0; i<argList.size(); ++i)
255  {
256  argv[i] = &argList[i].at(0);
257  }
258 
260  for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
261  {
262  rtabmap::ParametersMap::iterator jter = parameters_.find(iter->first);
263  if(jter!=parameters_.end())
264  {
265  NODELET_INFO( "Update odometry parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
266  jter->second = iter->second;
267  }
268  }
269 
270  // Backward compatibility
271  for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=Parameters::getRemovedParameters().begin();
272  iter!=Parameters::getRemovedParameters().end();
273  ++iter)
274  {
275  std::string vStr;
276  if(pnh.getParam(iter->first, vStr))
277  {
278  if(iter->second.first && parameters_.find(iter->second.second) != parameters_.end())
279  {
280  // can be migrated
281  parameters_.at(iter->second.second)= vStr;
282  NODELET_WARN( "Odometry: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
283  iter->first.c_str(), iter->second.second.c_str(), vStr.c_str());
284  }
285  else
286  {
287  if(iter->second.second.empty())
288  {
289  NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore!",
290  iter->first.c_str());
291  }
292  else
293  {
294  NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
295  iter->first.c_str(), iter->second.second.c_str());
296  }
297  }
298  }
299  }
300 
301  Parameters::parse(parameters_, Parameters::kOdomResetCountdown(), resetCountdown_);
302  parameters_.at(Parameters::kOdomResetCountdown()) = "0"; // use modified reset countdown here
303 
304  this->updateParameters(parameters_);
305 
306  odometry_ = Odometry::create(parameters_);
307  if(!initialPose.isIdentity())
308  {
309  odometry_->reset(initialPose);
310  }
311 
312  resetSrv_ = nh.advertiseService("reset_odom", &OdometryROS::reset, this);
313  resetToPoseSrv_ = nh.advertiseService("reset_odom_to_pose", &OdometryROS::resetToPose, this);
314  pauseSrv_ = nh.advertiseService("pause_odom", &OdometryROS::pause, this);
315  resumeSrv_ = nh.advertiseService("resume_odom", &OdometryROS::resume, this);
316 
317  setLogDebugSrv_ = pnh.advertiseService("log_debug", &OdometryROS::setLogDebug, this);
318  setLogInfoSrv_ = pnh.advertiseService("log_info", &OdometryROS::setLogInfo, this);
319  setLogWarnSrv_ = pnh.advertiseService("log_warning", &OdometryROS::setLogWarn, this);
320  setLogErrorSrv_ = pnh.advertiseService("log_error", &OdometryROS::setLogError, this);
321 
322  onOdomInit();
323 }
324 
325 void OdometryROS::startWarningThread(const std::string & subscribedTopicsMsg, bool approxSync)
326 {
327  warningThread_ = new boost::thread(boost::bind(&OdometryROS::warningLoop, this, subscribedTopicsMsg, approxSync));
328  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
329 }
330 
331 void OdometryROS::warningLoop(const std::string & subscribedTopicsMsg, bool approxSync)
332 {
333  ros::Duration r(5.0);
334  while(!callbackCalled_)
335  {
336  r.sleep();
337  if(!callbackCalled_)
338  {
339  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
340  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
341  "header are set. %s%s",
342  getName().c_str(),
343  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
344  "topics should have all the exact timestamp for the callback to be called.",
345  subscribedTopicsMsg.c_str());
346  }
347  }
348 }
349 
350 Transform OdometryROS::getTransform(const std::string & fromFrameId, const std::string & toFrameId, const ros::Time & stamp) const
351 {
352  // TF ready?
353  Transform transform;
354  try
355  {
356  if(waitForTransform_ && !stamp.isZero() && waitForTransformDuration_ > 0.0)
357  {
358  //if(!tfBuffer_.canTransform(fromFrameId, toFrameId, stamp, ros::Duration(1)))
359  std::string errorMsg;
360  if(!tfListener_.waitForTransform(fromFrameId, toFrameId, stamp, ros::Duration(waitForTransformDuration_), ros::Duration(0.01), &errorMsg))
361  {
362  NODELET_WARN( "odometry: Could not get transform from %s to %s (stamp=%f) after %f seconds (\"wait_for_transform_duration\"=%f)! Error=\"%s\"",
363  fromFrameId.c_str(), toFrameId.c_str(), stamp.toSec(), waitForTransformDuration_, waitForTransformDuration_, errorMsg.c_str());
364  return transform;
365  }
366  }
367 
369  tfListener_.lookupTransform(fromFrameId, toFrameId, stamp, tmp);
370  transform = rtabmap_ros::transformFromTF(tmp);
371  }
372  catch(tf::TransformException & ex)
373  {
374  NODELET_WARN( "%s",ex.what());
375  }
376  return transform;
377 }
378 
379 void OdometryROS::processData(const SensorData & data, const ros::Time & stamp)
380 {
381  if(!data.imageRaw().empty())
382  {
383  if(odometry_->getPose().isIdentity() &&
384  !groundTruthFrameId_.empty())
385  {
386  // sync with the first value of the ground truth
388  if(initialPose.isNull())
389  {
390  NODELET_WARN("Ground truth frames \"%s\" -> \"%s\" are set but failed to "
391  "get them, odometry won't be synchronized with ground truth.",
393  }
394  else
395  {
396  NODELET_INFO( "Initializing odometry pose to %s (from \"%s\" -> \"%s\")",
397  initialPose.prettyPrint().c_str(),
398  groundTruthFrameId_.c_str(),
399  groundTruthBaseFrameId_.c_str());
400  odometry_->reset(initialPose);
401  }
402  }
403  }
404 
405  Transform guessCurrentPose;
406  if(!guessFrameId_.empty())
407  {
408  Transform previousPose = this->getTransform(guessFrameId_, frameId_, guessStamp_>0.0?ros::Time(guessStamp_):stamp);
409  guessCurrentPose = this->getTransform(guessFrameId_, frameId_, stamp);
410  if(!previousPose.isNull() && !guessCurrentPose.isNull())
411  {
412  if(guess_.isNull())
413  {
414  guess_ = previousPose.inverse() * guessCurrentPose;
415  }
416  else
417  {
418  guess_ = guess_ * previousPose.inverse() * guessCurrentPose;
419  }
420  if(guessStamp_>0.0 && (guessMinTranslation_ > 0.0 || guessMinRotation_ > 0.0))
421  {
422  float x,y,z,roll,pitch,yaw;
423  guess_.getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
424  if((guessMinTranslation_ <= 0.0 || uMax3(fabs(x), fabs(y), fabs(z)) < guessMinTranslation_) &&
425  (guessMinRotation_ <= 0.0 || uMax3(fabs(roll), fabs(pitch), fabs(yaw)) < guessMinRotation_))
426  {
427  // Ignore odometry update, we didn't move enough
428  if(publishTf_)
429  {
430  geometry_msgs::TransformStamped correctionMsg;
431  correctionMsg.child_frame_id = guessFrameId_;
432  correctionMsg.header.frame_id = odomFrameId_;
433  correctionMsg.header.stamp = stamp;
434  Transform correction = odometry_->getPose() * guess_ * guessCurrentPose.inverse();
435  rtabmap_ros::transformToGeometryMsg(correction, correctionMsg.transform);
436  tfBroadcaster_.sendTransform(correctionMsg);
437  }
438  guessStamp_ = stamp.toSec();
439  return;
440  }
441  }
442  guessStamp_ = stamp.toSec();
443  }
444  else
445  {
446  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());
447  return;
448  }
449  }
450 
451  // process data
454  SensorData dataCpy = data;
455  rtabmap::Transform pose = odometry_->process(dataCpy, guess_, &info);
456  guess_.setNull();
457  if(!pose.isNull())
458  {
460 
461  //*********************
462  // Update odometry
463  //*********************
465  poseMsg.child_frame_id = frameId_;
466  poseMsg.header.frame_id = odomFrameId_;
467  poseMsg.header.stamp = stamp;
468  rtabmap_ros::transformToGeometryMsg(pose, poseMsg.transform);
469 
470  if(publishTf_)
471  {
472  if(!guessFrameId_.empty())
473  {
474  //publish correction of actual odometry so we have /odom -> /odom_guess -> /base_link
475  geometry_msgs::TransformStamped correctionMsg;
476  correctionMsg.child_frame_id = guessFrameId_;
477  correctionMsg.header.frame_id = odomFrameId_;
478  correctionMsg.header.stamp = stamp;
479  Transform correction = pose * guessCurrentPose.inverse();
480  rtabmap_ros::transformToGeometryMsg(correction, correctionMsg.transform);
481  tfBroadcaster_.sendTransform(correctionMsg);
482  }
483  else
484  {
485  tfBroadcaster_.sendTransform(poseMsg);
486  }
487  }
488 
490  {
491  //next, we'll publish the odometry message over ROS
492  nav_msgs::Odometry odom;
493  odom.header.stamp = stamp; // use corresponding time stamp to image
494  odom.header.frame_id = odomFrameId_;
495  odom.child_frame_id = frameId_;
496 
497  //set the position
498  odom.pose.pose.position.x = poseMsg.transform.translation.x;
499  odom.pose.pose.position.y = poseMsg.transform.translation.y;
500  odom.pose.pose.position.z = poseMsg.transform.translation.z;
501  odom.pose.pose.orientation = poseMsg.transform.rotation;
502 
503  //set covariance
504  // libviso2 uses approximately vel variance * 2
505  odom.pose.covariance.at(0) = info.reg.covariance.at<double>(0,0)*2; // xx
506  odom.pose.covariance.at(7) = info.reg.covariance.at<double>(1,1)*2; // yy
507  odom.pose.covariance.at(14) = info.reg.covariance.at<double>(2,2)*2; // zz
508  odom.pose.covariance.at(21) = info.reg.covariance.at<double>(3,3)*2; // rr
509  odom.pose.covariance.at(28) = info.reg.covariance.at<double>(4,4)*2; // pp
510  odom.pose.covariance.at(35) = info.reg.covariance.at<double>(5,5)*2; // yawyaw
511 
512  //set velocity
513  bool setTwist = !odometry_->previousVelocityTransform().isNull();
514  if(setTwist)
515  {
516  float x,y,z,roll,pitch,yaw;
518  odom.twist.twist.linear.x = x;
519  odom.twist.twist.linear.y = y;
520  odom.twist.twist.linear.z = z;
521  odom.twist.twist.angular.x = roll;
522  odom.twist.twist.angular.y = pitch;
523  odom.twist.twist.angular.z = yaw;
524  }
525 
526  odom.twist.covariance.at(0) = setTwist?info.reg.covariance.at<double>(0,0):BAD_COVARIANCE; // xx
527  odom.twist.covariance.at(7) = setTwist?info.reg.covariance.at<double>(1,1):BAD_COVARIANCE; // yy
528  odom.twist.covariance.at(14) = setTwist?info.reg.covariance.at<double>(2,2):BAD_COVARIANCE; // zz
529  odom.twist.covariance.at(21) = setTwist?info.reg.covariance.at<double>(3,3):BAD_COVARIANCE; // rr
530  odom.twist.covariance.at(28) = setTwist?info.reg.covariance.at<double>(4,4):BAD_COVARIANCE; // pp
531  odom.twist.covariance.at(35) = setTwist?info.reg.covariance.at<double>(5,5):BAD_COVARIANCE; // yawyaw
532 
533  //publish the message
534  if(setTwist || publishNullWhenLost_)
535  {
536  odomPub_.publish(odom);
537  }
538  }
539 
540  // local map / reference frame
541  if(odomLocalMap_.getNumSubscribers() && !info.localMap.empty())
542  {
543  pcl::PointCloud<pcl::PointXYZRGB> cloud;
544  for(std::map<int, cv::Point3f>::const_iterator iter=info.localMap.begin(); iter!=info.localMap.end(); ++iter)
545  {
546  bool inlier = info.words.find(iter->first) != info.words.end();
547  pcl::PointXYZRGB pt(inlier?0:255, 255, 0);
548  pt.x = iter->second.x;
549  pt.y = iter->second.y;
550  pt.z = iter->second.z;
551  cloud.push_back(pt);
552  }
553  sensor_msgs::PointCloud2 cloudMsg;
554  pcl::toROSMsg(cloud, cloudMsg);
555  cloudMsg.header.stamp = stamp; // use corresponding time stamp to image
556  cloudMsg.header.frame_id = odomFrameId_;
557  odomLocalMap_.publish(cloudMsg);
558  }
559 
561  {
562  // check which type of Odometry is using
563  if(odometry_->getType() == Odometry::kTypeF2M) // If it's Frame to Map Odometry
564  {
565  const std::multimap<int, cv::Point3f> & words3 = ((OdometryF2M*)odometry_)->getLastFrame().getWords3();
566  if(words3.size())
567  {
568  pcl::PointCloud<pcl::PointXYZ> cloud;
569  for(std::multimap<int, cv::Point3f>::const_iterator iter=words3.begin(); iter!=words3.end(); ++iter)
570  {
571  // transform to odom frame
572  cv::Point3f pt = util3d::transformPoint(iter->second, pose);
573  cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
574  }
575 
576  sensor_msgs::PointCloud2 cloudMsg;
577  pcl::toROSMsg(cloud, cloudMsg);
578  cloudMsg.header.stamp = stamp; // use corresponding time stamp to image
579  cloudMsg.header.frame_id = odomFrameId_;
580  odomLastFrame_.publish(cloudMsg);
581  }
582  }
583  else if(odometry_->getType() == Odometry::kTypeF2F) // if Using Frame to Frame Odometry
584  {
585  const Signature & refFrame = ((OdometryF2F*)odometry_)->getRefFrame();
586 
587  if(refFrame.getWords3().size())
588  {
589  pcl::PointCloud<pcl::PointXYZ> cloud;
590  for(std::multimap<int, cv::Point3f>::const_iterator iter=refFrame.getWords3().begin(); iter!=refFrame.getWords3().end(); ++iter)
591  {
592  // transform to odom frame
593  cv::Point3f pt = util3d::transformPoint(iter->second, pose);
594  cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
595  }
596  sensor_msgs::PointCloud2 cloudMsg;
597  pcl::toROSMsg(cloud, cloudMsg);
598  cloudMsg.header.stamp = stamp; // use corresponding time stamp to image
599  cloudMsg.header.frame_id = odomFrameId_;
600  odomLastFrame_.publish(cloudMsg);
601  }
602  }
603  }
604 
606  {
607  sensor_msgs::PointCloud2 cloudMsg;
608  if(info.localScanMap.hasNormals())
609  {
610  pcl::PointCloud<pcl::PointNormal>::Ptr cloud = util3d::laserScanToPointCloudNormal(info.localScanMap, info.localScanMap.localTransform());
611  pcl::toROSMsg(*cloud, cloudMsg);
612  }
613  else
614  {
615  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::laserScanToPointCloud(info.localScanMap, info.localScanMap.localTransform());
616  pcl::toROSMsg(*cloud, cloudMsg);
617  }
618 
619  cloudMsg.header.stamp = stamp; // use corresponding time stamp to image
620  cloudMsg.header.frame_id = odomFrameId_;
621  odomLocalScanMap_.publish(cloudMsg);
622  }
623  }
624  else if(data.imageRaw().empty() && !data.imu().empty())
625  {
626  return;
627  }
628  else if(publishNullWhenLost_)
629  {
630  //NODELET_WARN( "Odometry lost!");
631 
632  //send null pose to notify that odometry is lost
633  nav_msgs::Odometry odom;
634  odom.header.stamp = stamp; // use corresponding time stamp to image
635  odom.header.frame_id = odomFrameId_;
636  odom.child_frame_id = frameId_;
637  odom.pose.covariance.at(0) = BAD_COVARIANCE; // xx
638  odom.pose.covariance.at(7) = BAD_COVARIANCE; // yy
639  odom.pose.covariance.at(14) = BAD_COVARIANCE; // zz
640  odom.pose.covariance.at(21) = BAD_COVARIANCE; // rr
641  odom.pose.covariance.at(28) = BAD_COVARIANCE; // pp
642  odom.pose.covariance.at(35) = BAD_COVARIANCE; // yawyaw
643  odom.twist.covariance.at(0) = BAD_COVARIANCE; // xx
644  odom.twist.covariance.at(7) = BAD_COVARIANCE; // yy
645  odom.twist.covariance.at(14) = BAD_COVARIANCE; // zz
646  odom.twist.covariance.at(21) = BAD_COVARIANCE; // rr
647  odom.twist.covariance.at(28) = BAD_COVARIANCE; // pp
648  odom.twist.covariance.at(35) = BAD_COVARIANCE; // yawyaw
649 
650  //publish the message
651  odomPub_.publish(odom);
652  }
653 
654  if(pose.isNull() && resetCurrentCount_ > 0)
655  {
656  NODELET_WARN( "Odometry lost! Odometry will be reset after next %d consecutive unsuccessful odometry updates...", resetCurrentCount_);
657 
659  if(resetCurrentCount_ == 0)
660  {
661  // Check TF to see if sensor fusion is used (e.g., the output of robot_localization)
662  Transform tfPose = this->getTransform(odomFrameId_, frameId_, stamp);
663  if(tfPose.isNull())
664  {
665  NODELET_WARN( "Odometry automatically reset to latest computed pose!");
667  }
668  else
669  {
670  NODELET_WARN( "Odometry automatically reset to latest odometry pose available from TF (%s->%s)!",
671  odomFrameId_.c_str(), frameId_.c_str());
672  odometry_->reset(tfPose);
673  }
674 
675  }
676  }
677 
679  {
680  rtabmap_ros::OdomInfo infoMsg;
681  odomInfoToROS(info, infoMsg);
682  infoMsg.header.stamp = stamp; // use corresponding time stamp to image
683  infoMsg.header.frame_id = odomFrameId_;
684  odomInfoPub_.publish(infoMsg);
685  }
686 
687  if(!data.imageRaw().empty())
688  {
689  if(visParams_)
690  {
691  if(icpParams_)
692  {
693  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());
694  }
695  else
696  {
697  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());
698  }
699  }
700  else
701  {
702  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());
703  }
704  }
705 }
706 
707 bool OdometryROS::reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
708 {
709  NODELET_INFO( "visual_odometry: reset odom!");
710  odometry_->reset();
711  guess_.setNull();
712  guessStamp_ = 0.0;
714  this->flushCallbacks();
715  return true;
716 }
717 
718 bool OdometryROS::resetToPose(rtabmap_ros::ResetPose::Request& req, rtabmap_ros::ResetPose::Response&)
719 {
720  Transform pose(req.x, req.y, req.z, req.roll, req.pitch, req.yaw);
721  NODELET_INFO( "visual_odometry: reset odom to pose %s!", pose.prettyPrint().c_str());
722  odometry_->reset(pose);
723  guess_.setNull();
724  guessStamp_ = 0.0;
726  this->flushCallbacks();
727  return true;
728 }
729 
730 bool OdometryROS::pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
731 {
732  if(paused_)
733  {
734  NODELET_WARN( "visual_odometry: Already paused!");
735  }
736  else
737  {
738  paused_ = true;
739  NODELET_INFO( "visual_odometry: paused!");
740  }
741  return true;
742 }
743 
744 bool OdometryROS::resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
745 {
746  if(!paused_)
747  {
748  NODELET_WARN( "visual_odometry: Already running!");
749  }
750  else
751  {
752  paused_ = false;
753  NODELET_INFO( "visual_odometry: resumed!");
754  }
755  return true;
756 }
757 
758 bool OdometryROS::setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
759 {
760  NODELET_INFO( "visual_odometry: Set log level to Debug");
762  return true;
763 }
764 bool OdometryROS::setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
765 {
766  NODELET_INFO( "visual_odometry: Set log level to Info");
768  return true;
769 }
770 bool OdometryROS::setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
771 {
772  NODELET_INFO( "visual_odometry: Set log level to Warning");
774  return true;
775 }
776 bool OdometryROS::setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
777 {
778  NODELET_INFO( "visual_odometry: Set log level to Error");
780  return true;
781 }
782 
783 
784 }
const std::multimap< int, cv::Point3f > & getWords3() const
std::string groundTruthBaseFrameId_
Definition: OdometryROS.h:98
static std::string homeDir()
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
const rtabmap::ParametersMap & parameters() const
Definition: OdometryROS.h:72
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 odomFrameId_
Definition: OdometryROS.h:96
void processData(const rtabmap::SensorData &data, const ros::Time &stamp)
std::string uReplaceChar(const std::string &str, char before, char after)
std::vector< double > values
virtual void reset(const Transform &initialPose=Transform::getIdentity())
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition: OdometryROS.h:121
std::map< int, cv::Point3f > localMap
bool deleteParam(const std::string &key) const
virtual void updateParameters(rtabmap::ParametersMap &parameters)
Definition: OdometryROS.h:87
boost::thread * warningThread_
Definition: OdometryROS.h:91
ros::Publisher odomLocalScanMap_
Definition: OdometryROS.h:111
bool sleep() const
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:118
bool isEmpty() const
#define BAD_COVARIANCE
Definition: OdometryROS.cpp:54
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:97
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
ros::ServiceServer setLogDebugSrv_
Definition: OdometryROS.h:117
const cv::Mat & imageRaw() const
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:108
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:119
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
const Transform & previousVelocityTransform() const
ros::ServiceServer resetToPoseSrv_
Definition: OdometryROS.h:114
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
bool resume(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
rtabmap::ParametersMap parameters_
Definition: OdometryROS.h:106
ros::ServiceServer setLogErrorSrv_
Definition: OdometryROS.h:120
bool setLogError(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void startWarningThread(const std::string &subscribedTopicsMsg, bool approxSync)
virtual void flushCallbacks()=0
ros::ServiceServer resetSrv_
Definition: OdometryROS.h:113
Transform localTransform() const
ros::ServiceServer pauseSrv_
Definition: OdometryROS.h:115
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
ros::ServiceServer resumeSrv_
Definition: OdometryROS.h:116
ros::Publisher odomLocalMap_
Definition: OdometryROS.h:110
void sendTransform(const geometry_msgs::TransformStamped &transform)
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
#define false
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
std::multimap< int, cv::KeyPoint > words
static WallTime now()
bool exists()
rtabmap::Odometry * odometry_
Definition: OdometryROS.h:90
ros::Publisher odomInfoPub_
Definition: OdometryROS.h:109
tf::TransformListener tfListener_
Definition: OdometryROS.h:122
bool getParam(const std::string &key, std::string &s) const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
rtabmap::Transform guess_
Definition: OdometryROS.h:130
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)
std::string guessFrameId_
Definition: OdometryROS.h:99
RegistrationInfo reg
bool ok() const
Transform inverse() const
bool hasParam(const std::string &key) const
bool resetToPose(rtabmap_ros::ResetPose::Request &, rtabmap_ros::ResetPose::Response &)
r
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
ros::Publisher odomLastFrame_
Definition: OdometryROS.h:112
rtabmap::Transform transformFromTF(const tf::Transform &transform)
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04