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


amcl
Author(s): Brian P. Gerkey, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:02