OdometryROS.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap_ros/OdometryROS.h"
00029 
00030 #include <sensor_msgs/Image.h>
00031 #include <sensor_msgs/image_encodings.h>
00032 #include <sensor_msgs/PointCloud2.h>
00033 #include <nav_msgs/Odometry.h>
00034 
00035 #include <pcl_conversions/pcl_conversions.h>
00036 
00037 #include <cv_bridge/cv_bridge.h>
00038 
00039 #include <rtabmap/core/Rtabmap.h>
00040 #include <rtabmap/core/OdometryF2M.h>
00041 #include <rtabmap/core/OdometryF2F.h>
00042 #include <rtabmap/core/util3d.h>
00043 #include <rtabmap/core/util3d_transforms.h>
00044 #include <rtabmap/core/Memory.h>
00045 #include <rtabmap/core/Signature.h>
00046 #include "rtabmap_ros/MsgConversion.h"
00047 #include "rtabmap_ros/OdomInfo.h"
00048 #include "rtabmap/utilite/UConversion.h"
00049 #include "rtabmap/utilite/ULogger.h"
00050 #include "rtabmap/utilite/UStl.h"
00051 #include "rtabmap/utilite/UFile.h"
00052 #include "rtabmap/utilite/UMath.h"
00053 
00054 #define BAD_COVARIANCE 9999
00055 
00056 using namespace rtabmap;
00057 
00058 namespace rtabmap_ros {
00059 
00060 OdometryROS::OdometryROS(bool stereoParams, bool visParams, bool icpParams) :
00061         odometry_(0),
00062         warningThread_(0),
00063         callbackCalled_(false),
00064         frameId_("base_link"),
00065         odomFrameId_("odom"),
00066         groundTruthFrameId_(""),
00067         groundTruthBaseFrameId_(""),
00068         guessFrameId_(""),
00069         guessMinTranslation_(0.0),
00070         guessMinRotation_(0.0),
00071         publishTf_(true),
00072         waitForTransform_(true),
00073         waitForTransformDuration_(0.1), // 100 ms
00074         publishNullWhenLost_(true),
00075         paused_(false),
00076         resetCountdown_(0),
00077         resetCurrentCount_(0),
00078         stereoParams_(stereoParams),
00079         visParams_(visParams),
00080         icpParams_(icpParams),
00081         guessStamp_(0.0)
00082 {
00083 
00084 }
00085 
00086 OdometryROS::~OdometryROS()
00087 {
00088         if(warningThread_)
00089         {
00090                 callbackCalled();
00091                 warningThread_->join();
00092                 delete warningThread_;
00093         }
00094         ros::NodeHandle & pnh = getPrivateNodeHandle();
00095         if(pnh.ok())
00096         {
00097                 for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
00098                 {
00099                         pnh.deleteParam(iter->first);
00100                 }
00101         }
00102 
00103         delete odometry_;
00104 }
00105 
00106 void OdometryROS::onInit()
00107 {
00108         ros::NodeHandle & nh = getNodeHandle();
00109         ros::NodeHandle & pnh = getPrivateNodeHandle();
00110 
00111         odomPub_ = nh.advertise<nav_msgs::Odometry>("odom", 1);
00112         odomInfoPub_ = nh.advertise<rtabmap_ros::OdomInfo>("odom_info", 1);
00113         odomLocalMap_ = nh.advertise<sensor_msgs::PointCloud2>("odom_local_map", 1);
00114         odomLocalScanMap_ = nh.advertise<sensor_msgs::PointCloud2>("odom_local_scan_map", 1);
00115         odomLastFrame_ = nh.advertise<sensor_msgs::PointCloud2>("odom_last_frame", 1);
00116 
00117         Transform initialPose = Transform::getIdentity();
00118         std::string initialPoseStr;
00119         std::string configPath;
00120         pnh.param("frame_id", frameId_, frameId_);
00121         pnh.param("odom_frame_id", odomFrameId_, odomFrameId_);
00122         pnh.param("publish_tf", publishTf_, publishTf_);
00123         if(pnh.hasParam("tf_prefix"))
00124         {
00125                 NODELET_ERROR("tf_prefix parameter has been removed, use directly odom_frame_id and frame_id parameters.");
00126         }
00127         pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
00128         pnh.param("wait_for_transform_duration",  waitForTransformDuration_, waitForTransformDuration_);
00129         pnh.param("initial_pose", initialPoseStr, initialPoseStr); // "x y z roll pitch yaw"
00130         pnh.param("ground_truth_frame_id", groundTruthFrameId_, groundTruthFrameId_);
00131         pnh.param("ground_truth_base_frame_id", groundTruthBaseFrameId_, frameId_);
00132         pnh.param("config_path", configPath, configPath);
00133         pnh.param("publish_null_when_lost", publishNullWhenLost_, publishNullWhenLost_);
00134         if(pnh.hasParam("guess_from_tf"))
00135         {
00136                 if(!pnh.hasParam("guess_frame_id"))
00137                 {
00138                         NODELET_ERROR("Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
00139                 }
00140                 else
00141                 {
00142                         NODELET_WARN("Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
00143                 }
00144         }
00145         pnh.param("guess_frame_id", guessFrameId_, guessFrameId_); // odometry guess frame
00146         pnh.param("guess_min_translation", guessMinTranslation_, guessMinTranslation_);
00147         pnh.param("guess_min_rotation", guessMinRotation_, guessMinRotation_);
00148 
00149         if(publishTf_ && !guessFrameId_.empty() && guessFrameId_.compare(odomFrameId_) == 0)
00150         {
00151                 NODELET_WARN( "\"publish_tf\" and \"guess_frame_id\" cannot be used "
00152                                 "at the same time if \"guess_frame_id\" and \"odom_frame_id\" "
00153                                 "are the same frame (value=\"%s\"). \"guess_frame_id\" is disabled.", odomFrameId_.c_str());
00154                 guessFrameId_.clear();
00155         }
00156         NODELET_INFO("Odometry: frame_id               = %s", frameId_.c_str());
00157         NODELET_INFO("Odometry: odom_frame_id          = %s", odomFrameId_.c_str());
00158         NODELET_INFO("Odometry: publish_tf             = %s", publishTf_?"true":"false");
00159         NODELET_INFO("Odometry: wait_for_transform     = %s", waitForTransform_?"true":"false");
00160         NODELET_INFO("Odometry: wait_for_transform_duration  = %f", waitForTransformDuration_);
00161         NODELET_INFO("Odometry: initial_pose           = %s", initialPose.prettyPrint().c_str());
00162         NODELET_INFO("Odometry: ground_truth_frame_id  = %s", groundTruthFrameId_.c_str());
00163         NODELET_INFO("Odometry: ground_truth_base_frame_id = %s", groundTruthBaseFrameId_.c_str());
00164         NODELET_INFO("Odometry: config_path            = %s", configPath.c_str());
00165         NODELET_INFO("Odometry: publish_null_when_lost = %s", publishNullWhenLost_?"true":"false");
00166         NODELET_INFO("Odometry: guess_frame_id         = %s", guessFrameId_.c_str());
00167         NODELET_INFO("Odometry: guess_min_translation  = %f", guessMinTranslation_);
00168         NODELET_INFO("Odometry: guess_min_rotation     = %f", guessMinRotation_);
00169 
00170         configPath = uReplaceChar(configPath, '~', UDirectory::homeDir());
00171         if(configPath.size() && configPath.at(0) != '/')
00172         {
00173                 configPath = UDirectory::currentDir(true) + configPath;
00174         }
00175 
00176         if(initialPoseStr.size())
00177         {
00178                 std::vector<std::string> values = uListToVector(uSplit(initialPoseStr, ' '));
00179                 if(values.size() == 6)
00180                 {
00181                         initialPose = Transform(
00182                                         uStr2Float(values[0]), uStr2Float(values[1]), uStr2Float(values[2]),
00183                                         uStr2Float(values[3]), uStr2Float(values[4]), uStr2Float(values[5]));
00184                 }
00185                 else
00186                 {
00187                         NODELET_ERROR( "Wrong initial_pose format: %s (should be \"x y z roll pitch yaw\" with angle in radians). "
00188                                           "Identity will be used...", initialPoseStr.c_str());
00189                 }
00190         }
00191 
00192 
00193         //parameters
00194         parameters_ = Parameters::getDefaultOdometryParameters(stereoParams_, visParams_, icpParams_);
00195         parameters_.insert(*Parameters::getDefaultParameters().find(Parameters::kRtabmapImagesAlreadyRectified()));
00196         if(!configPath.empty())
00197         {
00198                 if(UFile::exists(configPath.c_str()))
00199                 {
00200                         NODELET_INFO( "Odometry: Loading parameters from %s", configPath.c_str());
00201                         rtabmap::ParametersMap allParameters;
00202                         Parameters::readINI(configPath.c_str(), allParameters);
00203                         // only update odometry parameters
00204                         for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
00205                         {
00206                                 ParametersMap::iterator jter = allParameters.find(iter->first);
00207                                 if(jter!=allParameters.end())
00208                                 {
00209                                         iter->second = jter->second;
00210                                 }
00211                         }
00212                 }
00213                 else
00214                 {
00215                         NODELET_ERROR( "Config file \"%s\" not found!", configPath.c_str());
00216                 }
00217         }
00218         for(rtabmap::ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
00219         {
00220                 std::string vStr;
00221                 bool vBool;
00222                 int vInt;
00223                 double vDouble;
00224                 if(pnh.getParam(iter->first, vStr))
00225                 {
00226                         NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
00227                         iter->second = vStr;
00228                 }
00229                 else if(pnh.getParam(iter->first, vBool))
00230                 {
00231                         NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
00232                         iter->second = uBool2Str(vBool);
00233                 }
00234                 else if(pnh.getParam(iter->first, vDouble))
00235                 {
00236                         NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble).c_str());
00237                         iter->second = uNumber2Str(vDouble);
00238                 }
00239                 else if(pnh.getParam(iter->first, vInt))
00240                 {
00241                         NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
00242                         iter->second = uNumber2Str(vInt);
00243                 }
00244 
00245                 if(iter->first.compare(Parameters::kVisMinInliers()) == 0 && atoi(iter->second.c_str()) < 8)
00246                 {
00247                         NODELET_WARN( "Parameter min_inliers must be >= 8, setting to 8...");
00248                         iter->second = uNumber2Str(8);
00249                 }
00250         }
00251 
00252         std::vector<std::string> argList = getMyArgv();
00253         char * argv[argList.size()];
00254         for(unsigned int i=0; i<argList.size(); ++i)
00255         {
00256                 argv[i] = &argList[i].at(0);
00257         }
00258 
00259         rtabmap::ParametersMap parameters = rtabmap::Parameters::parseArguments(argList.size(), argv);
00260         for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00261         {
00262                 rtabmap::ParametersMap::iterator jter = parameters_.find(iter->first);
00263                 if(jter!=parameters_.end())
00264                 {
00265                         NODELET_INFO( "Update odometry parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
00266                         jter->second = iter->second;
00267                 }
00268         }
00269 
00270         // Backward compatibility
00271         for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=Parameters::getRemovedParameters().begin();
00272                 iter!=Parameters::getRemovedParameters().end();
00273                 ++iter)
00274         {
00275                 std::string vStr;
00276                 if(pnh.getParam(iter->first, vStr))
00277                 {
00278                         if(iter->second.first && parameters_.find(iter->second.second) != parameters_.end())
00279                         {
00280                                 // can be migrated
00281                                 parameters_.at(iter->second.second)= vStr;
00282                                 NODELET_WARN( "Odometry: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
00283                                                 iter->first.c_str(), iter->second.second.c_str(), vStr.c_str());
00284                         }
00285                         else
00286                         {
00287                                 if(iter->second.second.empty())
00288                                 {
00289                                         NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore!",
00290                                                         iter->first.c_str());
00291                                 }
00292                                 else
00293                                 {
00294                                         NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
00295                                                         iter->first.c_str(), iter->second.second.c_str());
00296                                 }
00297                         }
00298                 }
00299         }
00300 
00301         Parameters::parse(parameters_, Parameters::kOdomResetCountdown(), resetCountdown_);
00302         parameters_.at(Parameters::kOdomResetCountdown()) = "0"; // use modified reset countdown here
00303 
00304         this->updateParameters(parameters_);
00305 
00306         odometry_ = Odometry::create(parameters_);
00307         if(!initialPose.isIdentity())
00308         {
00309                 odometry_->reset(initialPose);
00310         }
00311 
00312         resetSrv_ = nh.advertiseService("reset_odom", &OdometryROS::reset, this);
00313         resetToPoseSrv_ = nh.advertiseService("reset_odom_to_pose", &OdometryROS::resetToPose, this);
00314         pauseSrv_ = nh.advertiseService("pause_odom", &OdometryROS::pause, this);
00315         resumeSrv_ = nh.advertiseService("resume_odom", &OdometryROS::resume, this);
00316 
00317         setLogDebugSrv_ = pnh.advertiseService("log_debug", &OdometryROS::setLogDebug, this);
00318         setLogInfoSrv_ = pnh.advertiseService("log_info", &OdometryROS::setLogInfo, this);
00319         setLogWarnSrv_ = pnh.advertiseService("log_warning", &OdometryROS::setLogWarn, this);
00320         setLogErrorSrv_ = pnh.advertiseService("log_error", &OdometryROS::setLogError, this);
00321 
00322         onOdomInit();
00323 }
00324 
00325 void OdometryROS::startWarningThread(const std::string & subscribedTopicsMsg, bool approxSync)
00326 {
00327         warningThread_ = new boost::thread(boost::bind(&OdometryROS::warningLoop, this, subscribedTopicsMsg, approxSync));
00328         NODELET_INFO("%s", subscribedTopicsMsg.c_str());
00329 }
00330 
00331 void OdometryROS::warningLoop(const std::string & subscribedTopicsMsg, bool approxSync)
00332 {
00333         ros::Duration r(5.0);
00334         while(!callbackCalled_)
00335         {
00336                 r.sleep();
00337                 if(!callbackCalled_)
00338                 {
00339                         ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
00340                                         "published (\"$ rostopic hz my_topic\") and the timestamps in their "
00341                                         "header are set. %s%s",
00342                                         getName().c_str(),
00343                                         approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
00344                                                 "topics should have all the exact timestamp for the callback to be called.",
00345                                         subscribedTopicsMsg.c_str());
00346                 }
00347         }
00348 }
00349 
00350 Transform OdometryROS::getTransform(const std::string & fromFrameId, const std::string & toFrameId, const ros::Time & stamp) const
00351 {
00352         // TF ready?
00353         Transform transform;
00354         try
00355         {
00356                 if(waitForTransform_ && !stamp.isZero() && waitForTransformDuration_ > 0.0)
00357                 {
00358                         //if(!tfBuffer_.canTransform(fromFrameId, toFrameId, stamp, ros::Duration(1)))
00359                         std::string errorMsg;
00360                         if(!tfListener_.waitForTransform(fromFrameId, toFrameId, stamp, ros::Duration(waitForTransformDuration_), ros::Duration(0.01), &errorMsg))
00361                         {
00362                                 NODELET_WARN( "odometry: Could not get transform from %s to %s (stamp=%f) after %f seconds (\"wait_for_transform_duration\"=%f)! Error=\"%s\"",
00363                                                 fromFrameId.c_str(), toFrameId.c_str(), stamp.toSec(), waitForTransformDuration_, waitForTransformDuration_, errorMsg.c_str());
00364                                 return transform;
00365                         }
00366                 }
00367 
00368                 tf::StampedTransform tmp;
00369                 tfListener_.lookupTransform(fromFrameId, toFrameId, stamp, tmp);
00370                 transform = rtabmap_ros::transformFromTF(tmp);
00371         }
00372         catch(tf::TransformException & ex)
00373         {
00374                 NODELET_WARN( "%s",ex.what());
00375         }
00376         return transform;
00377 }
00378 
00379 void OdometryROS::processData(const SensorData & data, const ros::Time & stamp)
00380 {
00381         if(!data.imageRaw().empty())
00382         {
00383                 if(odometry_->getPose().isIdentity() &&
00384                    !groundTruthFrameId_.empty())
00385                 {
00386                         // sync with the first value of the ground truth
00387                         Transform initialPose = getTransform(groundTruthFrameId_, groundTruthBaseFrameId_, stamp);
00388                         if(initialPose.isNull())
00389                         {
00390                                 NODELET_WARN("Ground truth frames \"%s\" -> \"%s\" are set but failed to "
00391                                                 "get them, odometry won't be synchronized with ground truth.",
00392                                                 groundTruthFrameId_.c_str(), groundTruthBaseFrameId_.c_str());
00393                         }
00394                         else
00395                         {
00396                                 NODELET_INFO( "Initializing odometry pose to %s (from \"%s\" -> \"%s\")",
00397                                                 initialPose.prettyPrint().c_str(),
00398                                                 groundTruthFrameId_.c_str(),
00399                                                 groundTruthBaseFrameId_.c_str());
00400                                 odometry_->reset(initialPose);
00401                         }
00402                 }
00403         }
00404 
00405         Transform guessCurrentPose;
00406         if(!guessFrameId_.empty())
00407         {
00408                 Transform previousPose = this->getTransform(guessFrameId_, frameId_, guessStamp_>0.0?ros::Time(guessStamp_):stamp);
00409                 guessCurrentPose = this->getTransform(guessFrameId_, frameId_, stamp);
00410                 if(!previousPose.isNull() && !guessCurrentPose.isNull())
00411                 {
00412                         if(guess_.isNull())
00413                         {
00414                                 guess_ = previousPose.inverse() * guessCurrentPose;
00415                         }
00416                         else
00417                         {
00418                                 guess_ = guess_ * previousPose.inverse() * guessCurrentPose;
00419                         }
00420                         if(guessStamp_>0.0 && (guessMinTranslation_ > 0.0 || guessMinRotation_ > 0.0))
00421                         {
00422                                 float x,y,z,roll,pitch,yaw;
00423                                 guess_.getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
00424                                 if((guessMinTranslation_ <= 0.0 || uMax3(fabs(x), fabs(y), fabs(z)) < guessMinTranslation_) &&
00425                                    (guessMinRotation_ <= 0.0 || uMax3(fabs(roll), fabs(pitch), fabs(yaw)) < guessMinRotation_))
00426                                 {
00427                                         // Ignore odometry update, we didn't move enough
00428                                         if(publishTf_)
00429                                         {
00430                                                 geometry_msgs::TransformStamped correctionMsg;
00431                                                 correctionMsg.child_frame_id = guessFrameId_;
00432                                                 correctionMsg.header.frame_id = odomFrameId_;
00433                                                 correctionMsg.header.stamp = stamp;
00434                                                 Transform correction = odometry_->getPose() * guess_ * guessCurrentPose.inverse();
00435                                                 rtabmap_ros::transformToGeometryMsg(correction, correctionMsg.transform);
00436                                                 tfBroadcaster_.sendTransform(correctionMsg);
00437                                         }
00438                                         guessStamp_ = stamp.toSec();
00439                                         return;
00440                                 }
00441                         }
00442                         guessStamp_ = stamp.toSec();
00443                 }
00444                 else
00445                 {
00446                         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());
00447                         return;
00448                 }
00449         }
00450 
00451         // process data
00452         ros::WallTime time = ros::WallTime::now();
00453         rtabmap::OdometryInfo info;
00454         SensorData dataCpy = data;
00455         rtabmap::Transform pose = odometry_->process(dataCpy, guess_, &info);
00456         guess_.setNull();
00457         if(!pose.isNull())
00458         {
00459                 resetCurrentCount_ = resetCountdown_;
00460 
00461                 //*********************
00462                 // Update odometry
00463                 //*********************
00464                 geometry_msgs::TransformStamped poseMsg;
00465                 poseMsg.child_frame_id = frameId_;
00466                 poseMsg.header.frame_id = odomFrameId_;
00467                 poseMsg.header.stamp = stamp;
00468                 rtabmap_ros::transformToGeometryMsg(pose, poseMsg.transform);
00469 
00470                 if(publishTf_)
00471                 {
00472                         if(!guessFrameId_.empty())
00473                         {
00474                                 //publish correction of actual odometry so we have /odom -> /odom_guess -> /base_link
00475                                 geometry_msgs::TransformStamped correctionMsg;
00476                                 correctionMsg.child_frame_id = guessFrameId_;
00477                                 correctionMsg.header.frame_id = odomFrameId_;
00478                                 correctionMsg.header.stamp = stamp;
00479                                 Transform correction = pose * guessCurrentPose.inverse();
00480                                 rtabmap_ros::transformToGeometryMsg(correction, correctionMsg.transform);
00481                                 tfBroadcaster_.sendTransform(correctionMsg);
00482                         }
00483                         else
00484                         {
00485                                 tfBroadcaster_.sendTransform(poseMsg);
00486                         }
00487                 }
00488 
00489                 if(odomPub_.getNumSubscribers())
00490                 {
00491                         //next, we'll publish the odometry message over ROS
00492                         nav_msgs::Odometry odom;
00493                         odom.header.stamp = stamp; // use corresponding time stamp to image
00494                         odom.header.frame_id = odomFrameId_;
00495                         odom.child_frame_id = frameId_;
00496 
00497                         //set the position
00498                         odom.pose.pose.position.x = poseMsg.transform.translation.x;
00499                         odom.pose.pose.position.y = poseMsg.transform.translation.y;
00500                         odom.pose.pose.position.z = poseMsg.transform.translation.z;
00501                         odom.pose.pose.orientation = poseMsg.transform.rotation;
00502 
00503                         //set covariance
00504                         // libviso2 uses approximately vel variance * 2
00505                         odom.pose.covariance.at(0) = info.reg.covariance.at<double>(0,0)*2;  // xx
00506                         odom.pose.covariance.at(7) = info.reg.covariance.at<double>(1,1)*2;  // yy
00507                         odom.pose.covariance.at(14) = info.reg.covariance.at<double>(2,2)*2; // zz
00508                         odom.pose.covariance.at(21) = info.reg.covariance.at<double>(3,3)*2; // rr
00509                         odom.pose.covariance.at(28) = info.reg.covariance.at<double>(4,4)*2; // pp
00510                         odom.pose.covariance.at(35) = info.reg.covariance.at<double>(5,5)*2; // yawyaw
00511 
00512                         //set velocity
00513                         bool setTwist = !odometry_->previousVelocityTransform().isNull();
00514                         if(setTwist)
00515                         {
00516                                 float x,y,z,roll,pitch,yaw;
00517                                 odometry_->previousVelocityTransform().getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
00518                                 odom.twist.twist.linear.x = x;
00519                                 odom.twist.twist.linear.y = y;
00520                                 odom.twist.twist.linear.z = z;
00521                                 odom.twist.twist.angular.x = roll;
00522                                 odom.twist.twist.angular.y = pitch;
00523                                 odom.twist.twist.angular.z = yaw;
00524                         }
00525 
00526                         odom.twist.covariance.at(0) = setTwist?info.reg.covariance.at<double>(0,0):BAD_COVARIANCE;  // xx
00527                         odom.twist.covariance.at(7) = setTwist?info.reg.covariance.at<double>(1,1):BAD_COVARIANCE;  // yy
00528                         odom.twist.covariance.at(14) = setTwist?info.reg.covariance.at<double>(2,2):BAD_COVARIANCE; // zz
00529                         odom.twist.covariance.at(21) = setTwist?info.reg.covariance.at<double>(3,3):BAD_COVARIANCE; // rr
00530                         odom.twist.covariance.at(28) = setTwist?info.reg.covariance.at<double>(4,4):BAD_COVARIANCE; // pp
00531                         odom.twist.covariance.at(35) = setTwist?info.reg.covariance.at<double>(5,5):BAD_COVARIANCE; // yawyaw
00532 
00533                         //publish the message
00534                         if(setTwist || publishNullWhenLost_)
00535                         {
00536                                 odomPub_.publish(odom);
00537                         }
00538                 }
00539 
00540                 // local map / reference frame
00541                 if(odomLocalMap_.getNumSubscribers() && !info.localMap.empty())
00542                 {
00543                         pcl::PointCloud<pcl::PointXYZRGB> cloud;
00544                         for(std::map<int, cv::Point3f>::const_iterator iter=info.localMap.begin(); iter!=info.localMap.end(); ++iter)
00545                         {
00546                                 bool inlier = info.words.find(iter->first) != info.words.end();
00547                                 pcl::PointXYZRGB pt(inlier?0:255, 255, 0);
00548                                 pt.x = iter->second.x;
00549                                 pt.y = iter->second.y;
00550                                 pt.z = iter->second.z;
00551                                 cloud.push_back(pt);
00552                         }
00553                         sensor_msgs::PointCloud2 cloudMsg;
00554                         pcl::toROSMsg(cloud, cloudMsg);
00555                         cloudMsg.header.stamp = stamp; // use corresponding time stamp to image
00556                         cloudMsg.header.frame_id = odomFrameId_;
00557                         odomLocalMap_.publish(cloudMsg);
00558                 }
00559 
00560                 if(odomLastFrame_.getNumSubscribers())
00561                 {
00562                         // check which type of Odometry is using
00563                         if(odometry_->getType() == Odometry::kTypeF2M) // If it's Frame to Map Odometry
00564                         {
00565                                 const std::multimap<int, cv::Point3f> & words3  = ((OdometryF2M*)odometry_)->getLastFrame().getWords3();
00566                                 if(words3.size())
00567                                 {
00568                                         pcl::PointCloud<pcl::PointXYZ> cloud;
00569                                         for(std::multimap<int, cv::Point3f>::const_iterator iter=words3.begin(); iter!=words3.end(); ++iter)
00570                                         {
00571                                                 // transform to odom frame
00572                                                 cv::Point3f pt = util3d::transformPoint(iter->second, pose);
00573                                                 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
00574                                         }
00575 
00576                                         sensor_msgs::PointCloud2 cloudMsg;
00577                                         pcl::toROSMsg(cloud, cloudMsg);
00578                                         cloudMsg.header.stamp = stamp; // use corresponding time stamp to image
00579                                         cloudMsg.header.frame_id = odomFrameId_;
00580                                         odomLastFrame_.publish(cloudMsg);
00581                                 }
00582                         }
00583                         else if(odometry_->getType() == Odometry::kTypeF2F) // if Using Frame to Frame Odometry
00584                         {
00585                                 const Signature & refFrame = ((OdometryF2F*)odometry_)->getRefFrame();
00586 
00587                                 if(refFrame.getWords3().size())
00588                                 {
00589                                         pcl::PointCloud<pcl::PointXYZ> cloud;
00590                                         for(std::multimap<int, cv::Point3f>::const_iterator iter=refFrame.getWords3().begin(); iter!=refFrame.getWords3().end(); ++iter)
00591                                         {
00592                                                 // transform to odom frame
00593                                                 cv::Point3f pt = util3d::transformPoint(iter->second, pose);
00594                                                 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
00595                                         }
00596                                         sensor_msgs::PointCloud2 cloudMsg;
00597                                         pcl::toROSMsg(cloud, cloudMsg);
00598                                         cloudMsg.header.stamp = stamp; // use corresponding time stamp to image
00599                                         cloudMsg.header.frame_id = odomFrameId_;
00600                                         odomLastFrame_.publish(cloudMsg);
00601                                 }
00602                         }
00603                 }
00604 
00605                 if(odomLocalScanMap_.getNumSubscribers() && !info.localScanMap.isEmpty())
00606                 {
00607                         sensor_msgs::PointCloud2 cloudMsg;
00608                         if(info.localScanMap.hasNormals())
00609                         {
00610                                 pcl::PointCloud<pcl::PointNormal>::Ptr cloud = util3d::laserScanToPointCloudNormal(info.localScanMap, info.localScanMap.localTransform());
00611                                 pcl::toROSMsg(*cloud, cloudMsg);
00612                         }
00613                         else
00614                         {
00615                                 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::laserScanToPointCloud(info.localScanMap, info.localScanMap.localTransform());
00616                                 pcl::toROSMsg(*cloud, cloudMsg);
00617                         }
00618 
00619                         cloudMsg.header.stamp = stamp; // use corresponding time stamp to image
00620                         cloudMsg.header.frame_id = odomFrameId_;
00621                         odomLocalScanMap_.publish(cloudMsg);
00622                 }
00623         }
00624         else if(data.imageRaw().empty() && !data.imu().empty())
00625         {
00626                 return;
00627         }
00628         else if(publishNullWhenLost_)
00629         {
00630                 //NODELET_WARN( "Odometry lost!");
00631 
00632                 //send null pose to notify that odometry is lost
00633                 nav_msgs::Odometry odom;
00634                 odom.header.stamp = stamp; // use corresponding time stamp to image
00635                 odom.header.frame_id = odomFrameId_;
00636                 odom.child_frame_id = frameId_;
00637                 odom.pose.covariance.at(0) = BAD_COVARIANCE;  // xx
00638                 odom.pose.covariance.at(7) = BAD_COVARIANCE;  // yy
00639                 odom.pose.covariance.at(14) = BAD_COVARIANCE; // zz
00640                 odom.pose.covariance.at(21) = BAD_COVARIANCE; // rr
00641                 odom.pose.covariance.at(28) = BAD_COVARIANCE; // pp
00642                 odom.pose.covariance.at(35) = BAD_COVARIANCE; // yawyaw
00643                 odom.twist.covariance.at(0) = BAD_COVARIANCE;  // xx
00644                 odom.twist.covariance.at(7) = BAD_COVARIANCE;  // yy
00645                 odom.twist.covariance.at(14) = BAD_COVARIANCE; // zz
00646                 odom.twist.covariance.at(21) = BAD_COVARIANCE; // rr
00647                 odom.twist.covariance.at(28) = BAD_COVARIANCE; // pp
00648                 odom.twist.covariance.at(35) = BAD_COVARIANCE; // yawyaw
00649 
00650                 //publish the message
00651                 odomPub_.publish(odom);
00652         }
00653 
00654         if(pose.isNull() && resetCurrentCount_ > 0)
00655         {
00656                 NODELET_WARN( "Odometry lost! Odometry will be reset after next %d consecutive unsuccessful odometry updates...", resetCurrentCount_);
00657 
00658                 --resetCurrentCount_;
00659                 if(resetCurrentCount_ == 0)
00660                 {
00661                         // Check TF to see if sensor fusion is used (e.g., the output of robot_localization)
00662                         Transform tfPose = this->getTransform(odomFrameId_, frameId_, stamp);
00663                         if(tfPose.isNull())
00664                         {
00665                                 NODELET_WARN( "Odometry automatically reset to latest computed pose!");
00666                                 odometry_->reset(odometry_->getPose());
00667                         }
00668                         else
00669                         {
00670                                 NODELET_WARN( "Odometry automatically reset to latest odometry pose available from TF (%s->%s)!",
00671                                                 odomFrameId_.c_str(), frameId_.c_str());
00672                                 odometry_->reset(tfPose);
00673                         }
00674 
00675                 }
00676         }
00677 
00678         if(odomInfoPub_.getNumSubscribers())
00679         {
00680                 rtabmap_ros::OdomInfo infoMsg;
00681                 odomInfoToROS(info, infoMsg);
00682                 infoMsg.header.stamp = stamp; // use corresponding time stamp to image
00683                 infoMsg.header.frame_id = odomFrameId_;
00684                 odomInfoPub_.publish(infoMsg);
00685         }
00686 
00687         if(!data.imageRaw().empty())
00688         {
00689                 if(visParams_)
00690                 {
00691                         if(icpParams_)
00692                         {
00693                                 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());
00694                         }
00695                         else
00696                         {
00697                                 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());
00698                         }
00699                 }
00700                 else
00701                 {
00702                         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());
00703                 }
00704         }
00705 }
00706 
00707 bool OdometryROS::reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00708 {
00709         NODELET_INFO( "visual_odometry: reset odom!");
00710         odometry_->reset();
00711         guess_.setNull();
00712         guessStamp_ = 0.0;
00713         resetCurrentCount_ = resetCountdown_;
00714         this->flushCallbacks();
00715         return true;
00716 }
00717 
00718 bool OdometryROS::resetToPose(rtabmap_ros::ResetPose::Request& req, rtabmap_ros::ResetPose::Response&)
00719 {
00720         Transform pose(req.x, req.y, req.z, req.roll, req.pitch, req.yaw);
00721         NODELET_INFO( "visual_odometry: reset odom to pose %s!", pose.prettyPrint().c_str());
00722         odometry_->reset(pose);
00723         guess_.setNull();
00724         guessStamp_ = 0.0;
00725         resetCurrentCount_ = resetCountdown_;
00726         this->flushCallbacks();
00727         return true;
00728 }
00729 
00730 bool OdometryROS::pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00731 {
00732         if(paused_)
00733         {
00734                 NODELET_WARN( "visual_odometry: Already paused!");
00735         }
00736         else
00737         {
00738                 paused_ = true;
00739                 NODELET_INFO( "visual_odometry: paused!");
00740         }
00741         return true;
00742 }
00743 
00744 bool OdometryROS::resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00745 {
00746         if(!paused_)
00747         {
00748                 NODELET_WARN( "visual_odometry: Already running!");
00749         }
00750         else
00751         {
00752                 paused_ = false;
00753                 NODELET_INFO( "visual_odometry: resumed!");
00754         }
00755         return true;
00756 }
00757 
00758 bool OdometryROS::setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00759 {
00760         NODELET_INFO( "visual_odometry: Set log level to Debug");
00761         ULogger::setLevel(ULogger::kDebug);
00762         return true;
00763 }
00764 bool OdometryROS::setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00765 {
00766         NODELET_INFO( "visual_odometry: Set log level to Info");
00767         ULogger::setLevel(ULogger::kInfo);
00768         return true;
00769 }
00770 bool OdometryROS::setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00771 {
00772         NODELET_INFO( "visual_odometry: Set log level to Warning");
00773         ULogger::setLevel(ULogger::kWarning);
00774         return true;
00775 }
00776 bool OdometryROS::setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00777 {
00778         NODELET_INFO( "visual_odometry: Set log level to Error");
00779         ULogger::setLevel(ULogger::kError);
00780         return true;
00781 }
00782 
00783 
00784 }


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:49