30 #include <sensor_msgs/Image.h> 32 #include <sensor_msgs/PointCloud2.h> 33 #include <nav_msgs/Odometry.h> 47 #include "rtabmap_ros/OdomInfo.h" 54 #define BAD_COVARIANCE 9999 60 OdometryROS::OdometryROS(
bool stereoParams,
bool visParams,
bool icpParams) :
63 callbackCalled_(
false),
64 frameId_(
"base_link"),
66 groundTruthFrameId_(
""),
67 groundTruthBaseFrameId_(
""),
69 guessMinTranslation_(0.0),
70 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),
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.");
151 NODELET_WARN(
"\"publish_tf\" and \"guess_frame_id\" cannot be used " 152 "at the same time if \"guess_frame_id\" and \"odom_frame_id\" " 153 "are the same frame (value=\"%s\"). \"guess_frame_id\" is disabled.",
odomFrameId_.c_str());
159 NODELET_INFO(
"Odometry: wait_for_transform = %s",
waitForTransform_?
"true":
"false");
161 NODELET_INFO(
"Odometry: initial_pose = %s", initialPose.prettyPrint().c_str());
164 NODELET_INFO(
"Odometry: config_path = %s", configPath.c_str());
166 NODELET_INFO(
"Odometry: guess_frame_id = %s",
guessFrameId_.c_str());
171 if(configPath.size() && configPath.at(0) !=
'/')
176 if(initialPoseStr.size())
179 if(values.size() == 6)
187 NODELET_ERROR(
"Wrong initial_pose format: %s (should be \"x y z roll pitch yaw\" with angle in radians). " 188 "Identity will be used...", initialPoseStr.c_str());
195 parameters_.insert(*Parameters::getDefaultParameters().
find(Parameters::kRtabmapImagesAlreadyRectified()));
196 if(!configPath.empty())
200 NODELET_INFO(
"Odometry: Loading parameters from %s", configPath.c_str());
202 Parameters::readINI(configPath.c_str(), allParameters);
204 for(ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
206 ParametersMap::iterator jter = allParameters.find(iter->first);
207 if(jter!=allParameters.end())
209 iter->second = jter->second;
215 NODELET_ERROR(
"Config file \"%s\" not found!", configPath.c_str());
218 for(rtabmap::ParametersMap::iterator iter=parameters_.begin(); iter!=parameters_.end(); ++iter)
226 NODELET_INFO(
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(), vStr.c_str());
229 else if(pnh.
getParam(iter->first, vBool))
231 NODELET_INFO(
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(),
uBool2Str(vBool).c_str());
234 else if(pnh.
getParam(iter->first, vDouble))
236 NODELET_INFO(
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vDouble).c_str());
239 else if(pnh.
getParam(iter->first, vInt))
241 NODELET_INFO(
"Setting odometry parameter \"%s\"=\"%s\"", iter->first.c_str(),
uNumber2Str(vInt).c_str());
245 if(iter->first.compare(Parameters::kVisMinInliers()) == 0 && atoi(iter->second.c_str()) < 8)
247 NODELET_WARN(
"Parameter min_inliers must be >= 8, setting to 8...");
252 std::vector<std::string> argList =
getMyArgv();
253 char * argv[argList.size()];
254 for(
unsigned int i=0; i<argList.size(); ++i)
256 argv[i] = &argList[i].at(0);
260 for(rtabmap::ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
262 rtabmap::ParametersMap::iterator jter = parameters_.find(iter->first);
263 if(jter!=parameters_.end())
265 NODELET_INFO(
"Update odometry parameter \"%s\"=\"%s\" from arguments", iter->first.c_str(), iter->second.c_str());
266 jter->second = iter->second;
271 for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter=Parameters::getRemovedParameters().begin();
272 iter!=Parameters::getRemovedParameters().end();
278 if(iter->second.first && parameters_.find(iter->second.second) != parameters_.end())
281 parameters_.at(iter->second.second)= vStr;
282 NODELET_WARN(
"Odometry: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
283 iter->first.c_str(), iter->second.second.c_str(), vStr.c_str());
287 if(iter->second.second.empty())
289 NODELET_ERROR(
"Odometry: Parameter \"%s\" doesn't exist anymore!",
290 iter->first.c_str());
294 NODELET_ERROR(
"Odometry: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
295 iter->first.c_str(), iter->second.second.c_str());
301 Parameters::parse(parameters_, Parameters::kOdomResetCountdown(),
resetCountdown_);
302 parameters_.at(Parameters::kOdomResetCountdown()) =
"0";
306 odometry_ = Odometry::create(parameters_);
307 if(!initialPose.isIdentity())
339 ROS_WARN(
"%s: Did not receive data since 5 seconds! Make sure the input topics are " 340 "published (\"$ rostopic hz my_topic\") and the timestamps in their " 341 "header are set. %s%s",
343 approxSync?
"":
"Parameter \"approx_sync\" is false, which means that input " 344 "topics should have all the exact timestamp for the callback to be called.",
345 subscribedTopicsMsg.c_str());
359 std::string errorMsg;
362 NODELET_WARN(
"odometry: Could not get transform from %s to %s (stamp=%f) after %f seconds (\"wait_for_transform_duration\"=%f)! Error=\"%s\"",
390 NODELET_WARN(
"Ground truth frames \"%s\" -> \"%s\" are set but failed to " 391 "get them, odometry won't be synchronized with ground truth.",
396 NODELET_INFO(
"Initializing odometry pose to %s (from \"%s\" -> \"%s\")",
410 if(!previousPose.
isNull() && !guessCurrentPose.
isNull())
433 correctionMsg.header.stamp = stamp;
446 NODELET_ERROR(
"\"guess_from_tf\" is true, but guess cannot be computed between frames \"%s\" -> \"%s\". Aborting odometry update...",
guessFrameId_.c_str(),
frameId_.c_str());
467 poseMsg.header.stamp = stamp;
478 correctionMsg.header.stamp = stamp;
492 nav_msgs::Odometry odom;
493 odom.header.stamp = stamp;
498 odom.pose.pose.position.x = poseMsg.transform.translation.x;
499 odom.pose.pose.position.y = poseMsg.transform.translation.y;
500 odom.pose.pose.position.z = poseMsg.transform.translation.z;
501 odom.pose.pose.orientation = poseMsg.transform.rotation;
505 odom.pose.covariance.at(0) = info.
reg.
covariance.at<
double>(0,0)*2;
506 odom.pose.covariance.at(7) = info.
reg.
covariance.at<
double>(1,1)*2;
507 odom.pose.covariance.at(14) = info.
reg.
covariance.at<
double>(2,2)*2;
508 odom.pose.covariance.at(21) = info.
reg.
covariance.at<
double>(3,3)*2;
509 odom.pose.covariance.at(28) = info.
reg.
covariance.at<
double>(4,4)*2;
510 odom.pose.covariance.at(35) = info.
reg.
covariance.at<
double>(5,5)*2;
518 odom.twist.twist.linear.x = x;
519 odom.twist.twist.linear.y = y;
520 odom.twist.twist.linear.z = z;
521 odom.twist.twist.angular.x =
roll;
522 odom.twist.twist.angular.y =
pitch;
523 odom.twist.twist.angular.z =
yaw;
543 pcl::PointCloud<pcl::PointXYZRGB> cloud;
544 for(std::map<int, cv::Point3f>::const_iterator iter=info.
localMap.begin(); iter!=info.
localMap.end(); ++iter)
546 bool inlier = info.
words.find(iter->first) != info.
words.end();
547 pcl::PointXYZRGB pt(inlier?0:255, 255, 0);
548 pt.x = iter->second.x;
549 pt.y = iter->second.y;
550 pt.z = iter->second.z;
553 sensor_msgs::PointCloud2 cloudMsg;
555 cloudMsg.header.stamp = stamp;
565 const std::multimap<int, cv::Point3f> & words3 = ((
OdometryF2M*)
odometry_)->getLastFrame().getWords3();
568 pcl::PointCloud<pcl::PointXYZ> cloud;
569 for(std::multimap<int, cv::Point3f>::const_iterator iter=words3.begin(); iter!=words3.end(); ++iter)
572 cv::Point3f pt = util3d::transformPoint(iter->second, pose);
573 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
576 sensor_msgs::PointCloud2 cloudMsg;
578 cloudMsg.header.stamp = stamp;
589 pcl::PointCloud<pcl::PointXYZ> cloud;
590 for(std::multimap<int, cv::Point3f>::const_iterator iter=refFrame.
getWords3().begin(); iter!=refFrame.
getWords3().end(); ++iter)
593 cv::Point3f pt = util3d::transformPoint(iter->second, pose);
594 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
596 sensor_msgs::PointCloud2 cloudMsg;
598 cloudMsg.header.stamp = stamp;
607 sensor_msgs::PointCloud2 cloudMsg;
619 cloudMsg.header.stamp = stamp;
633 nav_msgs::Odometry odom;
634 odom.header.stamp = stamp;
665 NODELET_WARN(
"Odometry automatically reset to latest computed pose!");
670 NODELET_WARN(
"Odometry automatically reset to latest odometry pose available from TF (%s->%s)!",
680 rtabmap_ros::OdomInfo infoMsg;
682 infoMsg.header.stamp = stamp;
693 NODELET_INFO(
"Odom: quality=%d, ratio=%f, std dev=%fm|%frad, update time=%fs", info.
reg.
inliers, info.
reg.
icpInliersRatio, pose.
isNull()?0.0f:
std::sqrt(info.
reg.
covariance.at<
double>(0,0)), pose.
isNull()?0.0f:
std::sqrt(info.
reg.
covariance.at<
double>(5,5)), (
ros::WallTime::now()-time).toSec());
720 Transform pose(req.x, req.y, req.z, req.roll, req.pitch, req.yaw);
760 NODELET_INFO(
"visual_odometry: Set log level to Debug");
766 NODELET_INFO(
"visual_odometry: Set log level to Info");
772 NODELET_INFO(
"visual_odometry: Set log level to Warning");
778 NODELET_INFO(
"visual_odometry: Set log level to Error");
const std::multimap< int, cv::Point3f > & getWords3() const
std::string groundTruthBaseFrameId_
static std::string homeDir()
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
const rtabmap::ParametersMap & parameters() 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)
void processData(const rtabmap::SensorData &data, const ros::Time &stamp)
std::string uReplaceChar(const std::string &str, char before, char after)
std::vector< double > values
virtual void reset(const Transform &initialPose=Transform::getIdentity())
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
tf2_ros::TransformBroadcaster tfBroadcaster_
std::map< int, cv::Point3f > localMap
bool deleteParam(const std::string &key) const
virtual void updateParameters(rtabmap::ParametersMap ¶meters)
double waitForTransformDuration_
boost::thread * warningThread_
ros::Publisher odomLocalScanMap_
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)
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
ros::ServiceServer setLogDebugSrv_
const cv::Mat & imageRaw() const
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)
const Transform & previousVelocityTransform() const
ros::ServiceServer resetToPoseSrv_
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
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)
virtual void flushCallbacks()=0
ros::ServiceServer resetSrv_
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_
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
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_
bool hasParam(const std::string &key) const
bool resetToPose(rtabmap_ros::ResetPose::Request &, rtabmap_ros::ResetPose::Response &)
ros::Publisher odomLastFrame_
rtabmap::Transform transformFromTF(const tf::Transform &transform)
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)