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),
84 odomStrategy_(
Parameters::defaultOdomStrategy()),
85 waitIMUToinit_(
false),
123 Transform initialPose = Transform::getIdentity();
124 std::string initialPoseStr;
125 std::string configPath;
131 NODELET_ERROR(
"tf_prefix parameter has been removed, use directly odom_frame_id and frame_id parameters.");
135 pnh.
param(
"initial_pose", initialPoseStr, initialPoseStr);
138 pnh.
param(
"config_path", configPath, configPath);
144 NODELET_ERROR(
"Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
148 NODELET_WARN(
"Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
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: initial_pose = %s", initialPose.prettyPrint().c_str());
176 NODELET_INFO(
"Odometry: config_path = %s", configPath.c_str());
178 NODELET_INFO(
"Odometry: guess_frame_id = %s",
guessFrameId_.c_str());
181 NODELET_INFO(
"Odometry: guess_min_time = %f",
guessMinTime_);
183 NODELET_INFO(
"Odometry: max_update_rate = %f Hz",
maxUpdateRate_);
184 NODELET_INFO(
"Odometry: wait_imu_to_init = %s",
waitIMUToinit_?
"true":
"false");
187 if(configPath.size() && configPath.at(0) !=
'/')
192 if(initialPoseStr.size())
195 if(values.size() == 6)
203 NODELET_ERROR(
"Wrong initial_pose format: %s (should be \"x y z roll pitch yaw\" with angle in radians). " 204 "Identity will be used...", initialPoseStr.c_str());
223 parameters_.insert(*Parameters::getDefaultParameters().
find(Parameters::kRtabmapImagesAlreadyRectified()));
224 if(!configPath.empty())
228 NODELET_INFO(
"Odometry: Loading parameters from %s", configPath.c_str());
230 Parameters::readINI(configPath.c_str(), allParameters);
234 ParametersMap::iterator jter = allParameters.find(iter->first);
235 if(jter!=allParameters.end())
237 iter->second = jter->second;
243 NODELET_ERROR(
"Config file \"%s\" not found!", configPath.c_str());
254 NODELET_INFO(
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
257 else if(pnh.
getParam(iter->first, vBool))
259 NODELET_INFO(
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(),
uBool2Str(vBool).c_str());
262 else if(pnh.
getParam(iter->first, vDouble))
264 NODELET_INFO(
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vDouble).c_str());
267 else if(pnh.
getParam(iter->first, vInt))
269 NODELET_INFO(
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vInt).c_str());
273 if(iter->first.compare(Parameters::kVisMinInliers()) == 0 && atoi(iter->second.c_str()) < 8)
275 NODELET_WARN(
"Parameter min_inliers must be >= 8, setting to 8...");
280 std::vector<std::string> argList =
getMyArgv();
281 char **
argv =
new char*[argList.size()];
282 for(
unsigned int i=0; i<argList.size(); ++i)
284 argv[i] = &argList[i].at(0);
289 for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
291 rtabmap::ParametersMap::iterator jter =
parameters_.find(iter->first);
294 NODELET_INFO(
"Update odometry parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
295 jter->second = iter->second;
299 NODELET_INFO(
"Odometry: Ignored parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
304 for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=Parameters::getRemovedParameters().begin();
305 iter!=Parameters::getRemovedParameters().end();
315 NODELET_WARN(
"Odometry: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
316 iter->first.c_str(), iter->second.second.c_str(), vStr.c_str());
320 if(iter->second.second.empty())
322 NODELET_ERROR(
"Odometry: Parameter \"%s\" doesn't exist anymore!",
323 iter->first.c_str());
327 NODELET_ERROR(
"Odometry: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
328 iter->first.c_str(), iter->second.second.c_str());
335 parameters_.at(Parameters::kOdomResetCountdown()) =
"0";
340 if(!initialPose.isIdentity())
360 pnh.
param(
"queue_size", queueSize, queueSize);
362 NODELET_INFO(
"odometry: Subscribing to IMU topic %s",
imuSub_.
getTopic().c_str());
382 ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are " 383 "published (\"$ rostopic hz my_topic\") and the timestamps in their " 384 "header are set. %s%s",
386 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input " 387 "topics should have all the exact timestamp for the callback to be called.",
388 subscribedTopicsMsg.c_str());
402 std::string errorMsg;
405 NODELET_WARN(
"odometry: Could not get transform from %s to %s (stamp=%f) after %f seconds (\"wait_for_transform_duration\"=%f)! Error=\"%s\"",
433 double stamp = msg->header.stamp.toSec();
435 if(this->
frameId().compare(msg->header.frame_id) != 0)
439 if(localTransform.
isNull())
441 ROS_ERROR(
"Could not transform IMU msg from frame \"%s\" to frame \"%s\", TF not available at time %f",
442 msg->header.frame_id.c_str(), this->
frameId().c_str(),
stamp);
446 IMU imu(cv::Vec4d(msg->orientation.x, msg->orientation.y, msg->orientation.z, msg->orientation.w),
447 cv::Mat(3,3,CV_64FC1,(
void*)msg->orientation_covariance.data()).clone(),
448 cv::Vec3d(msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z),
449 cv::Mat(3,3,CV_64FC1,(
void*)msg->angular_velocity_covariance.data()).clone(),
450 cv::Vec3d(msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z),
451 cv::Mat(3,3,CV_64FC1,(
void*)msg->linear_acceleration_covariance.data()).clone(),
463 if(!imu.localTransform().isNull())
465 if(imu.orientation()[0] != 0 || imu.orientation()[1] != 0 || imu.orientation()[2] != 0 || imu.orientation()[3] != 0)
467 Transform rotation(0,0,0, imu.orientation()[0], imu.orientation()[1], imu.orientation()[2], imu.orientation()[3]);
470 this->
reset(rotation);
472 rotation.getEulerAngles(r,p,y);
473 NODELET_WARN(
"odometry: Initialized odometry with IMU's orientation (rpy = %f %f %f).", r,p,y);
475 else if(imu.linearAcceleration()[0]!=0.0 &&
476 imu.linearAcceleration()[1]!=0.0 &&
477 imu.linearAcceleration()[2]!=0.0 &&
478 !imu.localTransform().isNull())
480 Eigen::Vector3f n(imu.linearAcceleration()[0], imu.linearAcceleration()[1], imu.linearAcceleration()[2]);
481 n = imu.localTransform().rotation().toEigen3f() * n;
483 Eigen::Vector3f z(0,0,1);
486 R = Eigen::Quaternionf().setFromTwoVectors(n,z);
488 R(0,0), R(0,1), R(0,2), 0,
489 R(1,0), R(1,1), R(1,2), 0,
490 R(2,0), R(2,1), R(2,2), 0);
491 this->
reset(rotation);
494 NODELET_WARN(
"odometry: Initialized odometry with IMU's accelerometer (rpy = %f %f %f).", r,p,y);
500 imus_.insert(std::make_pair(stamp, imu));
509 if(
imus_.size() > 1000)
521 NODELET_WARN(
"odometry: waiting imu to initialize orientation (wait_imu_to_init=true)");
535 "published faster than data rate. (last image stamp " 536 "buffered=%f and new one is %f, last imu stamp received=%f)",
545 std::map<double, rtabmap::IMU>::iterator iterEnd =
imus_.lower_bound(stamp.
toSec());
546 if(iterEnd!=
imus_.end())
550 for(std::map<double, rtabmap::IMU>::iterator iter=
imus_.begin(); iter!=iterEnd;)
553 SensorData dataIMU(iter->second, 0, iter->first);
566 NODELET_WARN(
"Odometry: Detected not valid consecutive stamps (previous=%fs new=%fs). New stamp should be always greater than previous stamp. This new data is ignored. This message will appear only once.",
582 NODELET_WARN(
"Odometry: Aborting odometry update, higher frame rate detected (%f Hz) than the expected one (%f Hz). (stamps: previous=%fs new=%fs)",
598 NODELET_WARN(
"Ground truth frames \"%s\" -> \"%s\" are set but failed to " 599 "get them, odometry won't be initialized with ground truth.",
604 NODELET_INFO(
"Initializing odometry pose to %s (from \"%s\" -> \"%s\")",
621 if(!previousPose.
isNull() && !guessCurrentPose.
isNull())
645 correctionMsg.header.stamp =
stamp;
658 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());
683 poseMsg.header.stamp =
stamp;
694 correctionMsg.header.stamp =
stamp;
709 odom.header.stamp =
stamp;
714 odom.pose.pose.position.x = poseMsg.transform.translation.x;
715 odom.pose.pose.position.y = poseMsg.transform.translation.y;
716 odom.pose.pose.position.z = poseMsg.transform.translation.z;
717 odom.pose.pose.orientation = poseMsg.transform.rotation;
721 odom.pose.covariance.at(0) = info.
reg.
covariance.at<
double>(0,0)*2;
722 odom.pose.covariance.at(7) = info.
reg.
covariance.at<
double>(1,1)*2;
723 odom.pose.covariance.at(14) = info.
reg.
covariance.at<
double>(2,2)*2;
724 odom.pose.covariance.at(21) = info.
reg.
covariance.at<
double>(3,3)*2;
725 odom.pose.covariance.at(28) = info.
reg.
covariance.at<
double>(4,4)*2;
726 odom.pose.covariance.at(35) = info.
reg.
covariance.at<
double>(5,5)*2;
734 odom.twist.twist.linear.x = x;
735 odom.twist.twist.linear.y = y;
736 odom.twist.twist.linear.z = z;
737 odom.twist.twist.angular.x =
roll;
738 odom.twist.twist.angular.y =
pitch;
739 odom.twist.twist.angular.z =
yaw;
759 pcl::PointCloud<pcl::PointXYZRGB> cloud;
760 for(std::map<int, cv::Point3f>::const_iterator iter=info.
localMap.begin(); iter!=info.
localMap.end(); ++iter)
762 bool inlier = info.
words.find(iter->first) != info.
words.end();
766 pt.x = iter->second.x;
767 pt.y = iter->second.y;
768 pt.z = iter->second.z;
771 sensor_msgs::PointCloud2 cloudMsg;
773 cloudMsg.header.stamp =
stamp;
783 const std::vector<cv::Point3f> & words3 = ((
OdometryF2M*)
odometry_)->getLastFrame().getWords3();
786 pcl::PointCloud<pcl::PointXYZ> cloud;
787 for(std::vector<cv::Point3f>::const_iterator iter=words3.begin(); iter!=words3.end(); ++iter)
790 cv::Point3f pt = util3d::transformPoint(*iter, pose);
791 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
794 sensor_msgs::PointCloud2 cloudMsg;
796 cloudMsg.header.stamp =
stamp;
807 pcl::PointCloud<pcl::PointXYZ> cloud;
808 for(std::vector<cv::Point3f>::const_iterator iter=refFrame.
getWords3().begin(); iter!=refFrame.
getWords3().end(); ++iter)
811 cv::Point3f pt = util3d::transformPoint(*iter, pose);
812 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
814 sensor_msgs::PointCloud2 cloudMsg;
816 cloudMsg.header.stamp =
stamp;
825 sensor_msgs::PointCloud2 cloudMsg;
847 cloudMsg.header.stamp =
stamp;
862 odom.header.stamp =
stamp;
893 NODELET_WARN(
"Odometry automatically reset to latest computed pose!");
898 NODELET_WARN(
"Odometry automatically reset to latest odometry pose available from TF (%s->%s)!",
908 rtabmap_ros::OdomInfo infoMsg;
910 infoMsg.header.stamp =
stamp;
917 if(!sensorFrameId.empty())
919 rtabmap_ros::RGBDImage msg;
921 msg.header.stamp =
stamp;
922 msg.header.frame_id = sensorFrameId;
927 ROS_WARN(
"Sensor frame not set, cannot convert SensorData to RGBDImage");
937 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());
961 Transform pose(req.x, req.y, req.z, req.roll, req.pitch, req.yaw);
1010 NODELET_INFO(
"visual_odometry: Set log level to Debug");
1016 NODELET_INFO(
"visual_odometry: Set log level to Info");
1022 NODELET_INFO(
"visual_odometry: Set log level to Warning");
1028 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)
const rtabmap::ParametersMap & parameters() const
double expectedUpdateRate_
ros::Publisher odomRgbdImagePub_
const std::string & frameId() const
unsigned int framesProcessed() const
const V_string & getMyArgv() const
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
void odomInfoToROS(const rtabmap::OdometryInfo &info, rtabmap_ros::OdomInfo &msg)
std::string uReplaceChar(const std::string &str, char before, char after)
std::vector< double > values
virtual void reset(const Transform &initialPose=Transform::getIdentity())
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
bool deleteParam(const std::string &key) const
virtual void updateParameters(rtabmap::ParametersMap ¶meters)
double waitForTransformDuration_
boost::thread * warningThread_
ros::Publisher odomLocalScanMap_
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_
const std::string & getName() const
bool pause(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
std::map< std::string, std::string > ParametersMap
bool publishNullWhenLost_
const Transform & getPose() const
virtual Odometry::Type getType()=0
std::string groundTruthFrameId_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
const LaserScan & laserScanRaw() const
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
ros::ServiceServer setLogDebugSrv_
const cv::Mat & imageRaw() const
void processData(const rtabmap::SensorData &data, const ros::Time &stamp, const std::string &sensorFrameId)
static void setLevel(ULogger::Level level)
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
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
ros::ServiceServer setLogWarnSrv_
static std::string currentDir(bool trailingSeparator=false)
std::string uNumber2Str(unsigned int number)
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 &)
rtabmap::ParametersMap parameters_
ros::ServiceServer setLogErrorSrv_
bool setLogError(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void startWarningThread(const std::string &subscribedTopicsMsg, bool approxSync)
std::string getTopic() const
virtual void flushCallbacks()=0
ros::ServiceServer resetSrv_
std::map< double, rtabmap::IMU > imus_
Transform localTransform() const
ros::ServiceServer pauseSrv_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
ros::ServiceServer resumeSrv_
ros::Publisher odomLocalMap_
rtabmap::Transform guessPreviousPose_
GLM_FUNC_DECL detail::tquat< T, P > rotation(detail::tvec3< T, P > const &orig, detail::tvec3< T, P > const &dest)
const Transform & getVelocityGuess() 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 &)
uint32_t getNumSubscribers() const
const std::vector< cv::Point3f > & getWords3() const
std::multimap< int, cv::KeyPoint > words
rtabmap::Odometry * odometry_
ros::Publisher odomInfoPub_
tf::TransformListener tfListener_
bool getParam(const std::string &key, std::string &s) const
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)
std::string guessFrameId_
void setGroundTruth(const Transform &pose)
bool hasParam(const std::string &key) const
bool resetToPose(rtabmap_ros::ResetPose::Request &, rtabmap_ros::ResetPose::Response &)
virtual bool canProcessIMU() const
ros::Publisher odomLastFrame_
rtabmap::Transform transformFromTF(const tf::Transform &transform)
std::pair< rtabmap::SensorData, std::pair< ros::Time, std::string > > bufferedData_
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool hasIntensity() const
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)