00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "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_transforms.h>
00043 #include <rtabmap/core/Memory.h>
00044 #include <rtabmap/core/Signature.h>
00045 #include "rtabmap_ros/MsgConversion.h"
00046 #include "rtabmap_ros/OdomInfo.h"
00047 #include "rtabmap/utilite/UConversion.h"
00048 #include "rtabmap/utilite/ULogger.h"
00049 #include "rtabmap/utilite/UStl.h"
00050 #include "rtabmap/utilite/UFile.h"
00051
00052 #define BAD_COVARIANCE 9999
00053
00054 using namespace rtabmap;
00055
00056 namespace rtabmap_ros {
00057
00058 OdometryROS::OdometryROS(bool stereo) :
00059 odometry_(0),
00060 frameId_("base_link"),
00061 odomFrameId_("odom"),
00062 groundTruthFrameId_(""),
00063 publishTf_(true),
00064 waitForTransform_(true),
00065 waitForTransformDuration_(0.1),
00066 publishNullWhenLost_(true),
00067 guessFromTf_(false),
00068 paused_(false),
00069 resetCountdown_(0),
00070 resetCurrentCount_(0),
00071 stereo_(stereo)
00072 {
00073
00074 }
00075
00076 OdometryROS::~OdometryROS()
00077 {
00078 ros::NodeHandle & pnh = getPrivateNodeHandle();
00079 if(pnh.ok())
00080 {
00081 for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
00082 {
00083 pnh.deleteParam(iter->first);
00084 }
00085 }
00086
00087 delete odometry_;
00088 }
00089
00090 void OdometryROS::onInit()
00091 {
00092 ros::NodeHandle & nh = getNodeHandle();
00093 ros::NodeHandle & pnh = getPrivateNodeHandle();
00094
00095 odomPub_ = nh.advertise<nav_msgs::Odometry>("odom", 1);
00096 odomInfoPub_ = nh.advertise<rtabmap_ros::OdomInfo>("odom_info", 1);
00097 odomLocalMap_ = nh.advertise<sensor_msgs::PointCloud2>("odom_local_map", 1);
00098 odomLastFrame_ = nh.advertise<sensor_msgs::PointCloud2>("odom_last_frame", 1);
00099
00100 Transform initialPose = Transform::getIdentity();
00101 std::string initialPoseStr;
00102 std::string tfPrefix;
00103 std::string configPath;
00104 pnh.param("frame_id", frameId_, frameId_);
00105 pnh.param("odom_frame_id", odomFrameId_, odomFrameId_);
00106 pnh.param("publish_tf", publishTf_, publishTf_);
00107 pnh.param("tf_prefix", tfPrefix, tfPrefix);
00108 pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
00109 pnh.param("wait_for_transform_duration", waitForTransformDuration_, waitForTransformDuration_);
00110 pnh.param("initial_pose", initialPoseStr, initialPoseStr);
00111 pnh.param("ground_truth_frame_id", groundTruthFrameId_, groundTruthFrameId_);
00112 pnh.param("config_path", configPath, configPath);
00113 pnh.param("publish_null_when_lost", publishNullWhenLost_, publishNullWhenLost_);
00114 pnh.param("guess_from_tf", guessFromTf_, guessFromTf_);
00115
00116 if(publishTf_ && guessFromTf_)
00117 {
00118 NODELET_WARN( "\"publish_tf\" and \"guess_from_tf\" cannot be used at the same time. \"guess_from_tf\" is disabled.");
00119 guessFromTf_ = false;
00120 }
00121
00122 configPath = uReplaceChar(configPath, '~', UDirectory::homeDir());
00123 if(configPath.size() && configPath.at(0) != '/')
00124 {
00125 configPath = UDirectory::currentDir(true) + configPath;
00126 }
00127
00128 if(!tfPrefix.empty())
00129 {
00130 if(!frameId_.empty())
00131 {
00132 frameId_ = tfPrefix + "/" + frameId_;
00133 }
00134 if(!odomFrameId_.empty())
00135 {
00136 odomFrameId_ = tfPrefix + "/" + odomFrameId_;
00137 }
00138 if(!groundTruthFrameId_.empty())
00139 {
00140 groundTruthFrameId_ = tfPrefix + "/" + groundTruthFrameId_;
00141 }
00142 }
00143
00144 if(initialPoseStr.size())
00145 {
00146 std::vector<std::string> values = uListToVector(uSplit(initialPoseStr, ' '));
00147 if(values.size() == 6)
00148 {
00149 initialPose = Transform(
00150 uStr2Float(values[0]), uStr2Float(values[1]), uStr2Float(values[2]),
00151 uStr2Float(values[3]), uStr2Float(values[4]), uStr2Float(values[5]));
00152 }
00153 else
00154 {
00155 NODELET_ERROR( "Wrong initial_pose format: %s (should be \"x y z roll pitch yaw\" with angle in radians). "
00156 "Identity will be used...", initialPoseStr.c_str());
00157 }
00158 }
00159
00160
00161
00162 parameters_ = Parameters::getDefaultOdometryParameters(stereo_);
00163 if(!configPath.empty())
00164 {
00165 if(UFile::exists(configPath.c_str()))
00166 {
00167 NODELET_INFO( "Odometry: Loading parameters from %s", configPath.c_str());
00168 rtabmap::ParametersMap allParameters;
00169 Parameters::readINI(configPath.c_str(), allParameters);
00170
00171 for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
00172 {
00173 ParametersMap::iterator jter = allParameters.find(iter->first);
00174 if(jter!=allParameters.end())
00175 {
00176 iter->second = jter->second;
00177 }
00178 }
00179 }
00180 else
00181 {
00182 NODELET_ERROR( "Config file \"%s\" not found!", configPath.c_str());
00183 }
00184 }
00185 for(rtabmap::ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
00186 {
00187 std::string vStr;
00188 bool vBool;
00189 int vInt;
00190 double vDouble;
00191 if(pnh.getParam(iter->first, vStr))
00192 {
00193 NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
00194 iter->second = vStr;
00195 }
00196 else if(pnh.getParam(iter->first, vBool))
00197 {
00198 NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uBool2Str(vBool).c_str());
00199 iter->second = uBool2Str(vBool);
00200 }
00201 else if(pnh.getParam(iter->first, vDouble))
00202 {
00203 NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vDouble).c_str());
00204 iter->second = uNumber2Str(vDouble);
00205 }
00206 else if(pnh.getParam(iter->first, vInt))
00207 {
00208 NODELET_INFO( "Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), uNumber2Str(vInt).c_str());
00209 iter->second = uNumber2Str(vInt);
00210 }
00211
00212 if(iter->first.compare(Parameters::kVisMinInliers()) == 0 && atoi(iter->second.c_str()) < 8)
00213 {
00214 NODELET_WARN( "Parameter min_inliers must be >= 8, setting to 8...");
00215 iter->second = uNumber2Str(8);
00216 }
00217 }
00218
00219 std::vector<std::string> argList = getMyArgv();
00220 char * argv[argList.size()];
00221 for(unsigned int i=0; i<argList.size(); ++i)
00222 {
00223 argv[i] = &argList[i].at(0);
00224 }
00225
00226 rtabmap::ParametersMap parameters = rtabmap::Parameters::parseArguments(argList.size(), argv);
00227 for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00228 {
00229 rtabmap::ParametersMap::iterator jter = parameters_.find(iter->first);
00230 if(jter!=parameters_.end())
00231 {
00232 NODELET_INFO( "Update odometry parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
00233 jter->second = iter->second;
00234 }
00235 }
00236
00237
00238 for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=Parameters::getRemovedParameters().begin();
00239 iter!=Parameters::getRemovedParameters().end();
00240 ++iter)
00241 {
00242 std::string vStr;
00243 if(pnh.getParam(iter->first, vStr))
00244 {
00245 if(iter->second.first)
00246 {
00247
00248 parameters_.at(iter->second.second)= vStr;
00249 NODELET_WARN( "Odometry: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
00250 iter->first.c_str(), iter->second.second.c_str(), vStr.c_str());
00251 }
00252 else
00253 {
00254 if(iter->second.second.empty())
00255 {
00256 NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore!",
00257 iter->first.c_str());
00258 }
00259 else
00260 {
00261 NODELET_ERROR( "Odometry: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
00262 iter->first.c_str(), iter->second.second.c_str());
00263 }
00264 }
00265 }
00266 }
00267
00268 Parameters::parse(parameters_, Parameters::kOdomResetCountdown(), resetCountdown_);
00269 parameters_.at(Parameters::kOdomResetCountdown()) = "0";
00270 odometry_ = Odometry::create(parameters_);
00271 if(!initialPose.isIdentity())
00272 {
00273 odometry_->reset(initialPose);
00274 }
00275
00276 resetSrv_ = nh.advertiseService("reset_odom", &OdometryROS::reset, this);
00277 resetToPoseSrv_ = nh.advertiseService("reset_odom_to_pose", &OdometryROS::resetToPose, this);
00278 pauseSrv_ = nh.advertiseService("pause_odom", &OdometryROS::pause, this);
00279 resumeSrv_ = nh.advertiseService("resume_odom", &OdometryROS::resume, this);
00280
00281 setLogDebugSrv_ = pnh.advertiseService("log_debug", &OdometryROS::setLogDebug, this);
00282 setLogInfoSrv_ = pnh.advertiseService("log_info", &OdometryROS::setLogInfo, this);
00283 setLogWarnSrv_ = pnh.advertiseService("log_warning", &OdometryROS::setLogWarn, this);
00284 setLogErrorSrv_ = pnh.advertiseService("log_error", &OdometryROS::setLogError, this);
00285
00286 onOdomInit();
00287 }
00288
00289 Transform OdometryROS::getTransform(const std::string & fromFrameId, const std::string & toFrameId, const ros::Time & stamp) const
00290 {
00291
00292 Transform transform;
00293 try
00294 {
00295 if(waitForTransform_ && !stamp.isZero() && waitForTransformDuration_ > 0.0)
00296 {
00297
00298 if(!tfListener_.waitForTransform(fromFrameId, toFrameId, stamp, ros::Duration(waitForTransformDuration_)))
00299 {
00300 NODELET_WARN( "odometry: Could not get transform from %s to %s (stamp=%f) after %f seconds (\"wait_for_transform_duration\"=%f)!",
00301 fromFrameId.c_str(), toFrameId.c_str(), stamp.toSec(), waitForTransformDuration_, waitForTransformDuration_);
00302 return transform;
00303 }
00304 }
00305
00306 tf::StampedTransform tmp;
00307 tfListener_.lookupTransform(fromFrameId, toFrameId, stamp, tmp);
00308 transform = rtabmap_ros::transformFromTF(tmp);
00309 }
00310 catch(tf::TransformException & ex)
00311 {
00312 NODELET_WARN( "%s",ex.what());
00313 }
00314 return transform;
00315 }
00316
00317 void OdometryROS::processData(const SensorData & data, const ros::Time & stamp)
00318 {
00319 if(odometry_->getPose().isIdentity() &&
00320 !groundTruthFrameId_.empty())
00321 {
00322
00323 Transform initialPose = getTransform(groundTruthFrameId_, frameId_, stamp);
00324 if(initialPose.isNull())
00325 {
00326 return;
00327 }
00328
00329 NODELET_INFO( "Initializing odometry pose to %s (from \"%s\" -> \"%s\")",
00330 initialPose.prettyPrint().c_str(),
00331 groundTruthFrameId_.c_str(),
00332 frameId_.c_str());
00333 odometry_->reset(initialPose);
00334 }
00335
00336 Transform guess;
00337 if(guessFromTf_)
00338 {
00339 Transform previousPose = this->getTransform(odomFrameId_, frameId_, ros::Time(odometry_->previousStamp()));
00340 Transform pose = this->getTransform(odomFrameId_, frameId_, stamp);
00341 if(!previousPose.isNull() && !pose.isNull())
00342 {
00343 guess = previousPose.inverse() * pose;
00344
00345
00346
00347
00348
00349
00350
00351
00352
00353
00354 }
00355 }
00356
00357
00358 ros::WallTime time = ros::WallTime::now();
00359 rtabmap::OdometryInfo info;
00360 SensorData dataCpy = data;
00361 rtabmap::Transform pose = odometry_->process(dataCpy, guess, &info);
00362 if(!pose.isNull())
00363 {
00364 resetCurrentCount_ = resetCountdown_;
00365
00366
00367
00368
00369 geometry_msgs::TransformStamped poseMsg;
00370 poseMsg.child_frame_id = frameId_;
00371 poseMsg.header.frame_id = odomFrameId_;
00372 poseMsg.header.stamp = stamp;
00373 rtabmap_ros::transformToGeometryMsg(pose, poseMsg.transform);
00374
00375 if(publishTf_)
00376 {
00377 tfBroadcaster_.sendTransform(poseMsg);
00378 }
00379
00380 if(odomPub_.getNumSubscribers())
00381 {
00382
00383 nav_msgs::Odometry odom;
00384 odom.header.stamp = stamp;
00385 odom.header.frame_id = odomFrameId_;
00386 odom.child_frame_id = frameId_;
00387
00388
00389 odom.pose.pose.position.x = poseMsg.transform.translation.x;
00390 odom.pose.pose.position.y = poseMsg.transform.translation.y;
00391 odom.pose.pose.position.z = poseMsg.transform.translation.z;
00392 odom.pose.pose.orientation = poseMsg.transform.rotation;
00393
00394
00395
00396 odom.pose.covariance.at(0) = info.variance*2;
00397 odom.pose.covariance.at(7) = info.variance*2;
00398 odom.pose.covariance.at(14) = info.variance*2;
00399 odom.pose.covariance.at(21) = info.variance*2;
00400 odom.pose.covariance.at(28) = info.variance*2;
00401 odom.pose.covariance.at(35) = info.variance*2;
00402
00403
00404 bool setTwist = !odometry_->previousVelocityTransform().isNull();
00405 if(setTwist)
00406 {
00407 float x,y,z,roll,pitch,yaw;
00408 odometry_->previousVelocityTransform().getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
00409 odom.twist.twist.linear.x = x;
00410 odom.twist.twist.linear.y = y;
00411 odom.twist.twist.linear.z = z;
00412 odom.twist.twist.angular.x = roll;
00413 odom.twist.twist.angular.y = pitch;
00414 odom.twist.twist.angular.z = yaw;
00415 }
00416
00417 odom.twist.covariance.at(0) = setTwist?info.variance:BAD_COVARIANCE;
00418 odom.twist.covariance.at(7) = setTwist?info.variance:BAD_COVARIANCE;
00419 odom.twist.covariance.at(14) = setTwist?info.variance:BAD_COVARIANCE;
00420 odom.twist.covariance.at(21) = setTwist?info.variance:BAD_COVARIANCE;
00421 odom.twist.covariance.at(28) = setTwist?info.variance:BAD_COVARIANCE;
00422 odom.twist.covariance.at(35) = setTwist?info.variance:BAD_COVARIANCE;
00423
00424
00425 odomPub_.publish(odom);
00426 }
00427
00428
00429 if(odomLocalMap_.getNumSubscribers() && dynamic_cast<OdometryF2M*>(odometry_))
00430 {
00431 pcl::PointCloud<pcl::PointXYZ> cloud;
00432 const std::multimap<int, cv::Point3f> & map = ((OdometryF2M*)odometry_)->getMap().getWords3();
00433 for(std::multimap<int, cv::Point3f>::const_iterator iter=map.begin(); iter!=map.end(); ++iter)
00434 {
00435 cloud.push_back(pcl::PointXYZ(iter->second.x, iter->second.y, iter->second.z));
00436 }
00437 sensor_msgs::PointCloud2 cloudMsg;
00438 pcl::toROSMsg(cloud, cloudMsg);
00439 cloudMsg.header.stamp = stamp;
00440 cloudMsg.header.frame_id = odomFrameId_;
00441 odomLocalMap_.publish(cloudMsg);
00442 }
00443
00444 if(odomLastFrame_.getNumSubscribers())
00445 {
00446 if(dynamic_cast<OdometryF2M*>(odometry_))
00447 {
00448 const std::multimap<int, cv::Point3f> & words3 = ((OdometryF2M*)odometry_)->getLastFrame().getWords3();
00449 if(words3.size())
00450 {
00451 pcl::PointCloud<pcl::PointXYZ> cloud;
00452 for(std::multimap<int, cv::Point3f>::const_iterator iter=words3.begin(); iter!=words3.end(); ++iter)
00453 {
00454
00455 cv::Point3f pt = util3d::transformPoint(iter->second, pose);
00456 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
00457 }
00458
00459 sensor_msgs::PointCloud2 cloudMsg;
00460 pcl::toROSMsg(cloud, cloudMsg);
00461 cloudMsg.header.stamp = stamp;
00462 cloudMsg.header.frame_id = odomFrameId_;
00463 odomLastFrame_.publish(cloudMsg);
00464 }
00465 }
00466 else
00467 {
00468
00469 const Signature & refFrame = ((OdometryF2F*)odometry_)->getRefFrame();
00470 if(refFrame.getWords3().size())
00471 {
00472 pcl::PointCloud<pcl::PointXYZ> cloud;
00473 for(std::multimap<int, cv::Point3f>::const_iterator iter=refFrame.getWords3().begin(); iter!=refFrame.getWords3().end(); ++iter)
00474 {
00475
00476 cv::Point3f pt = util3d::transformPoint(iter->second, pose);
00477 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
00478 }
00479 sensor_msgs::PointCloud2 cloudMsg;
00480 pcl::toROSMsg(cloud, cloudMsg);
00481 cloudMsg.header.stamp = stamp;
00482 cloudMsg.header.frame_id = odomFrameId_;
00483 odomLastFrame_.publish(cloudMsg);
00484 }
00485 }
00486 }
00487 }
00488 else if(publishNullWhenLost_)
00489 {
00490
00491
00492
00493 nav_msgs::Odometry odom;
00494 odom.header.stamp = stamp;
00495 odom.header.frame_id = odomFrameId_;
00496 odom.child_frame_id = frameId_;
00497 odom.pose.covariance.at(0) = BAD_COVARIANCE;
00498 odom.pose.covariance.at(7) = BAD_COVARIANCE;
00499 odom.pose.covariance.at(14) = BAD_COVARIANCE;
00500 odom.pose.covariance.at(21) = BAD_COVARIANCE;
00501 odom.pose.covariance.at(28) = BAD_COVARIANCE;
00502 odom.pose.covariance.at(35) = BAD_COVARIANCE;
00503 odom.twist.covariance.at(0) = BAD_COVARIANCE;
00504 odom.twist.covariance.at(7) = BAD_COVARIANCE;
00505 odom.twist.covariance.at(14) = BAD_COVARIANCE;
00506 odom.twist.covariance.at(21) = BAD_COVARIANCE;
00507 odom.twist.covariance.at(28) = BAD_COVARIANCE;
00508 odom.twist.covariance.at(35) = BAD_COVARIANCE;
00509
00510
00511 odomPub_.publish(odom);
00512 }
00513
00514 if(pose.isNull() && resetCurrentCount_ > 0)
00515 {
00516 NODELET_WARN( "Odometry lost! Odometry will be reset after next %d consecutive unsuccessful odometry updates...", resetCurrentCount_);
00517
00518 --resetCurrentCount_;
00519 if(resetCurrentCount_ == 0)
00520 {
00521
00522 Transform tfPose = this->getTransform(odomFrameId_, frameId_, stamp);
00523 if(tfPose.isNull())
00524 {
00525 NODELET_WARN( "Odometry automatically reset to latest computed pose!");
00526 odometry_->reset(odometry_->getPose());
00527 }
00528 else
00529 {
00530 NODELET_WARN( "Odometry automatically reset to latest odometry pose available from TF (%s->%s)!",
00531 odomFrameId_.c_str(), frameId_.c_str());
00532 odometry_->reset(tfPose);
00533 }
00534
00535 }
00536 }
00537
00538 if(odomInfoPub_.getNumSubscribers())
00539 {
00540 rtabmap_ros::OdomInfo infoMsg;
00541 odomInfoToROS(info, infoMsg);
00542 infoMsg.header.stamp = stamp;
00543 infoMsg.header.frame_id = odomFrameId_;
00544 odomInfoPub_.publish(infoMsg);
00545 }
00546
00547 NODELET_INFO( "Odom: quality=%d, std dev=%fm, update time=%fs", info.inliers, pose.isNull()?0.0f:std::sqrt(info.variance), (ros::WallTime::now()-time).toSec());
00548 }
00549
00550 bool OdometryROS::isOdometryF2M() const
00551 {
00552 return dynamic_cast<OdometryF2M*>(odometry_) != 0;
00553 }
00554
00555 bool OdometryROS::reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00556 {
00557 NODELET_INFO( "visual_odometry: reset odom!");
00558 odometry_->reset();
00559 this->flushCallbacks();
00560 return true;
00561 }
00562
00563 bool OdometryROS::resetToPose(rtabmap_ros::ResetPose::Request& req, rtabmap_ros::ResetPose::Response&)
00564 {
00565 Transform pose(req.x, req.y, req.z, req.roll, req.pitch, req.yaw);
00566 NODELET_INFO( "visual_odometry: reset odom to pose %s!", pose.prettyPrint().c_str());
00567 odometry_->reset(pose);
00568 this->flushCallbacks();
00569 return true;
00570 }
00571
00572 bool OdometryROS::pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00573 {
00574 if(paused_)
00575 {
00576 NODELET_WARN( "visual_odometry: Already paused!");
00577 }
00578 else
00579 {
00580 paused_ = true;
00581 NODELET_INFO( "visual_odometry: paused!");
00582 }
00583 return true;
00584 }
00585
00586 bool OdometryROS::resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00587 {
00588 if(!paused_)
00589 {
00590 NODELET_WARN( "visual_odometry: Already running!");
00591 }
00592 else
00593 {
00594 paused_ = false;
00595 NODELET_INFO( "visual_odometry: resumed!");
00596 }
00597 return true;
00598 }
00599
00600 bool OdometryROS::setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00601 {
00602 NODELET_INFO( "visual_odometry: Set log level to Debug");
00603 ULogger::setLevel(ULogger::kDebug);
00604 return true;
00605 }
00606 bool OdometryROS::setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00607 {
00608 NODELET_INFO( "visual_odometry: Set log level to Info");
00609 ULogger::setLevel(ULogger::kInfo);
00610 return true;
00611 }
00612 bool OdometryROS::setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00613 {
00614 NODELET_INFO( "visual_odometry: Set log level to Warning");
00615 ULogger::setLevel(ULogger::kWarning);
00616 return true;
00617 }
00618 bool OdometryROS::setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00619 {
00620 NODELET_INFO( "visual_odometry: Set log level to Error");
00621 ULogger::setLevel(ULogger::kError);
00622 return true;
00623 }
00624
00625
00626 }