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


amcl
Author(s): Brian P. Gerkey
autogenerated on Sat Dec 28 2013 17:14:46