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


amcl
Author(s): Brian P. Gerkey, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:07:48