00001 #include "mrpt_rbpf_slam/mrpt_rbpf_slam_wrapper.h"
00002 #include <mrpt/maps/CBeaconMap.h>
00003 #include <mrpt/maps/COccupancyGridMap2D.h>
00004 #include <mrpt_rbpf_slam/options.h>
00005 using mrpt::maps::CBeaconMap;
00006 using mrpt::maps::COccupancyGridMap2D;
00007
00008 namespace {
00009 bool isFileExists(const std::string &name) {
00010 std::ifstream f(name.c_str());
00011 return f.good();
00012 }
00013 }
00014
00015 namespace mrpt_rbpf_slam {
00016 PFslamWrapper::PFslamWrapper() {
00017 mrpt_bridge::convert(ros::Time(0), timeLastUpdate_);
00018 }
00019
00020 bool PFslamWrapper::getParams(const ros::NodeHandle &nh_p) {
00021 ROS_INFO("READ PARAM FROM LAUNCH FILE");
00022 nh_p.param<double>("rawlog_play_delay", rawlog_play_delay_, 0.1);
00023 ROS_INFO("rawlog_play_delay: %f", rawlog_play_delay_);
00024
00025 nh_p.getParam("rawlog_filename", rawlog_filename_);
00026 ROS_INFO("rawlog_filename: %s", rawlog_filename_.c_str());
00027
00028 nh_p.getParam("ini_filename", ini_filename_);
00029 ROS_INFO("ini_filename: %s", ini_filename_.c_str());
00030
00031 nh_p.param<std::string>("global_frame_id", global_frame_id_, "map");
00032 ROS_INFO("global_frame_id: %s", global_frame_id_.c_str());
00033
00034 nh_p.param<std::string>("odom_frame_id", odom_frame_id_, "odom");
00035 ROS_INFO("odom_frame_id: %s", odom_frame_id_.c_str());
00036
00037 nh_p.param<std::string>("base_frame_id", base_frame_id_, "base_link");
00038 ROS_INFO("base_frame_id: %s", base_frame_id_.c_str());
00039
00040 nh_p.param<std::string>("sensor_source", sensor_source_, "scan");
00041 ROS_INFO("sensor_source: %s", sensor_source_.c_str());
00042
00043 PFslam::Options options;
00044 if (!loadOptions(nh_p, options)) {
00045 ROS_ERROR("Not able to read all parameters!");
00046 return false;
00047 }
00048 initSlam(std::move(options));
00049 return true;
00050 }
00051
00052 bool PFslamWrapper::init(ros::NodeHandle &nh) {
00053
00054 if (!isFileExists(ini_filename_)) {
00055 ROS_ERROR_STREAM("CAN'T READ INI FILE" << ini_filename_);
00056 return false;
00057 }
00058
00059 PFslam::readIniFile(ini_filename_);
00060
00061
00062 if (isFileExists(rawlog_filename_)) {
00063 ROS_WARN_STREAM("PLAY FROM RAWLOG FILE: " << rawlog_filename_);
00064 PFslam::readRawlog(rawlog_filename_, data_);
00065 rawlog_play_ = true;
00066 }
00067
00069
00070 pub_map_ = nh.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00071 pub_metadata_ = nh.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
00072
00073 pub_particles_ =
00074 nh.advertise<geometry_msgs::PoseArray>("particlecloud", 1, true);
00075
00076 pub_particles_beacons_ =
00077 nh.advertise<geometry_msgs::PoseArray>("particlecloud_beacons", 1, true);
00078 beacon_viz_pub_ =
00079 nh.advertise<visualization_msgs::MarkerArray>("/beacons_viz", 1);
00080
00081
00082 std::vector<std::string> lstSources;
00083 mrpt::system::tokenize(sensor_source_, " ,\t\n", lstSources);
00084 ROS_ASSERT_MSG(!lstSources.empty(),
00085 "*Fatal*: At least one sensor source must be provided in "
00086 "~sensor_sources (e.g. "
00087 "\"scan\" or \"beacon\")");
00088
00090 sensorSub_.resize(lstSources.size());
00091 for (size_t i = 0; i < lstSources.size(); i++) {
00092 if (lstSources[i].find("scan") != std::string::npos) {
00093 sensorSub_[i] =
00094 nh.subscribe(lstSources[i], 1, &PFslamWrapper::laserCallback, this);
00095 } else {
00096 sensorSub_[i] =
00097 nh.subscribe(lstSources[i], 1, &PFslamWrapper::callbackBeacon, this);
00098 }
00099 }
00100
00101 mapBuilder_ = mrpt::slam::CMetricMapBuilderRBPF(options_.rbpfMappingOptions_);
00102 init3Dwindow();
00103 return true;
00104 }
00105
00106 void PFslamWrapper::odometryForCallback(
00107 mrpt::obs::CObservationOdometry::Ptr &odometry,
00108 const std_msgs::Header &_msg_header) {
00109 mrpt::poses::CPose3D poseOdom;
00110 if (this->waitForTransform(poseOdom, odom_frame_id_, base_frame_id_,
00111 _msg_header.stamp, ros::Duration(1))) {
00112 odometry = mrpt::obs::CObservationOdometry::Create();
00113 odometry->sensorLabel = odom_frame_id_;
00114 odometry->hasEncodersInfo = false;
00115 odometry->hasVelocities = false;
00116 odometry->odometry.x() = poseOdom.x();
00117 odometry->odometry.y() = poseOdom.y();
00118 odometry->odometry.phi() = poseOdom.yaw();
00119 }
00120 }
00121
00122 bool PFslamWrapper::waitForTransform(
00123 mrpt::poses::CPose3D &des, const std::string &target_frame,
00124 const std::string &source_frame, const ros::Time &time,
00125 const ros::Duration &timeout, const ros::Duration &polling_sleep_duration) {
00126 tf::StampedTransform transform;
00127 try {
00128 listenerTF_.waitForTransform(target_frame, source_frame, time, timeout,
00129 polling_sleep_duration);
00130 listenerTF_.lookupTransform(target_frame, source_frame, time, transform);
00131 } catch (tf::TransformException ex) {
00132 ROS_ERROR("Failed to get transform target_frame (%s) to source_frame (%s). "
00133 "TransformException: %s",
00134 target_frame.c_str(), source_frame.c_str(), ex.what());
00135 return false;
00136 }
00137 mrpt_bridge::convert(transform, des);
00138 return true;
00139 }
00140
00141 void PFslamWrapper::laserCallback(const sensor_msgs::LaserScan &msg) {
00142 using namespace mrpt::maps;
00143 using namespace mrpt::obs;
00144 CObservation2DRangeScan::Ptr laser = CObservation2DRangeScan::Create();
00145
00146 if (laser_poses_.find(msg.header.frame_id) == laser_poses_.end()) {
00147 updateSensorPose(msg.header.frame_id);
00148 } else {
00149 mrpt::poses::CPose3D pose = laser_poses_[msg.header.frame_id];
00150 mrpt_bridge::convert(msg, laser_poses_[msg.header.frame_id], *laser);
00151
00152 sensory_frame_ = CSensoryFrame::Create();
00153 CObservationOdometry::Ptr odometry;
00154 odometryForCallback(odometry, msg.header);
00155
00156 CObservation::Ptr obs = CObservation::Ptr(laser);
00157 sensory_frame_->insert(obs);
00158 observation(sensory_frame_, odometry);
00159 timeLastUpdate_ = sensory_frame_->getObservationByIndex(0)->timestamp;
00160
00161 tictac_.Tic();
00162 mapBuilder_.processActionObservation(*action_, *sensory_frame_);
00163 t_exec_ = tictac_.Tac();
00164 ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec_);
00165 publishMapPose();
00166 run3Dwindow();
00167 publishTF();
00168 }
00169 }
00170
00171 void PFslamWrapper::callbackBeacon(
00172 const mrpt_msgs::ObservationRangeBeacon &msg) {
00173 using namespace mrpt::maps;
00174 using namespace mrpt::obs;
00175
00176 CObservationBeaconRanges::Ptr beacon = CObservationBeaconRanges::Create();
00177 if (beacon_poses_.find(msg.header.frame_id) == beacon_poses_.end()) {
00178 updateSensorPose(msg.header.frame_id);
00179 } else {
00180 mrpt_bridge::convert(msg, beacon_poses_[msg.header.frame_id], *beacon);
00181
00182 sensory_frame_ = CSensoryFrame::Create();
00183 CObservationOdometry::Ptr odometry;
00184 odometryForCallback(odometry, msg.header);
00185
00186 CObservation::Ptr obs = CObservation::Ptr(beacon);
00187 sensory_frame_->insert(obs);
00188 observation(sensory_frame_, odometry);
00189 timeLastUpdate_ = sensory_frame_->getObservationByIndex(0)->timestamp;
00190
00191 tictac_.Tic();
00192 mapBuilder_.processActionObservation(*action_, *sensory_frame_);
00193 t_exec_ = tictac_.Tac();
00194 ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec_);
00195
00196 publishMapPose();
00197 run3Dwindow();
00198 }
00199 }
00200
00201 void PFslamWrapper::publishMapPose() {
00202
00203 metric_map_ = mapBuilder_.mapPDF.getCurrentMostLikelyMetricMap();
00204 mapBuilder_.mapPDF.getEstimatedPosePDF(curPDF);
00205
00206
00207 COccupancyGridMap2D *grid = nullptr;
00208 CBeaconMap *bm = nullptr;
00209 #if MRPT_VERSION >= 0x199
00210 if (metric_map_->countMapsByClass<COccupancyGridMap2D>())
00211 grid = metric_map_->mapByClass<COccupancyGridMap2D>().get();
00212 bm = metric_map_->mapByClass<CBeaconMap>().get();
00213 #else
00214 if (metric_map_->m_gridMaps.size())
00215 grid = metric_map_->m_gridMaps[0].get();
00216 bm = metric_map_->getMapByClass<CBeaconMap>().get();
00217 #endif
00218
00219 if (grid) {
00220
00221 nav_msgs::OccupancyGrid msg;
00222 mrpt_bridge::convert(*grid, msg);
00223 pub_map_.publish(msg);
00224 pub_metadata_.publish(msg.info);
00225 }
00226
00227
00228 if (bm) {
00229 mrpt::opengl::CSetOfObjects::Ptr objs;
00230
00231 objs = mrpt::opengl::CSetOfObjects::Create();
00232
00233 bm->getAs3DObject(objs);
00234
00235 geometry_msgs::PoseArray poseArrayBeacons;
00236 poseArrayBeacons.header.frame_id = global_frame_id_;
00237 poseArrayBeacons.header.stamp = ros::Time::now();
00238
00239
00240 unsigned int objs_counter = 0;
00241 while (objs->getByClass<mrpt::opengl::CEllipsoid>(objs_counter)) {
00242 objs_counter++;
00243 }
00244 poseArrayBeacons.poses.resize(objs_counter);
00245 mrpt::opengl::CEllipsoid::Ptr beacon_particle;
00246
00247 for (size_t i = 0; i < objs_counter; i++) {
00248 beacon_particle = objs->getByClass<mrpt::opengl::CEllipsoid>(i);
00249 mrpt_bridge::convert(mrpt::poses::CPose3D(beacon_particle->getPose()),
00250 poseArrayBeacons.poses[i]);
00251 viz_beacons_.push_back(beacon_particle);
00252 }
00253 pub_particles_beacons_.publish(poseArrayBeacons);
00254 vizBeacons();
00255 viz_beacons_.clear();
00256 }
00257
00258
00259 geometry_msgs::PoseArray poseArray;
00260 poseArray.header.frame_id = global_frame_id_;
00261 poseArray.header.stamp = ros::Time::now();
00262 poseArray.poses.resize(curPDF.particlesCount());
00263 for (size_t i = 0; i < curPDF.particlesCount(); i++) {
00264 const auto p = mrpt::poses::CPose3D(curPDF.getParticlePose(i));
00265 mrpt_bridge::convert(p, poseArray.poses[i]);
00266 }
00267
00268 pub_particles_.publish(poseArray);
00269 }
00270
00271 void PFslamWrapper::vizBeacons() {
00272 if (viz_beacons_.size() == 0) {
00273 return;
00274 }
00275 visualization_msgs::MarkerArray ma;
00276 visualization_msgs::Marker marker;
00277
00278 marker.header.frame_id = "/map";
00279
00280 marker.id = 0;
00281 marker.type = visualization_msgs::Marker::SPHERE;
00282 marker.action = visualization_msgs::Marker::ADD;
00283 marker.lifetime = ros::Duration(1);
00284 marker.pose.position.x = 0;
00285 marker.pose.position.y = 0;
00286 marker.pose.position.z = 0;
00287 marker.pose.orientation.x = 0.0;
00288 marker.pose.orientation.y = 0.0;
00289 marker.pose.orientation.z = 0.0;
00290 marker.pose.orientation.w = 1.0;
00291 marker.scale.x = 0.12;
00292 marker.scale.y = 0.12;
00293 marker.scale.z = 0.12;
00294 marker.color.a = 1.0;
00295 marker.color.r = 1.0;
00296 marker.color.g = 0.0;
00297
00298 for (unsigned int i = 0; i < viz_beacons_.size(); i++) {
00299 mrpt::poses::CPose3D meanPose(viz_beacons_[i]->getPose());
00300 marker.type = visualization_msgs::Marker::SPHERE;
00301
00302 marker.pose.position.x = meanPose.x();
00303 marker.pose.position.y = meanPose.y();
00304 marker.pose.position.z = meanPose.z();
00305 marker.color.r = 1.0;
00306 marker.color.g = 0.0;
00307 marker.color.b = 0.0;
00308
00309 ma.markers.push_back(marker);
00310 marker.id++;
00311
00312 marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00313 marker.text = std::to_string(i);
00314
00315 marker.pose.position.x = meanPose.x();
00316 marker.pose.position.y = meanPose.y();
00317 marker.pose.position.z = meanPose.z() + 0.12;
00318 marker.color.r = 1.0;
00319 marker.color.g = 1.0;
00320 marker.color.b = 1.0;
00321
00322 ma.markers.push_back(marker);
00323 marker.id++;
00324 }
00325
00326 beacon_viz_pub_.publish(ma);
00327 }
00328
00329 void PFslamWrapper::updateSensorPose(const std::string &frame_id) {
00330 mrpt::poses::CPose3D pose;
00331 tf::StampedTransform transform;
00332 try {
00333 listenerTF_.lookupTransform(base_frame_id_, frame_id, ros::Time(0),
00334 transform);
00335
00336 tf::Vector3 translation = transform.getOrigin();
00337 tf::Quaternion quat = transform.getRotation();
00338 pose.x() = translation.x();
00339 pose.y() = translation.y();
00340 pose.z() = translation.z();
00341 tf::Matrix3x3 Rsrc(quat);
00342 mrpt::math::CMatrixDouble33 Rdes;
00343 for (int c = 0; c < 3; c++)
00344 for (int r = 0; r < 3; r++)
00345 Rdes(r, c) = Rsrc.getRow(r)[c];
00346 pose.setRotationMatrix(Rdes);
00347 laser_poses_[frame_id] = pose;
00348 beacon_poses_[frame_id] = pose;
00349 } catch (tf::TransformException ex) {
00350 ROS_ERROR("%s", ex.what());
00351 ros::Duration(1.0).sleep();
00352 }
00353 }
00354
00355 bool PFslamWrapper::rawlogPlay() {
00356 if (rawlog_play_ == false) {
00357 return false;
00358 } else {
00359 for (unsigned int i = 0; i < data_.size(); i++) {
00360 if (ros::ok()) {
00361 tictac_.Tic();
00362 mapBuilder_.processActionObservation(data_[i].first, data_[i].second);
00363 t_exec_ = tictac_.Tac();
00364 ROS_INFO("Map building executed in %.03fms", 1000.0f * t_exec_);
00365
00366 ros::Duration(rawlog_play_delay_).sleep();
00367
00368 metric_map_ = mapBuilder_.mapPDF.getCurrentMostLikelyMetricMap();
00369 mapBuilder_.mapPDF.getEstimatedPosePDF(curPDF);
00370
00371 COccupancyGridMap2D *grid = nullptr;
00372 CBeaconMap *bm = nullptr;
00373 #if MRPT_VERSION >= 0x199
00374 if (metric_map_->countMapsByClass<COccupancyGridMap2D>())
00375 grid = metric_map_->mapByClass<COccupancyGridMap2D>().get();
00376 bm = metric_map_->mapByClass<CBeaconMap>().get();
00377 #else
00378 if (metric_map_->m_gridMaps.size())
00379 grid = metric_map_->m_gridMaps[0].get();
00380 bm = metric_map_->getMapByClass<CBeaconMap>().get();
00381 #endif
00382
00383
00384 if (grid) {
00385 nav_msgs::OccupancyGrid msg;
00386
00387 mrpt_bridge::convert(*grid, msg);
00388 pub_map_.publish(msg);
00389 pub_metadata_.publish(msg.info);
00390 }
00391
00392
00393 if (bm) {
00394 mrpt::opengl::CSetOfObjects::Ptr objs;
00395 objs = mrpt::opengl::CSetOfObjects::Create();
00396 bm->getAs3DObject(objs);
00397
00398 geometry_msgs::PoseArray poseArrayBeacons;
00399 poseArrayBeacons.header.frame_id = global_frame_id_;
00400 poseArrayBeacons.header.stamp = ros::Time::now();
00401
00402 unsigned int objs_counter = 0;
00403 while (objs->getByClass<mrpt::opengl::CEllipsoid>(objs_counter)) {
00404 objs_counter++;
00405 }
00406 poseArrayBeacons.poses.resize(objs_counter);
00407 mrpt::opengl::CEllipsoid::Ptr beacon_particle;
00408
00409 for (size_t i = 0; i < objs_counter; i++) {
00410 beacon_particle = objs->getByClass<mrpt::opengl::CEllipsoid>(i);
00411 mrpt_bridge::convert(
00412 mrpt::poses::CPose3D(beacon_particle->getPose()),
00413 poseArrayBeacons.poses[i]);
00414 viz_beacons_.push_back(beacon_particle);
00415 }
00416 pub_particles_beacons_.publish(poseArrayBeacons);
00417 vizBeacons();
00418 viz_beacons_.clear();
00419 }
00420
00421
00422 geometry_msgs::PoseArray poseArray;
00423 poseArray.header.frame_id = global_frame_id_;
00424 poseArray.header.stamp = ros::Time::now();
00425 poseArray.poses.resize(curPDF.particlesCount());
00426 for (size_t i = 0; i < curPDF.particlesCount(); i++) {
00427 const auto p = mrpt::poses::CPose3D(curPDF.getParticlePose(i));
00428 mrpt_bridge::convert(p, poseArray.poses[i]);
00429 }
00430
00431 pub_particles_.publish(poseArray);
00432 }
00433 ros::spinOnce();
00434 run3Dwindow();
00435 }
00436 }
00437
00438
00439 if (win3D_)
00440 win3D_->waitForKey();
00441 return true;
00442 }
00443
00444 void PFslamWrapper::publishTF() {
00445
00446 mrpt::poses::CPose3D robotPose;
00447 mapBuilder_.mapPDF.getEstimatedPosePDF(curPDF);
00448
00449 curPDF.getMean(robotPose);
00450
00451 tf::Stamped<tf::Pose> odom_to_map;
00452 tf::Transform tmp_tf;
00453 ros::Time stamp;
00454 mrpt_bridge::convert(timeLastUpdate_, stamp);
00455 mrpt_bridge::convert(robotPose, tmp_tf);
00456
00457 try {
00458 tf::Stamped<tf::Pose> tmp_tf_stamped(tmp_tf.inverse(), stamp,
00459 base_frame_id_);
00460 listenerTF_.transformPose(odom_frame_id_, tmp_tf_stamped, odom_to_map);
00461 } catch (tf::TransformException ex) {
00462 ROS_ERROR("Failed to subtract global_frame (%s) from odom_frame (%s). "
00463 "TransformException: %s",
00464 global_frame_id_.c_str(), odom_frame_id_.c_str(), ex.what());
00465 return;
00466 }
00467
00468 tf::Transform latest_tf_ =
00469 tf::Transform(tf::Quaternion(odom_to_map.getRotation()),
00470 tf::Point(odom_to_map.getOrigin()));
00471
00472
00473
00474
00475 ros::Duration transform_tolerance_(0.5);
00476 ros::Time transform_expiration = (stamp + transform_tolerance_);
00477 tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(),
00478 transform_expiration, global_frame_id_,
00479 odom_frame_id_);
00480 tf_broadcaster_.sendTransform(tmp_tf_stamped);
00481 }
00482
00483 }