amcl_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * This library is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU Lesser General Public
7  * License as published by the Free Software Foundation; either
8  * version 2.1 of the License, or (at your option) any later version.
9  *
10  * This library is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13  * Lesser General Public License for more details.
14  *
15  * You should have received a copy of the GNU Lesser General Public
16  * License along with this library; if not, write to the Free Software
17  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
18  *
19  */
20 
21 /* Author: Brian Gerkey */
22 
23 #include <algorithm>
24 #include <vector>
25 #include <map>
26 #include <cmath>
27 #include <memory>
28 
29 #include <boost/bind.hpp>
30 #include <boost/thread/mutex.hpp>
31 
32 // Signal handling
33 #include <signal.h>
34 
35 #include "amcl/map/map.h"
36 #include "amcl/pf/pf.h"
37 #include "amcl/sensors/amcl_odom.h"
39 #include "portable_utils.hpp"
40 
41 #include "ros/assert.h"
42 
43 // roscpp
44 #include "ros/ros.h"
45 
46 // Messages that I need
47 #include "sensor_msgs/LaserScan.h"
48 #include "geometry_msgs/PoseWithCovarianceStamped.h"
49 #include "geometry_msgs/PoseArray.h"
50 #include "geometry_msgs/Pose.h"
51 #include "geometry_msgs/PoseStamped.h"
52 #include "nav_msgs/GetMap.h"
53 #include "nav_msgs/SetMap.h"
54 #include "std_srvs/Empty.h"
55 
56 // For transform support
58 #include "tf2/convert.h"
59 #include "tf2/utils.h"
61 #include "tf2_ros/buffer.h"
62 #include "tf2_ros/message_filter.h"
66 
67 // Dynamic_reconfigure
68 #include "dynamic_reconfigure/server.h"
69 #include "amcl/AMCLConfig.h"
70 
71 // Allows AMCL to run from bag file
72 #include <rosbag/bag.h>
73 #include <rosbag/view.h>
74 #include <boost/foreach.hpp>
75 
76 // For monitoring the estimator
78 
79 #define NEW_UNIFORM_SAMPLING 1
80 
81 using namespace amcl;
82 
83 // Pose hypothesis
84 typedef struct
85 {
86  // Total weight (weights sum to 1)
87  double weight;
88 
89  // Mean of pose esimate
91 
92  // Covariance of pose estimate
94 
95 } amcl_hyp_t;
96 
97 static double
98 normalize(double z)
99 {
100  return atan2(sin(z),cos(z));
101 }
102 static double
103 angle_diff(double a, double b)
104 {
105  double d1, d2;
106  a = normalize(a);
107  b = normalize(b);
108  d1 = a-b;
109  d2 = 2*M_PI - fabs(d1);
110  if(d1 > 0)
111  d2 *= -1.0;
112  if(fabs(d1) < fabs(d2))
113  return(d1);
114  else
115  return(d2);
116 }
117 
118 static const std::string scan_topic_ = "scan";
119 
120 /* This function is only useful to have the whole code work
121  * with old rosbags that have trailing slashes for their frames
122  */
123 inline
124 std::string stripSlash(const std::string& in)
125 {
126  std::string out = in;
127  if ( ( !in.empty() ) && (in[0] == '/') )
128  out.erase(0,1);
129  return out;
130 }
131 
132 class AmclNode
133 {
134  public:
135  AmclNode();
136  ~AmclNode();
137 
144  void runFromBag(const std::string &in_bag_fn, bool trigger_global_localization = false);
145 
146  int process();
147  void savePoseToServer();
148 
149  private:
150  std::shared_ptr<tf2_ros::TransformBroadcaster> tfb_;
151  std::shared_ptr<tf2_ros::TransformListener> tfl_;
152  std::shared_ptr<tf2_ros::Buffer> tf_;
153 
155 
158 
159  // Pose-generating function used to uniformly distribute particles over
160  // the map
161  static pf_vector_t uniformPoseGenerator(void* arg);
162 #if NEW_UNIFORM_SAMPLING
163  static std::vector<std::pair<int,int> > free_space_indices;
164 #endif
165  // Callbacks
166  bool globalLocalizationCallback(std_srvs::Empty::Request& req,
167  std_srvs::Empty::Response& res);
168  bool nomotionUpdateCallback(std_srvs::Empty::Request& req,
169  std_srvs::Empty::Response& res);
170  bool setMapCallback(nav_msgs::SetMap::Request& req,
171  nav_msgs::SetMap::Response& res);
172 
173  void laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan);
174  void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
175  void handleInitialPoseMessage(const geometry_msgs::PoseWithCovarianceStamped& msg);
176  void mapReceived(const nav_msgs::OccupancyGridConstPtr& msg);
177 
178  void handleMapMessage(const nav_msgs::OccupancyGrid& msg);
179  void freeMapDependentMemory();
180  map_t* convertMap( const nav_msgs::OccupancyGrid& map_msg );
181  void updatePoseFromServer();
182  void applyInitialPose();
183 
184  //parameter for what odom to use
185  std::string odom_frame_id_;
186 
187  //paramater to store latest odom pose
188  geometry_msgs::PoseStamped latest_odom_pose_;
189 
190  //parameter for what base to use
191  std::string base_frame_id_;
192  std::string global_frame_id_;
193 
196 
200 
201  geometry_msgs::PoseWithCovarianceStamped last_published_pose;
202 
204  char* mapdata;
205  int sx, sy;
206  double resolution;
207 
211  std::vector< AMCLLaser* > lasers_;
212  std::vector< bool > lasers_update_;
213  std::map< std::string, int > frame_to_laser_;
214 
215  // Particle filter
217  double pf_err_, pf_z_;
218  bool pf_init_;
220  double d_thresh_, a_thresh_;
225 
226  //Nomotion update control
227  bool m_force_update; // used to temporarily let amcl update samples even when no motion occurs...
228 
231 
234 
235  // For slowing play-back when reading directly from a bag file
237 
238  void requestMap();
239 
240  // Helper to get odometric pose from transform system
241  bool getOdomPose(geometry_msgs::PoseStamped& pose,
242  double& x, double& y, double& yaw,
243  const ros::Time& t, const std::string& f);
244 
245  //time for tolerance on the published transform,
246  //basically defines how long a map->odom transform is good for
248 
254  ros::ServiceServer nomotion_update_srv_; //to let amcl update samples without requiring motion
258 
260  void standardDeviationDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& diagnostic_status);
264 
268 
269  boost::recursive_mutex configuration_mutex_;
270  dynamic_reconfigure::Server<amcl::AMCLConfig> *dsrv_;
271  amcl::AMCLConfig default_config_;
273 
274  int max_beams_, min_particles_, max_particles_;
275  double alpha1_, alpha2_, alpha3_, alpha4_, alpha5_;
276  double alpha_slow_, alpha_fast_;
277  double z_hit_, z_short_, z_max_, z_rand_, sigma_hit_, lambda_short_;
278  //beam skip related params
280  double beam_skip_distance_, beam_skip_threshold_, beam_skip_error_threshold_;
283  double init_pose_[3];
284  double init_cov_[3];
288 
289  void reconfigureCB(amcl::AMCLConfig &config, uint32_t level);
290 
293  void checkLaserReceived(const ros::TimerEvent& event);
294 };
295 
296 #if NEW_UNIFORM_SAMPLING
297 std::vector<std::pair<int,int> > AmclNode::free_space_indices;
298 #endif
299 
300 #define USAGE "USAGE: amcl"
301 
303 
304 void sigintHandler(int sig)
305 {
306  // Save latest pose as we're shutting down.
307  amcl_node_ptr->savePoseToServer();
308  ros::shutdown();
309 }
310 
311 int
312 main(int argc, char** argv)
313 {
314  ros::init(argc, argv, "amcl");
315  ros::NodeHandle nh;
316 
317  // Override default sigint handler
318  signal(SIGINT, sigintHandler);
319 
320  // Make our node available to sigintHandler
321  amcl_node_ptr.reset(new AmclNode());
322 
323  if (argc == 1)
324  {
325  // run using ROS input
326  ros::spin();
327  }
328  else if ((argc >= 3) && (std::string(argv[1]) == "--run-from-bag"))
329  {
330  if (argc == 3)
331  {
332  amcl_node_ptr->runFromBag(argv[2]);
333  }
334  else if ((argc == 4) && (std::string(argv[3]) == "--global-localization"))
335  {
336  amcl_node_ptr->runFromBag(argv[2], true);
337  }
338  }
339 
340  // Without this, our boost locks are not shut down nicely
341  amcl_node_ptr.reset();
342 
343  // To quote Morgan, Hooray!
344  return(0);
345 }
346 
348  sent_first_transform_(false),
349  latest_tf_valid_(false),
350  map_(NULL),
351  pf_(NULL),
352  resample_count_(0),
353  odom_(NULL),
354  laser_(NULL),
355  private_nh_("~"),
356  initial_pose_hyp_(NULL),
357  first_map_received_(false),
358  first_reconfigure_call_(true)
359 {
360  boost::recursive_mutex::scoped_lock l(configuration_mutex_);
361 
362  // Grab params off the param server
363  private_nh_.param("use_map_topic", use_map_topic_, false);
364  private_nh_.param("first_map_only", first_map_only_, false);
365 
366  double tmp;
367  private_nh_.param("gui_publish_rate", tmp, -1.0);
369  private_nh_.param("save_pose_rate", tmp, 0.5);
370  save_pose_period = ros::Duration(1.0/tmp);
371 
372  private_nh_.param("laser_min_range", laser_min_range_, -1.0);
373  private_nh_.param("laser_max_range", laser_max_range_, -1.0);
374  private_nh_.param("laser_max_beams", max_beams_, 30);
375  private_nh_.param("min_particles", min_particles_, 100);
376  private_nh_.param("max_particles", max_particles_, 5000);
377  private_nh_.param("kld_err", pf_err_, 0.01);
378  private_nh_.param("kld_z", pf_z_, 0.99);
379  private_nh_.param("odom_alpha1", alpha1_, 0.2);
380  private_nh_.param("odom_alpha2", alpha2_, 0.2);
381  private_nh_.param("odom_alpha3", alpha3_, 0.2);
382  private_nh_.param("odom_alpha4", alpha4_, 0.2);
383  private_nh_.param("odom_alpha5", alpha5_, 0.2);
384 
385  private_nh_.param("do_beamskip", do_beamskip_, false);
386  private_nh_.param("beam_skip_distance", beam_skip_distance_, 0.5);
387  private_nh_.param("beam_skip_threshold", beam_skip_threshold_, 0.3);
388  if (private_nh_.hasParam("beam_skip_error_threshold_"))
389  {
390  private_nh_.param("beam_skip_error_threshold_", beam_skip_error_threshold_);
391  }
392  else
393  {
394  private_nh_.param("beam_skip_error_threshold", beam_skip_error_threshold_, 0.9);
395  }
396 
397  private_nh_.param("laser_z_hit", z_hit_, 0.95);
398  private_nh_.param("laser_z_short", z_short_, 0.1);
399  private_nh_.param("laser_z_max", z_max_, 0.05);
400  private_nh_.param("laser_z_rand", z_rand_, 0.05);
401  private_nh_.param("laser_sigma_hit", sigma_hit_, 0.2);
402  private_nh_.param("laser_lambda_short", lambda_short_, 0.1);
403  private_nh_.param("laser_likelihood_max_dist", laser_likelihood_max_dist_, 2.0);
404  std::string tmp_model_type;
405  private_nh_.param("laser_model_type", tmp_model_type, std::string("likelihood_field"));
406  if(tmp_model_type == "beam")
408  else if(tmp_model_type == "likelihood_field")
410  else if(tmp_model_type == "likelihood_field_prob"){
412  }
413  else
414  {
415  ROS_WARN("Unknown laser model type \"%s\"; defaulting to likelihood_field model",
416  tmp_model_type.c_str());
418  }
419 
420  private_nh_.param("odom_model_type", tmp_model_type, std::string("diff"));
421  if(tmp_model_type == "diff")
423  else if(tmp_model_type == "omni")
425  else if(tmp_model_type == "diff-corrected")
427  else if(tmp_model_type == "omni-corrected")
429  else
430  {
431  ROS_WARN("Unknown odom model type \"%s\"; defaulting to diff model",
432  tmp_model_type.c_str());
434  }
435 
436  private_nh_.param("update_min_d", d_thresh_, 0.2);
437  private_nh_.param("update_min_a", a_thresh_, M_PI/6.0);
438  private_nh_.param("odom_frame_id", odom_frame_id_, std::string("odom"));
439  private_nh_.param("base_frame_id", base_frame_id_, std::string("base_link"));
440  private_nh_.param("global_frame_id", global_frame_id_, std::string("map"));
441  private_nh_.param("resample_interval", resample_interval_, 2);
442  private_nh_.param("selective_resampling", selective_resampling_, false);
443  double tmp_tol;
444  private_nh_.param("transform_tolerance", tmp_tol, 0.1);
445  private_nh_.param("recovery_alpha_slow", alpha_slow_, 0.001);
446  private_nh_.param("recovery_alpha_fast", alpha_fast_, 0.1);
447  private_nh_.param("tf_broadcast", tf_broadcast_, true);
448 
449  // For diagnostics
450  private_nh_.param("std_warn_level_x", std_warn_level_x_, 0.2);
451  private_nh_.param("std_warn_level_y", std_warn_level_y_, 0.2);
452  private_nh_.param("std_warn_level_yaw", std_warn_level_yaw_, 0.1);
453 
454  transform_tolerance_.fromSec(tmp_tol);
455 
456  {
457  double bag_scan_period;
458  private_nh_.param("bag_scan_period", bag_scan_period, -1.0);
459  bag_scan_period_.fromSec(bag_scan_period);
460  }
461 
465 
467 
469  tfb_.reset(new tf2_ros::TransformBroadcaster());
470  tf_.reset(new tf2_ros::Buffer());
471  tfl_.reset(new tf2_ros::TransformListener(*tf_));
472 
473  pose_pub_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("amcl_pose", 2, true);
474  particlecloud_pub_ = nh_.advertise<geometry_msgs::PoseArray>("particlecloud", 2, true);
475  global_loc_srv_ = nh_.advertiseService("global_localization",
477  this);
480 
484  *tf_,
486  100,
487  nh_);
488  laser_scan_filter_->registerCallback(boost::bind(&AmclNode::laserReceived,
489  this, _1));
490  initial_pose_sub_ = nh_.subscribe("initialpose", 2, &AmclNode::initialPoseReceived, this);
491 
492  if(use_map_topic_) {
493  map_sub_ = nh_.subscribe("map", 1, &AmclNode::mapReceived, this);
494  ROS_INFO("Subscribed to map topic.");
495  } else {
496  requestMap();
497  }
498  m_force_update = false;
499 
500  dsrv_ = new dynamic_reconfigure::Server<amcl::AMCLConfig>(ros::NodeHandle("~"));
501  dynamic_reconfigure::Server<amcl::AMCLConfig>::CallbackType cb = boost::bind(&AmclNode::reconfigureCB, this, _1, _2);
502  dsrv_->setCallback(cb);
503 
504  // 15s timer to warn on lack of receipt of laser scans, #5209
506  check_laser_timer_ = nh_.createTimer(laser_check_interval_,
507  boost::bind(&AmclNode::checkLaserReceived, this, _1));
508 
510  diagnosic_updater_.add("Standard deviation", this, &AmclNode::standardDeviationDiagnostics);
511 }
512 
513 void AmclNode::reconfigureCB(AMCLConfig &config, uint32_t level)
514 {
515  boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
516 
517  //we don't want to do anything on the first call
518  //which corresponds to startup
520  {
521  first_reconfigure_call_ = false;
522  default_config_ = config;
523  return;
524  }
525 
526  if(config.restore_defaults) {
527  config = default_config_;
528  //avoid looping
529  config.restore_defaults = false;
530  }
531 
532  d_thresh_ = config.update_min_d;
533  a_thresh_ = config.update_min_a;
534 
535  resample_interval_ = config.resample_interval;
536 
537  laser_min_range_ = config.laser_min_range;
538  laser_max_range_ = config.laser_max_range;
539 
540  gui_publish_period = ros::Duration(1.0/config.gui_publish_rate);
541  save_pose_period = ros::Duration(1.0/config.save_pose_rate);
542 
543  transform_tolerance_.fromSec(config.transform_tolerance);
544 
545  max_beams_ = config.laser_max_beams;
546  alpha1_ = config.odom_alpha1;
547  alpha2_ = config.odom_alpha2;
548  alpha3_ = config.odom_alpha3;
549  alpha4_ = config.odom_alpha4;
550  alpha5_ = config.odom_alpha5;
551 
552  z_hit_ = config.laser_z_hit;
553  z_short_ = config.laser_z_short;
554  z_max_ = config.laser_z_max;
555  z_rand_ = config.laser_z_rand;
556  sigma_hit_ = config.laser_sigma_hit;
557  lambda_short_ = config.laser_lambda_short;
558  laser_likelihood_max_dist_ = config.laser_likelihood_max_dist;
559 
560  if(config.laser_model_type == "beam")
562  else if(config.laser_model_type == "likelihood_field")
564  else if(config.laser_model_type == "likelihood_field_prob")
566 
567  if(config.odom_model_type == "diff")
569  else if(config.odom_model_type == "omni")
571  else if(config.odom_model_type == "diff-corrected")
573  else if(config.odom_model_type == "omni-corrected")
575 
576  if(config.min_particles > config.max_particles)
577  {
578  ROS_WARN("You've set min_particles to be greater than max particles, this isn't allowed so they'll be set to be equal.");
579  config.max_particles = config.min_particles;
580  }
581 
582  min_particles_ = config.min_particles;
583  max_particles_ = config.max_particles;
584  alpha_slow_ = config.recovery_alpha_slow;
585  alpha_fast_ = config.recovery_alpha_fast;
586  tf_broadcast_ = config.tf_broadcast;
587 
588  do_beamskip_= config.do_beamskip;
589  beam_skip_distance_ = config.beam_skip_distance;
590  beam_skip_threshold_ = config.beam_skip_threshold;
591 
592  // Clear queued laser objects so that their parameters get updated
593  lasers_.clear();
594  lasers_update_.clear();
595  frame_to_laser_.clear();
596 
597  if( pf_ != NULL )
598  {
599  pf_free( pf_ );
600  pf_ = NULL;
601  }
605  (void *)map_);
607  pf_err_ = config.kld_err;
608  pf_z_ = config.kld_z;
609  pf_->pop_err = pf_err_;
610  pf_->pop_z = pf_z_;
611 
612  // Initialize the filter
613  pf_vector_t pf_init_pose_mean = pf_vector_zero();
614  pf_init_pose_mean.v[0] = last_published_pose.pose.pose.position.x;
615  pf_init_pose_mean.v[1] = last_published_pose.pose.pose.position.y;
616  pf_init_pose_mean.v[2] = tf2::getYaw(last_published_pose.pose.pose.orientation);
617  pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
618  pf_init_pose_cov.m[0][0] = last_published_pose.pose.covariance[6*0+0];
619  pf_init_pose_cov.m[1][1] = last_published_pose.pose.covariance[6*1+1];
620  pf_init_pose_cov.m[2][2] = last_published_pose.pose.covariance[6*5+5];
621  pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
622  pf_init_ = false;
623 
624  // Instantiate the sensor objects
625  // Odometry
626  delete odom_;
627  odom_ = new AMCLOdom();
628  ROS_ASSERT(odom_);
630  // Laser
631  delete laser_;
632  laser_ = new AMCLLaser(max_beams_, map_);
636  sigma_hit_, lambda_short_, 0.0);
638  ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
643  ROS_INFO("Done initializing likelihood field model with probabilities.");
644  }
646  ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
649  ROS_INFO("Done initializing likelihood field model.");
650  }
651 
652  odom_frame_id_ = stripSlash(config.odom_frame_id);
653  base_frame_id_ = stripSlash(config.base_frame_id);
654  global_frame_id_ = stripSlash(config.global_frame_id);
655 
656  delete laser_scan_filter_;
659  *tf_,
661  100,
662  nh_);
664  this, _1));
665 
666  initial_pose_sub_ = nh_.subscribe("initialpose", 2, &AmclNode::initialPoseReceived, this);
667 }
668 
669 
670 void AmclNode::runFromBag(const std::string &in_bag_fn, bool trigger_global_localization)
671 {
672  rosbag::Bag bag;
673  bag.open(in_bag_fn, rosbag::bagmode::Read);
674  std::vector<std::string> topics;
675  topics.push_back(std::string("tf"));
676  std::string scan_topic_name = "base_scan"; // TODO determine what topic this actually is from ROS
677  topics.push_back(scan_topic_name);
678  rosbag::View view(bag, rosbag::TopicQuery(topics));
679 
680  ros::Publisher laser_pub = nh_.advertise<sensor_msgs::LaserScan>(scan_topic_name, 100);
681  ros::Publisher tf_pub = nh_.advertise<tf2_msgs::TFMessage>("/tf", 100);
682 
683  // Sleep for a second to let all subscribers connect
684  ros::WallDuration(1.0).sleep();
685 
687 
688  // Wait for map
689  while (ros::ok())
690  {
691  {
692  boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
693  if (map_)
694  {
695  ROS_INFO("Map is ready");
696  break;
697  }
698  }
699  ROS_INFO("Waiting for map...");
701  }
702 
703  if (trigger_global_localization)
704  {
705  std_srvs::Empty empty_srv;
706  globalLocalizationCallback(empty_srv.request, empty_srv.response);
707  }
708 
709  BOOST_FOREACH(rosbag::MessageInstance const msg, view)
710  {
711  if (!ros::ok())
712  {
713  break;
714  }
715 
716  // Process any ros messages or callbacks at this point
718 
719  tf2_msgs::TFMessage::ConstPtr tf_msg = msg.instantiate<tf2_msgs::TFMessage>();
720  if (tf_msg != NULL)
721  {
722  tf_pub.publish(msg);
723  for (size_t ii=0; ii<tf_msg->transforms.size(); ++ii)
724  {
725  tf_->setTransform(tf_msg->transforms[ii], "rosbag_authority");
726  }
727  continue;
728  }
729 
730  sensor_msgs::LaserScan::ConstPtr base_scan = msg.instantiate<sensor_msgs::LaserScan>();
731  if (base_scan != NULL)
732  {
733  laser_pub.publish(msg);
734  laser_scan_filter_->add(base_scan);
736  {
738  }
739  continue;
740  }
741 
742  ROS_WARN_STREAM("Unsupported message type" << msg.getTopic());
743  }
744 
745  bag.close();
746 
747  double runtime = (ros::WallTime::now() - start).toSec();
748  ROS_INFO("Bag complete, took %.1f seconds to process, shutting down", runtime);
749 
750  const geometry_msgs::Quaternion & q(last_published_pose.pose.pose.orientation);
751  double yaw, pitch, roll;
752  tf2::Matrix3x3(tf2::Quaternion(q.x, q.y, q.z, q.w)).getEulerYPR(yaw,pitch,roll);
753  ROS_INFO("Final location %.3f, %.3f, %.3f with stamp=%f",
754  last_published_pose.pose.pose.position.x,
755  last_published_pose.pose.pose.position.y,
756  yaw, last_published_pose.header.stamp.toSec()
757  );
758 
759  ros::shutdown();
760 }
761 
762 
764 {
765  // We need to apply the last transform to the latest odom pose to get
766  // the latest map pose to store. We'll take the covariance from
767  // last_published_pose.
768  tf2::Transform odom_pose_tf2;
769  tf2::convert(latest_odom_pose_.pose, odom_pose_tf2);
770  tf2::Transform map_pose = latest_tf_.inverse() * odom_pose_tf2;
771 
772  double yaw = tf2::getYaw(map_pose.getRotation());
773 
774  ROS_DEBUG("Saving pose to server. x: %.3f, y: %.3f", map_pose.getOrigin().x(), map_pose.getOrigin().y() );
775 
776  private_nh_.setParam("initial_pose_x", map_pose.getOrigin().x());
777  private_nh_.setParam("initial_pose_y", map_pose.getOrigin().y());
778  private_nh_.setParam("initial_pose_a", yaw);
779  private_nh_.setParam("initial_cov_xx",
780  last_published_pose.pose.covariance[6*0+0]);
781  private_nh_.setParam("initial_cov_yy",
782  last_published_pose.pose.covariance[6*1+1]);
783  private_nh_.setParam("initial_cov_aa",
784  last_published_pose.pose.covariance[6*5+5]);
785 }
786 
788 {
789  init_pose_[0] = 0.0;
790  init_pose_[1] = 0.0;
791  init_pose_[2] = 0.0;
792  init_cov_[0] = 0.5 * 0.5;
793  init_cov_[1] = 0.5 * 0.5;
794  init_cov_[2] = (M_PI/12.0) * (M_PI/12.0);
795  // Check for NAN on input from param server, #5239
796  double tmp_pos;
797  private_nh_.param("initial_pose_x", tmp_pos, init_pose_[0]);
798  if(!std::isnan(tmp_pos))
799  init_pose_[0] = tmp_pos;
800  else
801  ROS_WARN("ignoring NAN in initial pose X position");
802  private_nh_.param("initial_pose_y", tmp_pos, init_pose_[1]);
803  if(!std::isnan(tmp_pos))
804  init_pose_[1] = tmp_pos;
805  else
806  ROS_WARN("ignoring NAN in initial pose Y position");
807  private_nh_.param("initial_pose_a", tmp_pos, init_pose_[2]);
808  if(!std::isnan(tmp_pos))
809  init_pose_[2] = tmp_pos;
810  else
811  ROS_WARN("ignoring NAN in initial pose Yaw");
812  private_nh_.param("initial_cov_xx", tmp_pos, init_cov_[0]);
813  if(!std::isnan(tmp_pos))
814  init_cov_[0] =tmp_pos;
815  else
816  ROS_WARN("ignoring NAN in initial covariance XX");
817  private_nh_.param("initial_cov_yy", tmp_pos, init_cov_[1]);
818  if(!std::isnan(tmp_pos))
819  init_cov_[1] = tmp_pos;
820  else
821  ROS_WARN("ignoring NAN in initial covariance YY");
822  private_nh_.param("initial_cov_aa", tmp_pos, init_cov_[2]);
823  if(!std::isnan(tmp_pos))
824  init_cov_[2] = tmp_pos;
825  else
826  ROS_WARN("ignoring NAN in initial covariance AA");
827 }
828 
829 void
831 {
833  if(d > laser_check_interval_)
834  {
835  ROS_WARN("No laser scan received (and thus no pose updates have been published) for %f seconds. Verify that data is being published on the %s topic.",
836  d.toSec(),
838  }
839 }
840 
841 void
843 {
844  boost::recursive_mutex::scoped_lock ml(configuration_mutex_);
845 
846  // get map via RPC
847  nav_msgs::GetMap::Request req;
848  nav_msgs::GetMap::Response resp;
849  ROS_INFO("Requesting the map...");
850  while(!ros::service::call("static_map", req, resp))
851  {
852  ROS_WARN("Request for map failed; trying again...");
853  ros::Duration d(0.5);
854  d.sleep();
855  }
856  handleMapMessage( resp.map );
857 }
858 
859 void
860 AmclNode::mapReceived(const nav_msgs::OccupancyGridConstPtr& msg)
861 {
863  return;
864  }
865 
866  handleMapMessage( *msg );
867 
868  first_map_received_ = true;
869 }
870 
871 void
872 AmclNode::handleMapMessage(const nav_msgs::OccupancyGrid& msg)
873 {
874  boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
875 
876  ROS_INFO("Received a %d X %d map @ %.3f m/pix\n",
877  msg.info.width,
878  msg.info.height,
879  msg.info.resolution);
880 
881  if(msg.header.frame_id != global_frame_id_)
882  ROS_WARN("Frame_id of map received:'%s' doesn't match global_frame_id:'%s'. This could cause issues with reading published topics",
883  msg.header.frame_id.c_str(),
884  global_frame_id_.c_str());
885 
887  // Clear queued laser objects because they hold pointers to the existing
888  // map, #5202.
889  lasers_.clear();
890  lasers_update_.clear();
891  frame_to_laser_.clear();
892 
893  map_ = convertMap(msg);
894 
895 #if NEW_UNIFORM_SAMPLING
896  // Index of free space
897  free_space_indices.resize(0);
898  for(int i = 0; i < map_->size_x; i++)
899  for(int j = 0; j < map_->size_y; j++)
900  if(map_->cells[MAP_INDEX(map_,i,j)].occ_state == -1)
901  free_space_indices.push_back(std::make_pair(i,j));
902 #endif
903  // Create the particle filter
907  (void *)map_);
909  pf_->pop_err = pf_err_;
910  pf_->pop_z = pf_z_;
911 
912  // Initialize the filter
914  pf_vector_t pf_init_pose_mean = pf_vector_zero();
915  pf_init_pose_mean.v[0] = init_pose_[0];
916  pf_init_pose_mean.v[1] = init_pose_[1];
917  pf_init_pose_mean.v[2] = init_pose_[2];
918  pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
919  pf_init_pose_cov.m[0][0] = init_cov_[0];
920  pf_init_pose_cov.m[1][1] = init_cov_[1];
921  pf_init_pose_cov.m[2][2] = init_cov_[2];
922  pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
923  pf_init_ = false;
924 
925  // Instantiate the sensor objects
926  // Odometry
927  delete odom_;
928  odom_ = new AMCLOdom();
929  ROS_ASSERT(odom_);
931  // Laser
932  delete laser_;
933  laser_ = new AMCLLaser(max_beams_, map_);
937  sigma_hit_, lambda_short_, 0.0);
939  ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
944  ROS_INFO("Done initializing likelihood field model.");
945  }
946  else
947  {
948  ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
951  ROS_INFO("Done initializing likelihood field model.");
952  }
953 
954  // In case the initial pose message arrived before the first map,
955  // try to apply the initial pose now that the map has arrived.
957 
958 }
959 
960 void
962 {
963  if( map_ != NULL ) {
964  map_free( map_ );
965  map_ = NULL;
966  }
967  if( pf_ != NULL ) {
968  pf_free( pf_ );
969  pf_ = NULL;
970  }
971  delete odom_;
972  odom_ = NULL;
973  delete laser_;
974  laser_ = NULL;
975 }
976 
981 map_t*
982 AmclNode::convertMap( const nav_msgs::OccupancyGrid& map_msg )
983 {
984  map_t* map = map_alloc();
985  ROS_ASSERT(map);
986 
987  map->size_x = map_msg.info.width;
988  map->size_y = map_msg.info.height;
989  map->scale = map_msg.info.resolution;
990  map->origin_x = map_msg.info.origin.position.x + (map->size_x / 2) * map->scale;
991  map->origin_y = map_msg.info.origin.position.y + (map->size_y / 2) * map->scale;
992  // Convert to player format
993  map->cells = (map_cell_t*)malloc(sizeof(map_cell_t)*map->size_x*map->size_y);
994  ROS_ASSERT(map->cells);
995  for(int i=0;i<map->size_x * map->size_y;i++)
996  {
997  if(map_msg.data[i] == 0)
998  map->cells[i].occ_state = -1;
999  else if(map_msg.data[i] == 100)
1000  map->cells[i].occ_state = +1;
1001  else
1002  map->cells[i].occ_state = 0;
1003  }
1004 
1005  return map;
1006 }
1007 
1009 {
1010  delete dsrv_;
1012  delete laser_scan_filter_;
1013  delete laser_scan_sub_;
1014  // TODO: delete everything allocated in constructor
1015 }
1016 
1017 bool
1018 AmclNode::getOdomPose(geometry_msgs::PoseStamped& odom_pose,
1019  double& x, double& y, double& yaw,
1020  const ros::Time& t, const std::string& f)
1021 {
1022  // Get the robot's pose
1023  geometry_msgs::PoseStamped ident;
1024  ident.header.frame_id = stripSlash(f);
1025  ident.header.stamp = t;
1026  tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
1027  try
1028  {
1029  this->tf_->transform(ident, odom_pose, odom_frame_id_);
1030  }
1031  catch(tf2::TransformException e)
1032  {
1033  ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what());
1034  return false;
1035  }
1036  x = odom_pose.pose.position.x;
1037  y = odom_pose.pose.position.y;
1038  yaw = tf2::getYaw(odom_pose.pose.orientation);
1039 
1040  return true;
1041 }
1042 
1043 
1046 {
1047  map_t* map = (map_t*)arg;
1048 #if NEW_UNIFORM_SAMPLING
1049  unsigned int rand_index = drand48() * free_space_indices.size();
1050  std::pair<int,int> free_point = free_space_indices[rand_index];
1051  pf_vector_t p;
1052  p.v[0] = MAP_WXGX(map, free_point.first);
1053  p.v[1] = MAP_WYGY(map, free_point.second);
1054  p.v[2] = drand48() * 2 * M_PI - M_PI;
1055 #else
1056  double min_x, max_x, min_y, max_y;
1057 
1058  min_x = (map->size_x * map->scale)/2.0 - map->origin_x;
1059  max_x = (map->size_x * map->scale)/2.0 + map->origin_x;
1060  min_y = (map->size_y * map->scale)/2.0 - map->origin_y;
1061  max_y = (map->size_y * map->scale)/2.0 + map->origin_y;
1062 
1063  pf_vector_t p;
1064 
1065  ROS_DEBUG("Generating new uniform sample");
1066  for(;;)
1067  {
1068  p.v[0] = min_x + drand48() * (max_x - min_x);
1069  p.v[1] = min_y + drand48() * (max_y - min_y);
1070  p.v[2] = drand48() * 2 * M_PI - M_PI;
1071  // Check that it's a free cell
1072  int i,j;
1073  i = MAP_GXWX(map, p.v[0]);
1074  j = MAP_GYWY(map, p.v[1]);
1075  if(MAP_VALID(map,i,j) && (map->cells[MAP_INDEX(map,i,j)].occ_state == -1))
1076  break;
1077  }
1078 #endif
1079  return p;
1080 }
1081 
1082 bool
1083 AmclNode::globalLocalizationCallback(std_srvs::Empty::Request& req,
1084  std_srvs::Empty::Response& res)
1085 {
1086  if( map_ == NULL ) {
1087  return true;
1088  }
1089  boost::recursive_mutex::scoped_lock gl(configuration_mutex_);
1090  ROS_INFO("Initializing with uniform distribution");
1092  (void *)map_);
1093  ROS_INFO("Global initialisation done!");
1094  pf_init_ = false;
1095  return true;
1096 }
1097 
1098 // force nomotion updates (amcl updating without requiring motion)
1099 bool
1100 AmclNode::nomotionUpdateCallback(std_srvs::Empty::Request& req,
1101  std_srvs::Empty::Response& res)
1102 {
1103  m_force_update = true;
1104  //ROS_INFO("Requesting no-motion update");
1105  return true;
1106 }
1107 
1108 bool
1109 AmclNode::setMapCallback(nav_msgs::SetMap::Request& req,
1110  nav_msgs::SetMap::Response& res)
1111 {
1112  handleMapMessage(req.map);
1113  handleInitialPoseMessage(req.initial_pose);
1114  res.success = true;
1115  return true;
1116 }
1117 
1118 void
1119 AmclNode::laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan)
1120 {
1121  std::string laser_scan_frame_id = stripSlash(laser_scan->header.frame_id);
1123  if( map_ == NULL ) {
1124  return;
1125  }
1126  boost::recursive_mutex::scoped_lock lr(configuration_mutex_);
1127  int laser_index = -1;
1128 
1129  // Do we have the base->base_laser Tx yet?
1130  if(frame_to_laser_.find(laser_scan_frame_id) == frame_to_laser_.end())
1131  {
1132  ROS_DEBUG("Setting up laser %d (frame_id=%s)\n", (int)frame_to_laser_.size(), laser_scan_frame_id.c_str());
1133  lasers_.push_back(new AMCLLaser(*laser_));
1134  lasers_update_.push_back(true);
1135  laser_index = frame_to_laser_.size();
1136 
1137  geometry_msgs::PoseStamped ident;
1138  ident.header.frame_id = laser_scan_frame_id;
1139  ident.header.stamp = ros::Time();
1140  tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
1141 
1142  geometry_msgs::PoseStamped laser_pose;
1143  try
1144  {
1145  this->tf_->transform(ident, laser_pose, base_frame_id_);
1146  }
1147  catch(tf2::TransformException& e)
1148  {
1149  ROS_ERROR("Couldn't transform from %s to %s, "
1150  "even though the message notifier is in use",
1151  laser_scan_frame_id.c_str(),
1152  base_frame_id_.c_str());
1153  return;
1154  }
1155 
1156  pf_vector_t laser_pose_v;
1157  laser_pose_v.v[0] = laser_pose.pose.position.x;
1158  laser_pose_v.v[1] = laser_pose.pose.position.y;
1159  // laser mounting angle gets computed later -> set to 0 here!
1160  laser_pose_v.v[2] = 0;
1161  lasers_[laser_index]->SetLaserPose(laser_pose_v);
1162  ROS_DEBUG("Received laser's pose wrt robot: %.3f %.3f %.3f",
1163  laser_pose_v.v[0],
1164  laser_pose_v.v[1],
1165  laser_pose_v.v[2]);
1166 
1167  frame_to_laser_[laser_scan_frame_id] = laser_index;
1168  } else {
1169  // we have the laser pose, retrieve laser index
1170  laser_index = frame_to_laser_[laser_scan_frame_id];
1171  }
1172 
1173  // Where was the robot when this scan was taken?
1174  pf_vector_t pose;
1175  if(!getOdomPose(latest_odom_pose_, pose.v[0], pose.v[1], pose.v[2],
1176  laser_scan->header.stamp, base_frame_id_))
1177  {
1178  ROS_ERROR("Couldn't determine robot's pose associated with laser scan");
1179  return;
1180  }
1181 
1182 
1183  pf_vector_t delta = pf_vector_zero();
1184 
1185  if(pf_init_)
1186  {
1187  // Compute change in pose
1188  //delta = pf_vector_coord_sub(pose, pf_odom_pose_);
1189  delta.v[0] = pose.v[0] - pf_odom_pose_.v[0];
1190  delta.v[1] = pose.v[1] - pf_odom_pose_.v[1];
1191  delta.v[2] = angle_diff(pose.v[2], pf_odom_pose_.v[2]);
1192 
1193  // See if we should update the filter
1194  bool update = fabs(delta.v[0]) > d_thresh_ ||
1195  fabs(delta.v[1]) > d_thresh_ ||
1196  fabs(delta.v[2]) > a_thresh_;
1197  update = update || m_force_update;
1198  m_force_update=false;
1199 
1200  // Set the laser update flags
1201  if(update)
1202  for(unsigned int i=0; i < lasers_update_.size(); i++)
1203  lasers_update_[i] = true;
1204  }
1205 
1206  bool force_publication = false;
1207  if(!pf_init_)
1208  {
1209  // Pose at last filter update
1210  pf_odom_pose_ = pose;
1211 
1212  // Filter is now initialized
1213  pf_init_ = true;
1214 
1215  // Should update sensor data
1216  for(unsigned int i=0; i < lasers_update_.size(); i++)
1217  lasers_update_[i] = true;
1218 
1219  force_publication = true;
1220 
1221  resample_count_ = 0;
1222  }
1223  // If the robot has moved, update the filter
1224  else if(pf_init_ && lasers_update_[laser_index])
1225  {
1226  //printf("pose\n");
1227  //pf_vector_fprintf(pose, stdout, "%.3f");
1228 
1229  AMCLOdomData odata;
1230  odata.pose = pose;
1231  // HACK
1232  // Modify the delta in the action data so the filter gets
1233  // updated correctly
1234  odata.delta = delta;
1235 
1236  // Use the action data to update the filter
1237  odom_->UpdateAction(pf_, (AMCLSensorData*)&odata);
1238 
1239  // Pose at last filter update
1240  //this->pf_odom_pose = pose;
1241  }
1242 
1243  bool resampled = false;
1244  // If the robot has moved, update the filter
1245  if(lasers_update_[laser_index])
1246  {
1247  AMCLLaserData ldata;
1248  ldata.sensor = lasers_[laser_index];
1249  ldata.range_count = laser_scan->ranges.size();
1250 
1251  // To account for lasers that are mounted upside-down, we determine the
1252  // min, max, and increment angles of the laser in the base frame.
1253  //
1254  // Construct min and max angles of laser, in the base_link frame.
1255  tf2::Quaternion q;
1256  q.setRPY(0.0, 0.0, laser_scan->angle_min);
1257  geometry_msgs::QuaternionStamped min_q, inc_q;
1258  min_q.header.stamp = laser_scan->header.stamp;
1259  min_q.header.frame_id = stripSlash(laser_scan->header.frame_id);
1260  tf2::convert(q, min_q.quaternion);
1261 
1262  q.setRPY(0.0, 0.0, laser_scan->angle_min + laser_scan->angle_increment);
1263  inc_q.header = min_q.header;
1264  tf2::convert(q, inc_q.quaternion);
1265  try
1266  {
1267  tf_->transform(min_q, min_q, base_frame_id_);
1268  tf_->transform(inc_q, inc_q, base_frame_id_);
1269  }
1270  catch(tf2::TransformException& e)
1271  {
1272  ROS_WARN("Unable to transform min/max laser angles into base frame: %s",
1273  e.what());
1274  return;
1275  }
1276 
1277  double angle_min = tf2::getYaw(min_q.quaternion);
1278  double angle_increment = tf2::getYaw(inc_q.quaternion) - angle_min;
1279 
1280  // wrapping angle to [-pi .. pi]
1281  angle_increment = fmod(angle_increment + 5*M_PI, 2*M_PI) - M_PI;
1282 
1283  ROS_DEBUG("Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min, angle_increment);
1284 
1285  // Apply range min/max thresholds, if the user supplied them
1286  if(laser_max_range_ > 0.0)
1287  ldata.range_max = std::min(laser_scan->range_max, (float)laser_max_range_);
1288  else
1289  ldata.range_max = laser_scan->range_max;
1290  double range_min;
1291  if(laser_min_range_ > 0.0)
1292  range_min = std::max(laser_scan->range_min, (float)laser_min_range_);
1293  else
1294  range_min = laser_scan->range_min;
1295  // The AMCLLaserData destructor will free this memory
1296  ldata.ranges = new double[ldata.range_count][2];
1297  ROS_ASSERT(ldata.ranges);
1298  for(int i=0;i<ldata.range_count;i++)
1299  {
1300  // amcl doesn't (yet) have a concept of min range. So we'll map short
1301  // readings to max range.
1302  if(laser_scan->ranges[i] <= range_min)
1303  ldata.ranges[i][0] = ldata.range_max;
1304  else
1305  ldata.ranges[i][0] = laser_scan->ranges[i];
1306  // Compute bearing
1307  ldata.ranges[i][1] = angle_min +
1308  (i * angle_increment);
1309  }
1310 
1311  lasers_[laser_index]->UpdateSensor(pf_, (AMCLSensorData*)&ldata);
1312 
1313  lasers_update_[laser_index] = false;
1314 
1315  pf_odom_pose_ = pose;
1316 
1317  // Resample the particles
1319  {
1321  resampled = true;
1322  }
1323 
1324  pf_sample_set_t* set = pf_->sets + pf_->current_set;
1325  ROS_DEBUG("Num samples: %d\n", set->sample_count);
1326 
1327  // Publish the resulting cloud
1328  // TODO: set maximum rate for publishing
1329  if (!m_force_update)
1330  {
1331  geometry_msgs::PoseArray cloud_msg;
1332  cloud_msg.header.stamp = ros::Time::now();
1333  cloud_msg.header.frame_id = global_frame_id_;
1334  cloud_msg.poses.resize(set->sample_count);
1335  for(int i=0;i<set->sample_count;i++)
1336  {
1337  cloud_msg.poses[i].position.x = set->samples[i].pose.v[0];
1338  cloud_msg.poses[i].position.y = set->samples[i].pose.v[1];
1339  cloud_msg.poses[i].position.z = 0;
1340  tf2::Quaternion q;
1341  q.setRPY(0, 0, set->samples[i].pose.v[2]);
1342  tf2::convert(q, cloud_msg.poses[i].orientation);
1343  }
1344  particlecloud_pub_.publish(cloud_msg);
1345  }
1346  }
1347 
1348  if(resampled || force_publication)
1349  {
1350  // Read out the current hypotheses
1351  double max_weight = 0.0;
1352  int max_weight_hyp = -1;
1353  std::vector<amcl_hyp_t> hyps;
1354  hyps.resize(pf_->sets[pf_->current_set].cluster_count);
1355  for(int hyp_count = 0;
1356  hyp_count < pf_->sets[pf_->current_set].cluster_count; hyp_count++)
1357  {
1358  double weight;
1359  pf_vector_t pose_mean;
1360  pf_matrix_t pose_cov;
1361  if (!pf_get_cluster_stats(pf_, hyp_count, &weight, &pose_mean, &pose_cov))
1362  {
1363  ROS_ERROR("Couldn't get stats on cluster %d", hyp_count);
1364  break;
1365  }
1366 
1367  hyps[hyp_count].weight = weight;
1368  hyps[hyp_count].pf_pose_mean = pose_mean;
1369  hyps[hyp_count].pf_pose_cov = pose_cov;
1370 
1371  if(hyps[hyp_count].weight > max_weight)
1372  {
1373  max_weight = hyps[hyp_count].weight;
1374  max_weight_hyp = hyp_count;
1375  }
1376  }
1377 
1378  if(max_weight > 0.0)
1379  {
1380  ROS_DEBUG("Max weight pose: %.3f %.3f %.3f",
1381  hyps[max_weight_hyp].pf_pose_mean.v[0],
1382  hyps[max_weight_hyp].pf_pose_mean.v[1],
1383  hyps[max_weight_hyp].pf_pose_mean.v[2]);
1384 
1385  /*
1386  puts("");
1387  pf_matrix_fprintf(hyps[max_weight_hyp].pf_pose_cov, stdout, "%6.3f");
1388  puts("");
1389  */
1390 
1391  geometry_msgs::PoseWithCovarianceStamped p;
1392  // Fill in the header
1393  p.header.frame_id = global_frame_id_;
1394  p.header.stamp = laser_scan->header.stamp;
1395  // Copy in the pose
1396  p.pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
1397  p.pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
1398 
1399  tf2::Quaternion q;
1400  q.setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]);
1401  tf2::convert(q, p.pose.pose.orientation);
1402  // Copy in the covariance, converting from 3-D to 6-D
1403  pf_sample_set_t* set = pf_->sets + pf_->current_set;
1404  for(int i=0; i<2; i++)
1405  {
1406  for(int j=0; j<2; j++)
1407  {
1408  // Report the overall filter covariance, rather than the
1409  // covariance for the highest-weight cluster
1410  //p.covariance[6*i+j] = hyps[max_weight_hyp].pf_pose_cov.m[i][j];
1411  p.pose.covariance[6*i+j] = set->cov.m[i][j];
1412  }
1413  }
1414  // Report the overall filter covariance, rather than the
1415  // covariance for the highest-weight cluster
1416  //p.covariance[6*5+5] = hyps[max_weight_hyp].pf_pose_cov.m[2][2];
1417  p.pose.covariance[6*5+5] = set->cov.m[2][2];
1418 
1419  /*
1420  printf("cov:\n");
1421  for(int i=0; i<6; i++)
1422  {
1423  for(int j=0; j<6; j++)
1424  printf("%6.3f ", p.covariance[6*i+j]);
1425  puts("");
1426  }
1427  */
1428 
1429  pose_pub_.publish(p);
1430  last_published_pose = p;
1431 
1432  ROS_DEBUG("New pose: %6.3f %6.3f %6.3f",
1433  hyps[max_weight_hyp].pf_pose_mean.v[0],
1434  hyps[max_weight_hyp].pf_pose_mean.v[1],
1435  hyps[max_weight_hyp].pf_pose_mean.v[2]);
1436 
1437  // subtracting base to odom from map to base and send map to odom instead
1438  geometry_msgs::PoseStamped odom_to_map;
1439  try
1440  {
1441  tf2::Quaternion q;
1442  q.setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]);
1443  tf2::Transform tmp_tf(q, tf2::Vector3(hyps[max_weight_hyp].pf_pose_mean.v[0],
1444  hyps[max_weight_hyp].pf_pose_mean.v[1],
1445  0.0));
1446 
1447  geometry_msgs::PoseStamped tmp_tf_stamped;
1448  tmp_tf_stamped.header.frame_id = base_frame_id_;
1449  tmp_tf_stamped.header.stamp = laser_scan->header.stamp;
1450  tf2::toMsg(tmp_tf.inverse(), tmp_tf_stamped.pose);
1451 
1452  this->tf_->transform(tmp_tf_stamped, odom_to_map, odom_frame_id_);
1453  }
1455  {
1456  ROS_DEBUG("Failed to subtract base to odom transform");
1457  return;
1458  }
1459 
1460  tf2::convert(odom_to_map.pose, latest_tf_);
1461  latest_tf_valid_ = true;
1462 
1463  if (tf_broadcast_ == true)
1464  {
1465  // We want to send a transform that is good up until a
1466  // tolerance time so that odom can be used
1467  ros::Time transform_expiration = (laser_scan->header.stamp +
1469  geometry_msgs::TransformStamped tmp_tf_stamped;
1470  tmp_tf_stamped.header.frame_id = global_frame_id_;
1471  tmp_tf_stamped.header.stamp = transform_expiration;
1472  tmp_tf_stamped.child_frame_id = odom_frame_id_;
1473  tf2::convert(latest_tf_.inverse(), tmp_tf_stamped.transform);
1474 
1475  this->tfb_->sendTransform(tmp_tf_stamped);
1476  sent_first_transform_ = true;
1477  }
1478  }
1479  else
1480  {
1481  ROS_ERROR("No pose!");
1482  }
1483  }
1484  else if(latest_tf_valid_)
1485  {
1486  if (tf_broadcast_ == true)
1487  {
1488  // Nothing changed, so we'll just republish the last transform, to keep
1489  // everybody happy.
1490  ros::Time transform_expiration = (laser_scan->header.stamp +
1492  geometry_msgs::TransformStamped tmp_tf_stamped;
1493  tmp_tf_stamped.header.frame_id = global_frame_id_;
1494  tmp_tf_stamped.header.stamp = transform_expiration;
1495  tmp_tf_stamped.child_frame_id = odom_frame_id_;
1496  tf2::convert(latest_tf_.inverse(), tmp_tf_stamped.transform);
1497  this->tfb_->sendTransform(tmp_tf_stamped);
1498  }
1499 
1500  // Is it time to save our last pose to the param server
1501  ros::Time now = ros::Time::now();
1502  if((save_pose_period.toSec() > 0.0) &&
1504  {
1505  this->savePoseToServer();
1506  save_pose_last_time = now;
1507  }
1508  }
1509 
1511 }
1512 
1513 void
1514 AmclNode::initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg)
1515 {
1517 }
1518 
1519 void
1520 AmclNode::handleInitialPoseMessage(const geometry_msgs::PoseWithCovarianceStamped& msg)
1521 {
1522  boost::recursive_mutex::scoped_lock prl(configuration_mutex_);
1523  if(msg.header.frame_id == "")
1524  {
1525  // This should be removed at some point
1526  ROS_WARN("Received initial pose with empty frame_id. You should always supply a frame_id.");
1527  }
1528  // We only accept initial pose estimates in the global frame, #5148.
1529  else if(stripSlash(msg.header.frame_id) != global_frame_id_)
1530  {
1531  ROS_WARN("Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"",
1532  stripSlash(msg.header.frame_id).c_str(),
1533  global_frame_id_.c_str());
1534  return;
1535  }
1536 
1537  // In case the client sent us a pose estimate in the past, integrate the
1538  // intervening odometric change.
1539  geometry_msgs::TransformStamped tx_odom;
1540  try
1541  {
1542  ros::Time now = ros::Time::now();
1543  // wait a little for the latest tf to become available
1544  tx_odom = tf_->lookupTransform(base_frame_id_, msg.header.stamp,
1547  }
1548  catch(tf2::TransformException e)
1549  {
1550  // If we've never sent a transform, then this is normal, because the
1551  // global_frame_id_ frame doesn't exist. We only care about in-time
1552  // transformation for on-the-move pose-setting, so ignoring this
1553  // startup condition doesn't really cost us anything.
1555  ROS_WARN("Failed to transform initial pose in time (%s)", e.what());
1556  tf2::convert(tf2::Transform::getIdentity(), tx_odom.transform);
1557  }
1558 
1559  tf2::Transform tx_odom_tf2;
1560  tf2::convert(tx_odom.transform, tx_odom_tf2);
1561  tf2::Transform pose_old, pose_new;
1562  tf2::convert(msg.pose.pose, pose_old);
1563  pose_new = pose_old * tx_odom_tf2;
1564 
1565  // Transform into the global frame
1566 
1567  ROS_INFO("Setting pose (%.6f): %.3f %.3f %.3f",
1568  ros::Time::now().toSec(),
1569  pose_new.getOrigin().x(),
1570  pose_new.getOrigin().y(),
1571  tf2::getYaw(pose_new.getRotation()));
1572  // Re-initialize the filter
1573  pf_vector_t pf_init_pose_mean = pf_vector_zero();
1574  pf_init_pose_mean.v[0] = pose_new.getOrigin().x();
1575  pf_init_pose_mean.v[1] = pose_new.getOrigin().y();
1576  pf_init_pose_mean.v[2] = tf2::getYaw(pose_new.getRotation());
1577  pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
1578  // Copy in the covariance, converting from 6-D to 3-D
1579  for(int i=0; i<2; i++)
1580  {
1581  for(int j=0; j<2; j++)
1582  {
1583  pf_init_pose_cov.m[i][j] = msg.pose.covariance[6*i+j];
1584  }
1585  }
1586  pf_init_pose_cov.m[2][2] = msg.pose.covariance[6*5+5];
1587 
1588  delete initial_pose_hyp_;
1589  initial_pose_hyp_ = new amcl_hyp_t();
1590  initial_pose_hyp_->pf_pose_mean = pf_init_pose_mean;
1591  initial_pose_hyp_->pf_pose_cov = pf_init_pose_cov;
1592  applyInitialPose();
1593 }
1594 
1600 void
1602 {
1603  boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
1604  if( initial_pose_hyp_ != NULL && map_ != NULL ) {
1606  pf_init_ = false;
1607 
1608  delete initial_pose_hyp_;
1609  initial_pose_hyp_ = NULL;
1610  }
1611 }
1612 
1613 void
1615 {
1616  double std_x = sqrt(last_published_pose.pose.covariance[6*0+0]);
1617  double std_y = sqrt(last_published_pose.pose.covariance[6*1+1]);
1618  double std_yaw = sqrt(last_published_pose.pose.covariance[6*5+5]);
1619 
1620  diagnostic_status.add("std_x", std_x);
1621  diagnostic_status.add("std_y", std_y);
1622  diagnostic_status.add("std_yaw", std_yaw);
1623  diagnostic_status.add("std_warn_level_x", std_warn_level_x_);
1624  diagnostic_status.add("std_warn_level_y", std_warn_level_y_);
1625  diagnostic_status.add("std_warn_level_yaw", std_warn_level_yaw_);
1626 
1627  if (std_x > std_warn_level_x_ || std_y > std_warn_level_y_ || std_yaw > std_warn_level_yaw_)
1628  {
1629  diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Too large");
1630  }
1631  else
1632  {
1633  diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::OK, "OK");
1634  }
1635 }
d
ros::ServiceServer set_map_srv_
Definition: amcl_node.cpp:255
msg
bool globalLocalizationCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: amcl_node.cpp:1083
bool tf_broadcast_
Definition: amcl_node.cpp:286
#define MAP_GXWX(map, x)
Definition: map.h:137
double beam_skip_distance_
Definition: amcl_node.cpp:280
static pf_vector_t uniformPoseGenerator(void *arg)
Definition: amcl_node.cpp:1045
ros::Time last_laser_received_ts_
Definition: amcl_node.cpp:291
int min_particles_
Definition: amcl_node.cpp:274
ros::Publisher pose_pub_
Definition: amcl_node.cpp:251
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
double beam_skip_error_threshold_
Definition: amcl_node.cpp:280
boost::shared_ptr< AmclNode > amcl_node_ptr
Definition: amcl_node.cpp:302
Chain d2()
double pop_err
Definition: pf.h:118
bool first_map_only_
Definition: amcl_node.cpp:195
ROSCPP_DECL void start()
double v[3]
Definition: pf_vector.h:40
std::string global_frame_id_
Definition: amcl_node.cpp:192
dynamic_reconfigure::Server< amcl::AMCLConfig > * dsrv_
Definition: amcl_node.cpp:270
void applyInitialPose()
Definition: amcl_node.cpp:1601
void open(std::string const &filename, uint32_t mode=bagmode::Read)
ros::Subscriber initial_pose_sub_
Definition: amcl_node.cpp:210
std::map< std::string, int > frame_to_laser_
Definition: amcl_node.cpp:213
Definition: pf.h:112
#define MAP_VALID(map, i, j)
Definition: map.h:141
map_cell_t * cells
Definition: map.h:73
double pf_err_
Definition: amcl_node.cpp:217
void summary(unsigned char lvl, const std::string s)
ros::Publisher particlecloud_pub_
Definition: amcl_node.cpp:252
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double laser_max_range_
Definition: amcl_node.cpp:224
geometry_msgs::PoseStamped latest_odom_pose_
Definition: amcl_node.cpp:188
pf_vector_t(* pf_init_model_fn_t)(void *init_data)
Definition: pf.h:45
int resample_count_
Definition: amcl_node.cpp:222
tf2::Transform latest_tf_
Definition: amcl_node.cpp:156
Definition: map.h:46
void setHardwareID(const std::string &hwid)
void checkLaserReceived(const ros::TimerEvent &event)
Definition: amcl_node.cpp:830
bool call(const std::string &service_name, MReq &req, MRes &res)
std::string base_frame_id_
Definition: amcl_node.cpp:191
double std_warn_level_yaw_
Definition: amcl_node.cpp:263
void SetModelBeam(double z_hit, double z_short, double z_max, double z_rand, double sigma_hit, double lambda_short, double chi_outlier)
Definition: amcl_laser.cpp:67
static double normalize(double z)
Definition: amcl_node.cpp:98
void mapReceived(const nav_msgs::OccupancyGridConstPtr &msg)
Definition: amcl_node.cpp:860
pf_vector_t pf_vector_zero()
Definition: pf_vector.c:38
double beam_skip_threshold_
Definition: amcl_node.cpp:280
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
pf_t * pf_alloc(int min_samples, int max_samples, double alpha_slow, double alpha_fast, pf_init_model_fn_t random_pose_fn, void *random_pose_data)
Definition: pf.c:46
int size_y
Definition: map.h:70
int max_particles_
Definition: amcl_node.cpp:274
laser_model_t
Definition: amcl_laser.h:38
static double drand48(void)
#define MAP_INDEX(map, i, j)
Definition: map.h:144
void add(const std::string &name, TaskFunction f)
double origin_x
Definition: map.h:64
double z_max_
Definition: amcl_node.cpp:277
double alpha4_
Definition: amcl_node.cpp:275
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
double z_short_
Definition: amcl_node.cpp:277
ros::Time last_cloud_pub_time
Definition: amcl_node.cpp:233
#define MAP_WXGX(map, i)
Definition: map.h:133
int resample_interval_
Definition: amcl_node.cpp:221
void updatePoseFromServer()
Definition: amcl_node.cpp:787
int main(int argc, char **argv)
Definition: amcl_node.cpp:312
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
double scale
Definition: map.h:67
#define MAP_GYWY(map, y)
Definition: map.h:138
void sigintHandler(int sig)
Definition: amcl_node.cpp:304
virtual bool UpdateAction(pf_t *pf, AMCLSensorData *data)
Definition: amcl_odom.cpp:113
odom_model_t odom_model_type_
Definition: amcl_node.cpp:282
#define ROS_WARN(...)
void savePoseToServer()
Definition: amcl_node.cpp:763
void close()
double alpha3_
Definition: amcl_node.cpp:275
#define MAP_WYGY(map, j)
Definition: map.h:134
double alpha1_
Definition: amcl_node.cpp:275
int size_x
Definition: map.h:70
Transform inverse() const
double init_pose_[3]
Definition: amcl_node.cpp:283
void SetModel(odom_model_t type, double alpha1, double alpha2, double alpha3, double alpha4, double alpha5=0)
Definition: amcl_odom.cpp:96
void pf_init(pf_t *pf, pf_vector_t mean, pf_matrix_t cov)
Definition: pf.c:136
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::vector< AMCLLaser *> lasers_
Definition: amcl_node.cpp:211
void getEulerYPR(tf2Scalar &yaw, tf2Scalar &pitch, tf2Scalar &roll, unsigned int solution_number=1) const
int pf_get_cluster_stats(pf_t *pf, int cluster, double *weight, pf_vector_t *mean, pf_matrix_t *cov)
Definition: pf.c:731
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
bool selective_resampling_
Definition: amcl_node.cpp:287
pf_vector_t pf_pose_mean
Definition: amcl_node.cpp:90
void add(const MEvent &evt)
AMCLLaser * laser_
Definition: amcl_node.cpp:230
ros::Subscriber initial_pose_sub_old_
Definition: amcl_node.cpp:256
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
double origin_y
Definition: map.h:64
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::ServiceServer nomotion_update_srv_
Definition: amcl_node.cpp:254
void publish(const boost::shared_ptr< M > &message) const
int occ_state
Definition: map.h:49
std::string odom_frame_id_
Definition: amcl_node.cpp:185
double z_hit_
Definition: amcl_node.cpp:277
double pop_z
Definition: pf.h:118
bool first_reconfigure_call_
Definition: amcl_node.cpp:267
Definition: map.h:61
void requestMap()
Definition: amcl_node.cpp:842
Duration & fromSec(double t)
void handleMapMessage(const nav_msgs::OccupancyGrid &msg)
Definition: amcl_node.cpp:872
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
int current_set
Definition: pf.h:125
std::vector< bool > lasers_update_
Definition: amcl_node.cpp:212
double alpha2_
Definition: amcl_node.cpp:275
AMCLSensor * sensor
Definition: amcl_sensor.h:88
#define ROS_INFO(...)
double alpha5_
Definition: amcl_node.cpp:275
static double angle_diff(double a, double b)
Definition: amcl_node.cpp:103
static std::vector< std::pair< int, int > > free_space_indices
Definition: amcl_node.cpp:163
double m[3][3]
Definition: pf_vector.h:47
ros::Duration cloud_pub_interval
Definition: amcl_node.cpp:232
double(* ranges)[2]
Definition: amcl_laser.h:54
double sigma_hit_
Definition: amcl_node.cpp:277
pf_matrix_t pf_matrix_zero()
Definition: pf_vector.c:134
ROSCPP_DECL bool ok()
pf_matrix_t pf_pose_cov
Definition: amcl_node.cpp:93
static const Transform & getIdentity()
void laserReceived(const sensor_msgs::LaserScanConstPtr &laser_scan)
Definition: amcl_node.cpp:1119
ros::Subscriber map_sub_
Definition: amcl_node.cpp:257
bool m_force_update
Definition: amcl_node.cpp:227
AMCLOdom * odom_
Definition: amcl_node.cpp:229
amcl_hyp_t * initial_pose_hyp_
Definition: amcl_node.cpp:265
void standardDeviationDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &diagnostic_status)
Definition: amcl_node.cpp:1614
std::shared_ptr< tf2_ros::TransformListener > tfl_
Definition: amcl_node.cpp:151
pf_vector_t pose
Definition: amcl_odom.h:50
std::shared_ptr< tf2_ros::TransformBroadcaster > tfb_
Definition: amcl_node.cpp:150
ros::Duration transform_tolerance_
Definition: amcl_node.cpp:247
ros::Time save_pose_last_time
Definition: amcl_node.cpp:198
void pf_set_selective_resampling(pf_t *pf, int selective_resampling)
Definition: pf.c:689
map_t * convertMap(const nav_msgs::OccupancyGrid &map_msg)
Definition: amcl_node.cpp:982
std::shared_ptr< tf2_ros::Buffer > tf_
Definition: amcl_node.cpp:152
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep() const
void SetModelLikelihoodField(double z_hit, double z_rand, double sigma_hit, double max_occ_dist)
Definition: amcl_laser.cpp:86
ROSCPP_DECL void spin()
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
bool sent_first_transform_
Definition: amcl_node.cpp:154
void pf_init_model(pf_t *pf, pf_init_model_fn_t init_fn, void *init_data)
Definition: pf.c:178
ros::WallDuration bag_scan_period_
Definition: amcl_node.cpp:236
static const std::string scan_topic_
Definition: amcl_node.cpp:118
#define ROS_WARN_STREAM(args)
bool first_map_received_
Definition: amcl_node.cpp:266
bool hasParam(const std::string &key) const
double alpha_slow_
Definition: amcl_node.cpp:276
boost::shared_ptr< T > instantiate() const
double getYaw(const A &a)
map_t * map_
Definition: amcl_node.cpp:203
ros::NodeHandle nh_
Definition: amcl_node.cpp:249
ros::ServiceServer global_loc_srv_
Definition: amcl_node.cpp:253
char * mapdata
Definition: amcl_node.cpp:204
B toMsg(const A &a)
ros::Timer check_laser_timer_
Definition: amcl_node.cpp:272
geometry_msgs::PoseWithCovarianceStamped last_published_pose
Definition: amcl_node.cpp:201
bool use_map_topic_
Definition: amcl_node.cpp:194
double lambda_short_
Definition: amcl_node.cpp:277
boost::recursive_mutex configuration_mutex_
Definition: amcl_node.cpp:269
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
static WallTime now()
void pf_update_resample(pf_t *pf)
Definition: pf.c:363
void map_free(map_t *map)
Definition: map.c:61
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
pf_t * pf_
Definition: amcl_node.cpp:216
void freeMapDependentMemory()
Definition: amcl_node.cpp:961
diagnostic_updater::Updater diagnosic_updater_
Definition: amcl_node.cpp:259
ros::Duration gui_publish_period
Definition: amcl_node.cpp:197
laser_model_t laser_model_type_
Definition: amcl_node.cpp:285
amcl::AMCLConfig default_config_
Definition: amcl_node.cpp:271
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
ros::Duration save_pose_period
Definition: amcl_node.cpp:199
double weight
Definition: amcl_node.cpp:87
bool nomotionUpdateCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: amcl_node.cpp:1100
Quaternion getRotation() const
odom_model_t
Definition: amcl_odom.h:38
static Time now()
bool do_beamskip_
Definition: amcl_node.cpp:279
double d_thresh_
Definition: amcl_node.cpp:220
void convert(const A &a, B &b)
ROSCPP_DECL void shutdown()
double std_warn_level_x_
Definition: amcl_node.cpp:261
void reconfigureCB(amcl::AMCLConfig &config, uint32_t level)
Definition: amcl_node.cpp:513
double pf_z_
Definition: amcl_node.cpp:217
void runFromBag(const std::string &in_bag_fn, bool trigger_global_localization=false)
Uses TF and LaserScan messages from bag file to drive AMCL instead.
Definition: amcl_node.cpp:670
ros::NodeHandle private_nh_
Definition: amcl_node.cpp:250
void add(const std::string &key, const T &val)
map_t * map_alloc(void)
Definition: map.c:38
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
bool pf_init_
Definition: amcl_node.cpp:218
message_filters::Subscriber< sensor_msgs::LaserScan > * laser_scan_sub_
Definition: amcl_node.cpp:208
bool sleep() const
void handleInitialPoseMessage(const geometry_msgs::PoseWithCovarianceStamped &msg)
Definition: amcl_node.cpp:1520
std::string const & getTopic() const
#define ROS_ASSERT(cond)
pf_sample_set_t sets[2]
Definition: pf.h:126
void pf_free(pf_t *pf)
Definition: pf.c:118
bool latest_tf_valid_
Definition: amcl_node.cpp:157
ros::Duration laser_check_interval_
Definition: amcl_node.cpp:292
double std_warn_level_y_
Definition: amcl_node.cpp:262
int cluster_count
Definition: pf.h:100
double resolution
Definition: amcl_node.cpp:206
#define ROS_ERROR(...)
std::string stripSlash(const std::string &in)
Definition: amcl_node.cpp:124
void SetModelLikelihoodFieldProb(double z_hit, double z_rand, double sigma_hit, double max_occ_dist, bool do_beamskip, double beam_skip_distance, double beam_skip_threshold, double beam_skip_error_threshold)
Definition: amcl_laser.cpp:100
tf2_ros::MessageFilter< sensor_msgs::LaserScan > * laser_scan_filter_
Definition: amcl_node.cpp:209
bool getOdomPose(geometry_msgs::PoseStamped &pose, double &x, double &y, double &yaw, const ros::Time &t, const std::string &f)
Definition: amcl_node.cpp:1018
double laser_min_range_
Definition: amcl_node.cpp:223
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
double laser_likelihood_max_dist_
Definition: amcl_node.cpp:281
pf_vector_t delta
Definition: amcl_odom.h:53
pf_vector_t pf_odom_pose_
Definition: amcl_node.cpp:219
double alpha_fast_
Definition: amcl_node.cpp:276
int max_beams_
Definition: amcl_node.cpp:274
bool setMapCallback(nav_msgs::SetMap::Request &req, nav_msgs::SetMap::Response &res)
Definition: amcl_node.cpp:1109
double a_thresh_
Definition: amcl_node.cpp:220
void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
Definition: amcl_node.cpp:1514
double init_cov_[3]
Definition: amcl_node.cpp:284
Connection registerCallback(const C &callback)
#define ROS_DEBUG(...)
double z_rand_
Definition: amcl_node.cpp:277


amcl
Author(s): Brian P. Gerkey, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:00