00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #include <algorithm>
00024 #include <vector>
00025 #include <map>
00026
00027 #include <boost/bind.hpp>
00028 #include <boost/thread/mutex.hpp>
00029
00030 #include "map/map.h"
00031 #include "pf/pf.h"
00032 #include "sensors/amcl_odom.h"
00033 #include "sensors/amcl_laser.h"
00034
00035 #include "ros/assert.h"
00036
00037
00038 #include "ros/ros.h"
00039
00040
00041 #include "sensor_msgs/LaserScan.h"
00042 #include "geometry_msgs/PoseWithCovarianceStamped.h"
00043 #include "geometry_msgs/PoseArray.h"
00044 #include "geometry_msgs/Pose.h"
00045 #include "nav_msgs/GetMap.h"
00046 #include "std_srvs/Empty.h"
00047
00048
00049 #include "tf/transform_broadcaster.h"
00050 #include "tf/transform_listener.h"
00051 #include "tf/message_filter.h"
00052 #include "message_filters/subscriber.h"
00053
00054 #define NEW_UNIFORM_SAMPLING 1
00055
00056 using namespace amcl;
00057
00058
00059 typedef struct
00060 {
00061
00062 double weight;
00063
00064
00065 pf_vector_t pf_pose_mean;
00066
00067
00068 pf_matrix_t pf_pose_cov;
00069
00070 } amcl_hyp_t;
00071
00072 static double
00073 normalize(double z)
00074 {
00075 return atan2(sin(z),cos(z));
00076 }
00077 static double
00078 angle_diff(double a, double b)
00079 {
00080 double d1, d2;
00081 a = normalize(a);
00082 b = normalize(b);
00083 d1 = a-b;
00084 d2 = 2*M_PI - fabs(d1);
00085 if(d1 > 0)
00086 d2 *= -1.0;
00087 if(fabs(d1) < fabs(d2))
00088 return(d1);
00089 else
00090 return(d2);
00091 }
00092
00093 class AmclNode
00094 {
00095 public:
00096 AmclNode();
00097 ~AmclNode();
00098
00099 int process();
00100
00101 private:
00102 tf::TransformBroadcaster* tfb_;
00103 tf::TransformListener* tf_;
00104
00105 bool sent_first_transform_;
00106
00107 tf::Transform latest_tf_;
00108 bool latest_tf_valid_;
00109
00110
00111
00112 static pf_vector_t uniformPoseGenerator(void* arg);
00113 #if NEW_UNIFORM_SAMPLING
00114 static std::vector<std::pair<int,int> > free_space_indices;
00115 #endif
00116
00117 bool globalLocalizationCallback(std_srvs::Empty::Request& req,
00118 std_srvs::Empty::Response& res);
00119 void laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan);
00120 void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
00121 void initialPoseReceivedOld(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
00122
00123 double getYaw(tf::Pose& t);
00124
00125
00126 std::string odom_frame_id_;
00127
00128 std::string base_frame_id_;
00129 std::string global_frame_id_;
00130
00131 ros::Duration gui_publish_period;
00132 ros::Time save_pose_last_time;
00133 ros::Duration save_pose_period;
00134
00135 geometry_msgs::PoseWithCovarianceStamped last_published_pose;
00136
00137 map_t* map_;
00138 char* mapdata;
00139 int sx, sy;
00140 double resolution;
00141
00142 message_filters::Subscriber<sensor_msgs::LaserScan>* laser_scan_sub_;
00143 tf::MessageFilter<sensor_msgs::LaserScan>* laser_scan_filter_;
00144 message_filters::Subscriber<geometry_msgs::PoseWithCovarianceStamped>* initial_pose_sub_;
00145 tf::MessageFilter<geometry_msgs::PoseWithCovarianceStamped>* initial_pose_filter_;
00146 std::vector< AMCLLaser* > lasers_;
00147 std::vector< bool > lasers_update_;
00148 std::map< std::string, int > frame_to_laser_;
00149
00150
00151 pf_t *pf_;
00152 boost::mutex pf_mutex_;
00153 double pf_err_, pf_z_;
00154 bool pf_init_;
00155 pf_vector_t pf_odom_pose_;
00156 double d_thresh_, a_thresh_;
00157 int resample_interval_;
00158 int resample_count_;
00159 double laser_min_range_;
00160 double laser_max_range_;
00161
00162 AMCLOdom* odom_;
00163 AMCLLaser* laser_;
00164
00165 ros::Duration cloud_pub_interval;
00166 ros::Time last_cloud_pub_time;
00167
00168 map_t* requestMap();
00169
00170
00171 bool getOdomPose(tf::Stamped<tf::Pose>& pose,
00172 double& x, double& y, double& yaw,
00173 const ros::Time& t, const std::string& f);
00174
00175
00176
00177 ros::Duration transform_tolerance_;
00178
00179 ros::NodeHandle nh_;
00180 ros::NodeHandle private_nh_;
00181 ros::Publisher pose_pub_;
00182 ros::Publisher particlecloud_pub_;
00183 ros::ServiceServer global_loc_srv_;
00184 ros::Subscriber initial_pose_sub_old_;
00185 };
00186
00187 std::vector<std::pair<int,int> > AmclNode::free_space_indices;
00188
00189 #define USAGE "USAGE: amcl"
00190
00191 int
00192 main(int argc, char** argv)
00193 {
00194 ros::init(argc, argv, "amcl");
00195 ros::NodeHandle nh;
00196
00197 AmclNode an;
00198
00199 ros::spin();
00200
00201
00202 return(0);
00203 }
00204
00205 AmclNode::AmclNode() :
00206 sent_first_transform_(false),
00207 latest_tf_valid_(false),
00208 map_(NULL),
00209 pf_(NULL),
00210 resample_count_(0),
00211 private_nh_("~")
00212 {
00213
00214 int max_beams, min_particles, max_particles;
00215 double alpha1, alpha2, alpha3, alpha4, alpha5;
00216 double alpha_slow, alpha_fast;
00217 double z_hit, z_short, z_max, z_rand, sigma_hit, lambda_short;
00218 double pf_err, pf_z;
00219
00220 double tmp;
00221 private_nh_.param("gui_publish_rate", tmp, -1.0);
00222 gui_publish_period = ros::Duration(1.0/tmp);
00223 private_nh_.param("save_pose_rate", tmp, 0.5);
00224 save_pose_period = ros::Duration(1.0/tmp);
00225
00226 private_nh_.param("laser_min_range", laser_min_range_, -1.0);
00227 private_nh_.param("laser_max_range", laser_max_range_, -1.0);
00228 private_nh_.param("laser_max_beams", max_beams, 30);
00229 private_nh_.param("min_particles", min_particles, 100);
00230 private_nh_.param("max_particles", max_particles, 5000);
00231 private_nh_.param("kld_err", pf_err, 0.01);
00232 private_nh_.param("kld_z", pf_z, 0.99);
00233 private_nh_.param("odom_alpha1", alpha1, 0.2);
00234 private_nh_.param("odom_alpha2", alpha2, 0.2);
00235 private_nh_.param("odom_alpha3", alpha3, 0.2);
00236 private_nh_.param("odom_alpha4", alpha4, 0.2);
00237 private_nh_.param("odom_alpha5", alpha5, 0.2);
00238
00239 private_nh_.param("laser_z_hit", z_hit, 0.95);
00240 private_nh_.param("laser_z_short", z_short, 0.1);
00241 private_nh_.param("laser_z_max", z_max, 0.05);
00242 private_nh_.param("laser_z_rand", z_rand, 0.05);
00243 private_nh_.param("laser_sigma_hit", sigma_hit, 0.2);
00244 private_nh_.param("laser_lambda_short", lambda_short, 0.1);
00245 double laser_likelihood_max_dist;
00246 private_nh_.param("laser_likelihood_max_dist",
00247 laser_likelihood_max_dist, 2.0);
00248 std::string tmp_model_type;
00249 laser_model_t laser_model_type;
00250 private_nh_.param("laser_model_type", tmp_model_type, std::string("likelihood_field"));
00251 if(tmp_model_type == "beam")
00252 laser_model_type = LASER_MODEL_BEAM;
00253 else if(tmp_model_type == "likelihood_field")
00254 laser_model_type = LASER_MODEL_LIKELIHOOD_FIELD;
00255 else
00256 {
00257 ROS_WARN("Unknown laser model type \"%s\"; defaulting to likelihood_field model",
00258 tmp_model_type.c_str());
00259 laser_model_type = LASER_MODEL_LIKELIHOOD_FIELD;
00260 }
00261
00262 odom_model_t odom_model_type;
00263 private_nh_.param("odom_model_type", tmp_model_type, std::string("diff"));
00264 if(tmp_model_type == "diff")
00265 odom_model_type = ODOM_MODEL_DIFF;
00266 else if(tmp_model_type == "omni")
00267 odom_model_type = ODOM_MODEL_OMNI;
00268 else
00269 {
00270 ROS_WARN("Unknown odom model type \"%s\"; defaulting to diff model",
00271 tmp_model_type.c_str());
00272 odom_model_type = ODOM_MODEL_DIFF;
00273 }
00274
00275 private_nh_.param("update_min_d", d_thresh_, 0.2);
00276 private_nh_.param("update_min_a", a_thresh_, M_PI/6.0);
00277 private_nh_.param("odom_frame_id", odom_frame_id_, std::string("odom"));
00278 private_nh_.param("base_frame_id", base_frame_id_, std::string("base_link"));
00279 private_nh_.param("global_frame_id", global_frame_id_, std::string("map"));
00280 private_nh_.param("resample_interval", resample_interval_, 2);
00281 double tmp_tol;
00282 private_nh_.param("transform_tolerance", tmp_tol, 0.1);
00283 private_nh_.param("recovery_alpha_slow", alpha_slow, 0.001);
00284 private_nh_.param("recovery_alpha_fast", alpha_fast, 0.1);
00285
00286 transform_tolerance_.fromSec(tmp_tol);
00287
00288 double init_pose[3];
00289 private_nh_.param("initial_pose_x", init_pose[0], 0.0);
00290 private_nh_.param("initial_pose_y", init_pose[1], 0.0);
00291 private_nh_.param("initial_pose_a", init_pose[2], 0.0);
00292 double init_cov[3];
00293 private_nh_.param("initial_cov_xx", init_cov[0], 0.5 * 0.5);
00294 private_nh_.param("initial_cov_yy", init_cov[1], 0.5 * 0.5);
00295 private_nh_.param("initial_cov_aa", init_cov[2],
00296 (M_PI/12.0) * (M_PI/12.0));
00297
00298 cloud_pub_interval.fromSec(1.0);
00299 tfb_ = new tf::TransformBroadcaster();
00300 tf_ = new tf::TransformListener();
00301
00302 map_ = requestMap();
00303
00304 #if NEW_UNIFORM_SAMPLING
00305
00306 free_space_indices.resize(0);
00307 for(int i = 0; i < map_->size_x; i++)
00308 for(int j = 0; j < map_->size_y; j++)
00309 if(map_->cells[MAP_INDEX(map_,i,j)].occ_state == -1)
00310 free_space_indices.push_back(std::make_pair(i,j));
00311 #endif
00312
00313 pf_ = pf_alloc(min_particles, max_particles,
00314 alpha_slow, alpha_fast,
00315 (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
00316 (void *)map_);
00317 pf_->pop_err = pf_err;
00318 pf_->pop_z = pf_z;
00319
00320
00321 pf_vector_t pf_init_pose_mean = pf_vector_zero();
00322 pf_init_pose_mean.v[0] = init_pose[0];
00323 pf_init_pose_mean.v[1] = init_pose[1];
00324 pf_init_pose_mean.v[2] = init_pose[2];
00325 pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
00326 pf_init_pose_cov.m[0][0] = init_cov[0];
00327 pf_init_pose_cov.m[1][1] = init_cov[1];
00328 pf_init_pose_cov.m[2][2] = init_cov[2];
00329 pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
00330 pf_init_ = false;
00331
00332
00333
00334 odom_ = new AMCLOdom();
00335 ROS_ASSERT(odom_);
00336 if(odom_model_type == ODOM_MODEL_OMNI)
00337 odom_->SetModelOmni(alpha1, alpha2, alpha3, alpha4, alpha5);
00338 else
00339 odom_->SetModelDiff(alpha1, alpha2, alpha3, alpha4);
00340
00341 laser_ = new AMCLLaser(max_beams, map_);
00342 ROS_ASSERT(laser_);
00343 if(laser_model_type == LASER_MODEL_BEAM)
00344 laser_->SetModelBeam(z_hit, z_short, z_max, z_rand,
00345 sigma_hit, lambda_short, 0.0);
00346 else
00347 {
00348 ROS_INFO("Initializing likelihood field model; this can take some time on large maps...");
00349 laser_->SetModelLikelihoodField(z_hit, z_rand, sigma_hit,
00350 laser_likelihood_max_dist);
00351 ROS_INFO("Done initializing likelihood field model.");
00352 }
00353
00354 pose_pub_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("amcl_pose", 2);
00355 particlecloud_pub_ = nh_.advertise<geometry_msgs::PoseArray>("particlecloud", 2);
00356 global_loc_srv_ = nh_.advertiseService("global_localization",
00357 &AmclNode::globalLocalizationCallback,
00358 this);
00359 laser_scan_sub_ = new message_filters::Subscriber<sensor_msgs::LaserScan>(nh_, "scan", 100);
00360 laser_scan_filter_ =
00361 new tf::MessageFilter<sensor_msgs::LaserScan>(*laser_scan_sub_,
00362 *tf_,
00363 odom_frame_id_,
00364 100);
00365 laser_scan_filter_->registerCallback(boost::bind(&AmclNode::laserReceived,
00366 this, _1));
00367 initial_pose_sub_ = new message_filters::Subscriber<geometry_msgs::PoseWithCovarianceStamped>(nh_, "initialpose", 2);
00368 initial_pose_filter_ = new tf::MessageFilter<geometry_msgs::PoseWithCovarianceStamped>(*initial_pose_sub_, *tf_, global_frame_id_, 2);
00369 initial_pose_filter_->registerCallback(boost::bind(&AmclNode::initialPoseReceived, this, _1));
00370
00371 initial_pose_sub_old_ = nh_.subscribe("initialpose", 2, &AmclNode::initialPoseReceivedOld, this);
00372 }
00373
00374 map_t*
00375 AmclNode::requestMap()
00376 {
00377 map_t* map = map_alloc();
00378 ROS_ASSERT(map);
00379
00380
00381 nav_msgs::GetMap::Request req;
00382 nav_msgs::GetMap::Response resp;
00383 ROS_INFO("Requesting the map...");
00384 while(!ros::service::call("static_map", req, resp))
00385 {
00386 ROS_WARN("Request for map failed; trying again...");
00387 ros::Duration d(0.5);
00388 d.sleep();
00389 }
00390 ROS_INFO("Received a %d X %d map @ %.3f m/pix\n",
00391 resp.map.info.width,
00392 resp.map.info.height,
00393 resp.map.info.resolution);
00394
00395 map->size_x = resp.map.info.width;
00396 map->size_y = resp.map.info.height;
00397 map->scale = resp.map.info.resolution;
00398 map->origin_x = resp.map.info.origin.position.x + (map->size_x / 2) * map->scale;
00399 map->origin_y = resp.map.info.origin.position.y + (map->size_y / 2) * map->scale;
00400
00401 map->cells = (map_cell_t*)malloc(sizeof(map_cell_t)*map->size_x*map->size_y);
00402 ROS_ASSERT(map->cells);
00403 for(int i=0;i<map->size_x * map->size_y;i++)
00404 {
00405 if(resp.map.data[i] == 0)
00406 map->cells[i].occ_state = -1;
00407 else if(resp.map.data[i] == 100)
00408 map->cells[i].occ_state = +1;
00409 else
00410 map->cells[i].occ_state = 0;
00411 }
00412
00413 return map;
00414 }
00415
00416 AmclNode::~AmclNode()
00417 {
00418 map_free(map_);
00419 delete laser_scan_filter_;
00420 delete laser_scan_sub_;
00421 delete initial_pose_filter_;
00422 delete initial_pose_sub_;
00423 delete tfb_;
00424 delete tf_;
00425 pf_free(pf_);
00426 delete laser_;
00427 delete odom_;
00428
00429 }
00430
00431 bool
00432 AmclNode::getOdomPose(tf::Stamped<tf::Pose>& odom_pose,
00433 double& x, double& y, double& yaw,
00434 const ros::Time& t, const std::string& f)
00435 {
00436
00437 tf::Stamped<tf::Pose> ident (btTransform(tf::createIdentityQuaternion(),
00438 btVector3(0,0,0)), t, f);
00439 try
00440 {
00441 this->tf_->transformPose(odom_frame_id_, ident, odom_pose);
00442 }
00443 catch(tf::TransformException e)
00444 {
00445 ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what());
00446 return false;
00447 }
00448 x = odom_pose.getOrigin().x();
00449 y = odom_pose.getOrigin().y();
00450 double pitch,roll;
00451 odom_pose.getBasis().getEulerYPR(yaw, pitch, roll);
00452
00453 return true;
00454 }
00455
00456
00457 pf_vector_t
00458 AmclNode::uniformPoseGenerator(void* arg)
00459 {
00460 map_t* map = (map_t*)arg;
00461 #if NEW_UNIFORM_SAMPLING
00462 unsigned int rand_index = drand48() * free_space_indices.size();
00463 std::pair<int,int> free_point = free_space_indices[rand_index];
00464 pf_vector_t p;
00465 p.v[0] = MAP_WXGX(map, free_point.first);
00466 p.v[1] = MAP_WYGY(map, free_point.second);
00467 p.v[2] = drand48() * 2 * M_PI - M_PI;
00468 #else
00469 double min_x, max_x, min_y, max_y;
00470
00471 min_x = (map->size_x * map->scale)/2.0 - map->origin_x;
00472 max_x = (map->size_x * map->scale)/2.0 + map->origin_x;
00473 min_y = (map->size_y * map->scale)/2.0 - map->origin_y;
00474 max_y = (map->size_y * map->scale)/2.0 + map->origin_y;
00475
00476 pf_vector_t p;
00477
00478 ROS_DEBUG("Generating new uniform sample");
00479 for(;;)
00480 {
00481 p.v[0] = min_x + drand48() * (max_x - min_x);
00482 p.v[1] = min_y + drand48() * (max_y - min_y);
00483 p.v[2] = drand48() * 2 * M_PI - M_PI;
00484
00485 int i,j;
00486 i = MAP_GXWX(map, p.v[0]);
00487 j = MAP_GYWY(map, p.v[1]);
00488 if(MAP_VALID(map,i,j) && (map->cells[MAP_INDEX(map,i,j)].occ_state == -1))
00489 break;
00490 }
00491 #endif
00492 return p;
00493 }
00494
00495 bool
00496 AmclNode::globalLocalizationCallback(std_srvs::Empty::Request& req,
00497 std_srvs::Empty::Response& res)
00498 {
00499 pf_mutex_.lock();
00500 ROS_INFO("Initializing with uniform distribution");
00501 pf_init_model(pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
00502 (void *)map_);
00503 ROS_INFO("Global initialisation done!");
00504 pf_init_ = false;
00505 pf_mutex_.unlock();
00506 return true;
00507 }
00508
00509 void
00510 AmclNode::laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan)
00511 {
00512 int laser_index = -1;
00513
00514
00515 if(frame_to_laser_.find(laser_scan->header.frame_id) == frame_to_laser_.end())
00516 {
00517 ROS_DEBUG("Setting up laser %d (frame_id=%s)\n", (int)frame_to_laser_.size(), laser_scan->header.frame_id.c_str());
00518 lasers_.push_back(new AMCLLaser(*laser_));
00519 lasers_update_.push_back(true);
00520 laser_index = frame_to_laser_.size();
00521
00522 tf::Stamped<tf::Pose> ident (btTransform(tf::createIdentityQuaternion(),
00523 btVector3(0,0,0)),
00524 ros::Time(), laser_scan->header.frame_id);
00525 tf::Stamped<tf::Pose> laser_pose;
00526 try
00527 {
00528 this->tf_->transformPose(base_frame_id_, ident, laser_pose);
00529 }
00530 catch(tf::TransformException& e)
00531 {
00532 ROS_ERROR("Couldn't transform from %s to %s, "
00533 "even though the message notifier is in use",
00534 laser_scan->header.frame_id.c_str(),
00535 base_frame_id_.c_str());
00536 return;
00537 }
00538
00539 pf_vector_t laser_pose_v;
00540 laser_pose_v.v[0] = laser_pose.getOrigin().x();
00541 laser_pose_v.v[1] = laser_pose.getOrigin().y();
00542
00543 laser_pose_v.v[2] = 0;
00544 lasers_[laser_index]->SetLaserPose(laser_pose_v);
00545 ROS_DEBUG("Received laser's pose wrt robot: %.3f %.3f %.3f",
00546 laser_pose_v.v[0],
00547 laser_pose_v.v[1],
00548 laser_pose_v.v[2]);
00549
00550 frame_to_laser_[laser_scan->header.frame_id] = laser_index;
00551 } else {
00552
00553 laser_index = frame_to_laser_[laser_scan->header.frame_id];
00554 }
00555
00556
00557 tf::Stamped<tf::Pose> odom_pose;
00558 pf_vector_t pose;
00559 if(!getOdomPose(odom_pose, pose.v[0], pose.v[1], pose.v[2],
00560 laser_scan->header.stamp, base_frame_id_))
00561 {
00562 ROS_ERROR("Couldn't determine robot's pose associated with laser scan");
00563 return;
00564 }
00565
00566 pf_mutex_.lock();
00567
00568 pf_vector_t delta = pf_vector_zero();
00569
00570 if(pf_init_)
00571 {
00572
00573
00574 delta.v[0] = pose.v[0] - pf_odom_pose_.v[0];
00575 delta.v[1] = pose.v[1] - pf_odom_pose_.v[1];
00576 delta.v[2] = angle_diff(pose.v[2], pf_odom_pose_.v[2]);
00577
00578
00579 bool update = fabs(delta.v[0]) > d_thresh_ ||
00580 fabs(delta.v[1]) > d_thresh_ ||
00581 fabs(delta.v[2]) > a_thresh_;
00582
00583
00584 if(update)
00585 for(unsigned int i=0; i < lasers_update_.size(); i++)
00586 lasers_update_[i] = true;
00587 }
00588
00589 bool force_publication = false;
00590 if(!pf_init_)
00591 {
00592
00593 pf_odom_pose_ = pose;
00594
00595
00596 pf_init_ = true;
00597
00598
00599 for(unsigned int i=0; i < lasers_update_.size(); i++)
00600 lasers_update_[i] = true;
00601
00602 force_publication = true;
00603
00604 resample_count_ = 0;
00605 }
00606
00607 else if(pf_init_ && lasers_update_[laser_index])
00608 {
00609
00610
00611
00612 AMCLOdomData odata;
00613 odata.pose = pose;
00614
00615
00616
00617 odata.delta = delta;
00618
00619
00620 odom_->UpdateAction(pf_, (AMCLSensorData*)&odata);
00621
00622
00623
00624 }
00625
00626 bool resampled = false;
00627
00628 if(lasers_update_[laser_index])
00629 {
00630 AMCLLaserData ldata;
00631 ldata.sensor = lasers_[laser_index];
00632 ldata.range_count = laser_scan->ranges.size();
00633
00634
00635
00636
00637
00638 tf::Quaternion q;
00639 q.setRPY(0.0, 0.0, laser_scan->angle_min);
00640 tf::Stamped<tf::Quaternion> min_q(q, laser_scan->header.stamp,
00641 laser_scan->header.frame_id);
00642 q.setRPY(0.0, 0.0, laser_scan->angle_min + laser_scan->angle_increment);
00643 tf::Stamped<tf::Quaternion> inc_q(q, laser_scan->header.stamp,
00644 laser_scan->header.frame_id);
00645 try
00646 {
00647 tf_->transformQuaternion(base_frame_id_, min_q, min_q);
00648 tf_->transformQuaternion(base_frame_id_, inc_q, inc_q);
00649 }
00650 catch(tf::TransformException& e)
00651 {
00652 ROS_WARN("Unable to transform min/max laser angles into base frame: %s",
00653 e.what());
00654 return;
00655 }
00656
00657 double angle_min = tf::getYaw(min_q);
00658 double angle_increment = tf::getYaw(inc_q) - angle_min;
00659
00660
00661 angle_increment = fmod(angle_increment + 5*M_PI, 2*M_PI) - M_PI;
00662
00663 ROS_DEBUG("Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min, angle_increment);
00664
00665
00666 if(laser_max_range_ > 0.0)
00667 ldata.range_max = std::min(laser_scan->range_max, (float)laser_max_range_);
00668 else
00669 ldata.range_max = laser_scan->range_max;
00670 double range_min;
00671 if(laser_min_range_ > 0.0)
00672 range_min = std::max(laser_scan->range_min, (float)laser_min_range_);
00673 else
00674 range_min = laser_scan->range_min;
00675
00676 ldata.ranges = new double[ldata.range_count][2];
00677 ROS_ASSERT(ldata.ranges);
00678 for(int i=0;i<ldata.range_count;i++)
00679 {
00680
00681
00682 if(laser_scan->ranges[i] <= range_min)
00683 ldata.ranges[i][0] = ldata.range_max;
00684 else
00685 ldata.ranges[i][0] = laser_scan->ranges[i];
00686
00687 ldata.ranges[i][1] = angle_min +
00688 (i * angle_increment);
00689 }
00690
00691 lasers_[laser_index]->UpdateSensor(pf_, (AMCLSensorData*)&ldata);
00692
00693 lasers_update_[laser_index] = false;
00694
00695 pf_odom_pose_ = pose;
00696
00697
00698 if(!(++resample_count_ % resample_interval_))
00699 {
00700 pf_update_resample(pf_);
00701 resampled = true;
00702 }
00703
00704 pf_sample_set_t* set = pf_->sets + pf_->current_set;
00705 ROS_DEBUG("Num samples: %d\n", set->sample_count);
00706
00707
00708
00709 geometry_msgs::PoseArray cloud_msg;
00710 cloud_msg.header.stamp = ros::Time::now();
00711 cloud_msg.header.frame_id = global_frame_id_;
00712 cloud_msg.poses.resize(set->sample_count);
00713 for(int i=0;i<set->sample_count;i++)
00714 {
00715 tf::poseTFToMsg(tf::Pose(tf::createQuaternionFromYaw(set->samples[i].pose.v[2]),
00716 btVector3(set->samples[i].pose.v[0],
00717 set->samples[i].pose.v[1], 0)),
00718 cloud_msg.poses[i]);
00719
00720 }
00721
00722 particlecloud_pub_.publish(cloud_msg);
00723 }
00724
00725 if(resampled || force_publication)
00726 {
00727
00728 double max_weight = 0.0;
00729 int max_weight_hyp = -1;
00730 std::vector<amcl_hyp_t> hyps;
00731 hyps.resize(pf_->sets[pf_->current_set].cluster_count);
00732 for(int hyp_count = 0;
00733 hyp_count < pf_->sets[pf_->current_set].cluster_count; hyp_count++)
00734 {
00735 double weight;
00736 pf_vector_t pose_mean;
00737 pf_matrix_t pose_cov;
00738 if (!pf_get_cluster_stats(pf_, hyp_count, &weight, &pose_mean, &pose_cov))
00739 {
00740 ROS_ERROR("Couldn't get stats on cluster %d", hyp_count);
00741 break;
00742 }
00743
00744 hyps[hyp_count].weight = weight;
00745 hyps[hyp_count].pf_pose_mean = pose_mean;
00746 hyps[hyp_count].pf_pose_cov = pose_cov;
00747
00748 if(hyps[hyp_count].weight > max_weight)
00749 {
00750 max_weight = hyps[hyp_count].weight;
00751 max_weight_hyp = hyp_count;
00752 }
00753 }
00754
00755 if(max_weight > 0.0)
00756 {
00757 ROS_DEBUG("Max weight pose: %.3f %.3f %.3f",
00758 hyps[max_weight_hyp].pf_pose_mean.v[0],
00759 hyps[max_weight_hyp].pf_pose_mean.v[1],
00760 hyps[max_weight_hyp].pf_pose_mean.v[2]);
00761
00762
00763
00764
00765
00766
00767
00768 geometry_msgs::PoseWithCovarianceStamped p;
00769
00770 p.header.frame_id = global_frame_id_;
00771 p.header.stamp = laser_scan->header.stamp;
00772
00773 p.pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
00774 p.pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
00775 tf::quaternionTFToMsg(tf::createQuaternionFromYaw(hyps[max_weight_hyp].pf_pose_mean.v[2]),
00776 p.pose.pose.orientation);
00777
00778 pf_sample_set_t* set = pf_->sets + pf_->current_set;
00779 for(int i=0; i<2; i++)
00780 {
00781 for(int j=0; j<2; j++)
00782 {
00783
00784
00785
00786 p.pose.covariance[6*i+j] = set->cov.m[i][j];
00787 }
00788 }
00789
00790
00791
00792 p.pose.covariance[6*3+3] = set->cov.m[2][2];
00793
00794
00795
00796
00797
00798
00799
00800
00801
00802
00803
00804 pose_pub_.publish(p);
00805 last_published_pose = p;
00806
00807 ROS_DEBUG("New pose: %6.3f %6.3f %6.3f",
00808 hyps[max_weight_hyp].pf_pose_mean.v[0],
00809 hyps[max_weight_hyp].pf_pose_mean.v[1],
00810 hyps[max_weight_hyp].pf_pose_mean.v[2]);
00811
00812
00813 tf::Stamped<tf::Pose> odom_to_map;
00814 try
00815 {
00816 tf::Transform tmp_tf(tf::createQuaternionFromYaw(hyps[max_weight_hyp].pf_pose_mean.v[2]),
00817 tf::Vector3(hyps[max_weight_hyp].pf_pose_mean.v[0],
00818 hyps[max_weight_hyp].pf_pose_mean.v[1],
00819 0.0));
00820 tf::Stamped<tf::Pose> tmp_tf_stamped (tmp_tf.inverse(),
00821 laser_scan->header.stamp,
00822 base_frame_id_);
00823 this->tf_->transformPose(odom_frame_id_,
00824 tmp_tf_stamped,
00825 odom_to_map);
00826 }
00827 catch(tf::TransformException)
00828 {
00829 ROS_DEBUG("Failed to subtract base to odom transform");
00830 pf_mutex_.unlock();
00831 return;
00832 }
00833
00834 latest_tf_ = tf::Transform(tf::Quaternion(odom_to_map.getRotation()),
00835 tf::Point(odom_to_map.getOrigin()));
00836 latest_tf_valid_ = true;
00837
00838
00839
00840 ros::Time transform_expiration = (laser_scan->header.stamp +
00841 transform_tolerance_);
00842 tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(),
00843 transform_expiration,
00844 global_frame_id_, odom_frame_id_);
00845 this->tfb_->sendTransform(tmp_tf_stamped);
00846 sent_first_transform_ = true;
00847 }
00848 else
00849 {
00850 ROS_ERROR("No pose!");
00851 }
00852 }
00853 else if(latest_tf_valid_)
00854 {
00855
00856
00857 ros::Time transform_expiration = (laser_scan->header.stamp +
00858 transform_tolerance_);
00859 tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(),
00860 transform_expiration,
00861 global_frame_id_, odom_frame_id_);
00862 this->tfb_->sendTransform(tmp_tf_stamped);
00863
00864
00865
00866 ros::Time now = ros::Time::now();
00867 if((save_pose_period.toSec() > 0.0) &&
00868 (now - save_pose_last_time) >= save_pose_period)
00869 {
00870
00871
00872
00873 tf::Pose map_pose = latest_tf_.inverse() * odom_pose;
00874 double yaw,pitch,roll;
00875 map_pose.getBasis().getEulerYPR(yaw, pitch, roll);
00876
00877 private_nh_.setParam("initial_pose_x", map_pose.getOrigin().x());
00878 private_nh_.setParam("initial_pose_y", map_pose.getOrigin().y());
00879 private_nh_.setParam("initial_pose_a", yaw);
00880 private_nh_.setParam("initial_cov_xx",
00881 last_published_pose.pose.covariance[6*0+0]);
00882 private_nh_.setParam("initial_cov_yy",
00883 last_published_pose.pose.covariance[6*1+1]);
00884 private_nh_.setParam("initial_cov_aa",
00885 last_published_pose.pose.covariance[6*3+3]);
00886 save_pose_last_time = now;
00887 }
00888 }
00889
00890 pf_mutex_.unlock();
00891 }
00892
00893 double
00894 AmclNode::getYaw(tf::Pose& t)
00895 {
00896 double yaw, pitch, roll;
00897 btMatrix3x3 mat = t.getBasis();
00898 mat.getEulerYPR(yaw,pitch,roll);
00899 return yaw;
00900 }
00901
00902 void
00903 AmclNode::initialPoseReceivedOld(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg)
00904 {
00905
00906 if(msg->header.frame_id == "")
00907 {
00908 ROS_WARN("Received initialpose message with header.frame_id == "". This behavior is deprecated; you should always set the frame_id");
00909 initialPoseReceived(msg);
00910 }
00911 }
00912
00913 void
00914 AmclNode::initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg)
00915 {
00916
00917
00918 tf::StampedTransform tx_odom;
00919 try
00920 {
00921 tf_->lookupTransform(base_frame_id_, ros::Time::now(),
00922 base_frame_id_, msg->header.stamp,
00923 global_frame_id_, tx_odom);
00924 }
00925 catch(tf::TransformException e)
00926 {
00927
00928
00929
00930
00931 if(sent_first_transform_)
00932 ROS_WARN("Failed to transform initial pose in time (%s)", e.what());
00933 tx_odom.setIdentity();
00934 }
00935
00936 tf::Pose pose_old, pose_new;
00937 tf::poseMsgToTF(msg->pose.pose, pose_old);
00938 pose_new = tx_odom.inverse() * pose_old;
00939
00940 ROS_INFO("Setting pose (%.6f): %.3f %.3f %.3f",
00941 ros::Time::now().toSec(),
00942 pose_new.getOrigin().x(),
00943 pose_new.getOrigin().y(),
00944 getYaw(pose_new));
00945
00946 pf_vector_t pf_init_pose_mean = pf_vector_zero();
00947 pf_init_pose_mean.v[0] = pose_new.getOrigin().x();
00948 pf_init_pose_mean.v[1] = pose_new.getOrigin().y();
00949 pf_init_pose_mean.v[2] = getYaw(pose_new);
00950 pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
00951
00952 for(int i=0; i<2; i++)
00953 {
00954 for(int j=0; j<2; j++)
00955 {
00956 pf_init_pose_cov.m[i][j] = msg->pose.covariance[6*i+j];
00957 }
00958 }
00959 pf_init_pose_cov.m[2][2] = msg->pose.covariance[6*3+3];
00960
00961 pf_mutex_.lock();
00962 pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
00963 pf_init_ = false;
00964 pf_mutex_.unlock();
00965 }