mrpt_localization_node.cpp
Go to the documentation of this file.
1 /***********************************************************************************
2  * Revised BSD License *
3  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at> *
4  * All rights reserved. *
5  * *
6  * Redistribution and use in source and binary forms, with or without *
7  * modification, are permitted provided that the following conditions are met: *
8  * * Redistributions of source code must retain the above copyright *
9  * notice, this list of conditions and the following disclaimer. *
10  * * Redistributions in binary form must reproduce the above copyright *
11  * notice, this list of conditions and the following disclaimer in the *
12  * documentation and/or other materials provided with the distribution. *
13  * * Neither the name of the Vienna University of Technology nor the *
14  * names of its contributors may be used to endorse or promote products *
15  * derived from this software without specific prior written permission. *
16  * *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  *AND *
19  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20  **
21  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
22  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
23  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
24  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  **
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
27  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
28  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
29  **
30  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  ** *
32  ***********************************************************************************/
33 
34 #include <geometry_msgs/PoseArray.h>
35 #include <mrpt/obs/CObservationBeaconRanges.h>
36 #include <mrpt/obs/CObservationRobotPose.h>
37 #include <mrpt/ros1bridge/laser_scan.h>
38 #include <mrpt/ros1bridge/map.h>
39 #include <mrpt/ros1bridge/pose.h>
40 #include <mrpt/ros1bridge/time.h>
41 #include <mrpt/system/COutputLogger.h>
44 
45 #include <boost/interprocess/sync/scoped_lock.hpp>
46 
47 using namespace mrpt::obs;
48 using namespace mrpt::system;
49 
50 #include <mrpt/maps/COccupancyGridMap2D.h>
51 
52 #include "mrpt_localization_node.h"
53 using mrpt::maps::COccupancyGridMap2D;
54 
55 int main(int argc, char** argv)
56 {
57  ros::init(argc, argv, "localization");
58  ros::NodeHandle nh;
59  PFLocalizationNode my_node(nh);
60  my_node.init();
61  my_node.loop();
62  return 0;
63 }
64 
68  nh_(n),
69  first_map_received_(false),
70  loop_count_(0)
71 {
72 }
73 
75 {
77 }
78 
80 {
81  // Use MRPT library the same log level as on ROS nodes (only for
82  // MRPT_VERSION >= 0x150)
84 
86  if(param()->init_x || param()->init_y || param()->init_phi)
87  {
88  auto init_pose = mrpt::poses::CPose2D(param()->init_x, param()->init_y, param()->init_phi);
89  auto cov = mrpt::math::CMatrixDouble33::Zero();
90  cov(0,0) = cov(1,1) = mrpt::square(param()->init_std_xy);
91  cov(2,2) = mrpt::square(param()->init_std_phi);
92  initial_pose_ = mrpt::poses::CPosePDFGaussian(init_pose, cov);
93  update_counter_ = 0;
94  state_ = INIT;
95  }
97  "initialpose", 1, &PFLocalizationNode::callbackInitialpose, this);
98 
101 
102  // Subscribe to one or more laser sources:
103  std::vector<std::string> sources;
104  mrpt::system::tokenize(param()->sensor_sources, " ,\t\n", sources);
106  !sources.empty(),
107  "*Fatal*: At least one sensor source must be provided in "
108  "~sensor_sources (e.g. \"scan\" or \"beacon\")");
109  sub_sensors_.resize(sources.size());
110  for (size_t i = 0; i < sources.size(); i++)
111  {
112  if (sources[i].find("scan") != std::string::npos)
113  {
115  sources[i], 1, &PFLocalizationNode::callbackLaser, this);
116  }
117  else if (sources[i].find("beacon") != std::string::npos)
118  {
120  sources[i], 1, &PFLocalizationNode::callbackBeacon, this);
121  }
122  else
123  {
125  sources[i], 1, &PFLocalizationNode::callbackRobotPose, this);
126  }
127  }
128 
129  if (!param()->map_file.empty())
130  {
131  if (metric_map_->countMapsByClass<COccupancyGridMap2D>())
132  {
133  mrpt::ros1bridge::toROS(
134  *metric_map_->mapByClass<COccupancyGridMap2D>(), resp_.map);
135  }
136  pub_map_ = nh_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
137  pub_metadata_ =
138  nh_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
140  "static_map", &PFLocalizationNode::mapCallback, this);
141  }
143  nh_.advertise<geometry_msgs::PoseArray>("particlecloud", 1, true);
144 
145  pub_pose_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>(
146  "mrpt_pose", 2, true);
147 }
148 
150 {
151  ROS_INFO("loop");
152  for (ros::Rate rate(param()->rate); ros::ok(); loop_count_++)
153  {
155 
156  if ((loop_count_ % param()->map_update_skip == 0) &&
157  (metric_map_->countMapsByClass<COccupancyGridMap2D>()))
158  publishMap();
159  if (loop_count_ % param()->particlecloud_update_skip == 0)
161  if (param()->tf_broadcast) publishTF();
162  if (param()->pose_broadcast) publishPose();
163 
164  ros::spinOnce();
165  rate.sleep();
166  }
167 }
168 
170  mrpt::poses::CPose3D& des, const std::string& target_frame,
171  const std::string& source_frame, const ros::Time& time,
172  const ros::Duration& timeout, const ros::Duration& polling_sleep_duration)
173 {
174  geometry_msgs::TransformStamped transform;
175  try
176  {
177  transform = tf_buffer_.lookupTransform(
178  target_frame, source_frame, time, timeout);
179  }
180  catch (const tf2::TransformException& e)
181  {
182  ROS_WARN(
183  "Failed to get transform target_frame (%s) to source_frame (%s): "
184  "%s",
185  target_frame.c_str(), source_frame.c_str(), e.what());
186  return false;
187  }
188  tf2::Transform tx;
189  tf2::fromMsg(transform.transform, tx);
190  des = mrpt::ros1bridge::fromROS(tx);
191  return true;
192 }
193 
194 void PFLocalizationNode::callbackLaser(const sensor_msgs::LaserScan& _msg)
195 {
196  using namespace mrpt::maps;
197  using namespace mrpt::obs;
198 
200 
201  // ROS_INFO("callbackLaser");
202  auto laser = CObservation2DRangeScan::Create();
203 
204  // printf("callbackLaser %s\n", _msg.header.frame_id.c_str());
205  if (laser_poses_.find(_msg.header.frame_id) == laser_poses_.end())
206  {
207  updateSensorPose(_msg.header.frame_id);
208  }
209  else if (state_ != IDLE) // updating filter; we must be moving or
210  // update_while_stopped set to true
211  {
212  if (param()->update_sensor_pose)
213  {
214  updateSensorPose(_msg.header.frame_id);
215  }
216  // mrpt::poses::CPose3D pose = laser_poses_[_msg.header.frame_id];
217  // ROS_INFO("LASER POSE %4.3f, %4.3f, %4.3f, %4.3f, %4.3f, %4.3f",
218  // pose.x(), pose.y(), pose.z(), pose.roll(), pose.pitch(), pose.yaw());
219  mrpt::ros1bridge::fromROS(
220  _msg, laser_poses_[_msg.header.frame_id], *laser);
221 
222  auto sf = CSensoryFrame::Create();
223  CObservationOdometry::Ptr odometry;
224  odometryForCallback(odometry, _msg.header);
225 
226  CObservation::Ptr obs = CObservation::Ptr(laser);
227  sf->insert(obs);
228  observation(sf, odometry);
229  if (param()->gui_mrpt) show3DDebug(sf);
230  }
231 }
232 
234  const mrpt_msgs::ObservationRangeBeacon& _msg)
235 {
236  using namespace mrpt::maps;
237  using namespace mrpt::obs;
238 
240 
241  // ROS_INFO("callbackBeacon");
242  auto beacon = CObservationBeaconRanges::Create();
243  // printf("callbackBeacon %s\n", _msg.header.frame_id.c_str());
244  if (beacon_poses_.find(_msg.header.frame_id) == beacon_poses_.end())
245  {
246  updateSensorPose(_msg.header.frame_id);
247  }
248  else if (state_ != IDLE) // updating filter; we must be moving or
249  // update_while_stopped set to true
250  {
251  if (param()->update_sensor_pose)
252  {
253  updateSensorPose(_msg.header.frame_id);
254  }
255  // mrpt::poses::CPose3D pose = beacon_poses_[_msg.header.frame_id];
256  // ROS_INFO("BEACON POSE %4.3f, %4.3f, %4.3f, %4.3f, %4.3f, %4.3f",
257  // pose.x(), pose.y(), pose.z(), pose.roll(), pose.pitch(), pose.yaw());
259  _msg, beacon_poses_[_msg.header.frame_id], *beacon);
260 
261  auto sf = CSensoryFrame::Create();
262  CObservationOdometry::Ptr odometry;
263  odometryForCallback(odometry, _msg.header);
264 
265  CObservation::Ptr obs = CObservation::Ptr(beacon);
266  sf->insert(obs);
267  observation(sf, odometry);
268  if (param()->gui_mrpt) show3DDebug(sf);
269  }
270 }
271 
273  const geometry_msgs::PoseWithCovarianceStamped& _msg)
274 {
275  using namespace mrpt::maps;
276  using namespace mrpt::obs;
277 
279 
280  // Robot pose externally provided; we update filter regardless state_
281  // attribute's value, as these
282  // corrections are typically independent from robot motion (e.g. inputs from
283  // GPS or tracking system)
284  // XXX admittedly an arbitrary choice; feel free to open an issue if you
285  // think it doesn't make sense
286 
287  static std::string base_frame_id = param()->base_frame_id;
288  static std::string global_frame_id = param()->global_frame_id;
289 
290  geometry_msgs::TransformStamped map_to_obs_tf_msg;
291  try
292  {
293  map_to_obs_tf_msg = tf_buffer_.lookupTransform(
294  global_frame_id, _msg.header.frame_id, ros::Time(0.0),
295  ros::Duration(0.5));
296  }
297  catch (const tf2::TransformException& e)
298  {
299  ROS_WARN(
300  "Failed to get transform target_frame (%s) to source_frame (%s): "
301  "%s",
302  global_frame_id.c_str(), _msg.header.frame_id.c_str(), e.what());
303  return;
304  }
305  tf2::Transform map_to_obs_tf;
306  tf2::fromMsg(map_to_obs_tf_msg.transform, map_to_obs_tf);
307 
308  // Transform observation into global frame, including covariance. For that,
309  // we must first obtain
310  // the global frame -> observation frame tf as a Pose msg, as required by
311  // pose_cov_ops::compose
312  geometry_msgs::Pose map_to_obs_pose;
313  tf2::toMsg(map_to_obs_tf, map_to_obs_pose);
314 
315  geometry_msgs::PoseWithCovarianceStamped obs_pose_world;
316  obs_pose_world.header.stamp = _msg.header.stamp;
317  obs_pose_world.header.frame_id = global_frame_id;
318  pose_cov_ops::compose(map_to_obs_pose, _msg.pose, obs_pose_world.pose);
319 
320  // Ensure the covariance matrix can be inverted (no zeros in the diagonal)
321  for (unsigned int i = 0; i < obs_pose_world.pose.covariance.size(); ++i)
322  {
323  if (i / 6 == i % 6 && obs_pose_world.pose.covariance[i] <= 0.0)
324  obs_pose_world.pose.covariance[i] =
325  std::numeric_limits<double>().infinity();
326  }
327 
328  // Covert the received pose into an observation the filter can integrate
329  auto feature = CObservationRobotPose::Create();
330 
331  feature->sensorLabel = _msg.header.frame_id;
332  feature->timestamp = mrpt::ros1bridge::fromROS(_msg.header.stamp);
333  feature->pose = mrpt::ros1bridge::fromROS(obs_pose_world.pose);
334 
335  auto sf = CSensoryFrame::Create();
336  CObservationOdometry::Ptr odometry;
337  odometryForCallback(odometry, _msg.header);
338 
339  CObservation::Ptr obs = CObservation::Ptr(feature);
340  sf->insert(obs);
341  observation(sf, odometry);
342  if (param()->gui_mrpt) show3DDebug(sf);
343 }
344 
346  CObservationOdometry::Ptr& _odometry, const std_msgs::Header& _msg_header)
347 {
348  std::string base_frame_id = param()->base_frame_id;
349  std::string odom_frame_id = param()->odom_frame_id;
350  mrpt::poses::CPose3D poseOdom;
351  if (this->waitForTransform(
352  poseOdom, odom_frame_id, base_frame_id, _msg_header.stamp,
353  ros::Duration(1.0)))
354  {
355  _odometry = CObservationOdometry::Create();
356  _odometry->sensorLabel = odom_frame_id;
357  _odometry->hasEncodersInfo = false;
358  _odometry->hasVelocities = false;
359  _odometry->odometry.x() = poseOdom.x();
360  _odometry->odometry.y() = poseOdom.y();
361  _odometry->odometry.phi() = poseOdom.yaw();
362  }
363 }
364 
366 {
367  int wait_counter = 0;
368  int wait_limit = 10;
369 
370  if (param()->use_map_topic)
371  {
372  sub_map_ =
374  ROS_INFO("Subscribed to map topic.");
375 
376  while (!first_map_received_ && ros::ok() && wait_counter < wait_limit)
377  {
378  ROS_INFO("waiting for map callback..");
379  ros::Duration(0.5).sleep();
380  ros::spinOnce();
381  wait_counter++;
382  }
383  if (wait_counter != wait_limit)
384  {
385  return true;
386  }
387  }
388  else
389  {
390  client_map_ = nh_.serviceClient<nav_msgs::GetMap>("static_map");
391  nav_msgs::GetMap srv;
392  while (!client_map_.call(srv) && ros::ok() && wait_counter < wait_limit)
393  {
394  ROS_INFO("waiting for map service!");
395  ros::Duration(0.5).sleep();
396  wait_counter++;
397  }
399  if (wait_counter != wait_limit)
400  {
401  ROS_INFO_STREAM("Map service complete.");
402  updateMap(srv.response.map);
403  return true;
404  }
405  }
406 
407  ROS_WARN_STREAM("No map received.");
408  return false;
409 }
410 
411 void PFLocalizationNode::callbackMap(const nav_msgs::OccupancyGrid& msg)
412 {
413  if (param()->first_map_only && first_map_received_)
414  {
415  return;
416  }
417 
418  ROS_INFO_STREAM("Map received.");
419  updateMap(msg);
420 
421  first_map_received_ = true;
422 }
423 
424 void PFLocalizationNode::updateSensorPose(std::string _frame_id)
425 {
426  mrpt::poses::CPose3D pose;
427 
428  std::string base_frame_id = param()->base_frame_id;
429 
430  geometry_msgs::TransformStamped transformStmp;
431  try
432  {
433  ros::Duration timeout(1.0);
434 
435  transformStmp = tf_buffer_.lookupTransform(
436  base_frame_id, _frame_id, ros::Time(0), timeout);
437  }
438  catch (const tf2::TransformException& e)
439  {
440  ROS_WARN(
441  "Failed to get transform target_frame (%s) to source_frame (%s): "
442  "%s",
443  base_frame_id.c_str(), _frame_id.c_str(), e.what());
444  return;
445  }
446  tf2::Transform transform;
447  tf2::fromMsg(transformStmp.transform, transform);
448 
449  tf2::Vector3 translation = transform.getOrigin();
450  tf2::Quaternion quat = transform.getRotation();
451  pose.x() = translation.x();
452  pose.y() = translation.y();
453  pose.z() = translation.z();
454  tf2::Matrix3x3 Rsrc(quat);
455  mrpt::math::CMatrixDouble33 Rdes;
456  for (int c = 0; c < 3; c++)
457  {
458  for (int r = 0; r < 3; r++)
459  {
460  Rdes(r, c) = Rsrc.getRow(r)[c];
461  }
462  }
463 
464  pose.setRotationMatrix(Rdes);
465  laser_poses_[_frame_id] = pose;
466  beacon_poses_[_frame_id] = pose;
467 }
468 
470  const geometry_msgs::PoseWithCovarianceStamped& _msg)
471 {
472  const geometry_msgs::PoseWithCovariance& pose = _msg.pose;
473 
474  // SE(3) -> SE(2) explicit conversion:
475  initial_pose_ =
476  mrpt::poses::CPosePDFGaussian(mrpt::ros1bridge::fromROS(pose));
477 
478  update_counter_ = 0;
479  state_ = INIT;
480 }
481 
482 void PFLocalizationNode::callbackOdometry(const nav_msgs::Odometry& _msg)
483 {
484  // We always update the filter if update_while_stopped is true, regardless
485  // robot is moving or
486  // not; otherwise, update filter if we are moving or at initialization (100
487  // first iterations)
488  bool moving = std::abs(_msg.twist.twist.linear.x) > 1e-3 ||
489  std::abs(_msg.twist.twist.linear.y) > 1e-3 ||
490  std::abs(_msg.twist.twist.linear.z) > 1e-3 ||
491  std::abs(_msg.twist.twist.angular.x) > 1e-3 ||
492  std::abs(_msg.twist.twist.angular.y) > 1e-3 ||
493  std::abs(_msg.twist.twist.angular.z) > 1e-3;
494  if (param()->update_while_stopped || moving)
495  {
496  if (state_ == IDLE)
497  {
498  state_ = RUN;
499  }
500  }
501  else if (state_ == RUN && update_counter_ >= 100)
502  {
503  state_ = IDLE;
504  }
505 }
506 
507 void PFLocalizationNode::updateMap(const nav_msgs::OccupancyGrid& _msg)
508 {
509  ASSERT_(metric_map_->countMapsByClass<COccupancyGridMap2D>());
510  mrpt::ros1bridge::fromROS(
511  _msg, *metric_map_->mapByClass<COccupancyGridMap2D>());
512 }
513 
515  nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res)
516 {
517  ROS_INFO("mapCallback: service requested!\n");
518  res = resp_;
519  return true;
520 }
521 
523 {
524  resp_.map.header.stamp = ros::Time::now();
525  resp_.map.header.frame_id = param()->global_frame_id;
526  resp_.map.header.seq = loop_count_;
527  if (pub_map_.getNumSubscribers() > 0)
528  {
529  pub_map_.publish(resp_.map);
530  }
532  {
533  pub_metadata_.publish(resp_.map.info);
534  }
535 }
536 
538 {
540  {
541  geometry_msgs::PoseArray poseArray;
542  poseArray.header.frame_id = param()->global_frame_id;
543  poseArray.header.stamp = ros::Time::now();
544  poseArray.header.seq = loop_count_;
545  poseArray.poses.resize(pdf_.particlesCount());
546  for (size_t i = 0; i < pdf_.particlesCount(); i++)
547  {
548  const auto p = mrpt::math::TPose3D(pdf_.getParticlePose(i));
549  poseArray.poses[i] = mrpt::ros1bridge::toROS_Pose(p);
550  }
551  mrpt::poses::CPose2D p;
552  pub_particles_.publish(poseArray);
553  }
554 }
555 
561 {
562  static std::string base_frame_id = param()->base_frame_id;
563  static std::string odom_frame_id = param()->odom_frame_id;
564  static std::string global_frame_id = param()->global_frame_id;
565 
566  const mrpt::poses::CPose2D robotPoseFromPF = [this]() {
567  return pdf_.getMeanVal();
568  }();
569 
570  tf2::Transform baseOnMap_tf;
571  tf2::fromMsg(mrpt::ros1bridge::toROS_Pose(robotPoseFromPF), baseOnMap_tf);
572 
573  ros::Time time_last_update(0.0);
574  if (state_ == RUN)
575  {
576  time_last_update = mrpt::ros1bridge::toROS(time_last_update_);
577 
578  // Last update time can be too far in the past if we where not updating
579  // filter, due to robot stopped or no
580  // observations for a while (we optionally show a warning in the second
581  // case)
582  // We use time zero if so when getting base -> odom tf to prevent an
583  // extrapolation into the past exception
584  if ((ros::Time::now() - time_last_update).toSec() >
585  param()->no_update_tolerance)
586  {
587  if ((ros::Time::now() - time_last_input_).toSec() >
588  param()->no_inputs_tolerance)
589  {
591  2.0,
592  "No observations received for %.2fs (tolerance %.2fs); are "
593  "robot sensors working?",
594  (ros::Time::now() - time_last_input_).toSec(),
595  param()->no_inputs_tolerance);
596  }
597  else
598  {
600  2.0,
601  "No filter updates for %.2fs (tolerance %.2fs); probably "
602  "robot stopped for a while",
603  (ros::Time::now() - time_last_update).toSec(),
604  param()->no_update_tolerance);
605  }
606 
607  time_last_update = ros::Time(0.0);
608  }
609  }
610 
611  tf2::Transform odomOnBase_tf;
612 
613  {
614  geometry_msgs::TransformStamped transform;
615  try
616  {
617  transform = tf_buffer_.lookupTransform(
618  base_frame_id, odom_frame_id, time_last_update,
619  ros::Duration(0.1));
620  }
621  catch (const tf2::TransformException& e)
622  {
624  2.0,
625  "Failed to get transform target_frame (%s) to source_frame "
626  "(%s): "
627  "%s",
628  base_frame_id.c_str(), odom_frame_id.c_str(), e.what());
630  2.0,
631  "Ensure that your mobile base driver is broadcasting %s -> %s "
632  "tf",
633  odom_frame_id.c_str(), base_frame_id.c_str());
634 
635  return;
636  }
637  tf2::Transform tx;
638  tf2::fromMsg(transform.transform, tx);
639  odomOnBase_tf = tx;
640  }
641 
642  // We want to send a transform that is good up until a tolerance time so
643  // that odom can be used
644  ros::Time transform_expiration =
645  (time_last_update.isZero() ? ros::Time::now() : time_last_update) +
647 
648  tf2::Stamped<tf2::Transform> tmp_tf_stamped(
649  baseOnMap_tf * odomOnBase_tf, transform_expiration, global_frame_id);
650 
651  geometry_msgs::TransformStamped tfGeom = tf2::toMsg(tmp_tf_stamped);
652  tfGeom.child_frame_id = odom_frame_id;
653 
655 }
656 
661 {
662  // cov for x, y, phi (meter, meter, radian)
663  const auto [cov, mean] = pdf_.getCovarianceAndMean();
664 
665  geometry_msgs::PoseWithCovarianceStamped p;
666 
667  // Fill in the header
668  p.header.frame_id = param()->global_frame_id;
669  if (loop_count_ < 10 || state_ == IDLE)
670  {
671  // on first iterations timestamp differs a lot from ROS time
672  p.header.stamp = ros::Time::now();
673  }
674  else
675  {
676  p.header.stamp = mrpt::ros1bridge::toROS(time_last_update_);
677  }
678 
679  // Copy in the pose
680  p.pose.pose = mrpt::ros1bridge::toROS_Pose(mean);
681 
682  // Copy in the covariance, converting from 3-D to 6-D
683  for (int i = 0; i < 3; i++)
684  {
685  for (int j = 0; j < 3; j++)
686  {
687  int ros_i = i;
688  int ros_j = j;
689  if (i == 2 || j == 2)
690  {
691  ros_i = i == 2 ? 5 : i;
692  ros_j = j == 2 ? 5 : j;
693  }
694  p.pose.covariance[ros_i * 6 + ros_j] = cov(i, j);
695  }
696  }
697 
698  pub_pose_.publish(p);
699 }
700 
702 {
703  // Set ROS log level also on MRPT internal log system; level enums are fully
704  // compatible
705  std::map<std::string, ros::console::levels::Level> loggers;
706  ros::console::get_loggers(loggers);
707  if (loggers.find("ros.roscpp") != loggers.end())
708  pdf_.setVerbosityLevel(
709  static_cast<VerbosityLevel>(loggers["ros.roscpp"]));
710  if (loggers.find("ros.mrpt_localization") != loggers.end())
711  pdf_.setVerbosityLevel(
712  static_cast<VerbosityLevel>(loggers["ros.mrpt_localization"]));
713 }
PFLocalizationNode::callbackLaser
void callbackLaser(const sensor_msgs::LaserScan &)
Definition: mrpt_localization_node.cpp:194
PFLocalizationNode::callbackInitialpose
void callbackInitialpose(const geometry_msgs::PoseWithCovarianceStamped &)
Definition: mrpt_localization_node.cpp:469
beacon.h
PFLocalizationNode
ROS Node.
Definition: mrpt_localization_node.h:61
PFLocalizationNode::mapCallback
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: mrpt_localization_node.cpp:514
PFLocalizationNode::Parameters::global_frame_id
std::string global_frame_id
Definition: mrpt_localization_node.h:89
main
int main(int argc, char **argv)
Definition: mrpt_localization_node.cpp:55
PFLocalizationNode::publishPose
void publishPose()
Publish the current pose of the robot.
Definition: mrpt_localization_node.cpp:660
PFLocalizationNode::publishTF
void publishTF()
Publish map -> odom tf; as the filter provides map -> base, we multiply it by base -> odom.
Definition: mrpt_localization_node.cpp:560
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
PFLocalizationCore::time_last_update_
mrpt::system::TTimeStamp time_last_update_
time of the last update
Definition: mrpt_localization_core.h:97
tf2::fromMsg
void fromMsg(const A &, B &b)
PFLocalizationNode::Parameters::base_frame_id
std::string base_frame_id
Definition: mrpt_localization_node.h:87
PFLocalizationNode::waitForTransform
bool waitForTransform(mrpt::poses::CPose3D &des, const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01))
Definition: mrpt_localization_node.cpp:169
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
PFLocalizationNode::first_map_received_
bool first_map_received_
Definition: mrpt_localization_node.h:121
PFLocalizationNode::publishMap
void publishMap()
Definition: mrpt_localization_node.cpp:522
PFLocalizationNode::sub_map_
ros::Subscriber sub_map_
Definition: mrpt_localization_node.h:128
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::spinOnce
ROSCPP_DECL void spinOnce()
PFLocalization::show3DDebug
void show3DDebug(CSensoryFrame::Ptr _observations)
Definition: mrpt_localization.cpp:250
PFLocalizationNode::odometryForCallback
void odometryForCallback(CObservationOdometry::Ptr &, const std_msgs::Header &)
Definition: mrpt_localization_node.cpp:345
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
pose_cov_ops.h
tf2::Transform::getOrigin
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
PFLocalizationCore::RUN
@ RUN
Definition: mrpt_localization_core.h:59
tf2::Stamped
mrpt_localization_node.h
PFLocalizationNode::pub_metadata_
ros::Publisher pub_metadata_
Definition: mrpt_localization_node.h:132
PFLocalizationNode::Parameters::update
void update(const unsigned long &loop_count)
Definition: mrpt_localization_node_parameters.cpp:95
PFLocalizationNode::callbackRobotPose
void callbackRobotPose(const geometry_msgs::PoseWithCovarianceStamped &)
Definition: mrpt_localization_node.cpp:272
PFLocalizationNode::sub_odometry_
ros::Subscriber sub_odometry_
Definition: mrpt_localization_node.h:126
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
PFLocalizationNode::callbackBeacon
void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon &)
Definition: mrpt_localization_node.cpp:233
PFLocalization
Definition: mrpt_localization.h:45
PFLocalizationNode::laser_poses_
std::map< std::string, mrpt::poses::CPose3D > laser_poses_
Definition: mrpt_localization_node.h:141
PFLocalizationNode::param
Parameters * param()
Definition: mrpt_localization_node.cpp:74
PFLocalizationNode::sub_init_pose_
ros::Subscriber sub_init_pose_
Definition: mrpt_localization_node.h:125
pose_cov_ops::compose
void compose(const Pose &a, const Pose &b, Pose &out)
mrpt_msgs_bridge::fromROS
bool fromROS(const marker_msgs::MarkerDetection &_msg, const mrpt::poses::CPose3D &sensorPoseOnRobot, mrpt::obs::CObservationBeaconRanges &_obj)
PFLocalizationCore::observation
void observation(CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
Definition: mrpt_localization_core.cpp:105
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
PFLocalizationNode::callbackMap
void callbackMap(const nav_msgs::OccupancyGrid &)
Definition: mrpt_localization_node.cpp:411
PFLocalizationNode::client_map_
ros::ServiceClient client_map_
Definition: mrpt_localization_node.h:129
PFLocalizationNode::callbackOdometry
void callbackOdometry(const nav_msgs::Odometry &)
Definition: mrpt_localization_node.cpp:482
PFLocalization::init
void init()
Definition: mrpt_localization.cpp:71
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
PFLocalizationNode::PFLocalizationNode
PFLocalizationNode(ros::NodeHandle &n)
Definition: mrpt_localization_node.cpp:66
PFLocalizationNode::~PFLocalizationNode
virtual ~PFLocalizationNode()
Definition: mrpt_localization_node.cpp:65
PFLocalizationCore::update_counter_
size_t update_counter_
Definition: mrpt_localization_core.h:99
TimeBase< Time, Duration >::isZero
bool isZero() const
PFLocalizationNode::waitForMap
virtual bool waitForMap()
Definition: mrpt_localization_node.cpp:365
PFLocalizationNode::pub_map_
ros::Publisher pub_map_
Definition: mrpt_localization_node.h:131
tf2::Transform
PFLocalizationNode::beacon_poses_
std::map< std::string, mrpt::poses::CPose3D > beacon_poses_
Definition: mrpt_localization_node.h:142
tf2::Transform::getRotation
Quaternion getRotation() const
ros::ServiceClient::shutdown
void shutdown()
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
ROS_WARN
#define ROS_WARN(...)
PFLocalization::param_
Parameters * param_
Definition: mrpt_localization.h:98
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
PFLocalizationNode::Parameters
Definition: mrpt_localization_node.h:64
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
PFLocalizationNode::sub_sensors_
std::vector< ros::Subscriber > sub_sensors_
Definition: mrpt_localization_node.h:127
PFLocalizationNode::service_map_
ros::ServiceServer service_map_
Definition: mrpt_localization_node.h:134
PFLocalizationCore::pdf_
mrpt::slam::CMonteCarloLocalization2D pdf_
the filter
Definition: mrpt_localization_core.h:93
PFLocalizationCore::INIT
@ INIT
Definition: mrpt_localization_core.h:58
PFLocalizationNode::init
void init()
Definition: mrpt_localization_node.cpp:79
PFLocalizationNode::nh_
ros::NodeHandle nh_
Definition: mrpt_localization_node.h:120
PFLocalizationNode::updateMap
void updateMap(const nav_msgs::OccupancyGrid &)
Definition: mrpt_localization_node.cpp:507
tf2::Matrix3x3::getRow
const TF2SIMD_FORCE_INLINE Vector3 & getRow(int i) const
PFLocalizationCore::initial_pose_
mrpt::poses::CPosePDFGaussian initial_pose_
initial posed used in initializeFilter()
Definition: mrpt_localization_core.h:95
PFLocalizationNode::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: mrpt_localization_node.h:136
PFLocalizationNode::loop_count_
unsigned long long loop_count_
Definition: mrpt_localization_node.h:123
PFLocalizationNode::time_last_input_
ros::Time time_last_input_
Definition: mrpt_localization_node.h:122
ros::Time
PFLocalizationNode::loop
void loop()
Definition: mrpt_localization_node.cpp:149
PFLocalizationNode::Parameters::transform_tolerance
double transform_tolerance
Definition: mrpt_localization_node.h:78
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
tf2::Quaternion
tf2::toMsg
B toMsg(const A &a)
PFLocalizationCore::metric_map_
CMultiMetricMap::Ptr metric_map_
map
Definition: mrpt_localization_core.h:88
ros::Rate
PFLocalizationNode::pub_particles_
ros::Publisher pub_particles_
Definition: mrpt_localization_node.h:130
ros::Duration::sleep
bool sleep() const
PFLocalizationNode::updateSensorPose
void updateSensorPose(std::string frame_id)
Definition: mrpt_localization_node.cpp:424
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
tf2::Matrix3x3
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
PFLocalizationNode::Parameters::odom_frame_id
std::string odom_frame_id
Definition: mrpt_localization_node.h:88
PFLocalizationNode::publishParticles
void publishParticles()
Definition: mrpt_localization_node.cpp:537
ros::Duration
ros::console::get_loggers
ROSCONSOLE_DECL bool get_loggers(std::map< std::string, levels::Level > &loggers)
PFLocalizationNode::resp_
nav_msgs::GetMap::Response resp_
Definition: mrpt_localization_node.h:124
PFLocalizationNode::pub_pose_
ros::Publisher pub_pose_
Definition: mrpt_localization_node.h:133
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
PFLocalizationCore::state_
PFStates state_
updates
Definition: mrpt_localization_core.h:101
ROS_DEBUG_THROTTLE
#define ROS_DEBUG_THROTTLE(period,...)
ros::NodeHandle
PFLocalizationCore::IDLE
@ IDLE
Definition: mrpt_localization_core.h:60
PFLocalizationNode::tf_broadcaster_
tf2_ros::TransformBroadcaster tf_broadcaster_
Definition: mrpt_localization_node.h:139
ros::Time::now
static Time now()
PFLocalizationNode::useROSLogLevel
void useROSLogLevel()
Definition: mrpt_localization_node.cpp:701


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Tue Sep 17 2024 02:10:20