00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <boost/interprocess/sync/scoped_lock.hpp>
00035 #include <geometry_msgs/PoseArray.h>
00036 #include <pose_cov_ops/pose_cov_ops.h>
00037
00038 #include <mrpt_bridge/pose.h>
00039 #include <mrpt_bridge/laser_scan.h>
00040 #include <mrpt_bridge/time.h>
00041 #include <mrpt_bridge/map.h>
00042 #include <mrpt_bridge/beacon.h>
00043
00044 #include <mrpt/version.h>
00045 #include <mrpt/obs/CObservationBeaconRanges.h>
00046 using namespace mrpt::obs;
00047
00048 #include <mrpt/version.h>
00049
00050 #if MRPT_VERSION >= 0x199
00051 #include <mrpt/system/COutputLogger.h>
00052 using namespace mrpt::system;
00053 #else
00054 #include <mrpt/utils/COutputLogger.h>
00055 using namespace mrpt::utils;
00056 #endif
00057
00058 #include <mrpt/obs/CObservationRobotPose.h>
00059
00060 #include "mrpt_localization_node.h"
00061
00062 #include <mrpt/maps/COccupancyGridMap2D.h>
00063 using mrpt::maps::COccupancyGridMap2D;
00064
00065 int main(int argc, char** argv)
00066 {
00067 ros::init(argc, argv, "localization");
00068 ros::NodeHandle nh;
00069 PFLocalizationNode my_node(nh);
00070 my_node.init();
00071 my_node.loop();
00072 return 0;
00073 }
00074
00075 PFLocalizationNode::~PFLocalizationNode() {}
00076 PFLocalizationNode::PFLocalizationNode(ros::NodeHandle& n)
00077 : PFLocalization(new PFLocalizationNode::Parameters(this)),
00078 nh_(n),
00079 first_map_received_(false),
00080 loop_count_(0)
00081 {
00082 }
00083
00084 PFLocalizationNode::Parameters* PFLocalizationNode::param()
00085 {
00086 return (PFLocalizationNode::Parameters*)param_;
00087 }
00088
00089 void PFLocalizationNode::init()
00090 {
00091
00092
00093 useROSLogLevel();
00094
00095 PFLocalization::init();
00096 sub_init_pose_ = nh_.subscribe(
00097 "initialpose", 1, &PFLocalizationNode::callbackInitialpose, this);
00098
00099 sub_odometry_ =
00100 nh_.subscribe("odom", 1, &PFLocalizationNode::callbackOdometry, this);
00101
00102
00103 std::vector<std::string> sources;
00104 mrpt::system::tokenize(param()->sensor_sources, " ,\t\n", sources);
00105 ROS_ASSERT_MSG(
00106 !sources.empty(),
00107 "*Fatal*: At least one sensor source must be provided in "
00108 "~sensor_sources (e.g. \"scan\" or \"beacon\")");
00109 sub_sensors_.resize(sources.size());
00110 for (size_t i = 0; i < sources.size(); i++)
00111 {
00112 if (sources[i].find("scan") != std::string::npos)
00113 {
00114 sub_sensors_[i] = nh_.subscribe(
00115 sources[i], 1, &PFLocalizationNode::callbackLaser, this);
00116 }
00117 else if (sources[i].find("beacon") != std::string::npos)
00118 {
00119 sub_sensors_[i] = nh_.subscribe(
00120 sources[i], 1, &PFLocalizationNode::callbackBeacon, this);
00121 }
00122 else
00123 {
00124 sub_sensors_[i] = nh_.subscribe(
00125 sources[i], 1, &PFLocalizationNode::callbackRobotPose, this);
00126 }
00127 }
00128
00129 if (!param()->map_file.empty())
00130 {
00131 #if MRPT_VERSION >= 0x199
00132 if (metric_map_.countMapsByClass<COccupancyGridMap2D>())
00133 {
00134 mrpt_bridge::convert(
00135 *metric_map_.mapByClass<COccupancyGridMap2D>(), resp_.map);
00136 }
00137 #else
00138 if (metric_map_.m_gridMaps.size())
00139 {
00140 mrpt_bridge::convert(*metric_map_.m_gridMaps[0], resp_.map);
00141 }
00142 #endif
00143 pub_map_ = nh_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00144 pub_metadata_ =
00145 nh_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
00146 service_map_ = nh_.advertiseService(
00147 "static_map", &PFLocalizationNode::mapCallback, this);
00148 }
00149 pub_particles_ =
00150 nh_.advertise<geometry_msgs::PoseArray>("particlecloud", 1, true);
00151
00152 pub_pose_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>(
00153 "mrpt_pose", 2, true);
00154 }
00155
00156 void PFLocalizationNode::loop()
00157 {
00158 ROS_INFO("loop");
00159 for (ros::Rate rate(param()->rate); ros::ok(); loop_count_++)
00160 {
00161 param()->update(loop_count_);
00162
00163 if ((loop_count_ % param()->map_update_skip == 0) &&
00164 #if MRPT_VERSION >= 0x199
00165 (metric_map_.countMapsByClass<COccupancyGridMap2D>()))
00166 #else
00167 (metric_map_.m_gridMaps.size()))
00168 #endif
00169 publishMap();
00170 if (loop_count_ % param()->particlecloud_update_skip == 0)
00171 publishParticles();
00172 if (param()->tf_broadcast) publishTF();
00173 if (param()->pose_broadcast) publishPose();
00174
00175 ros::spinOnce();
00176 rate.sleep();
00177 }
00178 }
00179
00180 bool PFLocalizationNode::waitForTransform(
00181 mrpt::poses::CPose3D& des, const std::string& target_frame,
00182 const std::string& source_frame, const ros::Time& time,
00183 const ros::Duration& timeout, const ros::Duration& polling_sleep_duration)
00184 {
00185 tf::StampedTransform transform;
00186 try
00187 {
00188 tf_listener_.waitForTransform(
00189 target_frame, source_frame, time, timeout, polling_sleep_duration);
00190 tf_listener_.lookupTransform(
00191 target_frame, source_frame, time, transform);
00192 }
00193 catch (tf::TransformException& e)
00194 {
00195 ROS_WARN(
00196 "Failed to get transform target_frame (%s) to source_frame (%s): "
00197 "%s",
00198 target_frame.c_str(), source_frame.c_str(), e.what());
00199 return false;
00200 }
00201 mrpt_bridge::convert(transform, des);
00202 return true;
00203 }
00204
00205 void PFLocalizationNode::callbackLaser(const sensor_msgs::LaserScan& _msg)
00206 {
00207 using namespace mrpt::maps;
00208 using namespace mrpt::obs;
00209
00210 time_last_input_ = ros::Time::now();
00211
00212
00213 auto laser = CObservation2DRangeScan::Create();
00214
00215
00216 if (laser_poses_.find(_msg.header.frame_id) == laser_poses_.end())
00217 {
00218 updateSensorPose(_msg.header.frame_id);
00219 }
00220 else if (state_ != IDLE)
00221
00222 {
00223
00224
00225
00226 mrpt_bridge::convert(_msg, laser_poses_[_msg.header.frame_id], *laser);
00227
00228 auto sf = CSensoryFrame::Create();
00229 CObservationOdometry::Ptr odometry;
00230 odometryForCallback(odometry, _msg.header);
00231
00232 CObservation::Ptr obs = CObservation::Ptr(laser);
00233 sf->insert(obs);
00234 observation(sf, odometry);
00235 if (param()->gui_mrpt) show3DDebug(sf);
00236 }
00237 }
00238
00239 void PFLocalizationNode::callbackBeacon(
00240 const mrpt_msgs::ObservationRangeBeacon& _msg)
00241 {
00242 using namespace mrpt::maps;
00243 using namespace mrpt::obs;
00244
00245 time_last_input_ = ros::Time::now();
00246
00247
00248 auto beacon = CObservationBeaconRanges::Create();
00249
00250 if (beacon_poses_.find(_msg.header.frame_id) == beacon_poses_.end())
00251 {
00252 updateSensorPose(_msg.header.frame_id);
00253 }
00254 else if (state_ != IDLE)
00255
00256 {
00257
00258
00259
00260 mrpt_bridge::convert(
00261 _msg, beacon_poses_[_msg.header.frame_id], *beacon);
00262
00263 auto sf = CSensoryFrame::Create();
00264 CObservationOdometry::Ptr odometry;
00265 odometryForCallback(odometry, _msg.header);
00266
00267 CObservation::Ptr obs = CObservation::Ptr(beacon);
00268 sf->insert(obs);
00269 observation(sf, odometry);
00270 if (param()->gui_mrpt) show3DDebug(sf);
00271 }
00272 }
00273
00274 void PFLocalizationNode::callbackRobotPose(
00275 const geometry_msgs::PoseWithCovarianceStamped& _msg)
00276 {
00277 using namespace mrpt::maps;
00278 using namespace mrpt::obs;
00279
00280 time_last_input_ = ros::Time::now();
00281
00282
00283
00284
00285
00286
00287
00288
00289 static std::string base_frame_id =
00290 tf::resolve(param()->tf_prefix, param()->base_frame_id);
00291 static std::string global_frame_id =
00292 tf::resolve(param()->tf_prefix, param()->global_frame_id);
00293
00294 tf::StampedTransform map_to_obs_tf;
00295 try
00296 {
00297 tf_listener_.waitForTransform(
00298 global_frame_id, _msg.header.frame_id, ros::Time(0.0),
00299 ros::Duration(0.5));
00300 tf_listener_.lookupTransform(
00301 global_frame_id, _msg.header.frame_id, ros::Time(0.0),
00302 map_to_obs_tf);
00303 }
00304 catch (tf::TransformException& ex)
00305 {
00306 ROS_ERROR("%s", ex.what());
00307 return;
00308 }
00309
00310
00311
00312
00313
00314 geometry_msgs::Pose map_to_obs_pose;
00315 tf::pointTFToMsg(map_to_obs_tf.getOrigin(), map_to_obs_pose.position);
00316 tf::quaternionTFToMsg(
00317 map_to_obs_tf.getRotation(), map_to_obs_pose.orientation);
00318 geometry_msgs::PoseWithCovarianceStamped obs_pose_world;
00319 obs_pose_world.header.stamp = _msg.header.stamp;
00320 obs_pose_world.header.frame_id = global_frame_id;
00321 pose_cov_ops::compose(map_to_obs_pose, _msg.pose, obs_pose_world.pose);
00322
00323
00324 for (unsigned int i = 0; i < obs_pose_world.pose.covariance.size(); ++i)
00325 {
00326 if (i / 6 == i % 6 && obs_pose_world.pose.covariance[i] <= 0.0)
00327 obs_pose_world.pose.covariance[i] =
00328 std::numeric_limits<double>().infinity();
00329 }
00330
00331
00332 auto feature = CObservationRobotPose::Create();
00333
00334 feature->sensorLabel = _msg.header.frame_id;
00335 mrpt_bridge::convert(_msg.header.stamp, feature->timestamp);
00336 mrpt_bridge::convert(obs_pose_world.pose, feature->pose);
00337
00338 auto sf = CSensoryFrame::Create();
00339 CObservationOdometry::Ptr odometry;
00340 odometryForCallback(odometry, _msg.header);
00341
00342 CObservation::Ptr obs = CObservation::Ptr(feature);
00343 sf->insert(obs);
00344 observation(sf, odometry);
00345 if (param()->gui_mrpt) show3DDebug(sf);
00346 }
00347
00348 void PFLocalizationNode::odometryForCallback(
00349 CObservationOdometry::Ptr& _odometry, const std_msgs::Header& _msg_header)
00350 {
00351 std::string base_frame_id =
00352 tf::resolve(param()->tf_prefix, param()->base_frame_id);
00353 std::string odom_frame_id =
00354 tf::resolve(param()->tf_prefix, param()->odom_frame_id);
00355 mrpt::poses::CPose3D poseOdom;
00356 if (this->waitForTransform(
00357 poseOdom, odom_frame_id, base_frame_id, _msg_header.stamp,
00358 ros::Duration(1.0)))
00359 {
00360 _odometry = CObservationOdometry::Create();
00361 _odometry->sensorLabel = odom_frame_id;
00362 _odometry->hasEncodersInfo = false;
00363 _odometry->hasVelocities = false;
00364 _odometry->odometry.x() = poseOdom.x();
00365 _odometry->odometry.y() = poseOdom.y();
00366 _odometry->odometry.phi() = poseOdom.yaw();
00367 }
00368 }
00369
00370 bool PFLocalizationNode::waitForMap()
00371 {
00372 int wait_counter = 0;
00373 int wait_limit = 10;
00374
00375 if (param()->use_map_topic)
00376 {
00377 sub_map_ =
00378 nh_.subscribe("map", 1, &PFLocalizationNode::callbackMap, this);
00379 ROS_INFO("Subscribed to map topic.");
00380
00381 while (!first_map_received_ && ros::ok() && wait_counter < wait_limit)
00382 {
00383 ROS_INFO("waiting for map callback..");
00384 ros::Duration(0.5).sleep();
00385 ros::spinOnce();
00386 wait_counter++;
00387 }
00388 if (wait_counter != wait_limit)
00389 {
00390 return true;
00391 }
00392 }
00393 else
00394 {
00395 client_map_ = nh_.serviceClient<nav_msgs::GetMap>("static_map");
00396 nav_msgs::GetMap srv;
00397 while (!client_map_.call(srv) && ros::ok() && wait_counter < wait_limit)
00398 {
00399 ROS_INFO("waiting for map service!");
00400 ros::Duration(0.5).sleep();
00401 wait_counter++;
00402 }
00403 client_map_.shutdown();
00404 if (wait_counter != wait_limit)
00405 {
00406 ROS_INFO_STREAM("Map service complete.");
00407 updateMap(srv.response.map);
00408 return true;
00409 }
00410 }
00411
00412 ROS_WARN_STREAM("No map received.");
00413 return false;
00414 }
00415
00416 void PFLocalizationNode::callbackMap(const nav_msgs::OccupancyGrid& msg)
00417 {
00418 if (param()->first_map_only && first_map_received_)
00419 {
00420 return;
00421 }
00422
00423 ROS_INFO_STREAM("Map received.");
00424 updateMap(msg);
00425
00426 first_map_received_ = true;
00427 }
00428
00429 void PFLocalizationNode::updateSensorPose(std::string _frame_id)
00430 {
00431 mrpt::poses::CPose3D pose;
00432 tf::StampedTransform transform;
00433 try
00434 {
00435 std::string base_frame_id =
00436 tf::resolve(param()->tf_prefix, param()->base_frame_id);
00437 tf_listener_.lookupTransform(
00438 base_frame_id, _frame_id, ros::Time(0), transform);
00439 tf::Vector3 translation = transform.getOrigin();
00440 tf::Quaternion quat = transform.getRotation();
00441 pose.x() = translation.x();
00442 pose.y() = translation.y();
00443 pose.z() = translation.z();
00444 tf::Matrix3x3 Rsrc(quat);
00445 mrpt::math::CMatrixDouble33 Rdes;
00446 for (int c = 0; c < 3; c++)
00447 for (int r = 0; r < 3; r++) Rdes(r, c) = Rsrc.getRow(r)[c];
00448 pose.setRotationMatrix(Rdes);
00449 laser_poses_[_frame_id] = pose;
00450 beacon_poses_[_frame_id] = pose;
00451 }
00452 catch (tf::TransformException& ex)
00453 {
00454 ROS_ERROR("%s", ex.what());
00455 ros::Duration(1.0).sleep();
00456 }
00457 }
00458
00459 void PFLocalizationNode::callbackInitialpose(
00460 const geometry_msgs::PoseWithCovarianceStamped& _msg)
00461 {
00462 const geometry_msgs::PoseWithCovariance& pose = _msg.pose;
00463 mrpt_bridge::convert(pose, initial_pose_);
00464 update_counter_ = 0;
00465 state_ = INIT;
00466 }
00467
00468 void PFLocalizationNode::callbackOdometry(const nav_msgs::Odometry& _msg)
00469 {
00470
00471
00472
00473
00474 bool moving = std::abs(_msg.twist.twist.linear.x) > 1e-3 ||
00475 std::abs(_msg.twist.twist.linear.y) > 1e-3 ||
00476 std::abs(_msg.twist.twist.linear.z) > 1e-3 ||
00477 std::abs(_msg.twist.twist.angular.x) > 1e-3 ||
00478 std::abs(_msg.twist.twist.angular.y) > 1e-3 ||
00479 std::abs(_msg.twist.twist.angular.z) > 1e-3;
00480 if (param()->update_while_stopped || moving)
00481 {
00482 if (state_ == IDLE)
00483 {
00484 state_ = RUN;
00485 }
00486 }
00487 else if (state_ == RUN && update_counter_ >= 100)
00488 {
00489 state_ = IDLE;
00490 }
00491 }
00492
00493 void PFLocalizationNode::updateMap(const nav_msgs::OccupancyGrid& _msg)
00494 {
00495 #if MRPT_VERSION >= 0x199
00496 ASSERT_(metric_map_.countMapsByClass<COccupancyGridMap2D>());
00497 mrpt_bridge::convert(_msg, *metric_map_.mapByClass<COccupancyGridMap2D>());
00498 #else
00499 ASSERT_(metric_map_.m_gridMaps.size() == 1);
00500 mrpt_bridge::convert(_msg, *metric_map_.m_gridMaps[0]);
00501 #endif
00502 }
00503
00504 bool PFLocalizationNode::mapCallback(
00505 nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res)
00506 {
00507 ROS_INFO("mapCallback: service requested!\n");
00508 res = resp_;
00509 return true;
00510 }
00511
00512 void PFLocalizationNode::publishMap()
00513 {
00514 resp_.map.header.stamp = ros::Time::now();
00515 resp_.map.header.frame_id =
00516 tf::resolve(param()->tf_prefix, param()->global_frame_id);
00517 resp_.map.header.seq = loop_count_;
00518 if (pub_map_.getNumSubscribers() > 0)
00519 {
00520 pub_map_.publish(resp_.map);
00521 }
00522 if (pub_metadata_.getNumSubscribers() > 0)
00523 {
00524 pub_metadata_.publish(resp_.map.info);
00525 }
00526 }
00527
00528 void PFLocalizationNode::publishParticles()
00529 {
00530 if (pub_particles_.getNumSubscribers() > 0)
00531 {
00532 geometry_msgs::PoseArray poseArray;
00533 poseArray.header.frame_id =
00534 tf::resolve(param()->tf_prefix, param()->global_frame_id);
00535 poseArray.header.stamp = ros::Time::now();
00536 poseArray.header.seq = loop_count_;
00537 poseArray.poses.resize(pdf_.particlesCount());
00538 for (size_t i = 0; i < pdf_.particlesCount(); i++)
00539 {
00540 mrpt::math::TPose2D p = pdf_.getParticlePose(i);
00541 mrpt_bridge::convert(p, poseArray.poses[i]);
00542 }
00543 mrpt::poses::CPose2D p;
00544 pub_particles_.publish(poseArray);
00545 }
00546 }
00547
00552 void PFLocalizationNode::publishTF()
00553 {
00554 static std::string base_frame_id =
00555 tf::resolve(param()->tf_prefix, param()->base_frame_id);
00556 static std::string odom_frame_id =
00557 tf::resolve(param()->tf_prefix, param()->odom_frame_id);
00558 static std::string global_frame_id =
00559 tf::resolve(param()->tf_prefix, param()->global_frame_id);
00560
00561 mrpt::poses::CPose2D robot_pose;
00562 pdf_.getMean(robot_pose);
00563 tf::StampedTransform base_on_map_tf, odom_on_base_tf;
00564 mrpt_bridge::convert(robot_pose, base_on_map_tf);
00565 ros::Time time_last_update(0.0);
00566 if (state_ == RUN)
00567 {
00568 mrpt_bridge::convert(time_last_update_, time_last_update);
00569
00570
00571
00572
00573
00574
00575
00576 if ((ros::Time::now() - time_last_update).toSec() >
00577 param()->no_update_tolerance)
00578 {
00579 if ((ros::Time::now() - time_last_input_).toSec() >
00580 param()->no_inputs_tolerance)
00581 {
00582 ROS_WARN_THROTTLE(
00583 2.0,
00584 "No observations received for %.2fs (tolerance %.2fs); are "
00585 "robot sensors working?",
00586 (ros::Time::now() - time_last_input_).toSec(),
00587 param()->no_inputs_tolerance);
00588 }
00589 else
00590 {
00591 ROS_DEBUG_THROTTLE(
00592 2.0,
00593 "No filter updates for %.2fs (tolerance %.2fs); probably "
00594 "robot stopped for a while",
00595 (ros::Time::now() - time_last_update).toSec(),
00596 param()->no_update_tolerance);
00597 }
00598
00599 time_last_update = ros::Time(0.0);
00600 }
00601 }
00602
00603 try
00604 {
00605
00606 tf_listener_.waitForTransform(
00607 base_frame_id, odom_frame_id, time_last_update, ros::Duration(0.1));
00608 tf_listener_.lookupTransform(
00609 base_frame_id, odom_frame_id, time_last_update, odom_on_base_tf);
00610 }
00611 catch (tf::TransformException& e)
00612 {
00613 ROS_WARN_THROTTLE(
00614 2.0, "Transform from base frame (%s) to odom frame (%s) failed: %s",
00615 base_frame_id.c_str(), odom_frame_id.c_str(), e.what());
00616 ROS_WARN_THROTTLE(
00617 2.0,
00618 "Ensure that your mobile base driver is broadcasting %s -> %s tf",
00619 odom_frame_id.c_str(), base_frame_id.c_str());
00620 return;
00621 }
00622
00623
00624
00625 ros::Time transform_expiration =
00626 (time_last_update.isZero() ? ros::Time::now() : time_last_update) +
00627 ros::Duration(param()->transform_tolerance);
00628 tf::StampedTransform tmp_tf_stamped(
00629 base_on_map_tf * odom_on_base_tf, transform_expiration, global_frame_id,
00630 odom_frame_id);
00631 tf_broadcaster_.sendTransform(tmp_tf_stamped);
00632 }
00633
00637 void PFLocalizationNode::publishPose()
00638 {
00639
00640 #if MRPT_VERSION >= 0x199
00641 const auto [cov, mean] = initial_pose_.getCovarianceAndMean();
00642 #else
00643 mrpt::math::CMatrixDouble33 cov;
00644 mrpt::poses::CPose2D mean;
00645 initial_pose_.getCovarianceAndMean(cov, mean);
00646 #endif
00647
00648 geometry_msgs::PoseWithCovarianceStamped p;
00649
00650
00651 p.header.frame_id =
00652 tf::resolve(param()->tf_prefix, param()->global_frame_id);
00653 if (loop_count_ < 10 || state_ == IDLE)
00654 p.header.stamp = ros::Time::now();
00655
00656 else
00657 mrpt_bridge::convert(time_last_update_, p.header.stamp);
00658
00659
00660 mrpt_bridge::convert(mean, p.pose.pose);
00661
00662
00663 for (int i = 0; i < 3; i++)
00664 {
00665 for (int j = 0; j < 3; j++)
00666 {
00667 int ros_i = i;
00668 int ros_j = j;
00669 if (i == 2 || j == 2)
00670 {
00671 ros_i = i == 2 ? 5 : i;
00672 ros_j = j == 2 ? 5 : j;
00673 }
00674 p.pose.covariance[ros_i * 6 + ros_j] = cov(i, j);
00675 }
00676 }
00677
00678 pub_pose_.publish(p);
00679 }
00680
00681 void PFLocalizationNode::useROSLogLevel()
00682 {
00683
00684
00685 std::map<std::string, ros::console::levels::Level> loggers;
00686 ros::console::get_loggers(loggers);
00687 if (loggers.find("ros.roscpp") != loggers.end())
00688 pdf_.setVerbosityLevel(
00689 static_cast<VerbosityLevel>(loggers["ros.roscpp"]));
00690 if (loggers.find("ros.mrpt_localization") != loggers.end())
00691 pdf_.setVerbosityLevel(
00692 static_cast<VerbosityLevel>(loggers["ros.mrpt_localization"]));
00693 }