30 #include <sensor_msgs/Image.h>
32 #include <sensor_msgs/PointCloud2.h>
33 #include <nav_msgs/Odometry.h>
47 #include "rtabmap_msgs/OdomInfo.h"
54 #define BAD_COVARIANCE 9999
60 OdometryROS::OdometryROS(
bool stereoParams,
bool visParams,
bool icpParams) :
62 frameId_(
"base_link"),
64 groundTruthFrameId_(
""),
65 groundTruthBaseFrameId_(
""),
67 guessMinTranslation_(0.0),
68 guessMinRotation_(0.0),
71 waitForTransform_(
true),
72 waitForTransformDuration_(0.1),
73 publishNullWhenLost_(
true),
74 publishCompressedSensorData_(
false),
77 resetCurrentCount_(0),
78 stereoParams_(stereoParams),
79 visParams_(visParams),
80 icpParams_(icpParams),
82 expectedUpdateRate_(0.0),
85 compressionImgFormat_(
".jpg"),
86 compressionParallelized_(
true),
87 odomStrategy_(
Parameters::defaultOdomStrategy()),
88 waitIMUToinit_(
false),
116 Transform initialPose = Transform::getIdentity();
117 std::string initialPoseStr;
118 std::string configPath;
124 NODELET_ERROR(
"tf_prefix parameter has been removed, use directly odom_frame_id and frame_id parameters.");
128 pnh.
param(
"initial_pose", initialPoseStr, initialPoseStr);
131 pnh.
param(
"config_path", configPath, configPath);
137 NODELET_ERROR(
"Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
141 NODELET_WARN(
"Parameter \"guess_from_tf\" doesn't exist anymore, it is enabled if \"guess_frame_id\" is set.");
159 pnh.
param(
"log_to_rosout_level", eventLevel, eventLevel);
165 NODELET_WARN(
"\"publish_tf\" and \"guess_frame_id\" cannot be used "
166 "at the same time if \"guess_frame_id\" and \"odom_frame_id\" "
167 "are the same frame (value=\"%s\"). \"guess_frame_id\" is disabled.",
odomFrameId_.c_str());
175 NODELET_INFO(
"Odometry: log_to_rosout_level = %d", eventLevel);
176 NODELET_INFO(
"Odometry: initial_pose = %s", initialPose.prettyPrint().c_str());
179 NODELET_INFO(
"Odometry: config_path = %s", configPath.c_str());
194 if(configPath.size() && configPath.at(0) !=
'/')
199 if(initialPoseStr.size())
210 NODELET_ERROR(
"Wrong initial_pose format: %s (should be \"x y z roll pitch yaw\" with angle in radians). "
211 "Identity will be used...", initialPoseStr.c_str());
230 parameters_.insert(*Parameters::getDefaultParameters().find(Parameters::kRtabmapImagesAlreadyRectified()));
231 if(!configPath.empty())
235 NODELET_INFO(
"Odometry: Loading parameters from %s", configPath.c_str());
237 Parameters::readINI(configPath.c_str(), allParameters);
241 ParametersMap::iterator jter = allParameters.find(
iter->first);
242 if(jter!=allParameters.end())
244 iter->second = jter->second;
250 NODELET_ERROR(
"Config file \"%s\" not found!", configPath.c_str());
261 NODELET_INFO(
"Setting odometry parameter \"%s\"=\"%s\"",
iter->first.c_str(), vStr.c_str());
280 if(
iter->first.compare(Parameters::kVisMinInliers()) == 0 && atoi(
iter->second.c_str()) < 8)
282 NODELET_WARN(
"Parameter min_inliers must be >= 8, setting to 8...");
287 std::vector<std::string> argList =
getMyArgv();
288 char **
argv =
new char*[argList.size()];
289 for(
unsigned int i=0;
i<argList.size(); ++
i)
291 argv[
i] = &argList[
i].at(0);
301 NODELET_INFO(
"Update odometry parameter \"%s\"=\"%s\" from arguments",
iter->first.c_str(),
iter->second.c_str());
302 jter->second =
iter->second;
306 NODELET_INFO(
"Odometry: Ignored parameter \"%s\"=\"%s\" from arguments",
iter->first.c_str(),
iter->second.c_str());
311 for(std::map<std::string, std::pair<bool, std::string> >::const_iterator
iter=Parameters::getRemovedParameters().begin();
312 iter!=Parameters::getRemovedParameters().end();
320 NODELET_WARN(
"Rtabmap: Parameter name changed: \"%s\" -> \"%s\". The new parameter is already used with value \"%s\", ignoring the old one with value \"%s\".",
321 iter->first.c_str(),
iter->second.second.c_str(),
parameters_.find(
iter->second.second)->second.c_str(), vStr.c_str());
327 NODELET_WARN(
"Odometry: Parameter name changed: \"%s\" -> \"%s\". Please update your launch file accordingly. Value \"%s\" is still set to the new parameter name.",
328 iter->first.c_str(),
iter->second.second.c_str(), vStr.c_str());
332 if(
iter->second.second.empty())
334 NODELET_ERROR(
"Odometry: Parameter \"%s\" doesn't exist anymore!",
335 iter->first.c_str());
339 NODELET_ERROR(
"Odometry: Parameter \"%s\" doesn't exist anymore! You may look at this similar parameter: \"%s\"",
340 iter->first.c_str(),
iter->second.second.c_str());
353 parameters_.at(Parameters::kOdomResetCountdown()) =
"0";
358 if(!initialPose.isIdentity())
378 pnh.
param(
"queue_size", queueSize, queueSize);
392 std::vector<diagnostic_updater::DiagnosticTask*> tasks;
395 uFormat(
"%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()),
418 double stamp =
msg->header.stamp.toSec();
424 if(localTransform.
isNull())
426 ROS_ERROR(
"Could not transform IMU msg from frame \"%s\" to frame \"%s\", TF not available at time %f",
427 msg->header.frame_id.c_str(),
this->frameId().c_str(), stamp);
431 IMU imu(cv::Vec4d(
msg->orientation.x,
msg->orientation.y,
msg->orientation.z,
msg->orientation.w),
432 cv::Mat(3,3,CV_64FC1,(
void*)
msg->orientation_covariance.data()).clone(),
433 cv::Vec3d(
msg->angular_velocity.x,
msg->angular_velocity.y,
msg->angular_velocity.z),
434 cv::Mat(3,3,CV_64FC1,(
void*)
msg->angular_velocity_covariance.data()).clone(),
435 cv::Vec3d(
msg->linear_acceleration.x,
msg->linear_acceleration.y,
msg->linear_acceleration.z),
436 cv::Mat(3,3,CV_64FC1,(
void*)
msg->linear_acceleration_covariance.data()).clone(),
442 imus_.insert(std::make_pair(stamp, imu));
443 if(
imus_.size() > 1000)
467 NODELET_ERROR(
"We didn't receive IMU newer than previous image (%f) and we just received a new image (%f). The previous image is dropped!",
504 std::vector<std::pair<double, IMU> > imus;
516 NODELET_WARN(
"Make sure IMU is published faster than data rate! (last image stamp=%f and last imu stamp received=%f). Buffering the image until an imu with same or greater stamp is received.",
522 std::map<double, rtabmap::IMU>::iterator iterEnd =
imus_.lower_bound(
header.stamp.toSec());
523 if(iterEnd!=
imus_.end())
527 for(std::map<double, rtabmap::IMU>::iterator
iter=
imus_.begin();
iter!=iterEnd;)
529 imus.push_back(*
iter);
534 for(
size_t i=0;
i<imus.size(); ++
i)
544 if(!
data.imageRaw().empty() || !
data.laserScanRaw().isEmpty())
548 NODELET_WARN(
"Odometry: Detected not valid consecutive stamps (previous=%fs new=%fs). "
549 "New stamp should be always greater than previous stamp. This new data is ignored.",
565 NODELET_WARN(
"Odometry: Aborting odometry update, higher frame rate detected (%f Hz) than the expected one (%f Hz). (stamps: previous=%fs new=%fs)",
574 if(!
data.imageRaw().empty() || !
data.laserScanRaw().isEmpty())
580 if(
x==0.0
f &&
y==0.0
f &&
z==0.0
f)
585 NODELET_WARN(
"Ground truth frames \"%s\" -> \"%s\" are set but failed to "
586 "get them, odometry won't be initialized with ground truth.",
591 NODELET_INFO(
"Initializing odometry pose to %s (from \"%s\" -> \"%s\")",
611 previousPose = guessCurrentPose;
619 if(!previousPose.
isNull() && !guessCurrentPose.
isNull())
640 geometry_msgs::TransformStamped correctionMsg;
643 correctionMsg.header.stamp =
header.stamp;
656 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());
668 data.setGroundTruth(groundTruth);
671 if(!tooOldPreviousData)
683 geometry_msgs::TransformStamped poseMsg;
686 poseMsg.header.stamp =
header.stamp;
694 geometry_msgs::TransformStamped correctionMsg;
697 correctionMsg.header.stamp =
header.stamp;
711 nav_msgs::Odometry odom;
712 odom.header.stamp =
header.stamp;
717 odom.pose.pose.position.x = poseMsg.transform.translation.x;
718 odom.pose.pose.position.y = poseMsg.transform.translation.y;
719 odom.pose.pose.position.z = poseMsg.transform.translation.z;
720 odom.pose.pose.orientation = poseMsg.transform.rotation;
724 odom.pose.covariance.at(0) =
info.reg.covariance.at<
double>(0,0)*2;
725 odom.pose.covariance.at(7) =
info.reg.covariance.at<
double>(1,1)*2;
726 odom.pose.covariance.at(14) =
info.reg.covariance.at<
double>(2,2)*2;
727 odom.pose.covariance.at(21) =
info.reg.covariance.at<
double>(3,3)*2;
728 odom.pose.covariance.at(28) =
info.reg.covariance.at<
double>(4,4)*2;
729 odom.pose.covariance.at(35) =
info.reg.covariance.at<
double>(5,5)*2;
737 odom.twist.twist.linear.x =
x;
738 odom.twist.twist.linear.y =
y;
739 odom.twist.twist.linear.z =
z;
740 odom.twist.twist.angular.x =
roll;
741 odom.twist.twist.angular.y =
pitch;
742 odom.twist.twist.angular.z =
yaw;
745 odom.twist.covariance.at(0) = setTwist?
info.reg.covariance.at<
double>(0,0):
BAD_COVARIANCE;
746 odom.twist.covariance.at(7) = setTwist?
info.reg.covariance.at<
double>(1,1):
BAD_COVARIANCE;
747 odom.twist.covariance.at(14) = setTwist?
info.reg.covariance.at<
double>(2,2):
BAD_COVARIANCE;
748 odom.twist.covariance.at(21) = setTwist?
info.reg.covariance.at<
double>(3,3):
BAD_COVARIANCE;
749 odom.twist.covariance.at(28) = setTwist?
info.reg.covariance.at<
double>(4,4):
BAD_COVARIANCE;
750 odom.twist.covariance.at(35) = setTwist?
info.reg.covariance.at<
double>(5,5):
BAD_COVARIANCE;
762 pcl::PointCloud<pcl::PointXYZRGB> cloud;
763 for(std::map<int, cv::Point3f>::const_iterator
iter=
info.localMap.begin();
iter!=
info.localMap.end(); ++
iter)
765 bool inlier =
info.words.find(
iter->first) !=
info.words.end();
769 pt.x =
iter->second.x;
770 pt.y =
iter->second.y;
771 pt.z =
iter->second.z;
774 sensor_msgs::PointCloud2 cloudMsg;
776 cloudMsg.header.stamp =
header.stamp;
786 const std::vector<cv::Point3f> & words3 = ((
OdometryF2M*)
odometry_)->getLastFrame().getWords3();
789 pcl::PointCloud<pcl::PointXYZ> cloud;
790 for(std::vector<cv::Point3f>::const_iterator
iter=words3.begin();
iter!=words3.end(); ++
iter)
793 cv::Point3f pt = util3d::transformPoint(*
iter, pose);
794 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
797 sensor_msgs::PointCloud2 cloudMsg;
799 cloudMsg.header.stamp =
header.stamp;
810 pcl::PointCloud<pcl::PointXYZ> cloud;
814 cv::Point3f pt = util3d::transformPoint(*
iter, pose);
815 cloud.push_back(pcl::PointXYZ(pt.x, pt.y, pt.z));
817 sensor_msgs::PointCloud2 cloudMsg;
819 cloudMsg.header.stamp =
header.stamp;
828 sensor_msgs::PointCloud2 cloudMsg;
829 if(
info.localScanMap.hasNormals() &&
info.localScanMap.hasIntensity())
831 pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloud = util3d::laserScanToPointCloudINormal(
info.localScanMap,
info.localScanMap.localTransform());
834 else if(
info.localScanMap.hasNormals())
836 pcl::PointCloud<pcl::PointNormal>::Ptr cloud = util3d::laserScanToPointCloudNormal(
info.localScanMap,
info.localScanMap.localTransform());
839 else if(
info.localScanMap.hasIntensity())
841 pcl::PointCloud<pcl::PointXYZI>::Ptr cloud = util3d::laserScanToPointCloudI(
info.localScanMap,
info.localScanMap.localTransform());
846 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::laserScanToPointCloud(
info.localScanMap,
info.localScanMap.localTransform());
850 cloudMsg.header.stamp =
header.stamp;
855 else if(
data.imageRaw().empty() &&
data.laserScanRaw().isEmpty() && !
data.imu().empty())
866 nav_msgs::Odometry odom;
867 odom.header.stamp =
header.stamp;
890 geometry_msgs::TransformStamped correctionMsg;
893 correctionMsg.header.stamp =
header.stamp;
902 if(tooOldPreviousData)
904 NODELET_WARN(
"Odometry lost! Odometry will be reset because last update "
905 "is %fs too old (>%fs, min_update_rate = %f Hz). Previous data stamp is %f while new data stamp is %f.",
917 NODELET_WARN(
"Odometry automatically reset based on latest guess available from TF (%s->%s, moved %s since got lost)!",
928 NODELET_WARN(
"Odometry automatically reset to latest computed pose!");
933 NODELET_WARN(
"Odometry automatically reset to latest odometry pose available from TF (%s->%s)!",
948 rtabmap_msgs::OdomInfo infoMsg;
950 infoMsg.header.stamp =
header.stamp;
958 infoMsg.wordInliers.clear();
959 infoMsg.wordMatches.clear();
960 infoMsg.wordsKeys.clear();
961 infoMsg.wordsValues.clear();
962 infoMsg.refCorners.clear();
963 infoMsg.newCorners.clear();
964 infoMsg.cornerInliers.clear();
965 infoMsg.localMapKeys.clear();
966 infoMsg.localMapValues.clear();
967 infoMsg.localScanMap = sensor_msgs::PointCloud2();
976 if(!
header.frame_id.empty())
978 rtabmap_msgs::RGBDImage
msg;
985 ROS_WARN(
"Sensor frame not set, cannot convert SensorData to RGBDImage");
991 rtabmap_msgs::SensorData
msg;
1001 msg.left = sensor_msgs::Image();
1002 msg.right = sensor_msgs::Image();
1003 msg.laser_scan = sensor_msgs::PointCloud2();
1004 msg.grid_ground.clear();
1005 msg.grid_obstacles.clear();
1006 msg.grid_empty_cells.clear();
1012 cv::Mat compressedImage;
1013 cv::Mat compressedDepth;
1014 cv::Mat compressedScan;
1020 if(!
data.imageRaw().empty())
1024 if(!
data.depthOrRightRaw().empty())
1028 if(!
data.laserScanRaw().isEmpty())
1030 ctLaserScan.
start();
1046 if(!compressedImage.empty() && !
data.stereoCameraModels().empty())
1048 data.setStereoImage(compressedImage, compressedDepth,
data.stereoCameraModels(),
false);
1050 else if(!compressedImage.empty() && !
data.cameraModels().empty())
1052 data.setRGBDImage(compressedImage, compressedDepth,
data.cameraModels(),
false);
1054 if(!compressedScan.empty())
1056 data.setLaserScan(
data.laserScanRaw().angleIncrement() == 0.0f?
1058 data.laserScanRaw().maxPoints(),
1059 data.laserScanRaw().rangeMax(),
1060 data.laserScanRaw().format(),
1061 data.laserScanRaw().localTransform()):
1063 data.laserScanRaw().format(),
1064 data.laserScanRaw().rangeMin(),
1065 data.laserScanRaw().rangeMax(),
1066 data.laserScanRaw().angleMin(),
1067 data.laserScanRaw().angleMax(),
1068 data.laserScanRaw().angleIncrement(),
1069 data.laserScanRaw().localTransform()),
false);
1071 rtabmap_msgs::SensorData
msg;
1082 NODELET_INFO(
"Odom: quality=%d, ratio=%f, std dev=%fm|%frad, update time=%fs, delay=%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(), delay);
1086 NODELET_INFO(
"Odom: quality=%d, std dev=%fm|%frad, update time=%fs, delay=%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(), delay);
1091 NODELET_INFO(
"Odom: ratio=%f, std dev=%fm|%frad, update time=%fs, delay=%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(), delay);
1116 Transform pose(req.x, req.y, req.z, req.roll, req.pitch, req.yaw);
1170 NODELET_INFO(
"visual_odometry: Set log level to Debug");
1176 NODELET_INFO(
"visual_odometry: Set log level to Info");
1182 NODELET_INFO(
"visual_odometry: Set log level to Warning");
1188 NODELET_INFO(
"visual_odometry: Set log level to Error");
1196 dataReceived_(
false)
1201 dataReceived_ =
true;
1209 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"No data received!");
1213 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Lost!");
1217 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Tracking.");