30 #include <sensor_msgs/Image.h>    32 #include <sensor_msgs/PointCloud2.h>    33 #include <nav_msgs/Odometry.h>    46 #include "rtabmap_ros/OdomInfo.h"    53 #define BAD_COVARIANCE 9999    59 OdometryROS::OdometryROS(
bool stereoParams, 
bool visParams, 
bool icpParams) :
    62         callbackCalled_(
false),
    63         frameId_(
"base_link"),
    65         groundTruthFrameId_(
""),
    66         groundTruthBaseFrameId_(
""),
    68         guessMinTranslation_(0.0),
    69         guessMinRotation_(0.0),
    72         waitForTransform_(
true),
    73         waitForTransformDuration_(0.1), 
    74         publishNullWhenLost_(
true),
    77         resetCurrentCount_(0),
    78         stereoParams_(stereoParams),
    79         visParams_(visParams),
    80         icpParams_(icpParams),
    82         expectedUpdateRate_(0.0),
    85         odomStrategy_(
Parameters::defaultOdomStrategy()),
    86         waitIMUToinit_(
false),
   117         Transform initialPose = Transform::getIdentity();
   118         std::string initialPoseStr;
   119         std::string configPath;
   125                 NODELET_ERROR(
"tf_prefix parameter has been removed, use directly odom_frame_id and frame_id parameters.");
   129         pnh.
param(
"initial_pose", initialPoseStr, initialPoseStr); 
   132         pnh.
param(
"config_path", configPath, configPath);
   138                         NODELET_ERROR(
"Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
   142                         NODELET_WARN(
"Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
   157         pnh.
param(
"log_to_rosout_level", eventLevel, eventLevel);
   163                 NODELET_WARN( 
"\"publish_tf\" and \"guess_frame_id\" cannot be used "   164                                 "at the same time if \"guess_frame_id\" and \"odom_frame_id\" "   165                                 "are the same frame (value=\"%s\"). \"guess_frame_id\" is disabled.", 
odomFrameId_.c_str());
   171         NODELET_INFO(
"Odometry: wait_for_transform     = %s", 
waitForTransform_?
"true":
"false");
   173         NODELET_INFO(
"Odometry: log_to_rosout_level    = %d", eventLevel);
   174         NODELET_INFO(
"Odometry: initial_pose           = %s", initialPose.prettyPrint().c_str());
   177         NODELET_INFO(
"Odometry: config_path            = %s", configPath.c_str());
   179         NODELET_INFO(
"Odometry: guess_frame_id         = %s", 
guessFrameId_.c_str());
   182         NODELET_INFO(
"Odometry: guess_min_time         = %f", 
guessMinTime_);
   184         NODELET_INFO(
"Odometry: max_update_rate        = %f Hz", 
maxUpdateRate_);
   185         NODELET_INFO(
"Odometry: min_update_rate        = %f Hz", 
minUpdateRate_);
   186         NODELET_INFO(
"Odometry: wait_imu_to_init       = %s", 
waitIMUToinit_?
"true":
"false");
   189         if(configPath.size() && configPath.at(0) != 
'/')
   194         if(initialPoseStr.size())
   197                 if(values.size() == 6)
   205                         NODELET_ERROR( 
"Wrong initial_pose format: %s (should be \"x y z roll pitch yaw\" with angle in radians). "   206                                           "Identity will be used...", initialPoseStr.c_str());
   225         parameters_.insert(*Parameters::getDefaultParameters().
find(Parameters::kRtabmapImagesAlreadyRectified()));
   226         if(!configPath.empty())
   230                         NODELET_INFO( 
"Odometry: Loading parameters from %s", configPath.c_str());
   232                         Parameters::readINI(configPath.c_str(), allParameters);
   236                                 ParametersMap::iterator jter = allParameters.find(iter->first);
   237                                 if(jter!=allParameters.end())
   239                                         iter->second = jter->second;
   245                         NODELET_ERROR( 
"Config file \"%s\" not found!", configPath.c_str());
   256                         NODELET_INFO( 
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
   259                 else if(pnh.
getParam(iter->first, vBool))
   261                         NODELET_INFO( 
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), 
uBool2Str(vBool).c_str());
   264                 else if(pnh.
getParam(iter->first, vDouble))
   266                         NODELET_INFO( 
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), 
uNumber2Str(vDouble, 6).c_str());
   269                 else if(pnh.
getParam(iter->first, vInt))
   271                         NODELET_INFO( 
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), 
uNumber2Str(vInt).c_str());
   275                 if(iter->first.compare(Parameters::kVisMinInliers()) == 0 && atoi(iter->second.c_str()) < 8)
   277                         NODELET_WARN( 
"Parameter min_inliers must be >= 8, setting to 8...");
   282         std::vector<std::string> argList = 
getMyArgv();
   283         char ** 
argv = 
new char*[argList.size()];
   284         for(
unsigned int i=0; i<argList.size(); ++i)
   286                 argv[i] = &argList[i].at(0);
   291         for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
   293                 rtabmap::ParametersMap::iterator jter = 
parameters_.find(iter->first);
   296                         NODELET_INFO( 
"Update odometry parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
   297                         jter->second = iter->second;
   301                         NODELET_INFO( 
"Odometry: Ignored parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
   306         for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=Parameters::getRemovedParameters().begin();
   307                 iter!=Parameters::getRemovedParameters().end();
   315                                 NODELET_WARN(
"Rtabmap: Parameter name changed: \"%s\" -> \"%s\". The new parameter is already used with value \"%s\", ignoring the old one with value \"%s\".",
   316                                                 iter->first.c_str(), iter->second.second.c_str(), 
parameters_.find(iter->second.second)->second.c_str(), vStr.c_str());
   322                                 NODELET_WARN( 
"Odometry: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
   323                                                 iter->first.c_str(), iter->second.second.c_str(), vStr.c_str());
   327                                 if(iter->second.second.empty())
   329                                         NODELET_ERROR( 
"Odometry: Parameter \"%s\" doesn't exist anymore!",
   330                                                         iter->first.c_str());
   334                                         NODELET_ERROR( 
"Odometry: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
   335                                                         iter->first.c_str(), iter->second.second.c_str());
   344                 pnh.
setParam(iter->first, iter->second);
   348         parameters_.at(Parameters::kOdomResetCountdown()) = 
"0"; 
   353         if(!initialPose.isIdentity())
   373                 pnh.
param(
"queue_size", queueSize, queueSize);
   375                 NODELET_INFO(
"odometry: Subscribing to IMU topic %s", 
imuSub_.
getTopic().c_str());
   395                         ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are "   396                                         "published (\"$ rostopic hz my_topic\") and the timestamps in their "   397                                         "header are set. %s%s",
   399                                         approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input "   400                                                 "topics should have all the exact timestamp for the callback to be called.",
   401                                         subscribedTopicsMsg.c_str());
   419                 double stamp = msg->header.stamp.toSec();
   421                 if(this->
frameId().compare(msg->header.frame_id) != 0)
   425                 if(localTransform.
isNull())
   427                         ROS_ERROR(
"Could not transform IMU msg from frame \"%s\" to frame \"%s\", TF not available at time %f",
   428                                         msg->header.frame_id.c_str(), this->
frameId().c_str(), 
stamp);
   432                 IMU imu(cv::Vec4d(msg->orientation.x, msg->orientation.y, msg->orientation.z, msg->orientation.w),
   433                                 cv::Mat(3,3,CV_64FC1,(
void*)msg->orientation_covariance.data()).clone(),
   434                                 cv::Vec3d(msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z),
   435                                 cv::Mat(3,3,CV_64FC1,(
void*)msg->angular_velocity_covariance.data()).clone(),
   436                                 cv::Vec3d(msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z),
   437                                 cv::Mat(3,3,CV_64FC1,(
void*)msg->linear_acceleration_covariance.data()).clone(),
   440                 imus_.insert(std::make_pair(stamp, imu));
   449                 if(
imus_.size() > 1000)
   472                                         "published faster than data rate. (last image stamp "   473                                         "buffered=%f and new one is %f, last imu stamp received=%f)",
   481         std::map<double, rtabmap::IMU>::iterator iterEnd = 
imus_.lower_bound(header.stamp.toSec());
   482         if(iterEnd!= 
imus_.end())
   486         for(std::map<double, rtabmap::IMU>::iterator iter=
imus_.begin(); iter!=iterEnd;)
   489                 SensorData dataIMU(iter->second, 0, iter->first);
   502                         NODELET_WARN(
"Odometry: Detected not valid consecutive stamps (previous=%fs new=%fs). "   503                                         "New stamp should be always greater than previous stamp. This new data is ignored.",
   519                         NODELET_WARN(
"Odometry: Aborting odometry update, higher frame rate detected (%f Hz) than the expected one (%f Hz). (stamps: previous=%fs new=%fs)",
   534                                 if(x==0.0
f && y==0.0
f && z==0.0
f)
   539                                                 NODELET_WARN(
"Ground truth frames \"%s\" -> \"%s\" are set but failed to "   540                                                                 "get them, odometry won't be initialized with ground truth.",
   545                                                 NODELET_INFO( 
"Initializing odometry pose to %s (from \"%s\" -> \"%s\")",
   565                         previousPose = guessCurrentPose;
   573                 if(!previousPose.isNull() && !guessCurrentPose.
isNull())
   597                                                 correctionMsg.header.stamp = header.stamp;
   610                         NODELET_ERROR(
"\"guess_frame_id\" is set, but guess cannot be computed between frames \"%s\" -> \"%s\". Aborting odometry update...", 
guessFrameId_.c_str(), 
frameId_.c_str());
   625         if(!tooOldPreviousData)
   640                 poseMsg.header.stamp = header.stamp;
   651                                 correctionMsg.header.stamp = header.stamp;
   666                         odom.header.stamp = header.stamp; 
   671                         odom.pose.pose.position.x = poseMsg.transform.translation.x;
   672                         odom.pose.pose.position.y = poseMsg.transform.translation.y;
   673                         odom.pose.pose.position.z = poseMsg.transform.translation.z;
   674                         odom.pose.pose.orientation = poseMsg.transform.rotation;
   678                         odom.pose.covariance.at(0) = info.
reg.
covariance.at<
double>(0,0)*2;  
   679                         odom.pose.covariance.at(7) = info.
reg.
covariance.at<
double>(1,1)*2;  
   680                         odom.pose.covariance.at(14) = info.
reg.
covariance.at<
double>(2,2)*2; 
   681                         odom.pose.covariance.at(21) = info.
reg.
covariance.at<
double>(3,3)*2; 
   682                         odom.pose.covariance.at(28) = info.
reg.
covariance.at<
double>(4,4)*2; 
   683                         odom.pose.covariance.at(35) = info.
reg.
covariance.at<
double>(5,5)*2; 
   691                                 odom.twist.twist.linear.x = x;
   692                                 odom.twist.twist.linear.y = 
y;
   693                                 odom.twist.twist.linear.z = 
z;
   694                                 odom.twist.twist.angular.x = 
roll;
   695                                 odom.twist.twist.angular.y = 
pitch;
   696                                 odom.twist.twist.angular.z = 
yaw;
   716                         pcl::PointCloud<pcl::PointXYZRGB> cloud;
   717                         for(std::map<int, cv::Point3f>::const_iterator iter=info.
localMap.begin(); iter!=info.
localMap.end(); ++iter)
   719                                 bool inlier = info.
words.find(iter->first) != info.
words.end();
   723                                 pt.
x = iter->second.x;
   724                                 pt.y = iter->second.y;
   725                                 pt.z = iter->second.z;
   728                         sensor_msgs::PointCloud2 cloudMsg;
   730                         cloudMsg.header.stamp = header.stamp; 
   740                                 const std::vector<cv::Point3f> & words3  = ((
OdometryF2M*)
odometry_)->getLastFrame().getWords3();
   743                                         pcl::PointCloud<pcl::PointXYZ> cloud;
   744                                         for(std::vector<cv::Point3f>::const_iterator iter=words3.begin(); iter!=words3.end(); ++iter)
   747                                                 cv::Point3f 
pt = util3d::transformPoint(*iter, pose);
   748                                                 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
   751                                         sensor_msgs::PointCloud2 cloudMsg;
   753                                         cloudMsg.header.stamp = header.stamp; 
   764                                         pcl::PointCloud<pcl::PointXYZ> cloud;
   765                                         for(std::vector<cv::Point3f>::const_iterator iter=refFrame.
getWords3().begin(); iter!=refFrame.
getWords3().end(); ++iter)
   768                                                 cv::Point3f 
pt = util3d::transformPoint(*iter, pose);
   769                                                 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
   771                                         sensor_msgs::PointCloud2 cloudMsg;
   773                                         cloudMsg.header.stamp = header.stamp; 
   782                         sensor_msgs::PointCloud2 cloudMsg;
   804                         cloudMsg.header.stamp = header.stamp; 
   821                         odom.header.stamp = header.stamp; 
   847                         correctionMsg.header.stamp = header.stamp;
   856                 if(tooOldPreviousData)
   858                         NODELET_WARN( 
"Odometry lost! Odometry will be reset because last update "   859                                         "is %fs too old (>%fs, min_update_rate = %f Hz). Previous data stamp is %f while new data stamp is %f.",
   872                                 NODELET_WARN( 
"Odometry automatically reset based on latest guess available from TF (%s->%s, moved %s since got lost)!",
   883                                         NODELET_WARN( 
"Odometry automatically reset to latest computed pose!");
   888                                         NODELET_WARN( 
"Odometry automatically reset to latest odometry pose available from TF (%s->%s)!",
   898                 rtabmap_ros::OdomInfo infoMsg;
   900                 infoMsg.header.stamp = header.stamp; 
   908                         infoMsg.wordInliers.clear();
   909                         infoMsg.wordMatches.clear();
   910                         infoMsg.wordsKeys.clear();
   911                         infoMsg.wordsValues.clear();
   912                         infoMsg.refCorners.clear();
   913                         infoMsg.newCorners.clear();
   914                         infoMsg.cornerInliers.clear();
   915                         infoMsg.localMapKeys.clear();
   916                         infoMsg.localMapValues.clear();
   917                         infoMsg.localScanMap = sensor_msgs::PointCloud2();
   924                 if(!header.frame_id.empty())
   926                         rtabmap_ros::RGBDImage msg;
   933                         ROS_WARN(
"Sensor frame not set, cannot convert SensorData to RGBDImage");
   945                                 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());
   969         Transform pose(req.x, req.y, req.z, req.roll, req.pitch, req.yaw);
  1018         NODELET_INFO( 
"visual_odometry: Set log level to Debug");
  1024         NODELET_INFO( 
"visual_odometry: Set log level to Info");
  1030         NODELET_INFO( 
"visual_odometry: Set log level to Warning");
  1036         NODELET_INFO( 
"visual_odometry: Set log level to Error");
 std::string groundTruthBaseFrameId_
static std::string homeDir()
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
std::pair< rtabmap::SensorData, std_msgs::Header > bufferedData_
double expectedUpdateRate_
ros::Publisher odomRgbdImagePub_
std::string getTopic() const
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
std::string uReplaceChar(const std::string &str, char before, char after)
std::vector< double > values
virtual void reset(const Transform &initialPose=Transform::getIdentity())
unsigned int framesProcessed() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
tf2_ros::TransformBroadcaster tfBroadcaster_
std::map< int, cv::Point3f > localMap
std::pair< std::string, std::string > ParametersPair
virtual void updateParameters(rtabmap::ParametersMap ¶meters)
ros::NodeHandle & getNodeHandle() const
const std::string & frameId() const
double waitForTransformDuration_
boost::thread * warningThread_
ros::Publisher odomLocalScanMap_
void odomInfoToROS(const rtabmap::OdometryInfo &info, rtabmap_ros::OdomInfo &msg, bool ignoreData=false)
void callbackIMU(const sensor_msgs::ImuConstPtr &msg)
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
ros::ServiceServer setLogInfoSrv_
bool pause(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
std::map< std::string, std::string > ParametersMap
const std::vector< cv::Point3f > & getWords3() const
bool publishNullWhenLost_
virtual void postProcessData(const rtabmap::SensorData &data, const std_msgs::Header &header) const
virtual Odometry::Type getType()=0
std::string groundTruthFrameId_
ros::NodeHandle & getPrivateNodeHandle() const
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_
static void setLevel(ULogger::Level level)
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
std::string uBool2Str(bool boolean)
Transform process(SensorData &data, OdometryInfo *info=0)
bool setLogWarn(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
virtual void onOdomInit()=0
#define UASSERT(condition)
std::list< std::string > uSplit(const std::string &str, char separator=' ')
const std::string & getName() const
ros::ServiceServer setLogWarnSrv_
static std::string currentDir(bool trailingSeparator=false)
std::string uNumber2Str(unsigned int number)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
T uMax3(const T &a, const T &b, const T &c)
ros::ServiceServer resetToPoseSrv_
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
void rgbdImageToROS(const rtabmap::SensorData &data, rtabmap_ros::RGBDImage &msg, const std::string &sensorFrameId)
bool resume(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
const Transform & getVelocityGuess() const
rtabmap::ParametersMap parameters_
double waitForTransformDuration() const
const cv::Mat & imageRaw() const
ros::ServiceServer setLogErrorSrv_
bool setLogError(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool getParam(const std::string &key, std::string &s) const
void startWarningThread(const std::string &subscribedTopicsMsg, bool approxSync)
static void setEventLevel(ULogger::Level eventSentLevel)
virtual void flushCallbacks()=0
ros::ServiceServer resetSrv_
std::map< double, rtabmap::IMU > imus_
ros::ServiceServer pauseSrv_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer resumeSrv_
rtabmap::Transform velocityGuess() const
ros::Publisher odomLocalMap_
rtabmap::Transform guessPreviousPose_
bool hasParam(const std::string &key) const
const V_string & getMyArgv() const
std::vector< V > uListToVector(const std::list< V > &list)
#define NODELET_INFO(...)
bool setLogInfo(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool reset(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
const LaserScan & laserScanRaw() const
std::multimap< int, cv::KeyPoint > words
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
rtabmap::Odometry * odometry_
ros::Publisher odomInfoPub_
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
rtabmap::Transform guess_
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
float uStr2Float(const std::string &str)
double guessMinTranslation_
bool find(const std::vector< unsigned int > &l, unsigned int n)
void processData(rtabmap::SensorData &data, const std_msgs::Header &header)
std::string guessFrameId_
bool hasIntensity() const
void setGroundTruth(const Transform &pose)
ros::Publisher odomInfoLitePub_
bool resetToPose(rtabmap_ros::ResetPose::Request &, rtabmap_ros::ResetPose::Response &)
const rtabmap::ParametersMap & parameters() const
const Transform & getPose() const
uint32_t getNumSubscribers() const
ros::Publisher odomLastFrame_
Transform localTransform() const
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)