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 <boost/interprocess/sync/scoped_lock.hpp>
35 #include <geometry_msgs/PoseArray.h>
36 #include <pose_cov_ops/pose_cov_ops.h>
37 
38 #include <mrpt_bridge/pose.h>
39 #include <mrpt_bridge/laser_scan.h>
40 #include <mrpt_bridge/time.h>
41 #include <mrpt_bridge/map.h>
42 #include <mrpt_bridge/beacon.h>
43 
44 #include <mrpt/version.h>
45 #include <mrpt/obs/CObservationBeaconRanges.h>
46 using namespace mrpt::obs;
47 
48 #include <mrpt/version.h>
49 //
50 #if MRPT_VERSION >= 0x199
51 #include <mrpt/system/COutputLogger.h>
52 using namespace mrpt::system;
53 #else
54 #include <mrpt/utils/COutputLogger.h>
55 using namespace mrpt::utils;
56 #endif
57 
58 #include <mrpt/obs/CObservationRobotPose.h>
59 
60 #include "mrpt_localization_node.h"
61 
62 #include <mrpt/maps/COccupancyGridMap2D.h>
63 using mrpt::maps::COccupancyGridMap2D;
64 
65 int main(int argc, char** argv)
66 {
67  ros::init(argc, argv, "localization");
68  ros::NodeHandle nh;
69  PFLocalizationNode my_node(nh);
70  my_node.init();
71  my_node.loop();
72  return 0;
73 }
74 
78  nh_(n),
79  first_map_received_(false),
80  loop_count_(0)
81 {
82 }
83 
85 {
87 }
88 
90 {
91  // Use MRPT library the same log level as on ROS nodes (only for
92  // MRPT_VERSION >= 0x150)
94 
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 MRPT_VERSION >= 0x199
132  if (metric_map_.countMapsByClass<COccupancyGridMap2D>())
133  {
134  mrpt_bridge::convert(
135  *metric_map_.mapByClass<COccupancyGridMap2D>(), resp_.map);
136  }
137 #else
138  if (metric_map_.m_gridMaps.size())
139  {
140  mrpt_bridge::convert(*metric_map_.m_gridMaps[0], resp_.map);
141  }
142 #endif
143  pub_map_ = nh_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
144  pub_metadata_ =
145  nh_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
147  "static_map", &PFLocalizationNode::mapCallback, this);
148  }
150  nh_.advertise<geometry_msgs::PoseArray>("particlecloud", 1, true);
151 
152  pub_pose_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>(
153  "mrpt_pose", 2, true);
154 }
155 
157 {
158  ROS_INFO("loop");
159  for (ros::Rate rate(param()->rate); ros::ok(); loop_count_++)
160  {
162 
163  if ((loop_count_ % param()->map_update_skip == 0) &&
164 #if MRPT_VERSION >= 0x199
165  (metric_map_.countMapsByClass<COccupancyGridMap2D>()))
166 #else
167  (metric_map_.m_gridMaps.size()))
168 #endif
169  publishMap();
170  if (loop_count_ % param()->particlecloud_update_skip == 0)
172  if (param()->tf_broadcast) publishTF();
173  if (param()->pose_broadcast) publishPose();
174 
175  ros::spinOnce();
176  rate.sleep();
177  }
178 }
179 
181  mrpt::poses::CPose3D& des, const std::string& target_frame,
182  const std::string& source_frame, const ros::Time& time,
183  const ros::Duration& timeout, const ros::Duration& polling_sleep_duration)
184 {
185  tf::StampedTransform transform;
186  try
187  {
189  target_frame, source_frame, time, timeout, polling_sleep_duration);
191  target_frame, source_frame, time, transform);
192  }
193  catch (tf::TransformException& e)
194  {
195  ROS_WARN(
196  "Failed to get transform target_frame (%s) to source_frame (%s): "
197  "%s",
198  target_frame.c_str(), source_frame.c_str(), e.what());
199  return false;
200  }
201  mrpt_bridge::convert(transform, des);
202  return true;
203 }
204 
205 void PFLocalizationNode::callbackLaser(const sensor_msgs::LaserScan& _msg)
206 {
207  using namespace mrpt::maps;
208  using namespace mrpt::obs;
209 
211 
212  // ROS_INFO("callbackLaser");
213  auto laser = CObservation2DRangeScan::Create();
214 
215  // printf("callbackLaser %s\n", _msg.header.frame_id.c_str());
216  if (laser_poses_.find(_msg.header.frame_id) == laser_poses_.end())
217  {
218  updateSensorPose(_msg.header.frame_id);
219  }
220  else if (state_ != IDLE) // updating filter; we must be moving or
221  // update_while_stopped set to true
222  {
223  // mrpt::poses::CPose3D pose = laser_poses_[_msg.header.frame_id];
224  // ROS_INFO("LASER POSE %4.3f, %4.3f, %4.3f, %4.3f, %4.3f, %4.3f",
225  // pose.x(), pose.y(), pose.z(), pose.roll(), pose.pitch(), pose.yaw());
226  mrpt_bridge::convert(_msg, laser_poses_[_msg.header.frame_id], *laser);
227 
228  auto sf = CSensoryFrame::Create();
229  CObservationOdometry::Ptr odometry;
230  odometryForCallback(odometry, _msg.header);
231 
232  CObservation::Ptr obs = CObservation::Ptr(laser);
233  sf->insert(obs);
234  observation(sf, odometry);
235  if (param()->gui_mrpt) show3DDebug(sf);
236  }
237 }
238 
240  const mrpt_msgs::ObservationRangeBeacon& _msg)
241 {
242  using namespace mrpt::maps;
243  using namespace mrpt::obs;
244 
246 
247  // ROS_INFO("callbackBeacon");
248  auto beacon = CObservationBeaconRanges::Create();
249  // printf("callbackBeacon %s\n", _msg.header.frame_id.c_str());
250  if (beacon_poses_.find(_msg.header.frame_id) == beacon_poses_.end())
251  {
252  updateSensorPose(_msg.header.frame_id);
253  }
254  else if (state_ != IDLE) // updating filter; we must be moving or
255  // update_while_stopped set to true
256  {
257  // mrpt::poses::CPose3D pose = beacon_poses_[_msg.header.frame_id];
258  // ROS_INFO("BEACON POSE %4.3f, %4.3f, %4.3f, %4.3f, %4.3f, %4.3f",
259  // pose.x(), pose.y(), pose.z(), pose.roll(), pose.pitch(), pose.yaw());
260  mrpt_bridge::convert(
261  _msg, beacon_poses_[_msg.header.frame_id], *beacon);
262 
263  auto sf = CSensoryFrame::Create();
264  CObservationOdometry::Ptr odometry;
265  odometryForCallback(odometry, _msg.header);
266 
267  CObservation::Ptr obs = CObservation::Ptr(beacon);
268  sf->insert(obs);
269  observation(sf, odometry);
270  if (param()->gui_mrpt) show3DDebug(sf);
271  }
272 }
273 
275  const geometry_msgs::PoseWithCovarianceStamped& _msg)
276 {
277  using namespace mrpt::maps;
278  using namespace mrpt::obs;
279 
281 
282  // Robot pose externally provided; we update filter regardless state_
283  // attribute's value, as these
284  // corrections are typically independent from robot motion (e.g. inputs from
285  // GPS or tracking system)
286  // XXX admittedly an arbitrary choice; feel free to open an issue if you
287  // think it doesn't make sense
288 
289  static std::string base_frame_id =
290  tf::resolve(param()->tf_prefix, param()->base_frame_id);
291  static std::string global_frame_id =
292  tf::resolve(param()->tf_prefix, param()->global_frame_id);
293 
294  tf::StampedTransform map_to_obs_tf;
295  try
296  {
298  global_frame_id, _msg.header.frame_id, ros::Time(0.0),
299  ros::Duration(0.5));
301  global_frame_id, _msg.header.frame_id, ros::Time(0.0),
302  map_to_obs_tf);
303  }
304  catch (tf::TransformException& ex)
305  {
306  ROS_ERROR("%s", ex.what());
307  return;
308  }
309 
310  // Transform observation into global frame, including covariance. For that,
311  // we must first obtain
312  // the global frame -> observation frame tf as a Pose msg, as required by
313  // pose_cov_ops::compose
314  geometry_msgs::Pose map_to_obs_pose;
315  tf::pointTFToMsg(map_to_obs_tf.getOrigin(), map_to_obs_pose.position);
317  map_to_obs_tf.getRotation(), map_to_obs_pose.orientation);
318  geometry_msgs::PoseWithCovarianceStamped obs_pose_world;
319  obs_pose_world.header.stamp = _msg.header.stamp;
320  obs_pose_world.header.frame_id = global_frame_id;
321  pose_cov_ops::compose(map_to_obs_pose, _msg.pose, obs_pose_world.pose);
322 
323  // Ensure the covariance matrix can be inverted (no zeros in the diagonal)
324  for (unsigned int i = 0; i < obs_pose_world.pose.covariance.size(); ++i)
325  {
326  if (i / 6 == i % 6 && obs_pose_world.pose.covariance[i] <= 0.0)
327  obs_pose_world.pose.covariance[i] =
328  std::numeric_limits<double>().infinity();
329  }
330 
331  // Covert the received pose into an observation the filter can integrate
332  auto feature = CObservationRobotPose::Create();
333 
334  feature->sensorLabel = _msg.header.frame_id;
335  mrpt_bridge::convert(_msg.header.stamp, feature->timestamp);
336  mrpt_bridge::convert(obs_pose_world.pose, feature->pose);
337 
338  auto sf = CSensoryFrame::Create();
339  CObservationOdometry::Ptr odometry;
340  odometryForCallback(odometry, _msg.header);
341 
342  CObservation::Ptr obs = CObservation::Ptr(feature);
343  sf->insert(obs);
344  observation(sf, odometry);
345  if (param()->gui_mrpt) show3DDebug(sf);
346 }
347 
349  CObservationOdometry::Ptr& _odometry, const std_msgs::Header& _msg_header)
350 {
351  std::string base_frame_id =
352  tf::resolve(param()->tf_prefix, param()->base_frame_id);
353  std::string odom_frame_id =
354  tf::resolve(param()->tf_prefix, param()->odom_frame_id);
355  mrpt::poses::CPose3D poseOdom;
356  if (this->waitForTransform(
357  poseOdom, odom_frame_id, base_frame_id, _msg_header.stamp,
358  ros::Duration(1.0)))
359  {
360  _odometry = CObservationOdometry::Create();
361  _odometry->sensorLabel = odom_frame_id;
362  _odometry->hasEncodersInfo = false;
363  _odometry->hasVelocities = false;
364  _odometry->odometry.x() = poseOdom.x();
365  _odometry->odometry.y() = poseOdom.y();
366  _odometry->odometry.phi() = poseOdom.yaw();
367  }
368 }
369 
371 {
372  int wait_counter = 0;
373  int wait_limit = 10;
374 
375  if (param()->use_map_topic)
376  {
377  sub_map_ =
379  ROS_INFO("Subscribed to map topic.");
380 
381  while (!first_map_received_ && ros::ok() && wait_counter < wait_limit)
382  {
383  ROS_INFO("waiting for map callback..");
384  ros::Duration(0.5).sleep();
385  ros::spinOnce();
386  wait_counter++;
387  }
388  if (wait_counter != wait_limit)
389  {
390  return true;
391  }
392  }
393  else
394  {
395  client_map_ = nh_.serviceClient<nav_msgs::GetMap>("static_map");
396  nav_msgs::GetMap srv;
397  while (!client_map_.call(srv) && ros::ok() && wait_counter < wait_limit)
398  {
399  ROS_INFO("waiting for map service!");
400  ros::Duration(0.5).sleep();
401  wait_counter++;
402  }
404  if (wait_counter != wait_limit)
405  {
406  ROS_INFO_STREAM("Map service complete.");
407  updateMap(srv.response.map);
408  return true;
409  }
410  }
411 
412  ROS_WARN_STREAM("No map received.");
413  return false;
414 }
415 
416 void PFLocalizationNode::callbackMap(const nav_msgs::OccupancyGrid& msg)
417 {
418  if (param()->first_map_only && first_map_received_)
419  {
420  return;
421  }
422 
423  ROS_INFO_STREAM("Map received.");
424  updateMap(msg);
425 
426  first_map_received_ = true;
427 }
428 
429 void PFLocalizationNode::updateSensorPose(std::string _frame_id)
430 {
431  mrpt::poses::CPose3D pose;
432  tf::StampedTransform transform;
433  try
434  {
435  std::string base_frame_id =
436  tf::resolve(param()->tf_prefix, param()->base_frame_id);
438  base_frame_id, _frame_id, ros::Time(0), transform);
439  tf::Vector3 translation = transform.getOrigin();
440  tf::Quaternion quat = transform.getRotation();
441  pose.x() = translation.x();
442  pose.y() = translation.y();
443  pose.z() = translation.z();
444  tf::Matrix3x3 Rsrc(quat);
445  mrpt::math::CMatrixDouble33 Rdes;
446  for (int c = 0; c < 3; c++)
447  for (int r = 0; r < 3; r++) Rdes(r, c) = Rsrc.getRow(r)[c];
448  pose.setRotationMatrix(Rdes);
449  laser_poses_[_frame_id] = pose;
450  beacon_poses_[_frame_id] = pose;
451  }
452  catch (tf::TransformException& ex)
453  {
454  ROS_ERROR("%s", ex.what());
455  ros::Duration(1.0).sleep();
456  }
457 }
458 
460  const geometry_msgs::PoseWithCovarianceStamped& _msg)
461 {
462  const geometry_msgs::PoseWithCovariance& pose = _msg.pose;
463  mrpt_bridge::convert(pose, initial_pose_);
464  update_counter_ = 0;
465  state_ = INIT;
466 }
467 
468 void PFLocalizationNode::callbackOdometry(const nav_msgs::Odometry& _msg)
469 {
470  // We always update the filter if update_while_stopped is true, regardless
471  // robot is moving or
472  // not; otherwise, update filter if we are moving or at initialization (100
473  // first iterations)
474  bool moving = std::abs(_msg.twist.twist.linear.x) > 1e-3 ||
475  std::abs(_msg.twist.twist.linear.y) > 1e-3 ||
476  std::abs(_msg.twist.twist.linear.z) > 1e-3 ||
477  std::abs(_msg.twist.twist.angular.x) > 1e-3 ||
478  std::abs(_msg.twist.twist.angular.y) > 1e-3 ||
479  std::abs(_msg.twist.twist.angular.z) > 1e-3;
480  if (param()->update_while_stopped || moving)
481  {
482  if (state_ == IDLE)
483  {
484  state_ = RUN;
485  }
486  }
487  else if (state_ == RUN && update_counter_ >= 100)
488  {
489  state_ = IDLE;
490  }
491 }
492 
493 void PFLocalizationNode::updateMap(const nav_msgs::OccupancyGrid& _msg)
494 {
495 #if MRPT_VERSION >= 0x199
496  ASSERT_(metric_map_.countMapsByClass<COccupancyGridMap2D>());
497  mrpt_bridge::convert(_msg, *metric_map_.mapByClass<COccupancyGridMap2D>());
498 #else
499  ASSERT_(metric_map_.m_gridMaps.size() == 1);
500  mrpt_bridge::convert(_msg, *metric_map_.m_gridMaps[0]);
501 #endif
502 }
503 
505  nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res)
506 {
507  ROS_INFO("mapCallback: service requested!\n");
508  res = resp_;
509  return true;
510 }
511 
513 {
514  resp_.map.header.stamp = ros::Time::now();
515  resp_.map.header.frame_id =
516  tf::resolve(param()->tf_prefix, param()->global_frame_id);
517  resp_.map.header.seq = loop_count_;
518  if (pub_map_.getNumSubscribers() > 0)
519  {
520  pub_map_.publish(resp_.map);
521  }
523  {
524  pub_metadata_.publish(resp_.map.info);
525  }
526 }
527 
529 {
531  {
532  geometry_msgs::PoseArray poseArray;
533  poseArray.header.frame_id =
534  tf::resolve(param()->tf_prefix, param()->global_frame_id);
535  poseArray.header.stamp = ros::Time::now();
536  poseArray.header.seq = loop_count_;
537  poseArray.poses.resize(pdf_.particlesCount());
538  for (size_t i = 0; i < pdf_.particlesCount(); i++)
539  {
540  mrpt::math::TPose2D p = pdf_.getParticlePose(i);
541  mrpt_bridge::convert(p, poseArray.poses[i]);
542  }
543  mrpt::poses::CPose2D p;
544  pub_particles_.publish(poseArray);
545  }
546 }
547 
553 {
554  static std::string base_frame_id =
555  tf::resolve(param()->tf_prefix, param()->base_frame_id);
556  static std::string odom_frame_id =
557  tf::resolve(param()->tf_prefix, param()->odom_frame_id);
558  static std::string global_frame_id =
559  tf::resolve(param()->tf_prefix, param()->global_frame_id);
560 
561  mrpt::poses::CPose2D robot_pose;
562  pdf_.getMean(robot_pose);
563  tf::StampedTransform base_on_map_tf, odom_on_base_tf;
564  mrpt_bridge::convert(robot_pose, base_on_map_tf);
565  ros::Time time_last_update(0.0);
566  if (state_ == RUN)
567  {
568  mrpt_bridge::convert(time_last_update_, time_last_update);
569 
570  // Last update time can be too far in the past if we where not updating
571  // filter, due to robot stopped or no
572  // observations for a while (we optionally show a warning in the second
573  // case)
574  // We use time zero if so when getting base -> odom tf to prevent an
575  // extrapolation into the past exception
576  if ((ros::Time::now() - time_last_update).toSec() >
577  param()->no_update_tolerance)
578  {
579  if ((ros::Time::now() - time_last_input_).toSec() >
580  param()->no_inputs_tolerance)
581  {
583  2.0,
584  "No observations received for %.2fs (tolerance %.2fs); are "
585  "robot sensors working?",
586  (ros::Time::now() - time_last_input_).toSec(),
587  param()->no_inputs_tolerance);
588  }
589  else
590  {
592  2.0,
593  "No filter updates for %.2fs (tolerance %.2fs); probably "
594  "robot stopped for a while",
595  (ros::Time::now() - time_last_update).toSec(),
596  param()->no_update_tolerance);
597  }
598 
599  time_last_update = ros::Time(0.0);
600  }
601  }
602 
603  try
604  {
605  // Get base -> odom transform
607  base_frame_id, odom_frame_id, time_last_update, ros::Duration(0.1));
609  base_frame_id, odom_frame_id, time_last_update, odom_on_base_tf);
610  }
611  catch (tf::TransformException& e)
612  {
614  2.0, "Transform from base frame (%s) to odom frame (%s) failed: %s",
615  base_frame_id.c_str(), odom_frame_id.c_str(), e.what());
617  2.0,
618  "Ensure that your mobile base driver is broadcasting %s -> %s tf",
619  odom_frame_id.c_str(), base_frame_id.c_str());
620  return;
621  }
622 
623  // We want to send a transform that is good up until a tolerance time so
624  // that odom can be used
625  ros::Time transform_expiration =
626  (time_last_update.isZero() ? ros::Time::now() : time_last_update) +
628  tf::StampedTransform tmp_tf_stamped(
629  base_on_map_tf * odom_on_base_tf, transform_expiration, global_frame_id,
630  odom_frame_id);
631  tf_broadcaster_.sendTransform(tmp_tf_stamped);
632 }
633 
638 {
639  // cov for x, y, phi (meter, meter, radian)
640 #if MRPT_VERSION >= 0x199
641  const auto [cov, mean] = initial_pose_.getCovarianceAndMean();
642 #else
643  mrpt::math::CMatrixDouble33 cov;
644  mrpt::poses::CPose2D mean;
645  initial_pose_.getCovarianceAndMean(cov, mean);
646 #endif
647 
648  geometry_msgs::PoseWithCovarianceStamped p;
649 
650  // Fill in the header
651  p.header.frame_id =
652  tf::resolve(param()->tf_prefix, param()->global_frame_id);
653  if (loop_count_ < 10 || state_ == IDLE)
654  p.header.stamp = ros::Time::now(); // on first iterations timestamp
655  // differs a lot from ROS time
656  else
657  mrpt_bridge::convert(time_last_update_, p.header.stamp);
658 
659  // Copy in the pose
660  mrpt_bridge::convert(mean, p.pose.pose);
661 
662  // Copy in the covariance, converting from 3-D to 6-D
663  for (int i = 0; i < 3; i++)
664  {
665  for (int j = 0; j < 3; j++)
666  {
667  int ros_i = i;
668  int ros_j = j;
669  if (i == 2 || j == 2)
670  {
671  ros_i = i == 2 ? 5 : i;
672  ros_j = j == 2 ? 5 : j;
673  }
674  p.pose.covariance[ros_i * 6 + ros_j] = cov(i, j);
675  }
676  }
677 
678  pub_pose_.publish(p);
679 }
680 
682 {
683  // Set ROS log level also on MRPT internal log system; level enums are fully
684  // compatible
685  std::map<std::string, ros::console::levels::Level> loggers;
686  ros::console::get_loggers(loggers);
687  if (loggers.find("ros.roscpp") != loggers.end())
688  pdf_.setVerbosityLevel(
689  static_cast<VerbosityLevel>(loggers["ros.roscpp"]));
690  if (loggers.find("ros.mrpt_localization") != loggers.end())
691  pdf_.setVerbosityLevel(
692  static_cast<VerbosityLevel>(loggers["ros.mrpt_localization"]));
693 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
CMultiMetricMap metric_map_
map
void callbackRobotPose(const geometry_msgs::PoseWithCovarianceStamped &)
ros::ServiceClient client_map_
void publish(const boost::shared_ptr< M > &message) const
void publishTF()
Publish map -> odom tf; as the filter provides map -> base, we multiply it by base -> odom...
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber sub_init_pose_
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCONSOLE_DECL bool get_loggers(std::map< std::string, levels::Level > &loggers)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
void publishPose()
Publish the current pose of the robot.
void observation(CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
TFSIMD_FORCE_INLINE const Vector3 & getRow(int i) const
bool waitForTransform(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), std::string *error_msg=NULL) const
std::string resolve(const std::string &prefix, const std::string &frame_name)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void updateSensorPose(std::string frame_id)
TFSIMD_FORCE_INLINE const tfScalar & z() const
#define ROS_WARN_THROTTLE(period,...)
std::map< std::string, mrpt::poses::CPose3D > beacon_poses_
void odometryForCallback(CObservationOdometry::Ptr &, const std_msgs::Header &)
void callbackOdometry(const nav_msgs::Odometry &)
#define ROS_INFO(...)
#define ROS_ASSERT_MSG(cond,...)
mrpt::slam::CMonteCarloLocalization2D pdf_
the filter
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
mrpt::poses::CPosePDFGaussian initial_pose_
initial posed used in initializeFilter()
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & y() const
void sendTransform(const StampedTransform &transform)
tf::TransformListener tf_listener_
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))
std::vector< ros::Subscriber > sub_sensors_
ros::Subscriber sub_odometry_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
PFLocalizationNode(ros::NodeHandle &n)
#define ROS_WARN_STREAM(args)
void callbackLaser(const sensor_msgs::LaserScan &)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
void callbackBeacon(const mrpt_msgs::ObservationRangeBeacon &)
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
tf::TransformBroadcaster tf_broadcaster_
unsigned long long loop_count_
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
int main(int argc, char **argv)
Quaternion getRotation() const
void show3DDebug(CSensoryFrame::Ptr _observations)
nav_msgs::GetMap::Response resp_
void update(const unsigned long &loop_count)
ros::ServiceServer service_map_
static Time now()
std::map< std::string, mrpt::poses::CPose3D > laser_poses_
void updateMap(const nav_msgs::OccupancyGrid &)
mrpt::system::TTimeStamp time_last_update_
time of the last update
void callbackInitialpose(const geometry_msgs::PoseWithCovarianceStamped &)
ROSCPP_DECL void spinOnce()
Parameters * param_
void callbackMap(const nav_msgs::OccupancyGrid &)
#define ROS_ERROR(...)
#define ROS_DEBUG_THROTTLE(period,...)
static void pointTFToMsg(const Point &bt_v, geometry_msgs::Point &msg_v)


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Thu Jun 6 2019 19:44:49