00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <costmap_2d/costmap_2d_ros.h>
00038 #include <sensor_msgs/point_cloud_conversion.h>
00039
00040 #include <limits>
00041
00042
00043 namespace costmap_2d {
00044
00045 double sign(double x){
00046 return x < 0.0 ? -1.0 : 1.0;
00047 }
00048
00049 Costmap2DROS::Costmap2DROS(std::string name, tf::TransformListener& tf) : name_(name), tf_(tf), costmap_(NULL),
00050 map_update_thread_(NULL), costmap_publisher_(NULL), stop_updates_(false),
00051 initialized_(true), stopped_(false), map_update_thread_shutdown_(false),
00052 save_debug_pgm_(false), map_initialized_(false), costmap_initialized_(false) {
00053 ros::NodeHandle private_nh("~/" + name);
00054 ros::NodeHandle g_nh;
00055
00056
00057 ros::NodeHandle prefix_nh;
00058 tf_prefix_ = tf::getPrefixParam(prefix_nh);
00059
00060 std::string map_type;
00061 private_nh.param("map_type", map_type, std::string("voxel"));
00062
00063 private_nh.param("publish_voxel_map", publish_voxel_, false);
00064
00065 if(publish_voxel_ && map_type == "voxel")
00066 voxel_pub_ = private_nh.advertise<costmap_2d::VoxelGrid>("voxel_grid", 1);
00067 else
00068 publish_voxel_ = false;
00069
00070 std::string topics_string;
00071
00072 private_nh.param("observation_sources", topics_string, std::string(""));
00073 ROS_INFO("Subscribed to Topics: %s", topics_string.c_str());
00074
00075 private_nh.param("global_frame", global_frame_, std::string("/map"));
00076
00077 global_frame_ = tf::resolve(tf_prefix_, global_frame_);
00078
00079 private_nh.param("robot_base_frame", robot_base_frame_, std::string("base_link"));
00080
00081 robot_base_frame_ = tf::resolve(tf_prefix_, robot_base_frame_);
00082
00083
00084 private_nh.param("save_debug_pgm", save_debug_pgm_, false);
00085
00086 bool static_map;
00087 unsigned int map_width, map_height;
00088 double map_resolution;
00089 double map_origin_x, map_origin_y;
00090
00091 private_nh.param("static_map", static_map, true);
00092
00093
00094 private_nh.param("rolling_window", rolling_window_, false);
00095
00096 double map_width_meters, map_height_meters;
00097 std::string map_topic;
00098 private_nh.param("map_topic", map_topic, std::string("map"));
00099 private_nh.param("width", map_width_meters, 10.0);
00100 private_nh.param("height", map_height_meters, 10.0);
00101 private_nh.param("resolution", map_resolution, 0.05);
00102 private_nh.param("origin_x", map_origin_x, 0.0);
00103 private_nh.param("origin_y", map_origin_y, 0.0);
00104 map_width = (unsigned int)(map_width_meters / map_resolution);
00105 map_height = (unsigned int)(map_height_meters / map_resolution);
00106
00107 if(static_map){
00108
00109 ROS_INFO("Requesting the map...\n");
00110 map_sub_ = g_nh.subscribe(map_topic, 1, &Costmap2DROS::incomingMap, this);
00111
00112 ros::Rate r(1.0);
00113 while(!map_initialized_ && ros::ok()){
00114 ros::spinOnce();
00115 ROS_INFO("Still waiting on map...\n");
00116 r.sleep();
00117 }
00118
00119
00120 bool user_map_params = false;
00121 user_map_params |= private_nh.hasParam("width");
00122 user_map_params |= private_nh.hasParam("height");
00123 user_map_params |= private_nh.hasParam("resolution");
00124 user_map_params |= private_nh.hasParam("origin_x");
00125 user_map_params |= private_nh.hasParam("origin_y");
00126
00127 if(user_map_params)
00128 ROS_WARN("You have set map parameters, but also requested to use the static map. Your parameters will be overwritten by those given by the map server");
00129
00130 {
00131
00132 boost::recursive_mutex::scoped_lock lock(map_data_lock_);
00133 map_width = (unsigned int)map_meta_data_.width;
00134 map_height = (unsigned int)map_meta_data_.height;
00135 map_resolution = map_meta_data_.resolution;
00136 map_origin_x = map_meta_data_.origin.position.x;
00137 map_origin_y = map_meta_data_.origin.position.y;
00138
00139 ROS_INFO("Received a %d X %d map at %f m/pix\n",
00140 map_width, map_height, map_resolution);
00141 }
00142
00143 }
00144
00145 ros::Time last_error = ros::Time::now();
00146 std::string tf_error;
00147
00148 while(!tf_.waitForTransform(global_frame_, robot_base_frame_, ros::Time(), ros::Duration(0.1), ros::Duration(0.01), &tf_error)){
00149 ros::spinOnce();
00150 if(last_error + ros::Duration(5.0) < ros::Time::now()){
00151 ROS_WARN("Waiting on transform from %s to %s to become available before running costmap, tf error: %s",
00152 robot_base_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());
00153 last_error = ros::Time::now();
00154 }
00155 }
00156
00157 private_nh.param("transform_tolerance", transform_tolerance_, 0.3);
00158
00159
00160 std::stringstream ss(topics_string);
00161
00162 double raytrace_range = 3.0;
00163 double obstacle_range = 2.5;
00164
00165 std::string source;
00166 while(ss >> source){
00167 ros::NodeHandle source_node(private_nh, source);
00168
00169 double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
00170 std::string topic, sensor_frame, data_type;
00171 source_node.param("topic", topic, source);
00172 source_node.param("sensor_frame", sensor_frame, std::string(""));
00173 source_node.param("observation_persistence", observation_keep_time, 0.0);
00174 source_node.param("expected_update_rate", expected_update_rate, 0.0);
00175 source_node.param("data_type", data_type, std::string("PointCloud"));
00176 source_node.param("min_obstacle_height", min_obstacle_height, 0.0);
00177 source_node.param("max_obstacle_height", max_obstacle_height, 2.0);
00178
00179 if(!(data_type == "PointCloud2" || data_type == "PointCloud" || data_type == "LaserScan")){
00180 ROS_FATAL("Only topics that use point clouds or laser scans are currently supported");
00181 throw std::runtime_error("Only topics that use point clouds or laser scans are currently supported");
00182 }
00183
00184
00185 bool clearing, marking;
00186 source_node.param("clearing", clearing, false);
00187 source_node.param("marking", marking, true);
00188
00189 std::string raytrace_range_param_name, obstacle_range_param_name;
00190 double source_raytrace_range, source_obstacle_range;
00191
00192
00193 if(!source_node.searchParam("obstacle_range", obstacle_range_param_name))
00194 source_obstacle_range = 2.5;
00195 else
00196 source_node.param(obstacle_range_param_name, source_obstacle_range, 2.5);
00197
00198
00199 if(!source_node.searchParam("raytrace_range", raytrace_range_param_name))
00200 source_raytrace_range = 3.0;
00201 else
00202 source_node.param(raytrace_range_param_name, source_raytrace_range, 3.0);
00203
00204
00205
00206 raytrace_range = std::max(raytrace_range, source_raytrace_range);
00207 obstacle_range = std::max(obstacle_range, source_obstacle_range);
00208
00209 ROS_DEBUG("Creating an observation buffer for source %s, topic %s, frame %s", source.c_str(), topic.c_str(), sensor_frame.c_str());
00210
00211
00212 observation_buffers_.push_back(boost::shared_ptr<ObservationBuffer>(new ObservationBuffer(topic, observation_keep_time,
00213 expected_update_rate, min_obstacle_height, max_obstacle_height, source_obstacle_range, source_raytrace_range, tf_, global_frame_, sensor_frame, transform_tolerance_)));
00214
00215
00216 if(marking)
00217 marking_buffers_.push_back(observation_buffers_.back());
00218
00219
00220 if(clearing)
00221 clearing_buffers_.push_back(observation_buffers_.back());
00222
00223 ROS_DEBUG("Created an observation buffer for source %s, topic %s, global frame: %s, expected update rate: %.2f, observation persistence: %.2f",
00224 source.c_str(), topic.c_str(), global_frame_.c_str(), expected_update_rate, observation_keep_time);
00225
00226
00227 if(data_type == "LaserScan"){
00228 boost::shared_ptr<message_filters::Subscriber<sensor_msgs::LaserScan> > sub(
00229 new message_filters::Subscriber<sensor_msgs::LaserScan>(g_nh, topic, 50));
00230
00231 boost::shared_ptr<tf::MessageFilter<sensor_msgs::LaserScan> > filter(
00232 new tf::MessageFilter<sensor_msgs::LaserScan>(*sub, tf_, global_frame_, 50));
00233 filter->registerCallback(boost::bind(&Costmap2DROS::laserScanCallback, this, _1, observation_buffers_.back()));
00234
00235 observation_subscribers_.push_back(sub);
00236 observation_notifiers_.push_back(filter);
00237
00238 observation_notifiers_.back()->setTolerance(ros::Duration(0.05));
00239 }
00240 else if(data_type == "PointCloud"){
00241 boost::shared_ptr<message_filters::Subscriber<sensor_msgs::PointCloud> > sub(
00242 new message_filters::Subscriber<sensor_msgs::PointCloud>(g_nh, topic, 50));
00243
00244 boost::shared_ptr<tf::MessageFilter<sensor_msgs::PointCloud> > filter(
00245 new tf::MessageFilter<sensor_msgs::PointCloud>(*sub, tf_, global_frame_, 50));
00246 filter->registerCallback(boost::bind(&Costmap2DROS::pointCloudCallback, this, _1, observation_buffers_.back()));
00247
00248 observation_subscribers_.push_back(sub);
00249 observation_notifiers_.push_back(filter);
00250 }
00251 else{
00252 boost::shared_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2> > sub(
00253 new message_filters::Subscriber<sensor_msgs::PointCloud2>(g_nh, topic, 50));
00254
00255 boost::shared_ptr<tf::MessageFilter<sensor_msgs::PointCloud2> > filter(
00256 new tf::MessageFilter<sensor_msgs::PointCloud2>(*sub, tf_, global_frame_, 50));
00257 filter->registerCallback(boost::bind(&Costmap2DROS::pointCloud2Callback, this, _1, observation_buffers_.back()));
00258
00259 observation_subscribers_.push_back(sub);
00260 observation_notifiers_.push_back(filter);
00261 }
00262
00263 if(sensor_frame != ""){
00264 std::vector<std::string> target_frames;
00265 target_frames.push_back(global_frame_);
00266 target_frames.push_back(sensor_frame);
00267 observation_notifiers_.back()->setTargetFrames(target_frames);
00268 }
00269
00270 }
00271
00272 double inscribed_radius, circumscribed_radius, inflation_radius;
00273 inscribed_radius = 0.46;
00274
00275 if(private_nh.hasParam("robot_radius")){
00276 private_nh.param("robot_radius", inscribed_radius, 0.46);
00277 }
00278
00279 circumscribed_radius = inscribed_radius;
00280 private_nh.param("inflation_radius", inflation_radius, 0.55);
00281
00282
00283 footprint_spec_ = loadRobotFootprint(private_nh, inscribed_radius, circumscribed_radius);
00284
00285 if(inscribed_radius > inflation_radius || circumscribed_radius > inflation_radius){
00286 ROS_WARN("You have set an inflation radius that is less than the inscribed and circumscribed radii of the robot. This is dangerous and could casue the robot to hit obstacles. Please change your inflation radius setting appropraitely.");
00287 }
00288
00289 if(footprint_spec_.size() > 2){
00290
00291 double min_dist = std::numeric_limits<double>::max();
00292 double max_dist = 0.0;
00293
00294 for(unsigned int i = 0; i < footprint_spec_.size() - 1; ++i){
00295
00296 double vertex_dist = distance(0.0, 0.0, footprint_spec_[i].x, footprint_spec_[i].y);
00297 double edge_dist = distanceToLine(0.0, 0.0, footprint_spec_[i].x, footprint_spec_[i].y, footprint_spec_[i+1].x, footprint_spec_[i+1].y);
00298 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
00299 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
00300 }
00301
00302
00303 double vertex_dist = distance(0.0, 0.0, footprint_spec_.back().x, footprint_spec_.back().y);
00304 double edge_dist = distanceToLine(0.0, 0.0, footprint_spec_.back().x, footprint_spec_.back().y, footprint_spec_.front().x, footprint_spec_.front().y);
00305 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
00306 max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
00307
00308 inscribed_radius = min_dist;
00309 circumscribed_radius = max_dist;
00310 }
00311
00312 double max_obstacle_height;
00313 private_nh.param("max_obstacle_height", max_obstacle_height, 2.0);
00314
00315 double cost_scale;
00316 private_nh.param("cost_scaling_factor", cost_scale, 10.0);
00317
00318 int temp_lethal_threshold, temp_unknown_cost_value;
00319 private_nh.param("lethal_cost_threshold", temp_lethal_threshold, int(100));
00320 private_nh.param("unknown_cost_value", temp_unknown_cost_value, int(0));
00321
00322 unsigned char lethal_threshold = std::max(std::min(temp_lethal_threshold, 255), 0);
00323 unsigned char unknown_cost_value = std::max(std::min(temp_unknown_cost_value, 255), 0);
00324
00325 bool track_unknown_space;
00326 private_nh.param("track_unknown_space", track_unknown_space, false);
00327
00328 struct timeval start, end;
00329 double start_t, end_t, t_diff;
00330 gettimeofday(&start, NULL);
00331 if(map_type == "costmap"){
00332
00333 boost::recursive_mutex::scoped_lock lock(map_data_lock_);
00334 costmap_ = new Costmap2D(map_width, map_height,
00335 map_resolution, map_origin_x, map_origin_y, inscribed_radius, circumscribed_radius, inflation_radius,
00336 obstacle_range, max_obstacle_height, raytrace_range, cost_scale, input_data_, lethal_threshold, track_unknown_space, unknown_cost_value);
00337 }
00338 else if(map_type == "voxel"){
00339
00340 int z_voxels;
00341 private_nh.param("z_voxels", z_voxels, 10);
00342
00343 double z_resolution, map_origin_z;
00344 private_nh.param("z_resolution", z_resolution, 0.2);
00345 private_nh.param("origin_z", map_origin_z, 0.0);
00346
00347 int unknown_threshold, mark_threshold;
00348 private_nh.param("unknown_threshold", unknown_threshold, z_voxels);
00349 private_nh.param("mark_threshold", mark_threshold, 0);
00350
00351 if(!(z_voxels >= 0 && unknown_threshold >= 0 && mark_threshold >= 0)){
00352 ROS_FATAL("Values for z_voxels, unknown_threshold, and mark_threshold parameters must be positive.");
00353 throw std::runtime_error("Values for z_voxels, unknown_threshold, and mark_threshold parameters must be positive.");
00354 }
00355
00356
00357 boost::recursive_mutex::scoped_lock lock(map_data_lock_);
00358 costmap_ = new VoxelCostmap2D(map_width, map_height, z_voxels, map_resolution, z_resolution, map_origin_x, map_origin_y, map_origin_z, inscribed_radius,
00359 circumscribed_radius, inflation_radius, obstacle_range, raytrace_range, cost_scale, input_data_, lethal_threshold, unknown_threshold, mark_threshold,
00360 unknown_cost_value);
00361 }
00362 else{
00363 ROS_FATAL("Unsuported map type");
00364 throw std::runtime_error("Unsuported map type");
00365 }
00366
00367 gettimeofday(&end, NULL);
00368 start_t = start.tv_sec + double(start.tv_usec) / 1e6;
00369 end_t = end.tv_sec + double(end.tv_usec) / 1e6;
00370 t_diff = end_t - start_t;
00371 ROS_DEBUG("New map construction time: %.9f", t_diff);
00372
00373 double map_publish_frequency;
00374 private_nh.param("publish_frequency", map_publish_frequency, 0.0);
00375
00376
00377 costmap_publisher_ = new Costmap2DPublisher(private_nh, map_publish_frequency, global_frame_);
00378 if(costmap_publisher_->active()){
00379 std::vector<geometry_msgs::Point> oriented_footprint;
00380 getOrientedFootprint(oriented_footprint);
00381 tf::Stamped<tf::Pose> global_pose;
00382 getRobotPose(global_pose);
00383 costmap_publisher_->updateCostmapData(*costmap_, oriented_footprint, global_pose);
00384 }
00385
00386
00387 double map_update_frequency;
00388 private_nh.param("update_frequency", map_update_frequency, 5.0);
00389 map_update_thread_ = new boost::thread(boost::bind(&Costmap2DROS::mapUpdateLoop, this, map_update_frequency));
00390
00391 costmap_initialized_ = true;
00392
00393 }
00394
00395 double Costmap2DROS::distanceToLine(double pX, double pY, double x0, double y0, double x1, double y1){
00396 double A = pX - x0;
00397 double B = pY - y0;
00398 double C = x1 - x0;
00399 double D = y1 - y0;
00400
00401 double dot = A * C + B * D;
00402 double len_sq = C * C + D * D;
00403 double param = dot / len_sq;
00404
00405 double xx,yy;
00406
00407 if(param < 0)
00408 {
00409 xx = x0;
00410 yy = y0;
00411 }
00412 else if(param > 1)
00413 {
00414 xx = x1;
00415 yy = y1;
00416 }
00417 else
00418 {
00419 xx = x0 + param * C;
00420 yy = y0 + param * D;
00421 }
00422
00423 return distance(pX,pY,xx,yy);
00424 }
00425
00426 std::vector<geometry_msgs::Point> Costmap2DROS::loadRobotFootprint(ros::NodeHandle node, double inscribed_radius, double circumscribed_radius){
00427 std::vector<geometry_msgs::Point> footprint;
00428 geometry_msgs::Point pt;
00429 double padding;
00430
00431 std::string padding_param, footprint_param;
00432 if(!node.searchParam("footprint_padding", padding_param))
00433 padding = 0.01;
00434 else
00435 node.param(padding_param, padding, 0.01);
00436
00437
00438 XmlRpc::XmlRpcValue footprint_list;
00439 if(node.searchParam("footprint", footprint_param)){
00440 node.getParam(footprint_param, footprint_list);
00441
00442 if(!(footprint_list.getType() == XmlRpc::XmlRpcValue::TypeArray && footprint_list.size() > 2)){
00443 ROS_FATAL("The footprint must be specified as list of lists on the parameter server with at least 3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
00444 throw std::runtime_error("The footprint must be specified as list of lists on the parameter server with at least 3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
00445 }
00446 for(int i = 0; i < footprint_list.size(); ++i){
00447
00448 XmlRpc::XmlRpcValue point = footprint_list[i];
00449 if(!(point.getType() == XmlRpc::XmlRpcValue::TypeArray && point.size() == 2)){
00450 ROS_FATAL("The footprint must be specified as list of lists on the parameter server eg: [[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
00451 throw std::runtime_error("The footprint must be specified as list of lists on the parameter server eg: [[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
00452 }
00453
00454
00455 if(!(point[0].getType() == XmlRpc::XmlRpcValue::TypeInt || point[0].getType() == XmlRpc::XmlRpcValue::TypeDouble)){
00456 ROS_FATAL("Values in the footprint specification must be numbers");
00457 throw std::runtime_error("Values in the footprint specification must be numbers");
00458 }
00459 pt.x = point[0].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(point[0]) : (double)(point[0]);
00460 pt.x += sign(pt.x) * padding;
00461
00462
00463 if(!(point[1].getType() == XmlRpc::XmlRpcValue::TypeInt || point[1].getType() == XmlRpc::XmlRpcValue::TypeDouble)){
00464 ROS_FATAL("Values in the footprint specification must be numbers");
00465 throw std::runtime_error("Values in the footprint specification must be numbers");
00466 }
00467 pt.y = point[1].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(point[1]) : (double)(point[1]);
00468 pt.y += sign(pt.y) * padding;
00469
00470 footprint.push_back(pt);
00471
00472 }
00473 }
00474 return footprint;
00475 }
00476
00477 Costmap2DROS::~Costmap2DROS(){
00478 map_update_thread_shutdown_ = true;
00479 if(map_update_thread_ != NULL){
00480 map_update_thread_->join();
00481 delete map_update_thread_;
00482 }
00483
00484 if(costmap_publisher_ != NULL){
00485 delete costmap_publisher_;
00486 }
00487
00488 if(costmap_ != NULL)
00489 delete costmap_;
00490 }
00491
00492 void Costmap2DROS::start(){
00493
00494 if(stopped_){
00495
00496 for(unsigned int i = 0; i < observation_subscribers_.size(); ++i){
00497 if(observation_subscribers_[i] != NULL)
00498 observation_subscribers_[i]->subscribe();
00499 }
00500 stopped_ = false;
00501 }
00502 for (unsigned int i=0; i < observation_buffers_.size(); ++i){
00503 if (observation_buffers_[i])
00504 observation_buffers_[i]->resetLastUpdated();
00505 }
00506 stop_updates_ = false;
00507
00508
00509 ros::Rate r(100.0);
00510 while(!initialized_)
00511 r.sleep();
00512 }
00513
00514 void Costmap2DROS::stop(){
00515 stop_updates_ = true;
00516
00517 for(unsigned int i = 0; i < observation_subscribers_.size(); ++i){
00518 if(observation_subscribers_[i] != NULL)
00519 observation_subscribers_[i]->unsubscribe();
00520 }
00521 initialized_ = false;
00522 stopped_ = true;
00523 }
00524
00525 void Costmap2DROS::addObservationBuffer(const boost::shared_ptr<ObservationBuffer>& buffer){
00526 if(buffer)
00527 observation_buffers_.push_back(buffer);
00528 }
00529
00530 void Costmap2DROS::laserScanCallback(const sensor_msgs::LaserScanConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer){
00531
00532 sensor_msgs::PointCloud2 cloud;
00533 cloud.header = message->header;
00534
00535
00536 try
00537 {
00538 projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, tf_);
00539 }
00540 catch (tf::TransformException &ex)
00541 {
00542 ROS_WARN ("High fidelity enabled, but TF returned a transform exception to frame %s: %s", global_frame_.c_str (), ex.what ());
00543 projector_.projectLaser(*message, cloud);
00544 }
00545
00546
00547 buffer->lock();
00548 buffer->bufferCloud(cloud);
00549 buffer->unlock();
00550 }
00551
00552 void Costmap2DROS::pointCloudCallback(const sensor_msgs::PointCloudConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer){
00553 sensor_msgs::PointCloud2 cloud2;
00554
00555 if(!sensor_msgs::convertPointCloudToPointCloud2(*message, cloud2)){
00556 ROS_ERROR("Failed to convert a PointCloud to a PointCloud2, dropping message");
00557 return;
00558 }
00559
00560
00561 buffer->lock();
00562 buffer->bufferCloud(cloud2);
00563 buffer->unlock();
00564 }
00565
00566 void Costmap2DROS::pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer){
00567
00568 buffer->lock();
00569 buffer->bufferCloud(*message);
00570 buffer->unlock();
00571 }
00572
00573 void Costmap2DROS::mapUpdateLoop(double frequency){
00574
00575 if(frequency == 0.0)
00576 return;
00577
00578 ros::NodeHandle nh;
00579 ros::Rate r(frequency);
00580 while(nh.ok() && !map_update_thread_shutdown_){
00581 struct timeval start, end;
00582 double start_t, end_t, t_diff;
00583 gettimeofday(&start, NULL);
00584 if(!stop_updates_){
00585 updateMap();
00586 initialized_ = true;
00587 }
00588 gettimeofday(&end, NULL);
00589 start_t = start.tv_sec + double(start.tv_usec) / 1e6;
00590 end_t = end.tv_sec + double(end.tv_usec) / 1e6;
00591 t_diff = end_t - start_t;
00592 ROS_DEBUG("Map update time: %.9f", t_diff);
00593
00594 r.sleep();
00595
00596 if(r.cycleTime() > ros::Duration(1 / frequency))
00597 ROS_WARN("Map update loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", frequency, r.cycleTime().toSec());
00598 }
00599 }
00600
00601 bool Costmap2DROS::getMarkingObservations(std::vector<Observation>& marking_observations) const {
00602 bool current = true;
00603
00604 for(unsigned int i = 0; i < marking_buffers_.size(); ++i){
00605 marking_buffers_[i]->lock();
00606 marking_buffers_[i]->getObservations(marking_observations);
00607 current = marking_buffers_[i]->isCurrent() && current;
00608 marking_buffers_[i]->unlock();
00609 }
00610 return current;
00611 }
00612
00613 bool Costmap2DROS::getClearingObservations(std::vector<Observation>& clearing_observations) const {
00614 bool current = true;
00615
00616 for(unsigned int i = 0; i < clearing_buffers_.size(); ++i){
00617 clearing_buffers_[i]->lock();
00618 clearing_buffers_[i]->getObservations(clearing_observations);
00619 current = clearing_buffers_[i]->isCurrent() && current;
00620 clearing_buffers_[i]->unlock();
00621 }
00622 return current;
00623 }
00624
00625
00626 void Costmap2DROS::updateMap(){
00627 tf::Stamped<tf::Pose> global_pose;
00628 if(!getRobotPose(global_pose))
00629 return;
00630
00631 double wx = global_pose.getOrigin().x();
00632 double wy = global_pose.getOrigin().y();
00633
00634 bool current = true;
00635 std::vector<Observation> observations, clearing_observations;
00636
00637
00638 current = current && getMarkingObservations(observations);
00639
00640
00641 current = current && getClearingObservations(clearing_observations);
00642
00643
00644 current_ = current;
00645
00646 boost::recursive_mutex::scoped_lock lock(lock_);
00647
00648 if(rolling_window_){
00649 double origin_x = wx - costmap_->getSizeInMetersX() / 2;
00650 double origin_y = wy - costmap_->getSizeInMetersY() / 2;
00651 costmap_->updateOrigin(origin_x, origin_y);
00652 }
00653 costmap_->updateWorld(wx, wy, observations, clearing_observations);
00654
00655
00656 clearRobotFootprint();
00657
00658 if(save_debug_pgm_)
00659 costmap_->saveMap(name_ + ".pgm");
00660
00661
00662 if(costmap_publisher_->active()){
00663 std::vector<geometry_msgs::Point> oriented_footprint;
00664 getOrientedFootprint(oriented_footprint);
00665 tf::Stamped<tf::Pose> global_pose;
00666 getRobotPose(global_pose);
00667 costmap_publisher_->updateCostmapData(*costmap_, oriented_footprint, global_pose);
00668 }
00669
00670 if(publish_voxel_){
00671 costmap_2d::VoxelGrid voxel_grid;
00672 ((VoxelCostmap2D*)costmap_)->getVoxelGridMessage(voxel_grid);
00673 voxel_grid.header.frame_id = global_frame_;
00674 voxel_grid.header.stamp = ros::Time::now();
00675 voxel_pub_.publish(voxel_grid);
00676 }
00677
00678 }
00679
00680 void Costmap2DROS::clearNonLethalWindow(double size_x, double size_y){
00681 tf::Stamped<tf::Pose> global_pose;
00682 if(!getRobotPose(global_pose))
00683 return;
00684
00685 double wx = global_pose.getOrigin().x();
00686 double wy = global_pose.getOrigin().y();
00687 lock_.lock();
00688 ROS_DEBUG("Clearing map in window");
00689 costmap_->clearNonLethal(wx, wy, size_x, size_y, true);
00690 lock_.unlock();
00691
00692
00693 updateMap();
00694 }
00695
00696 void Costmap2DROS::resetMapOutsideWindow(double size_x, double size_y){
00697 tf::Stamped<tf::Pose> global_pose;
00698 if(!getRobotPose(global_pose))
00699 return;
00700
00701 double wx = global_pose.getOrigin().x();
00702 double wy = global_pose.getOrigin().y();
00703 lock_.lock();
00704 ROS_DEBUG("Resetting map outside window");
00705 costmap_->resetMapOutsideWindow(wx, wy, size_x, size_y);
00706 lock_.unlock();
00707
00708
00709 updateMap();
00710
00711 }
00712
00713 void Costmap2DROS::getCostmapCopy(Costmap2D& costmap) const {
00714 boost::recursive_mutex::scoped_lock lock(lock_);
00715 costmap = *costmap_;
00716 }
00717
00718 void Costmap2DROS::incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map){
00719 if(!map_initialized_){
00720 initFromMap(*new_map);
00721 map_initialized_ = true;
00722 }
00723 else if(costmap_initialized_)
00724 updateStaticMap(*new_map);
00725 }
00726
00727 void Costmap2DROS::initFromMap(const nav_msgs::OccupancyGrid& map){
00728 boost::recursive_mutex::scoped_lock lock(map_data_lock_);
00729
00730
00731 unsigned int numCells = map.info.width * map.info.height;
00732 for(unsigned int i = 0; i < numCells; i++){
00733 input_data_.push_back((unsigned char) map.data[i]);
00734 }
00735
00736 map_meta_data_ = map.info;
00737 global_frame_ = tf::resolve(tf_prefix_, map.header.frame_id);
00738 }
00739
00740 void Costmap2DROS::updateStaticMap(const nav_msgs::OccupancyGrid& new_map){
00741 std::vector<unsigned char> new_map_data;
00742
00743 unsigned int numCells = new_map.info.width * new_map.info.height;
00744 for(unsigned int i = 0; i < numCells; i++){
00745 new_map_data.push_back((unsigned char) new_map.data[i]);
00746 }
00747
00748 double map_width = (unsigned int)new_map.info.width;
00749 double map_height = (unsigned int)new_map.info.height;
00750 double map_resolution = new_map.info.resolution;
00751 double map_origin_x = new_map.info.origin.position.x;
00752 double map_origin_y = new_map.info.origin.position.y;
00753
00754 if(fabs(map_resolution - costmap_->getResolution()) > 1e-6){
00755 ROS_ERROR("You cannot update a map with resolution: %.4f, with a new map that has resolution: %.4f",
00756 costmap_->getResolution(), map_resolution);
00757 return;
00758 }
00759
00760 if(fabs(new_map.info.origin.orientation.x) > 1e-6
00761 && fabs(new_map.info.origin.orientation.y) > 1e-6
00762 && fabs(new_map.info.origin.orientation.z) > 1e-6
00763 && (fabs(new_map.info.origin.orientation.w) > 1e-6 || fabs(new_map.info.origin.orientation.w - 1.0) > 1e-6)){
00764 ROS_ERROR("The costmap does not support origins that contain rotations. The origin must be aligned with the global_frame.");
00765 return;
00766 }
00767
00768 if(tf::resolve(tf_prefix_, new_map.header.frame_id) != tf::resolve(tf_prefix_, global_frame_)){
00769 std::string new_global_frame = tf::resolve(tf_prefix_, new_map.header.frame_id);
00770
00771 ROS_DEBUG("Map with a global_frame of: %s, updated with a new map that has a global frame of: %s, wiping map", global_frame_.c_str(), new_map.header.frame_id.c_str());
00772
00773
00774 for(unsigned int i = 0; i < observation_buffers_.size(); ++i){
00775 observation_buffers_[i]->lock();
00776 observation_buffers_[i]->setGlobalFrame(new_global_frame);
00777 observation_buffers_[i]->unlock();
00778 }
00779
00780
00781 boost::recursive_mutex::scoped_lock lock(lock_);
00782
00783
00784 costmap_->replaceFullMap(map_origin_x, map_origin_y, map_width, map_height, new_map_data);
00785
00786
00787 global_frame_ = new_global_frame;
00788
00789 return;
00790 }
00791
00792 boost::recursive_mutex::scoped_lock lock(lock_);
00793 costmap_->updateStaticMapWindow(map_origin_x, map_origin_y, map_width, map_height, new_map_data);
00794 }
00795
00796 void Costmap2DROS::getCostmapWindowCopy(double win_size_x, double win_size_y, Costmap2D& costmap) const {
00797 boost::recursive_mutex::scoped_lock lock(lock_);
00798 tf::Stamped<tf::Pose> global_pose;
00799 if(!getRobotPose(global_pose)){
00800 ROS_ERROR("Could not get a window of this costmap centered at the robot, because we failed to get the pose of the robot");
00801 return;
00802 }
00803 getCostmapWindowCopy(global_pose.getOrigin().x(), global_pose.getOrigin().y(), win_size_x, win_size_y, costmap);
00804 }
00805
00806 void Costmap2DROS::getCostmapWindowCopy(double win_center_x, double win_center_y, double win_size_x, double win_size_y, Costmap2D& costmap) const {
00807 boost::recursive_mutex::scoped_lock lock(lock_);
00808
00809
00810 double ll_x = std::min(std::max(win_center_x - win_size_x, costmap_->getOriginX()), costmap_->getSizeInMetersX());
00811 double ll_y = std::min(std::max(win_center_y - win_size_y, costmap_->getOriginY()), costmap_->getSizeInMetersY());
00812 double ur_x = std::min(std::max(win_center_x + win_size_x, costmap_->getOriginX()), costmap_->getSizeInMetersX());
00813 double ur_y = std::min(std::max(win_center_y + win_size_y, costmap_->getOriginY()), costmap_->getSizeInMetersY());
00814 double size_x = ur_x - ll_x;
00815 double size_y = ur_y - ll_y;
00816
00817
00818 costmap.copyCostmapWindow(*costmap_, ll_x, ll_y, size_x, size_y);
00819 }
00820
00821 unsigned int Costmap2DROS::getSizeInCellsX() const {
00822 boost::recursive_mutex::scoped_lock lock(lock_);
00823 return costmap_->getSizeInCellsX();
00824 }
00825
00826 unsigned int Costmap2DROS::getSizeInCellsY() const {
00827 boost::recursive_mutex::scoped_lock lock(lock_);
00828 return costmap_->getSizeInCellsY();
00829 }
00830
00831 double Costmap2DROS::getResolution() const {
00832 boost::recursive_mutex::scoped_lock lock(lock_);
00833 return costmap_->getResolution();
00834 }
00835
00836 bool Costmap2DROS::getRobotPose(tf::Stamped<tf::Pose>& global_pose) const {
00837 global_pose.setIdentity();
00838 tf::Stamped<tf::Pose> robot_pose;
00839 robot_pose.setIdentity();
00840 robot_pose.frame_id_ = robot_base_frame_;
00841 robot_pose.stamp_ = ros::Time();
00842 ros::Time current_time = ros::Time::now();
00843
00844
00845 try{
00846 tf_.transformPose(global_frame_, robot_pose, global_pose);
00847 }
00848 catch(tf::LookupException& ex) {
00849 ROS_ERROR("No Transform available Error: %s\n", ex.what());
00850 return false;
00851 }
00852 catch(tf::ConnectivityException& ex) {
00853 ROS_ERROR("Connectivity Error: %s\n", ex.what());
00854 return false;
00855 }
00856 catch(tf::ExtrapolationException& ex) {
00857 ROS_ERROR("Extrapolation Error: %s\n", ex.what());
00858 return false;
00859 }
00860
00861 if (current_time.toSec() - global_pose.stamp_.toSec() > transform_tolerance_) {
00862 ROS_WARN("Costmap2DROS transform timeout. Current time: %.4f, global_pose stamp: %.4f, tolerance: %.4f",
00863 current_time.toSec() ,global_pose.stamp_.toSec() ,transform_tolerance_);
00864 return false;
00865 }
00866
00867 return true;
00868 }
00869
00870 void Costmap2DROS::clearRobotFootprint(){
00871 tf::Stamped<tf::Pose> global_pose;
00872 if(!getRobotPose(global_pose))
00873 return;
00874
00875 clearRobotFootprint(global_pose);
00876 }
00877
00878 std::vector<geometry_msgs::Point> Costmap2DROS::getRobotFootprint() const {
00879 return footprint_spec_;
00880 }
00881
00882 void Costmap2DROS::getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint) const {
00883 tf::Stamped<tf::Pose> global_pose;
00884 if(!getRobotPose(global_pose))
00885 return;
00886
00887 double yaw = tf::getYaw(global_pose.getRotation());
00888
00889 getOrientedFootprint(global_pose.getOrigin().x(), global_pose.getOrigin().y(), yaw, oriented_footprint);
00890 }
00891
00892 void Costmap2DROS::getOrientedFootprint(double x, double y, double theta, std::vector<geometry_msgs::Point>& oriented_footprint) const {
00893
00894 double cos_th = cos(theta);
00895 double sin_th = sin(theta);
00896 for(unsigned int i = 0; i < footprint_spec_.size(); ++i){
00897 geometry_msgs::Point new_pt;
00898 new_pt.x = x + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th);
00899 new_pt.y = y + (footprint_spec_[i].x * sin_th + footprint_spec_[i].y * cos_th);
00900 oriented_footprint.push_back(new_pt);
00901 }
00902 }
00903
00904 bool Costmap2DROS::setConvexPolygonCost(const std::vector<geometry_msgs::Point>& polygon, unsigned char cost_value){
00905 lock_.lock();
00906 bool success = costmap_->setConvexPolygonCost(polygon, cost_value);
00907 lock_.unlock();
00908
00909
00910 updateMap();
00911
00912 return success;
00913 }
00914
00915 std::string Costmap2DROS::getGlobalFrameID() const {
00916 return global_frame_;
00917 }
00918
00919 std::string Costmap2DROS::getBaseFrameID() const {
00920 return robot_base_frame_;
00921 }
00922
00923 double Costmap2DROS::getInscribedRadius() const {
00924 boost::recursive_mutex::scoped_lock lock(lock_);
00925 return costmap_->getInscribedRadius();
00926 }
00927
00928 double Costmap2DROS::getCircumscribedRadius() const {
00929 boost::recursive_mutex::scoped_lock lock(lock_);
00930 return costmap_->getCircumscribedRadius();
00931 }
00932
00933 double Costmap2DROS::getInflationRadius() const {
00934 boost::recursive_mutex::scoped_lock lock(lock_);
00935 return costmap_->getInflationRadius();
00936 }
00937
00938 void Costmap2DROS::clearRobotFootprint(const tf::Stamped<tf::Pose>& global_pose){
00939 std::vector<geometry_msgs::Point> oriented_footprint;
00940
00941
00942 if(footprint_spec_.size() < 3){
00943
00944 double angle = 0;
00945 double step = 2 * M_PI / 72;
00946 while(angle < 2 * M_PI){
00947 geometry_msgs::Point pt;
00948 pt.x = getInscribedRadius() * cos(angle) + global_pose.getOrigin().x();
00949 pt.y = getInscribedRadius() * sin(angle) + global_pose.getOrigin().y();
00950 pt.z = 0.0;
00951 oriented_footprint.push_back(pt);
00952 angle += step;
00953 }
00954 }
00955 else{
00956 double yaw = tf::getYaw(global_pose.getRotation());
00957
00958
00959 double x = global_pose.getOrigin().x();
00960 double y = global_pose.getOrigin().y();
00961 double theta = yaw;
00962
00963
00964 getOrientedFootprint(x, y, theta, oriented_footprint);
00965 }
00966
00967
00968 boost::recursive_mutex::scoped_lock lock(lock_);
00969
00970
00971 if(!costmap_->setConvexPolygonCost(oriented_footprint, costmap_2d::FREE_SPACE))
00972 return;
00973
00974 double max_inflation_dist = 2 * (costmap_->getInflationRadius() + costmap_->getCircumscribedRadius());
00975
00976
00977 costmap_->clearNonLethal(global_pose.getOrigin().x(), global_pose.getOrigin().y(), max_inflation_dist, max_inflation_dist);
00978
00979
00980 costmap_->reinflateWindow(global_pose.getOrigin().x(), global_pose.getOrigin().y(),
00981 max_inflation_dist + 2 * costmap_->getInflationRadius(), max_inflation_dist + 2 * costmap_->getInflationRadius(), false);
00982
00983 }
00984
00985 };