amcl_node.cpp
Go to the documentation of this file.
00001 /*
00002  *  Copyright (c) 2008, Willow Garage, Inc.
00003  *  All rights reserved.
00004  *
00005  *  This library is free software; you can redistribute it and/or
00006  *  modify it under the terms of the GNU Lesser General Public
00007  *  License as published by the Free Software Foundation; either
00008  *  version 2.1 of the License, or (at your option) any later version.
00009  *
00010  *  This library is distributed in the hope that it will be useful,
00011  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00012  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00013  *  Lesser General Public License for more details.
00014  *
00015  *  You should have received a copy of the GNU Lesser General Public
00016  *  License along with this library; if not, write to the Free Software
00017  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00018  *
00019  */
00020 
00021 /* Author: Brian Gerkey */
00022 
00023 #include <algorithm>
00024 #include <vector>
00025 #include <map>
00026 #include <cmath>
00027 
00028 #include <boost/bind.hpp>
00029 #include <boost/thread/mutex.hpp>
00030 
00031 #include "map/map.h"
00032 #include "pf/pf.h"
00033 #include "sensors/amcl_odom.h"
00034 #include "sensors/amcl_laser.h"
00035 
00036 #include "ros/assert.h"
00037 
00038 // roscpp
00039 #include "ros/ros.h"
00040 
00041 // Messages that I need
00042 #include "sensor_msgs/LaserScan.h"
00043 #include "geometry_msgs/PoseWithCovarianceStamped.h"
00044 #include "geometry_msgs/PoseArray.h"
00045 #include "geometry_msgs/Pose.h"
00046 #include "nav_msgs/GetMap.h"
00047 #include "std_srvs/Empty.h"
00048 
00049 // For transform support
00050 #include "tf/transform_broadcaster.h"
00051 #include "tf/transform_listener.h"
00052 #include "tf/message_filter.h"
00053 #include "tf/tf.h"
00054 #include "message_filters/subscriber.h"
00055 
00056 // Dynamic_reconfigure
00057 #include "dynamic_reconfigure/server.h"
00058 #include "amcl/AMCLConfig.h"
00059 
00060 #define NEW_UNIFORM_SAMPLING 1
00061 
00062 using namespace amcl;
00063 
00064 // Pose hypothesis
00065 typedef struct
00066 {
00067   // Total weight (weights sum to 1)
00068   double weight;
00069 
00070   // Mean of pose esimate
00071   pf_vector_t pf_pose_mean;
00072 
00073   // Covariance of pose estimate
00074   pf_matrix_t pf_pose_cov;
00075 
00076 } amcl_hyp_t;
00077 
00078 static double
00079 normalize(double z)
00080 {
00081   return atan2(sin(z),cos(z));
00082 }
00083 static double
00084 angle_diff(double a, double b)
00085 {
00086   double d1, d2;
00087   a = normalize(a);
00088   b = normalize(b);
00089   d1 = a-b;
00090   d2 = 2*M_PI - fabs(d1);
00091   if(d1 > 0)
00092     d2 *= -1.0;
00093   if(fabs(d1) < fabs(d2))
00094     return(d1);
00095   else
00096     return(d2);
00097 }
00098 
00099 static const std::string scan_topic_ = "scan";
00100 
00101 class AmclNode
00102 {
00103   public:
00104     AmclNode();
00105     ~AmclNode();
00106 
00107     int process();
00108 
00109   private:
00110     tf::TransformBroadcaster* tfb_;
00111     tf::TransformListener* tf_;
00112 
00113     bool sent_first_transform_;
00114 
00115     tf::Transform latest_tf_;
00116     bool latest_tf_valid_;
00117 
00118     // Pose-generating function used to uniformly distribute particles over
00119     // the map
00120     static pf_vector_t uniformPoseGenerator(void* arg);
00121 #if NEW_UNIFORM_SAMPLING
00122     static std::vector<std::pair<int,int> > free_space_indices;
00123 #endif
00124     // Callbacks
00125     bool globalLocalizationCallback(std_srvs::Empty::Request& req,
00126                                     std_srvs::Empty::Response& res);
00127     bool nomotionUpdateCallback(std_srvs::Empty::Request& req,
00128                                     std_srvs::Empty::Response& res);
00129 
00130     void laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan);
00131     void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
00132     void mapReceived(const nav_msgs::OccupancyGridConstPtr& msg);
00133 
00134     void handleMapMessage(const nav_msgs::OccupancyGrid& msg);
00135     void freeMapDependentMemory();
00136     map_t* convertMap( const nav_msgs::OccupancyGrid& map_msg );
00137     void applyInitialPose();
00138 
00139     double getYaw(tf::Pose& t);
00140 
00141     //parameter for what odom to use
00142     std::string odom_frame_id_;
00143     //parameter for what base to use
00144     std::string base_frame_id_;
00145     std::string global_frame_id_;
00146 
00147     bool use_map_topic_;
00148     bool first_map_only_;
00149 
00150     ros::Duration gui_publish_period;
00151     ros::Time save_pose_last_time;
00152     ros::Duration save_pose_period;
00153 
00154     geometry_msgs::PoseWithCovarianceStamped last_published_pose;
00155 
00156     map_t* map_;
00157     char* mapdata;
00158     int sx, sy;
00159     double resolution;
00160 
00161     message_filters::Subscriber<sensor_msgs::LaserScan>* laser_scan_sub_;
00162     tf::MessageFilter<sensor_msgs::LaserScan>* laser_scan_filter_;
00163     ros::Subscriber initial_pose_sub_;
00164     std::vector< AMCLLaser* > lasers_;
00165     std::vector< bool > lasers_update_;
00166     std::map< std::string, int > frame_to_laser_;
00167 
00168     // Particle filter
00169     pf_t *pf_;
00170     double pf_err_, pf_z_;
00171     bool pf_init_;
00172     pf_vector_t pf_odom_pose_;
00173     double d_thresh_, a_thresh_;
00174     int resample_interval_;
00175     int resample_count_;
00176     double laser_min_range_;
00177     double laser_max_range_;
00178 
00179     //Nomotion update control
00180     bool m_force_update;  // used to temporarily let amcl update samples even when no motion occurs...
00181 
00182     AMCLOdom* odom_;
00183     AMCLLaser* laser_;
00184 
00185     ros::Duration cloud_pub_interval;
00186     ros::Time last_cloud_pub_time;
00187 
00188     void requestMap();
00189 
00190     // Helper to get odometric pose from transform system
00191     bool getOdomPose(tf::Stamped<tf::Pose>& pose,
00192                      double& x, double& y, double& yaw,
00193                      const ros::Time& t, const std::string& f);
00194 
00195     //time for tolerance on the published transform,
00196     //basically defines how long a map->odom transform is good for
00197     ros::Duration transform_tolerance_;
00198 
00199     ros::NodeHandle nh_;
00200     ros::NodeHandle private_nh_;
00201     ros::Publisher pose_pub_;
00202     ros::Publisher particlecloud_pub_;
00203     ros::ServiceServer global_loc_srv_;
00204     ros::ServiceServer nomotion_update_srv_; //to let amcl update samples without requiring motion
00205     ros::Subscriber initial_pose_sub_old_;
00206     ros::Subscriber map_sub_;
00207 
00208     amcl_hyp_t* initial_pose_hyp_;
00209     bool first_map_received_;
00210     bool first_reconfigure_call_;
00211 
00212     boost::recursive_mutex configuration_mutex_;
00213     dynamic_reconfigure::Server<amcl::AMCLConfig> *dsrv_;
00214     amcl::AMCLConfig default_config_;
00215     ros::Timer check_laser_timer_;
00216 
00217     int max_beams_, min_particles_, max_particles_;
00218     double alpha1_, alpha2_, alpha3_, alpha4_, alpha5_;
00219     double alpha_slow_, alpha_fast_;
00220     double z_hit_, z_short_, z_max_, z_rand_, sigma_hit_, lambda_short_;
00221     double laser_likelihood_max_dist_;
00222     odom_model_t odom_model_type_;
00223     double init_pose_[3];
00224     double init_cov_[3];
00225     laser_model_t laser_model_type_;
00226     bool tf_broadcast_;
00227 
00228     void reconfigureCB(amcl::AMCLConfig &config, uint32_t level);
00229 
00230     ros::Time last_laser_received_ts_;
00231     ros::Duration laser_check_interval_;
00232     void checkLaserReceived(const ros::TimerEvent& event);
00233 };
00234 
00235 std::vector<std::pair<int,int> > AmclNode::free_space_indices;
00236 
00237 #define USAGE "USAGE: amcl"
00238 
00239 int
00240 main(int argc, char** argv)
00241 {
00242   ros::init(argc, argv, "amcl");
00243   ros::NodeHandle nh;
00244 
00245   AmclNode an;
00246 
00247   ros::spin();
00248 
00249   // To quote Morgan, Hooray!
00250   return(0);
00251 }
00252 
00253 AmclNode::AmclNode() :
00254         sent_first_transform_(false),
00255         latest_tf_valid_(false),
00256         map_(NULL),
00257         pf_(NULL),
00258         resample_count_(0),
00259         odom_(NULL),
00260         laser_(NULL),
00261               private_nh_("~"),
00262         initial_pose_hyp_(NULL),
00263         first_map_received_(false),
00264         first_reconfigure_call_(true)
00265 {
00266   boost::recursive_mutex::scoped_lock l(configuration_mutex_);
00267 
00268   // Grab params off the param server
00269   private_nh_.param("use_map_topic", use_map_topic_, false);
00270   private_nh_.param("first_map_only", first_map_only_, false);
00271 
00272   double tmp;
00273   private_nh_.param("gui_publish_rate", tmp, -1.0);
00274   gui_publish_period = ros::Duration(1.0/tmp);
00275   private_nh_.param("save_pose_rate", tmp, 0.5);
00276   save_pose_period = ros::Duration(1.0/tmp);
00277 
00278   private_nh_.param("laser_min_range", laser_min_range_, -1.0);
00279   private_nh_.param("laser_max_range", laser_max_range_, -1.0);
00280   private_nh_.param("laser_max_beams", max_beams_, 30);
00281   private_nh_.param("min_particles", min_particles_, 100);
00282   private_nh_.param("max_particles", max_particles_, 5000);
00283   private_nh_.param("kld_err", pf_err_, 0.01);
00284   private_nh_.param("kld_z", pf_z_, 0.99);
00285   private_nh_.param("odom_alpha1", alpha1_, 0.2);
00286   private_nh_.param("odom_alpha2", alpha2_, 0.2);
00287   private_nh_.param("odom_alpha3", alpha3_, 0.2);
00288   private_nh_.param("odom_alpha4", alpha4_, 0.2);
00289   private_nh_.param("odom_alpha5", alpha5_, 0.2);
00290 
00291   private_nh_.param("laser_z_hit", z_hit_, 0.95);
00292   private_nh_.param("laser_z_short", z_short_, 0.1);
00293   private_nh_.param("laser_z_max", z_max_, 0.05);
00294   private_nh_.param("laser_z_rand", z_rand_, 0.05);
00295   private_nh_.param("laser_sigma_hit", sigma_hit_, 0.2);
00296   private_nh_.param("laser_lambda_short", lambda_short_, 0.1);
00297   private_nh_.param("laser_likelihood_max_dist", laser_likelihood_max_dist_, 2.0);
00298   std::string tmp_model_type;
00299   private_nh_.param("laser_model_type", tmp_model_type, std::string("likelihood_field"));
00300   if(tmp_model_type == "beam")
00301     laser_model_type_ = LASER_MODEL_BEAM;
00302   else if(tmp_model_type == "likelihood_field")
00303     laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD;
00304   else
00305   {
00306     ROS_WARN("Unknown laser model type \"%s\"; defaulting to likelihood_field model",
00307              tmp_model_type.c_str());
00308     laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD;
00309   }
00310 
00311   private_nh_.param("odom_model_type", tmp_model_type, std::string("diff"));
00312   if(tmp_model_type == "diff")
00313     odom_model_type_ = ODOM_MODEL_DIFF;
00314   else if(tmp_model_type == "omni")
00315     odom_model_type_ = ODOM_MODEL_OMNI;
00316   else
00317   {
00318     ROS_WARN("Unknown odom model type \"%s\"; defaulting to diff model",
00319              tmp_model_type.c_str());
00320     odom_model_type_ = ODOM_MODEL_DIFF;
00321   }
00322 
00323   private_nh_.param("update_min_d", d_thresh_, 0.2);
00324   private_nh_.param("update_min_a", a_thresh_, M_PI/6.0);
00325   private_nh_.param("odom_frame_id", odom_frame_id_, std::string("odom"));
00326   private_nh_.param("base_frame_id", base_frame_id_, std::string("base_link"));
00327   private_nh_.param("global_frame_id", global_frame_id_, std::string("map"));
00328   private_nh_.param("resample_interval", resample_interval_, 2);
00329   double tmp_tol;
00330   private_nh_.param("transform_tolerance", tmp_tol, 0.1);
00331   private_nh_.param("recovery_alpha_slow", alpha_slow_, 0.001);
00332   private_nh_.param("recovery_alpha_fast", alpha_fast_, 0.1);
00333   private_nh_.param("tf_broadcast", tf_broadcast_, true);
00334 
00335   transform_tolerance_.fromSec(tmp_tol);
00336 
00337   init_pose_[0] = 0.0;
00338   init_pose_[1] = 0.0;
00339   init_pose_[2] = 0.0;
00340   init_cov_[0] = 0.5 * 0.5;
00341   init_cov_[1] = 0.5 * 0.5;
00342   init_cov_[2] = (M_PI/12.0) * (M_PI/12.0);
00343   // Check for NAN on input from param server, #5239
00344   double tmp_pos;
00345   private_nh_.param("initial_pose_x", tmp_pos, init_pose_[0]);
00346   if(!std::isnan(tmp_pos))
00347     init_pose_[0] = tmp_pos;
00348   else 
00349     ROS_WARN("ignoring NAN in initial pose X position");
00350   private_nh_.param("initial_pose_y", tmp_pos, init_pose_[1]);
00351   if(!std::isnan(tmp_pos))
00352     init_pose_[1] = tmp_pos;
00353   else
00354     ROS_WARN("ignoring NAN in initial pose Y position");
00355   private_nh_.param("initial_pose_a", tmp_pos, init_pose_[2]);
00356   if(!std::isnan(tmp_pos))
00357     init_pose_[2] = tmp_pos;
00358   else
00359     ROS_WARN("ignoring NAN in initial pose Yaw");
00360   private_nh_.param("initial_cov_xx", tmp_pos, init_cov_[0]);
00361   if(!std::isnan(tmp_pos))
00362     init_cov_[0] =tmp_pos;
00363   else
00364     ROS_WARN("ignoring NAN in initial covariance XX");
00365   private_nh_.param("initial_cov_yy", tmp_pos, init_cov_[1]);
00366   if(!std::isnan(tmp_pos))
00367     init_cov_[1] = tmp_pos;
00368   else
00369     ROS_WARN("ignoring NAN in initial covariance YY");
00370   private_nh_.param("initial_cov_aa", tmp_pos, init_cov_[2]);
00371   if(!std::isnan(tmp_pos))
00372     init_cov_[2] = tmp_pos;
00373   else
00374     ROS_WARN("ignoring NAN in initial covariance AA");
00375 
00376   cloud_pub_interval.fromSec(1.0);
00377   tfb_ = new tf::TransformBroadcaster();
00378   tf_ = new tf::TransformListener();
00379 
00380   pose_pub_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("amcl_pose", 2);
00381   particlecloud_pub_ = nh_.advertise<geometry_msgs::PoseArray>("particlecloud", 2);
00382   global_loc_srv_ = nh_.advertiseService("global_localization", 
00383                                          &AmclNode::globalLocalizationCallback,
00384                                          this);
00385   nomotion_update_srv_= nh_.advertiseService("request_nomotion_update", &AmclNode::nomotionUpdateCallback, this);
00386 
00387   laser_scan_sub_ = new message_filters::Subscriber<sensor_msgs::LaserScan>(nh_, scan_topic_, 100);
00388   laser_scan_filter_ = 
00389           new tf::MessageFilter<sensor_msgs::LaserScan>(*laser_scan_sub_, 
00390                                                         *tf_, 
00391                                                         odom_frame_id_, 
00392                                                         100);
00393   laser_scan_filter_->registerCallback(boost::bind(&AmclNode::laserReceived,
00394                                                    this, _1));
00395   initial_pose_sub_ = nh_.subscribe("initialpose", 2, &AmclNode::initialPoseReceived, this);
00396 
00397   if(use_map_topic_) {
00398     map_sub_ = nh_.subscribe("map", 1, &AmclNode::mapReceived, this);
00399     ROS_INFO("Subscribed to map topic.");
00400   } else {
00401     requestMap();
00402   }
00403   m_force_update = false;
00404 
00405   dsrv_ = new dynamic_reconfigure::Server<amcl::AMCLConfig>(ros::NodeHandle("~"));
00406   dynamic_reconfigure::Server<amcl::AMCLConfig>::CallbackType cb = boost::bind(&AmclNode::reconfigureCB, this, _1, _2);
00407   dsrv_->setCallback(cb);
00408 
00409   // 15s timer to warn on lack of receipt of laser scans, #5209
00410   laser_check_interval_ = ros::Duration(15.0);
00411   check_laser_timer_ = nh_.createTimer(laser_check_interval_, 
00412                                        boost::bind(&AmclNode::checkLaserReceived, this, _1));
00413 }
00414 
00415 void AmclNode::reconfigureCB(AMCLConfig &config, uint32_t level)
00416 {
00417   boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
00418 
00419   //we don't want to do anything on the first call
00420   //which corresponds to startup
00421   if(first_reconfigure_call_)
00422   {
00423     first_reconfigure_call_ = false;
00424     default_config_ = config;
00425     return;
00426   }
00427 
00428   if(config.restore_defaults) {
00429     config = default_config_;
00430     //avoid looping
00431     config.restore_defaults = false;
00432   }
00433 
00434   d_thresh_ = config.update_min_d;
00435   a_thresh_ = config.update_min_a;
00436 
00437   resample_interval_ = config.resample_interval;
00438 
00439   laser_min_range_ = config.laser_min_range;
00440   laser_max_range_ = config.laser_max_range;
00441 
00442   gui_publish_period = ros::Duration(1.0/config.gui_publish_rate);
00443   save_pose_period = ros::Duration(1.0/config.save_pose_rate);
00444 
00445   transform_tolerance_.fromSec(config.transform_tolerance);
00446 
00447   max_beams_ = config.laser_max_beams;
00448   alpha1_ = config.odom_alpha1;
00449   alpha2_ = config.odom_alpha2;
00450   alpha3_ = config.odom_alpha3;
00451   alpha4_ = config.odom_alpha4;
00452   alpha5_ = config.odom_alpha5;
00453 
00454   z_hit_ = config.laser_z_hit;
00455   z_short_ = config.laser_z_short;
00456   z_max_ = config.laser_z_max;
00457   z_rand_ = config.laser_z_rand;
00458   sigma_hit_ = config.laser_sigma_hit;
00459   lambda_short_ = config.laser_lambda_short;
00460   laser_likelihood_max_dist_ = config.laser_likelihood_max_dist;
00461 
00462   if(config.laser_model_type == "beam")
00463     laser_model_type_ = LASER_MODEL_BEAM;
00464   else if(config.laser_model_type == "likelihood_field")
00465     laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD;
00466 
00467   if(config.odom_model_type == "diff")
00468     odom_model_type_ = ODOM_MODEL_DIFF;
00469   else if(config.odom_model_type == "omni")
00470     odom_model_type_ = ODOM_MODEL_OMNI;
00471 
00472   if(config.min_particles > config.max_particles)
00473   {
00474     ROS_WARN("You've set min_particles to be less than max particles, this isn't allowed so they'll be set to be equal.");
00475     config.max_particles = config.min_particles;
00476   }
00477 
00478   min_particles_ = config.min_particles;
00479   max_particles_ = config.max_particles;
00480   alpha_slow_ = config.recovery_alpha_slow;
00481   alpha_fast_ = config.recovery_alpha_fast;
00482   tf_broadcast_ = config.tf_broadcast;
00483 
00484   pf_ = pf_alloc(min_particles_, max_particles_,
00485                  alpha_slow_, alpha_fast_,
00486                  (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
00487                  (void *)map_);
00488   pf_err_ = config.kld_err; 
00489   pf_z_ = config.kld_z; 
00490   pf_->pop_err = pf_err_;
00491   pf_->pop_z = pf_z_;
00492 
00493   // Initialize the filter
00494   pf_vector_t pf_init_pose_mean = pf_vector_zero();
00495   pf_init_pose_mean.v[0] = last_published_pose.pose.pose.position.x;
00496   pf_init_pose_mean.v[1] = last_published_pose.pose.pose.position.y;
00497   pf_init_pose_mean.v[2] = tf::getYaw(last_published_pose.pose.pose.orientation);
00498   pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
00499   pf_init_pose_cov.m[0][0] = last_published_pose.pose.covariance[6*0+0];
00500   pf_init_pose_cov.m[1][1] = last_published_pose.pose.covariance[6*1+1];
00501   pf_init_pose_cov.m[2][2] = last_published_pose.pose.covariance[6*5+5];
00502   pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
00503   pf_init_ = false;
00504 
00505   // Instantiate the sensor objects
00506   // Odometry
00507   delete odom_;
00508   odom_ = new AMCLOdom();
00509   ROS_ASSERT(odom_);
00510   if(odom_model_type_ == ODOM_MODEL_OMNI)
00511     odom_->SetModelOmni(alpha1_, alpha2_, alpha3_, alpha4_, alpha5_);
00512   else
00513     odom_->SetModelDiff(alpha1_, alpha2_, alpha3_, alpha4_);
00514   // Laser
00515   delete laser_;
00516   laser_ = new AMCLLaser(max_beams_, map_);
00517   ROS_ASSERT(laser_);
00518   if(laser_model_type_ == LASER_MODEL_BEAM)
00519     laser_->SetModelBeam(z_hit_, z_short_, z_max_, z_rand_,
00520                          sigma_hit_, lambda_short_, 0.0);
00521   else
00522   {
00523     ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
00524     laser_->SetModelLikelihoodField(z_hit_, z_rand_, sigma_hit_,
00525                                     laser_likelihood_max_dist_);
00526     ROS_INFO("Done initializing likelihood field model.");
00527   }
00528 
00529   odom_frame_id_ = config.odom_frame_id;
00530   base_frame_id_ = config.base_frame_id;
00531   global_frame_id_ = config.global_frame_id;
00532 
00533   delete laser_scan_filter_;
00534   laser_scan_filter_ = 
00535           new tf::MessageFilter<sensor_msgs::LaserScan>(*laser_scan_sub_, 
00536                                                         *tf_, 
00537                                                         odom_frame_id_, 
00538                                                         100);
00539   laser_scan_filter_->registerCallback(boost::bind(&AmclNode::laserReceived,
00540                                                    this, _1));
00541 
00542   initial_pose_sub_ = nh_.subscribe("initialpose", 2, &AmclNode::initialPoseReceived, this);
00543 }
00544 
00545 void 
00546 AmclNode::checkLaserReceived(const ros::TimerEvent& event)
00547 {
00548   ros::Duration d = ros::Time::now() - last_laser_received_ts_;
00549   if(d > laser_check_interval_)
00550   {
00551     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.",
00552              d.toSec(),
00553              ros::names::resolve(scan_topic_).c_str());
00554   }
00555 }
00556 
00557 void
00558 AmclNode::requestMap()
00559 {
00560   boost::recursive_mutex::scoped_lock ml(configuration_mutex_);
00561 
00562   // get map via RPC
00563   nav_msgs::GetMap::Request  req;
00564   nav_msgs::GetMap::Response resp;
00565   ROS_INFO("Requesting the map...");
00566   while(!ros::service::call("static_map", req, resp))
00567   {
00568     ROS_WARN("Request for map failed; trying again...");
00569     ros::Duration d(0.5);
00570     d.sleep();
00571   }
00572   handleMapMessage( resp.map );
00573 }
00574 
00575 void
00576 AmclNode::mapReceived(const nav_msgs::OccupancyGridConstPtr& msg)
00577 {
00578   if( first_map_only_ && first_map_received_ ) {
00579     return;
00580   }
00581 
00582   handleMapMessage( *msg );
00583 
00584   first_map_received_ = true;
00585 }
00586 
00587 void
00588 AmclNode::handleMapMessage(const nav_msgs::OccupancyGrid& msg)
00589 {
00590   boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
00591 
00592   ROS_INFO("Received a %d X %d map @ %.3f m/pix\n",
00593            msg.info.width,
00594            msg.info.height,
00595            msg.info.resolution);
00596 
00597   freeMapDependentMemory();
00598   // Clear queued laser objects because they hold pointers to the existing
00599   // map, #5202.
00600   lasers_.clear();
00601   lasers_update_.clear();
00602   frame_to_laser_.clear();
00603 
00604   map_ = convertMap(msg);
00605 
00606 #if NEW_UNIFORM_SAMPLING
00607   // Index of free space
00608   free_space_indices.resize(0);
00609   for(int i = 0; i < map_->size_x; i++)
00610     for(int j = 0; j < map_->size_y; j++)
00611       if(map_->cells[MAP_INDEX(map_,i,j)].occ_state == -1)
00612         free_space_indices.push_back(std::make_pair(i,j));
00613 #endif
00614   // Create the particle filter
00615   pf_ = pf_alloc(min_particles_, max_particles_,
00616                  alpha_slow_, alpha_fast_,
00617                  (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
00618                  (void *)map_);
00619   pf_->pop_err = pf_err_;
00620   pf_->pop_z = pf_z_;
00621 
00622   // Initialize the filter
00623   pf_vector_t pf_init_pose_mean = pf_vector_zero();
00624   pf_init_pose_mean.v[0] = init_pose_[0];
00625   pf_init_pose_mean.v[1] = init_pose_[1];
00626   pf_init_pose_mean.v[2] = init_pose_[2];
00627   pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
00628   pf_init_pose_cov.m[0][0] = init_cov_[0];
00629   pf_init_pose_cov.m[1][1] = init_cov_[1];
00630   pf_init_pose_cov.m[2][2] = init_cov_[2];
00631   pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
00632   pf_init_ = false;
00633 
00634   // Instantiate the sensor objects
00635   // Odometry
00636   delete odom_;
00637   odom_ = new AMCLOdom();
00638   ROS_ASSERT(odom_);
00639   if(odom_model_type_ == ODOM_MODEL_OMNI)
00640     odom_->SetModelOmni(alpha1_, alpha2_, alpha3_, alpha4_, alpha5_);
00641   else
00642     odom_->SetModelDiff(alpha1_, alpha2_, alpha3_, alpha4_);
00643   // Laser
00644   delete laser_;
00645   laser_ = new AMCLLaser(max_beams_, map_);
00646   ROS_ASSERT(laser_);
00647   if(laser_model_type_ == LASER_MODEL_BEAM)
00648     laser_->SetModelBeam(z_hit_, z_short_, z_max_, z_rand_,
00649                          sigma_hit_, lambda_short_, 0.0);
00650   else
00651   {
00652     ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
00653     laser_->SetModelLikelihoodField(z_hit_, z_rand_, sigma_hit_,
00654                                     laser_likelihood_max_dist_);
00655     ROS_INFO("Done initializing likelihood field model.");
00656   }
00657 
00658   // In case the initial pose message arrived before the first map,
00659   // try to apply the initial pose now that the map has arrived.
00660   applyInitialPose();
00661 
00662 }
00663 
00664 void
00665 AmclNode::freeMapDependentMemory()
00666 {
00667   if( map_ != NULL ) {
00668     map_free( map_ );
00669     map_ = NULL;
00670   }
00671   if( pf_ != NULL ) {
00672     pf_free( pf_ );
00673     pf_ = NULL;
00674   }
00675   delete odom_;
00676   odom_ = NULL;
00677   delete laser_;
00678   laser_ = NULL;
00679 }
00680 
00685 map_t*
00686 AmclNode::convertMap( const nav_msgs::OccupancyGrid& map_msg )
00687 {
00688   map_t* map = map_alloc();
00689   ROS_ASSERT(map);
00690 
00691   map->size_x = map_msg.info.width;
00692   map->size_y = map_msg.info.height;
00693   map->scale = map_msg.info.resolution;
00694   map->origin_x = map_msg.info.origin.position.x + (map->size_x / 2) * map->scale;
00695   map->origin_y = map_msg.info.origin.position.y + (map->size_y / 2) * map->scale;
00696   // Convert to player format
00697   map->cells = (map_cell_t*)malloc(sizeof(map_cell_t)*map->size_x*map->size_y);
00698   ROS_ASSERT(map->cells);
00699   for(int i=0;i<map->size_x * map->size_y;i++)
00700   {
00701     if(map_msg.data[i] == 0)
00702       map->cells[i].occ_state = -1;
00703     else if(map_msg.data[i] == 100)
00704       map->cells[i].occ_state = +1;
00705     else
00706       map->cells[i].occ_state = 0;
00707   }
00708 
00709   return map;
00710 }
00711 
00712 AmclNode::~AmclNode()
00713 {
00714   delete dsrv_;
00715   freeMapDependentMemory();
00716   delete laser_scan_filter_;
00717   delete laser_scan_sub_;
00718   delete tfb_;
00719   delete tf_;
00720   // TODO: delete everything allocated in constructor
00721 }
00722 
00723 bool
00724 AmclNode::getOdomPose(tf::Stamped<tf::Pose>& odom_pose,
00725                       double& x, double& y, double& yaw,
00726                       const ros::Time& t, const std::string& f)
00727 {
00728   // Get the robot's pose
00729   tf::Stamped<tf::Pose> ident (tf::Transform(tf::createIdentityQuaternion(),
00730                                            tf::Vector3(0,0,0)), t, f);
00731   try
00732   {
00733     this->tf_->transformPose(odom_frame_id_, ident, odom_pose);
00734   }
00735   catch(tf::TransformException e)
00736   {
00737     ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what());
00738     return false;
00739   }
00740   x = odom_pose.getOrigin().x();
00741   y = odom_pose.getOrigin().y();
00742   double pitch,roll;
00743   odom_pose.getBasis().getEulerYPR(yaw, pitch, roll);
00744 
00745   return true;
00746 }
00747 
00748 
00749 pf_vector_t
00750 AmclNode::uniformPoseGenerator(void* arg)
00751 {
00752   map_t* map = (map_t*)arg;
00753 #if NEW_UNIFORM_SAMPLING
00754   unsigned int rand_index = drand48() * free_space_indices.size();
00755   std::pair<int,int> free_point = free_space_indices[rand_index];
00756   pf_vector_t p;
00757   p.v[0] = MAP_WXGX(map, free_point.first);
00758   p.v[1] = MAP_WYGY(map, free_point.second);
00759   p.v[2] = drand48() * 2 * M_PI - M_PI;
00760 #else
00761   double min_x, max_x, min_y, max_y;
00762 
00763   min_x = (map->size_x * map->scale)/2.0 - map->origin_x;
00764   max_x = (map->size_x * map->scale)/2.0 + map->origin_x;
00765   min_y = (map->size_y * map->scale)/2.0 - map->origin_y;
00766   max_y = (map->size_y * map->scale)/2.0 + map->origin_y;
00767 
00768   pf_vector_t p;
00769 
00770   ROS_DEBUG("Generating new uniform sample");
00771   for(;;)
00772   {
00773     p.v[0] = min_x + drand48() * (max_x - min_x);
00774     p.v[1] = min_y + drand48() * (max_y - min_y);
00775     p.v[2] = drand48() * 2 * M_PI - M_PI;
00776     // Check that it's a free cell
00777     int i,j;
00778     i = MAP_GXWX(map, p.v[0]);
00779     j = MAP_GYWY(map, p.v[1]);
00780     if(MAP_VALID(map,i,j) && (map->cells[MAP_INDEX(map,i,j)].occ_state == -1))
00781       break;
00782   }
00783 #endif
00784   return p;
00785 }
00786 
00787 bool
00788 AmclNode::globalLocalizationCallback(std_srvs::Empty::Request& req,
00789                                      std_srvs::Empty::Response& res)
00790 {
00791   if( map_ == NULL ) {
00792     return true;
00793   }
00794   boost::recursive_mutex::scoped_lock gl(configuration_mutex_);
00795   ROS_INFO("Initializing with uniform distribution");
00796   pf_init_model(pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
00797                 (void *)map_);
00798   ROS_INFO("Global initialisation done!");
00799   pf_init_ = false;
00800   return true;
00801 }
00802 
00803 // force nomotion updates (amcl updating without requiring motion)
00804 bool 
00805 AmclNode::nomotionUpdateCallback(std_srvs::Empty::Request& req,
00806                                      std_srvs::Empty::Response& res)
00807 {
00808         m_force_update = true;
00809         //ROS_INFO("Requesting no-motion update");
00810         return true;
00811 }
00812 
00813 void
00814 AmclNode::laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan)
00815 {
00816   last_laser_received_ts_ = ros::Time::now();
00817   if( map_ == NULL ) {
00818     return;
00819   }
00820   boost::recursive_mutex::scoped_lock lr(configuration_mutex_);
00821   int laser_index = -1;
00822 
00823   // Do we have the base->base_laser Tx yet?
00824   if(frame_to_laser_.find(laser_scan->header.frame_id) == frame_to_laser_.end())
00825   {
00826     ROS_DEBUG("Setting up laser %d (frame_id=%s)\n", (int)frame_to_laser_.size(), laser_scan->header.frame_id.c_str());
00827     lasers_.push_back(new AMCLLaser(*laser_));
00828     lasers_update_.push_back(true);
00829     laser_index = frame_to_laser_.size();
00830 
00831     tf::Stamped<tf::Pose> ident (tf::Transform(tf::createIdentityQuaternion(),
00832                                              tf::Vector3(0,0,0)),
00833                                  ros::Time(), laser_scan->header.frame_id);
00834     tf::Stamped<tf::Pose> laser_pose;
00835     try
00836     {
00837       this->tf_->transformPose(base_frame_id_, ident, laser_pose);
00838     }
00839     catch(tf::TransformException& e)
00840     {
00841       ROS_ERROR("Couldn't transform from %s to %s, "
00842                 "even though the message notifier is in use",
00843                 laser_scan->header.frame_id.c_str(),
00844                 base_frame_id_.c_str());
00845       return;
00846     }
00847 
00848     pf_vector_t laser_pose_v;
00849     laser_pose_v.v[0] = laser_pose.getOrigin().x();
00850     laser_pose_v.v[1] = laser_pose.getOrigin().y();
00851     // laser mounting angle gets computed later -> set to 0 here!
00852     laser_pose_v.v[2] = 0;
00853     lasers_[laser_index]->SetLaserPose(laser_pose_v);
00854     ROS_DEBUG("Received laser's pose wrt robot: %.3f %.3f %.3f",
00855               laser_pose_v.v[0],
00856               laser_pose_v.v[1],
00857               laser_pose_v.v[2]);
00858 
00859     frame_to_laser_[laser_scan->header.frame_id] = laser_index;
00860   } else {
00861     // we have the laser pose, retrieve laser index
00862     laser_index = frame_to_laser_[laser_scan->header.frame_id];
00863   }
00864 
00865   // Where was the robot when this scan was taken?
00866   tf::Stamped<tf::Pose> odom_pose;
00867   pf_vector_t pose;
00868   if(!getOdomPose(odom_pose, pose.v[0], pose.v[1], pose.v[2],
00869                   laser_scan->header.stamp, base_frame_id_))
00870   {
00871     ROS_ERROR("Couldn't determine robot's pose associated with laser scan");
00872     return;
00873   }
00874 
00875 
00876   pf_vector_t delta = pf_vector_zero();
00877 
00878   if(pf_init_)
00879   {
00880     // Compute change in pose
00881     //delta = pf_vector_coord_sub(pose, pf_odom_pose_);
00882     delta.v[0] = pose.v[0] - pf_odom_pose_.v[0];
00883     delta.v[1] = pose.v[1] - pf_odom_pose_.v[1];
00884     delta.v[2] = angle_diff(pose.v[2], pf_odom_pose_.v[2]);
00885 
00886     // See if we should update the filter
00887     bool update = fabs(delta.v[0]) > d_thresh_ ||
00888                   fabs(delta.v[1]) > d_thresh_ ||
00889                   fabs(delta.v[2]) > a_thresh_;
00890     update = update || m_force_update;
00891     m_force_update=false;
00892 
00893     // Set the laser update flags
00894     if(update)
00895       for(unsigned int i=0; i < lasers_update_.size(); i++)
00896         lasers_update_[i] = true;
00897   }
00898 
00899   bool force_publication = false;
00900   if(!pf_init_)
00901   {
00902     // Pose at last filter update
00903     pf_odom_pose_ = pose;
00904 
00905     // Filter is now initialized
00906     pf_init_ = true;
00907 
00908     // Should update sensor data
00909     for(unsigned int i=0; i < lasers_update_.size(); i++)
00910       lasers_update_[i] = true;
00911 
00912     force_publication = true;
00913 
00914     resample_count_ = 0;
00915   }
00916   // If the robot has moved, update the filter
00917   else if(pf_init_ && lasers_update_[laser_index])
00918   {
00919     //printf("pose\n");
00920     //pf_vector_fprintf(pose, stdout, "%.3f");
00921 
00922     AMCLOdomData odata;
00923     odata.pose = pose;
00924     // HACK
00925     // Modify the delta in the action data so the filter gets
00926     // updated correctly
00927     odata.delta = delta;
00928 
00929     // Use the action data to update the filter
00930     odom_->UpdateAction(pf_, (AMCLSensorData*)&odata);
00931 
00932     // Pose at last filter update
00933     //this->pf_odom_pose = pose;
00934   }
00935 
00936   bool resampled = false;
00937   // If the robot has moved, update the filter
00938   if(lasers_update_[laser_index])
00939   {
00940     AMCLLaserData ldata;
00941     ldata.sensor = lasers_[laser_index];
00942     ldata.range_count = laser_scan->ranges.size();
00943 
00944     // To account for lasers that are mounted upside-down, we determine the
00945     // min, max, and increment angles of the laser in the base frame.
00946     //
00947     // Construct min and max angles of laser, in the base_link frame.
00948     tf::Quaternion q;
00949     q.setRPY(0.0, 0.0, laser_scan->angle_min);
00950     tf::Stamped<tf::Quaternion> min_q(q, laser_scan->header.stamp,
00951                                       laser_scan->header.frame_id);
00952     q.setRPY(0.0, 0.0, laser_scan->angle_min + laser_scan->angle_increment);
00953     tf::Stamped<tf::Quaternion> inc_q(q, laser_scan->header.stamp,
00954                                       laser_scan->header.frame_id);
00955     try
00956     {
00957       tf_->transformQuaternion(base_frame_id_, min_q, min_q);
00958       tf_->transformQuaternion(base_frame_id_, inc_q, inc_q);
00959     }
00960     catch(tf::TransformException& e)
00961     {
00962       ROS_WARN("Unable to transform min/max laser angles into base frame: %s",
00963                e.what());
00964       return;
00965     }
00966 
00967     double angle_min = tf::getYaw(min_q);
00968     double angle_increment = tf::getYaw(inc_q) - angle_min;
00969 
00970     // wrapping angle to [-pi .. pi]
00971     angle_increment = fmod(angle_increment + 5*M_PI, 2*M_PI) - M_PI;
00972 
00973     ROS_DEBUG("Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min, angle_increment);
00974 
00975     // Apply range min/max thresholds, if the user supplied them
00976     if(laser_max_range_ > 0.0)
00977       ldata.range_max = std::min(laser_scan->range_max, (float)laser_max_range_);
00978     else
00979       ldata.range_max = laser_scan->range_max;
00980     double range_min;
00981     if(laser_min_range_ > 0.0)
00982       range_min = std::max(laser_scan->range_min, (float)laser_min_range_);
00983     else
00984       range_min = laser_scan->range_min;
00985     // The AMCLLaserData destructor will free this memory
00986     ldata.ranges = new double[ldata.range_count][2];
00987     ROS_ASSERT(ldata.ranges);
00988     for(int i=0;i<ldata.range_count;i++)
00989     {
00990       // amcl doesn't (yet) have a concept of min range.  So we'll map short
00991       // readings to max range.
00992       if(laser_scan->ranges[i] <= range_min)
00993         ldata.ranges[i][0] = ldata.range_max;
00994       else
00995         ldata.ranges[i][0] = laser_scan->ranges[i];
00996       // Compute bearing
00997       ldata.ranges[i][1] = angle_min +
00998               (i * angle_increment);
00999     }
01000 
01001     lasers_[laser_index]->UpdateSensor(pf_, (AMCLSensorData*)&ldata);
01002 
01003     lasers_update_[laser_index] = false;
01004 
01005     pf_odom_pose_ = pose;
01006 
01007     // Resample the particles
01008     if(!(++resample_count_ % resample_interval_))
01009     {
01010       pf_update_resample(pf_);
01011       resampled = true;
01012     }
01013 
01014     pf_sample_set_t* set = pf_->sets + pf_->current_set;
01015     ROS_DEBUG("Num samples: %d\n", set->sample_count);
01016 
01017     // Publish the resulting cloud
01018     // TODO: set maximum rate for publishing
01019     if (!m_force_update) {
01020       geometry_msgs::PoseArray cloud_msg;
01021       cloud_msg.header.stamp = ros::Time::now();
01022       cloud_msg.header.frame_id = global_frame_id_;
01023       cloud_msg.poses.resize(set->sample_count);
01024       for(int i=0;i<set->sample_count;i++)
01025       {
01026         tf::poseTFToMsg(tf::Pose(tf::createQuaternionFromYaw(set->samples[i].pose.v[2]),
01027                                  tf::Vector3(set->samples[i].pose.v[0],
01028                                            set->samples[i].pose.v[1], 0)),
01029                         cloud_msg.poses[i]);
01030       }
01031       particlecloud_pub_.publish(cloud_msg);
01032     }
01033   }
01034 
01035   if(resampled || force_publication)
01036   {
01037     // Read out the current hypotheses
01038     double max_weight = 0.0;
01039     int max_weight_hyp = -1;
01040     std::vector<amcl_hyp_t> hyps;
01041     hyps.resize(pf_->sets[pf_->current_set].cluster_count);
01042     for(int hyp_count = 0;
01043         hyp_count < pf_->sets[pf_->current_set].cluster_count; hyp_count++)
01044     {
01045       double weight;
01046       pf_vector_t pose_mean;
01047       pf_matrix_t pose_cov;
01048       if (!pf_get_cluster_stats(pf_, hyp_count, &weight, &pose_mean, &pose_cov))
01049       {
01050         ROS_ERROR("Couldn't get stats on cluster %d", hyp_count);
01051         break;
01052       }
01053 
01054       hyps[hyp_count].weight = weight;
01055       hyps[hyp_count].pf_pose_mean = pose_mean;
01056       hyps[hyp_count].pf_pose_cov = pose_cov;
01057 
01058       if(hyps[hyp_count].weight > max_weight)
01059       {
01060         max_weight = hyps[hyp_count].weight;
01061         max_weight_hyp = hyp_count;
01062       }
01063     }
01064 
01065     if(max_weight > 0.0)
01066     {
01067       ROS_DEBUG("Max weight pose: %.3f %.3f %.3f",
01068                 hyps[max_weight_hyp].pf_pose_mean.v[0],
01069                 hyps[max_weight_hyp].pf_pose_mean.v[1],
01070                 hyps[max_weight_hyp].pf_pose_mean.v[2]);
01071 
01072       /*
01073          puts("");
01074          pf_matrix_fprintf(hyps[max_weight_hyp].pf_pose_cov, stdout, "%6.3f");
01075          puts("");
01076        */
01077 
01078       geometry_msgs::PoseWithCovarianceStamped p;
01079       // Fill in the header
01080       p.header.frame_id = global_frame_id_;
01081       p.header.stamp = laser_scan->header.stamp;
01082       // Copy in the pose
01083       p.pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
01084       p.pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
01085       tf::quaternionTFToMsg(tf::createQuaternionFromYaw(hyps[max_weight_hyp].pf_pose_mean.v[2]),
01086                             p.pose.pose.orientation);
01087       // Copy in the covariance, converting from 3-D to 6-D
01088       pf_sample_set_t* set = pf_->sets + pf_->current_set;
01089       for(int i=0; i<2; i++)
01090       {
01091         for(int j=0; j<2; j++)
01092         {
01093           // Report the overall filter covariance, rather than the
01094           // covariance for the highest-weight cluster
01095           //p.covariance[6*i+j] = hyps[max_weight_hyp].pf_pose_cov.m[i][j];
01096           p.pose.covariance[6*i+j] = set->cov.m[i][j];
01097         }
01098       }
01099       // Report the overall filter covariance, rather than the
01100       // covariance for the highest-weight cluster
01101       //p.covariance[6*5+5] = hyps[max_weight_hyp].pf_pose_cov.m[2][2];
01102       p.pose.covariance[6*5+5] = set->cov.m[2][2];
01103 
01104       /*
01105          printf("cov:\n");
01106          for(int i=0; i<6; i++)
01107          {
01108          for(int j=0; j<6; j++)
01109          printf("%6.3f ", p.covariance[6*i+j]);
01110          puts("");
01111          }
01112        */
01113 
01114       pose_pub_.publish(p);
01115       last_published_pose = p;
01116 
01117       ROS_DEBUG("New pose: %6.3f %6.3f %6.3f",
01118                hyps[max_weight_hyp].pf_pose_mean.v[0],
01119                hyps[max_weight_hyp].pf_pose_mean.v[1],
01120                hyps[max_weight_hyp].pf_pose_mean.v[2]);
01121 
01122       // subtracting base to odom from map to base and send map to odom instead
01123       tf::Stamped<tf::Pose> odom_to_map;
01124       try
01125       {
01126         tf::Transform tmp_tf(tf::createQuaternionFromYaw(hyps[max_weight_hyp].pf_pose_mean.v[2]),
01127                              tf::Vector3(hyps[max_weight_hyp].pf_pose_mean.v[0],
01128                                          hyps[max_weight_hyp].pf_pose_mean.v[1],
01129                                          0.0));
01130         tf::Stamped<tf::Pose> tmp_tf_stamped (tmp_tf.inverse(),
01131                                               laser_scan->header.stamp,
01132                                               base_frame_id_);
01133         this->tf_->transformPose(odom_frame_id_,
01134                                  tmp_tf_stamped,
01135                                  odom_to_map);
01136       }
01137       catch(tf::TransformException)
01138       {
01139         ROS_DEBUG("Failed to subtract base to odom transform");
01140         return;
01141       }
01142 
01143       latest_tf_ = tf::Transform(tf::Quaternion(odom_to_map.getRotation()),
01144                                  tf::Point(odom_to_map.getOrigin()));
01145       latest_tf_valid_ = true;
01146 
01147       if (tf_broadcast_ == true)
01148       {
01149         // We want to send a transform that is good up until a
01150         // tolerance time so that odom can be used
01151         ros::Time transform_expiration = (laser_scan->header.stamp +
01152                                           transform_tolerance_);
01153         tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(),
01154                                             transform_expiration,
01155                                             global_frame_id_, odom_frame_id_);
01156         this->tfb_->sendTransform(tmp_tf_stamped);
01157         sent_first_transform_ = true;
01158       }
01159     }
01160     else
01161     {
01162       ROS_ERROR("No pose!");
01163     }
01164   }
01165   else if(latest_tf_valid_)
01166   {
01167     if (tf_broadcast_ == true)
01168     {
01169       // Nothing changed, so we'll just republish the last transform, to keep
01170       // everybody happy.
01171       ros::Time transform_expiration = (laser_scan->header.stamp +
01172                                         transform_tolerance_);
01173       tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(),
01174                                           transform_expiration,
01175                                           global_frame_id_, odom_frame_id_);
01176       this->tfb_->sendTransform(tmp_tf_stamped);
01177     }
01178 
01179     // Is it time to save our last pose to the param server
01180     ros::Time now = ros::Time::now();
01181     if((save_pose_period.toSec() > 0.0) &&
01182        (now - save_pose_last_time) >= save_pose_period)
01183     {
01184       // We need to apply the last transform to the latest odom pose to get
01185       // the latest map pose to store.  We'll take the covariance from
01186       // last_published_pose.
01187       tf::Pose map_pose = latest_tf_.inverse() * odom_pose;
01188       double yaw,pitch,roll;
01189       map_pose.getBasis().getEulerYPR(yaw, pitch, roll);
01190 
01191       private_nh_.setParam("initial_pose_x", map_pose.getOrigin().x());
01192       private_nh_.setParam("initial_pose_y", map_pose.getOrigin().y());
01193       private_nh_.setParam("initial_pose_a", yaw);
01194       private_nh_.setParam("initial_cov_xx", 
01195                                       last_published_pose.pose.covariance[6*0+0]);
01196       private_nh_.setParam("initial_cov_yy", 
01197                                       last_published_pose.pose.covariance[6*1+1]);
01198       private_nh_.setParam("initial_cov_aa", 
01199                                       last_published_pose.pose.covariance[6*5+5]);
01200       save_pose_last_time = now;
01201     }
01202   }
01203 
01204 }
01205 
01206 double
01207 AmclNode::getYaw(tf::Pose& t)
01208 {
01209   double yaw, pitch, roll;
01210   t.getBasis().getEulerYPR(yaw,pitch,roll);
01211   return yaw;
01212 }
01213 
01214 void
01215 AmclNode::initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg)
01216 {
01217   boost::recursive_mutex::scoped_lock prl(configuration_mutex_);
01218   if(msg->header.frame_id == "")
01219   {
01220     // This should be removed at some point
01221     ROS_WARN("Received initial pose with empty frame_id.  You should always supply a frame_id.");
01222   }
01223   // We only accept initial pose estimates in the global frame, #5148.
01224   else if(tf_->resolve(msg->header.frame_id) != tf_->resolve(global_frame_id_))
01225   {
01226     ROS_WARN("Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"",
01227              msg->header.frame_id.c_str(),
01228              global_frame_id_.c_str());
01229     return;
01230   }
01231 
01232   // In case the client sent us a pose estimate in the past, integrate the
01233   // intervening odometric change.
01234   tf::StampedTransform tx_odom;
01235   try
01236   {
01237     tf_->lookupTransform(base_frame_id_, ros::Time::now(),
01238                          base_frame_id_, msg->header.stamp,
01239                          global_frame_id_, tx_odom);
01240   }
01241   catch(tf::TransformException e)
01242   {
01243     // If we've never sent a transform, then this is normal, because the
01244     // global_frame_id_ frame doesn't exist.  We only care about in-time
01245     // transformation for on-the-move pose-setting, so ignoring this
01246     // startup condition doesn't really cost us anything.
01247     if(sent_first_transform_)
01248       ROS_WARN("Failed to transform initial pose in time (%s)", e.what());
01249     tx_odom.setIdentity();
01250   }
01251 
01252   tf::Pose pose_old, pose_new;
01253   tf::poseMsgToTF(msg->pose.pose, pose_old);
01254   pose_new = tx_odom.inverse() * pose_old;
01255 
01256   // Transform into the global frame
01257 
01258   ROS_INFO("Setting pose (%.6f): %.3f %.3f %.3f",
01259            ros::Time::now().toSec(),
01260            pose_new.getOrigin().x(),
01261            pose_new.getOrigin().y(),
01262            getYaw(pose_new));
01263   // Re-initialize the filter
01264   pf_vector_t pf_init_pose_mean = pf_vector_zero();
01265   pf_init_pose_mean.v[0] = pose_new.getOrigin().x();
01266   pf_init_pose_mean.v[1] = pose_new.getOrigin().y();
01267   pf_init_pose_mean.v[2] = getYaw(pose_new);
01268   pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
01269   // Copy in the covariance, converting from 6-D to 3-D
01270   for(int i=0; i<2; i++)
01271   {
01272     for(int j=0; j<2; j++)
01273     {
01274       pf_init_pose_cov.m[i][j] = msg->pose.covariance[6*i+j];
01275     }
01276   }
01277   pf_init_pose_cov.m[2][2] = msg->pose.covariance[6*5+5];
01278 
01279   delete initial_pose_hyp_;
01280   initial_pose_hyp_ = new amcl_hyp_t();
01281   initial_pose_hyp_->pf_pose_mean = pf_init_pose_mean;
01282   initial_pose_hyp_->pf_pose_cov = pf_init_pose_cov;
01283   applyInitialPose();
01284 }
01285 
01291 void
01292 AmclNode::applyInitialPose()
01293 {
01294   boost::recursive_mutex::scoped_lock cfl(configuration_mutex_);
01295   if( initial_pose_hyp_ != NULL && map_ != NULL ) {
01296     pf_init(pf_, initial_pose_hyp_->pf_pose_mean, initial_pose_hyp_->pf_pose_cov);
01297     pf_init_ = false;
01298 
01299     delete initial_pose_hyp_;
01300     initial_pose_hyp_ = NULL;
01301   }
01302 }


amcl
Author(s): Brian P. Gerkey
autogenerated on Mon Oct 6 2014 02:49:04