costmap_2d_ros.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * Author: Eitan Marder-Eppstein
00036  *********************************************************************/
00037 #include <costmap_2d/costmap_2d_ros.h>
00038 #include <sensor_msgs/point_cloud_conversion.h>
00039 
00040 #include <limits>
00041 
00042 using namespace std;
00043 
00044 namespace costmap_2d {
00045 
00046   double sign(double x){
00047     return x < 0.0 ? -1.0 : 1.0;
00048   }
00049 
00050   Costmap2DROS::Costmap2DROS(std::string name, tf::TransformListener& tf) : name_(name), tf_(tf), costmap_(NULL), 
00051                              map_update_thread_(NULL), costmap_publisher_(NULL), stop_updates_(false), 
00052                              initialized_(true), stopped_(false), map_update_thread_shutdown_(false), 
00053                              save_debug_pgm_(false), map_initialized_(false), costmap_initialized_(false), 
00054                              robot_stopped_(false), setup_(false){
00055     ros::NodeHandle private_nh("~/" + name);
00056     ros::NodeHandle g_nh;
00057 
00058     //get our tf prefix
00059     ros::NodeHandle prefix_nh;
00060     tf_prefix_ = tf::getPrefixParam(prefix_nh);
00061 
00062     std::string map_type;
00063     private_nh.param("map_type", map_type, std::string("voxel"));
00064 
00065     private_nh.param("publish_voxel_map", publish_voxel_, false);
00066 
00067     if(publish_voxel_ && map_type == "voxel")
00068       voxel_pub_ = private_nh.advertise<costmap_2d::VoxelGrid>("voxel_grid", 1);
00069     else
00070       publish_voxel_ = false;
00071 
00072     std::string topics_string;
00073     //get the topics that we'll subscribe to from the parameter server
00074     private_nh.param("observation_sources", topics_string, std::string(""));
00075     ROS_INFO("Subscribed to Topics: %s", topics_string.c_str());
00076 
00077     private_nh.param("global_frame", global_frame_, std::string("/map"));
00078     //make sure that we set the global frame appropriately based on the tf_prefix
00079     global_frame_ = tf::resolve(tf_prefix_, global_frame_);
00080 
00081     private_nh.param("robot_base_frame", robot_base_frame_, std::string("base_link"));
00082     //make sure that we set the base frame appropriately based on the tf_prefix
00083     robot_base_frame_ = tf::resolve(tf_prefix_, robot_base_frame_);
00084 
00085     //check if the user wants to save pgms of the costmap for debugging
00086     private_nh.param("save_debug_pgm", save_debug_pgm_, false);
00087 
00088     bool static_map;
00089     unsigned int map_width, map_height;
00090     double map_resolution;
00091     double map_origin_x, map_origin_y;
00092 
00093     private_nh.param("static_map", static_map, true);
00094 
00095     //check if we want a rolling window version of the costmap
00096     private_nh.param("rolling_window", rolling_window_, false);
00097 
00098     double map_width_meters, map_height_meters;
00099     std::string map_topic;
00100     private_nh.param("map_topic", map_topic, std::string("map"));
00101     private_nh.param("width", map_width_meters, 10.0);
00102     private_nh.param("height", map_height_meters, 10.0);
00103     private_nh.param("resolution", map_resolution, 0.05);
00104     private_nh.param("origin_x", map_origin_x, 0.0);
00105     private_nh.param("origin_y", map_origin_y, 0.0);
00106     map_width = (unsigned int)(map_width_meters / map_resolution);
00107     map_height = (unsigned int)(map_height_meters / map_resolution);
00108 
00109     if(static_map){
00110       //we'll subscribe to the latched topic that the map server uses
00111       ROS_INFO("Requesting the map...\n");
00112       map_sub_ = g_nh.subscribe(map_topic, 1, &Costmap2DROS::incomingMap, this);
00113 
00114       ros::Rate r(1.0);
00115       while(!map_initialized_ && ros::ok()){
00116         ros::spinOnce();
00117         ROS_INFO("Still waiting on map...\n");
00118         r.sleep();
00119       }
00120 
00121       //check if the user has set any parameters that will be overwritten
00122       bool user_map_params = false;
00123       user_map_params |= private_nh.hasParam("width");
00124       user_map_params |= private_nh.hasParam("height");
00125       user_map_params |= private_nh.hasParam("resolution");
00126       user_map_params |= private_nh.hasParam("origin_x");
00127       user_map_params |= private_nh.hasParam("origin_y");
00128 
00129       if(user_map_params)
00130         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");
00131 
00132       {
00133         //lock just in case something weird is going on with the compiler or scheduler
00134         boost::recursive_mutex::scoped_lock lock(map_data_lock_);
00135         map_width = (unsigned int)map_meta_data_.width;
00136         map_height = (unsigned int)map_meta_data_.height;
00137         map_resolution = map_meta_data_.resolution;
00138         map_origin_x = map_meta_data_.origin.position.x;
00139         map_origin_y = map_meta_data_.origin.position.y;
00140 
00141         ROS_INFO("Received a %d X %d map at %f m/pix\n",
00142             map_width, map_height, map_resolution);
00143       }
00144 
00145     }
00146 
00147     ros::Time last_error = ros::Time::now();
00148     std::string tf_error;
00149     //we need to make sure that the transform between the robot base frame and the global frame is available
00150     while(ros::ok() && !tf_.waitForTransform(global_frame_, robot_base_frame_, ros::Time(), ros::Duration(0.1), ros::Duration(0.01), &tf_error)){
00151       ros::spinOnce();
00152       if(last_error + ros::Duration(5.0) < ros::Time::now()){
00153         ROS_WARN("Waiting on transform from %s to %s to become available before running costmap, tf error: %s", 
00154             robot_base_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());
00155         last_error = ros::Time::now();
00156       }
00157     }
00158 
00159     private_nh.param("transform_tolerance", transform_tolerance_, 0.3);
00160 
00161     //now we need to split the topics based on whitespace which we can use a stringstream for
00162     std::stringstream ss(topics_string);
00163 
00164     double raytrace_range = 3.0;
00165     double obstacle_range = 2.5;
00166 
00167     std::string source;
00168     while(ss >> source){
00169       ros::NodeHandle source_node(private_nh, source);
00170       //get the parameters for the specific topic
00171       double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
00172       std::string topic, sensor_frame, data_type;
00173       source_node.param("topic", topic, source);
00174       source_node.param("sensor_frame", sensor_frame, std::string(""));
00175       source_node.param("observation_persistence", observation_keep_time, 0.0);
00176       source_node.param("expected_update_rate", expected_update_rate, 0.0);
00177       source_node.param("data_type", data_type, std::string("PointCloud"));
00178       source_node.param("min_obstacle_height", min_obstacle_height, 0.0);
00179       source_node.param("max_obstacle_height", max_obstacle_height, 2.0);
00180 
00181       if(!(data_type == "PointCloud2" || data_type == "PointCloud" || data_type == "LaserScan")){
00182         ROS_FATAL("Only topics that use point clouds or laser scans are currently supported");
00183         throw std::runtime_error("Only topics that use point clouds or laser scans are currently supported");
00184       }
00185 
00186 
00187       bool clearing, marking;
00188       source_node.param("clearing", clearing, false);
00189       source_node.param("marking", marking, true);
00190 
00191       std::string raytrace_range_param_name, obstacle_range_param_name;
00192       double source_raytrace_range, source_obstacle_range;
00193 
00194       //get the obstacle range for the sensor
00195       if(!source_node.searchParam("obstacle_range", obstacle_range_param_name))
00196         source_obstacle_range = 2.5;
00197       else
00198         source_node.param(obstacle_range_param_name, source_obstacle_range, 2.5);
00199 
00200       //get the raytrace range for the sensor
00201       if(!source_node.searchParam("raytrace_range", raytrace_range_param_name))
00202         source_raytrace_range = 3.0;
00203       else
00204         source_node.param(raytrace_range_param_name, source_raytrace_range, 3.0);
00205 
00206 
00207       //keep track of the maximum raytrace range for the costmap to be able to inflate efficiently
00208       raytrace_range = std::max(raytrace_range, source_raytrace_range);
00209       obstacle_range = std::max(obstacle_range, source_obstacle_range);
00210 
00211       ROS_DEBUG("Creating an observation buffer for source %s, topic %s, frame %s", source.c_str(), topic.c_str(), sensor_frame.c_str());
00212 
00213       //create an observation buffer
00214       observation_buffers_.push_back(boost::shared_ptr<ObservationBuffer>(new ObservationBuffer(topic, observation_keep_time, 
00215               expected_update_rate, min_obstacle_height, max_obstacle_height, source_obstacle_range, source_raytrace_range, tf_, global_frame_, sensor_frame, transform_tolerance_)));
00216 
00217       //check if we'll add this buffer to our marking observation buffers
00218       if(marking)
00219         marking_buffers_.push_back(observation_buffers_.back());
00220 
00221       //check if we'll also add this buffer to our clearing observation buffers
00222       if(clearing)
00223         clearing_buffers_.push_back(observation_buffers_.back());
00224 
00225       ROS_DEBUG("Created an observation buffer for source %s, topic %s, global frame: %s, expected update rate: %.2f, observation persistence: %.2f", 
00226           source.c_str(), topic.c_str(), global_frame_.c_str(), expected_update_rate, observation_keep_time);
00227 
00228       //create a callback for the topic
00229       if(data_type == "LaserScan"){
00230         boost::shared_ptr<message_filters::Subscriber<sensor_msgs::LaserScan> > sub(
00231               new message_filters::Subscriber<sensor_msgs::LaserScan>(g_nh, topic, 50));
00232 
00233         boost::shared_ptr<tf::MessageFilter<sensor_msgs::LaserScan> > filter(
00234             new tf::MessageFilter<sensor_msgs::LaserScan>(*sub, tf_, global_frame_, 50));
00235         filter->registerCallback(boost::bind(&Costmap2DROS::laserScanCallback, this, _1, observation_buffers_.back()));
00236 
00237         observation_subscribers_.push_back(sub);
00238         observation_notifiers_.push_back(filter);
00239 
00240         observation_notifiers_.back()->setTolerance(ros::Duration(0.05));
00241       }
00242       else if(data_type == "PointCloud"){
00243         boost::shared_ptr<message_filters::Subscriber<sensor_msgs::PointCloud> > sub(
00244               new message_filters::Subscriber<sensor_msgs::PointCloud>(g_nh, topic, 50));
00245 
00246         boost::shared_ptr<tf::MessageFilter<sensor_msgs::PointCloud> > filter(
00247             new tf::MessageFilter<sensor_msgs::PointCloud>(*sub, tf_, global_frame_, 50));
00248         filter->registerCallback(boost::bind(&Costmap2DROS::pointCloudCallback, this, _1, observation_buffers_.back()));
00249 
00250         observation_subscribers_.push_back(sub);
00251         observation_notifiers_.push_back(filter);
00252       }
00253       else{
00254         boost::shared_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2> > sub(
00255               new message_filters::Subscriber<sensor_msgs::PointCloud2>(g_nh, topic, 50));
00256 
00257         boost::shared_ptr<tf::MessageFilter<sensor_msgs::PointCloud2> > filter(
00258             new tf::MessageFilter<sensor_msgs::PointCloud2>(*sub, tf_, global_frame_, 50));
00259         filter->registerCallback(boost::bind(&Costmap2DROS::pointCloud2Callback, this, _1, observation_buffers_.back()));
00260 
00261         observation_subscribers_.push_back(sub);
00262         observation_notifiers_.push_back(filter);
00263       }
00264 
00265       if(sensor_frame != ""){
00266         std::vector<std::string> target_frames;
00267         target_frames.push_back(global_frame_);
00268         target_frames.push_back(sensor_frame);
00269         observation_notifiers_.back()->setTargetFrames(target_frames);
00270       }
00271 
00272     }
00273 
00274     double inscribed_radius, circumscribed_radius, inflation_radius;
00275     inscribed_radius = 0.46;
00276 
00277     if(private_nh.hasParam("robot_radius")){
00278       private_nh.param("robot_radius", inscribed_radius, 0.46);
00279     }
00280 
00281     circumscribed_radius = inscribed_radius;
00282     private_nh.param("inflation_radius", inflation_radius, 0.55);
00283 
00284     //load the robot footprint from the parameter server if its available in the global namespace
00285     footprint_spec_ = loadRobotFootprint(private_nh, inscribed_radius, circumscribed_radius);
00286 
00287     if(inscribed_radius > inflation_radius || circumscribed_radius > inflation_radius){
00288       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.");
00289     }
00290 
00291     if(footprint_spec_.size() > 2){
00292       //now we need to compute the inscribed/circumscribed radius of the robot from the footprint specification
00293       double min_dist = std::numeric_limits<double>::max();
00294       double max_dist = 0.0;
00295 
00296       for(unsigned int i = 0; i < footprint_spec_.size() - 1; ++i){
00297         //check the distance from the robot center point to the first vertex
00298         double vertex_dist = distance(0.0, 0.0, footprint_spec_[i].x, footprint_spec_[i].y);
00299         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);
00300         min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
00301         max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
00302       }
00303 
00304       //we also need to do the last vertex and the first vertex
00305       double vertex_dist = distance(0.0, 0.0, footprint_spec_.back().x, footprint_spec_.back().y);
00306       double edge_dist = distanceToLine(0.0, 0.0, footprint_spec_.back().x, footprint_spec_.back().y, footprint_spec_.front().x, footprint_spec_.front().y);
00307       min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
00308       max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
00309 
00310       inscribed_radius = min_dist;
00311       circumscribed_radius = max_dist;
00312     }
00313 
00314     double max_obstacle_height;
00315     private_nh.param("max_obstacle_height", max_obstacle_height, 2.0);
00316 
00317     double cost_scale;
00318     private_nh.param("cost_scaling_factor", cost_scale, 10.0);
00319 
00320     int temp_lethal_threshold, temp_unknown_cost_value;
00321     private_nh.param("lethal_cost_threshold", temp_lethal_threshold, int(100));
00322     private_nh.param("unknown_cost_value", temp_unknown_cost_value, int(0));
00323 
00324     unsigned char lethal_threshold = std::max(std::min(temp_lethal_threshold, 255), 0);
00325     unsigned char unknown_cost_value = std::max(std::min(temp_unknown_cost_value, 255), 0);
00326 
00327     bool track_unknown_space;
00328     private_nh.param("track_unknown_space", track_unknown_space, false);
00329 
00330     struct timeval start, end;
00331     double start_t, end_t, t_diff;
00332     gettimeofday(&start, NULL);
00333     if(map_type == "costmap"){
00334       //make sure to lock the map data
00335       boost::recursive_mutex::scoped_lock lock(map_data_lock_);
00336       costmap_ = new Costmap2D(map_width, map_height,
00337           map_resolution, map_origin_x, map_origin_y, inscribed_radius, circumscribed_radius, inflation_radius,
00338           obstacle_range, max_obstacle_height, raytrace_range, cost_scale, input_data_, lethal_threshold, track_unknown_space, unknown_cost_value);
00339     }
00340     else if(map_type == "voxel"){
00341 
00342       int z_voxels;
00343       private_nh.param("z_voxels", z_voxels, 10);
00344 
00345       double z_resolution, map_origin_z;
00346       private_nh.param("z_resolution", z_resolution, 0.2);
00347       private_nh.param("origin_z", map_origin_z, 0.0);
00348 
00349       int unknown_threshold, mark_threshold;
00350       private_nh.param("unknown_threshold", unknown_threshold, z_voxels);
00351       private_nh.param("mark_threshold", mark_threshold, 0);
00352 
00353       if(!(z_voxels >= 0 && unknown_threshold >= 0 && mark_threshold >= 0)){
00354         ROS_FATAL("Values for z_voxels, unknown_threshold, and mark_threshold parameters must be positive.");
00355         throw std::runtime_error("Values for z_voxels, unknown_threshold, and mark_threshold parameters must be positive.");
00356       }
00357 
00358       boost::recursive_mutex::scoped_lock lock(map_data_lock_);
00359       costmap_ = new VoxelCostmap2D(map_width, map_height, z_voxels, map_resolution, z_resolution, map_origin_x, map_origin_y, map_origin_z, inscribed_radius,
00360           circumscribed_radius, inflation_radius, obstacle_range, raytrace_range, cost_scale, input_data_, lethal_threshold, unknown_threshold, mark_threshold,
00361           unknown_cost_value);
00362     }
00363     else{
00364       ROS_FATAL("Unsuported map type");
00365       throw std::runtime_error("Unsuported map type");
00366     }
00367 
00368     gettimeofday(&end, NULL);
00369     start_t = start.tv_sec + double(start.tv_usec) / 1e6;
00370     end_t = end.tv_sec + double(end.tv_usec) / 1e6;
00371     t_diff = end_t - start_t;
00372     ROS_DEBUG("New map construction time: %.9f", t_diff);
00373 
00374     double map_publish_frequency;
00375     private_nh.param("publish_frequency", map_publish_frequency, 0.0);
00376 
00377     //create a publisher for the costmap if desired
00378     costmap_publisher_ = new Costmap2DPublisher(private_nh, map_publish_frequency, global_frame_);
00379     if(costmap_publisher_->active()){
00380       std::vector<geometry_msgs::Point> oriented_footprint;
00381       getOrientedFootprint(oriented_footprint);
00382       tf::Stamped<tf::Pose> global_pose;
00383       getRobotPose(global_pose);
00384       costmap_publisher_->updateCostmapData(*costmap_, oriented_footprint, global_pose);
00385     }
00386 
00387     //create a thread to handle updating the map
00388     double map_update_frequency;
00389     private_nh.param("update_frequency", map_update_frequency, 5.0);
00390     map_update_thread_ = new boost::thread(boost::bind(&Costmap2DROS::mapUpdateLoop, this, map_update_frequency));
00391 
00392     costmap_initialized_ = true;
00393     
00394     //Create a time r to check if the robot is moving
00395     timer_ = private_nh.createTimer(ros::Duration(.1), &Costmap2DROS::movementCB, this);
00396     dsrv_ = new dynamic_reconfigure::Server<Costmap2DConfig>(ros::NodeHandle("~/"+name));
00397     dynamic_reconfigure::Server<Costmap2DConfig>::CallbackType cb = boost::bind(&Costmap2DROS::reconfigureCB, this, _1, _2);
00398     dsrv_->setCallback(cb);
00399   }
00400 
00401   void Costmap2DROS::movementCB(const ros::TimerEvent &event) {
00402     //don't allow configuration to happen while this check occurs
00403     boost::recursive_mutex::scoped_lock mcl(configuration_mutex_);
00404 
00405     tf::Stamped<tf::Pose> new_pose;
00406 
00407     if(!getRobotPose(new_pose)){
00408       ROS_WARN_THROTTLE(1.0, "Could not get robot pose, cancelling reconfiguration");
00409       robot_stopped_ = false;
00410     }
00411     //make sure that the robot is not moving 
00412     else if(fabs((old_pose_.getOrigin() - new_pose.getOrigin()).length()) < 1e-3 && fabs(old_pose_.getRotation().angle(new_pose.getRotation())) < 1e-3)
00413     {
00414       old_pose_ = new_pose;
00415       robot_stopped_ = true;
00416     }
00417     else
00418     {
00419       old_pose_ = new_pose; 
00420       robot_stopped_ = false;
00421     }
00422   }
00423 
00424   void Costmap2DROS::reconfigureCB(Costmap2DConfig &config, uint32_t level) {
00425     ros::NodeHandle nh = ros::NodeHandle("~/"+name_);
00426     
00427     if(setup_ && config.restore_defaults) {
00428       config = default_config_;
00429       //in case someone set restore_defaults on the parameter server, avoid looping
00430       config.restore_defaults = false;
00431     }
00432 
00433     //change the configuration defaults to match the param server
00434     if(!setup_) {
00435       boost::recursive_mutex::scoped_lock rel(configuration_mutex_);
00436 
00437       last_config_ = config;
00438       maptype_config_ = config;
00439       default_config_ = config;
00440 
00441       setup_ = true;
00442     }
00443     else if(setup_ && robot_stopped_) {
00444       //lock before modifying anything
00445       boost::recursive_mutex::scoped_lock rel(configuration_mutex_);
00446 
00447       transform_tolerance_ = config.transform_tolerance;
00448 
00449       // shutdown and restart the map update loop at a new frequency
00450       map_update_thread_shutdown_ = true;
00451       map_update_thread_->join();
00452       boost::mutex::scoped_lock ml(map_update_mutex_);
00453 
00454       //check and configure a new robot footprint
00455       //accepts a lis of points formatted [[x1, y1],[x2,y2],....[xn,yn]]
00456       string footprint_string = config.footprint;
00457       boost::erase_all(footprint_string, " ");
00458       boost::char_separator<char> sep("[]");
00459       boost::tokenizer<boost::char_separator<char> > tokens(footprint_string, sep);
00460       vector<string> points(tokens.begin(), tokens.end());
00461 
00462       //parse the input string into points
00463       vector<geometry_msgs::Point> footprint_spec;
00464       bool circular = false;
00465       bool valid_foot = true;
00466 
00467       if(points.size() >= 5) {
00468         BOOST_FOREACH(string t, tokens) {
00469           if (t != ",") {
00470             boost::erase_all(t, " ");
00471             boost::char_separator<char> pt_sep(",");
00472             boost::tokenizer<boost::char_separator<char> > pt_tokens(t, pt_sep);
00473             std::vector<string> point(pt_tokens.begin(), pt_tokens.end());
00474 
00475             if(point.size() != 2) {
00476               ROS_WARN("Each point must have exactly 2 coordinates");
00477               valid_foot = false;
00478               break;
00479             }
00480 
00481             vector<double>tmp_pt;
00482             BOOST_FOREACH(string p, point) {
00483               istringstream iss(p);
00484               double temp;
00485               if(iss >> temp) {
00486                 tmp_pt.push_back(temp);
00487               }
00488               else {
00489                 ROS_WARN("Each coordinate must convert to a double.");
00490                 valid_foot = false;
00491                 break;
00492               }
00493             }
00494             if(!valid_foot)
00495               break;
00496 
00497             geometry_msgs::Point pt;
00498             pt.x = tmp_pt[0];
00499             pt.y = tmp_pt[1];
00500 
00501             footprint_spec.push_back(pt);
00502           }
00503         }
00504         if (valid_foot) {
00505           footprint_spec_ = footprint_spec;
00506         }
00507       }
00508       //clear the footprint for a circular robot
00509       else if((footprint_string == "[]" || footprint_string == "") && config.robot_radius > 0.0) {
00510         footprint_spec_ = vector<geometry_msgs::Point>();
00511         circular = true;
00512       }
00513       else if(config.footprint != last_config_.footprint) {
00514         ROS_ERROR("You must specify at least three points for the robot footprint, reverting to previous footprint");
00515         config.footprint = last_config_.footprint;
00516       }
00517       
00518       if(!valid_foot) {
00519         ROS_FATAL("The footprint must be specified as a list of at least three points, you specified %s", footprint_string.c_str());
00520         config.footprint = last_config_.footprint;
00521       }
00522 
00523       double inscribed_radius, circumscribed_radius;
00524       inscribed_radius = config.robot_radius;
00525       circumscribed_radius = inscribed_radius;
00526 
00527       //if we have a footprint, recaclulate the radii
00528       if(footprint_spec_.size() > 2){
00529         //now we need to compute the inscribed/circumscribed radius of the robot from the footprint specification
00530         double min_dist = std::numeric_limits<double>::max();
00531         double max_dist = 0.0;
00532 
00533         for(unsigned int i = 0; i < footprint_spec_.size() - 1; ++i){
00534           //check the distance from the robot center point to the first vertex
00535           double vertex_dist = distance(0.0, 0.0, footprint_spec_[i].x, footprint_spec_[i].y);
00536           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);
00537           min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
00538           max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
00539         }
00540 
00541 
00542         //we also need to do the last vertex and the first vertex
00543         double vertex_dist = distance(0.0, 0.0, footprint_spec_.back().x, footprint_spec_.back().y);
00544         double edge_dist = distanceToLine(0.0, 0.0, footprint_spec_.back().x, footprint_spec_.back().y, footprint_spec_.front().x, footprint_spec_.front().y);
00545         min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
00546         max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist));
00547 
00548         inscribed_radius = min_dist;
00549         circumscribed_radius = max_dist;
00550       }
00551       if(inscribed_radius > config.inflation_radius || circumscribed_radius > config.inflation_radius){
00552         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.");
00553       }
00554 
00555       //if both static map and rolling window are set, we'll use static map and warn
00556       if(config.static_map && config.rolling_window){
00557         ROS_WARN("You have selected both rolling window and static map, using static_map");
00558         config.rolling_window = false;
00559       }
00560 
00561       //check to see if the map needs to be regenerated
00562       //TODO: Make sure that this check actually does the right things
00563       bool user_params = false;
00564       bool map_params = false;
00565       if(config.max_obstacle_height != last_config_.max_obstacle_height ||
00566          config.max_obstacle_range != last_config_.max_obstacle_range ||
00567          config.raytrace_range != last_config_.raytrace_range ||
00568          config.cost_scaling_factor != last_config_.cost_scaling_factor ||
00569          config.inflation_radius != last_config_.inflation_radius ||
00570          config.footprint != last_config_.footprint ||
00571          config.robot_radius != last_config_.robot_radius ||
00572          config.static_map != last_config_.static_map ||
00573          config.rolling_window != last_config_.rolling_window ||
00574          config.unknown_cost_value != last_config_.unknown_cost_value ||
00575          config.width != last_config_.width ||
00576          config.height != last_config_.height ||
00577          config.resolution != last_config_.resolution ||
00578          config.origin_x != last_config_.origin_x ||
00579          config.origin_y != last_config_.origin_y ||
00580          config.lethal_cost_threshold != last_config_.lethal_cost_threshold ||
00581          config.map_topic != last_config_.map_topic ||
00582          config.origin_z != last_config_.origin_z ||
00583          config.z_resolution != last_config_.z_resolution ||
00584          config.unknown_threshold != last_config_.unknown_threshold ||
00585          config.mark_threshold != last_config_.mark_threshold ||
00586          config.track_unknown_space != last_config_.track_unknown_space ||
00587          config.map_type != last_config_.map_type ||
00588          config.static_map != last_config_.static_map ||
00589          config.rolling_window != last_config_.rolling_window)
00590       {
00591         user_params = true;
00592       }
00593 
00594       if(config.width != last_config_.width ||
00595          config.height != last_config_.height ||
00596          config.resolution != last_config_.resolution ||
00597          config.origin_x != last_config_.origin_x ||
00598          config.origin_y != last_config_.origin_y)
00599       {
00600         map_params = true;
00601       }
00602 
00603       if(user_params) {
00604         //unmangle rolling_window and static map
00605         //both can be false but if one is true then the other is not
00606         if(!config.static_map && !config.rolling_window){
00607           rolling_window_ = false;
00608           static_map_ = false;
00609 
00610           if(last_config_.static_map)
00611           {
00612             map_sub_.shutdown();
00613             map_initialized_ = false;
00614           }
00615         }
00616         else if(config.static_map) {
00617           static_map_ = true;
00618           rolling_window_ = false;
00619 
00620           //we'll subscribe to the latched topic that the map server uses
00621           ros::NodeHandle g_nh;
00622           map_sub_.shutdown();
00623           map_initialized_ = false;
00624           map_sub_ = g_nh.subscribe(config.map_topic, 1, &Costmap2DROS::incomingMap, this);
00625           ROS_INFO("Requesting new map on topic %s\n", map_sub_.getTopic().c_str());
00626 
00627           ros::Rate r(1.0);
00628           while(!map_initialized_ && ros::ok()){
00629             ros::spinOnce();
00630             ROS_INFO("Still waiting on new map...\n");
00631             r.sleep();
00632           }
00633         }
00634         else if(config.rolling_window) {
00635           rolling_window_ = true;
00636           static_map_ = false;
00637 
00638           if(last_config_.static_map)
00639           {
00640             map_sub_.shutdown();
00641             map_initialized_ = false;
00642           }
00643         }
00644 
00645         //make sure to lock before we start messing with the map
00646         boost::recursive_mutex::scoped_lock mdl(map_data_lock_);
00647 
00648         if(!config.static_map && last_config_.static_map) {
00649           config.width = maptype_config_.width;
00650           config.height = maptype_config_.height;
00651           config.resolution = maptype_config_.resolution;
00652           config.origin_x = maptype_config_.origin_x;
00653           config.origin_y = maptype_config_.origin_y;
00654 
00655           maptype_config_ = last_config_;
00656         }
00657 
00658 
00659         unsigned int size_x, size_y;
00660         size_x = ceil(config.width/config.resolution);
00661         size_y = ceil(config.height/config.resolution);
00662         double resolution = config.resolution;
00663         double origin_x = config.origin_x;
00664         double origin_y = config.origin_y;
00665 
00666         if(config.static_map)
00667         {
00668           if(map_params)
00669           {
00670             ROS_WARN("You're trying to change parameters that will be overwritten since static_map is set. Your changes will have no effect");
00671           }
00672 
00673           size_x = (unsigned int)map_meta_data_.width;
00674           size_y = (unsigned int)map_meta_data_.height;
00675           resolution = map_meta_data_.resolution;
00676           origin_x = map_meta_data_.origin.position.x;
00677           origin_y = map_meta_data_.origin.position.y;
00678 
00679           config.width = size_x;
00680           config.height = size_y;
00681           config.resolution = resolution;
00682           config.origin_x = origin_x;
00683           config.origin_y = origin_y;
00684 
00685           ROS_INFO("Received a %d X %d map at %f m/pix\n",
00686               size_x, size_y, resolution);
00687         }
00688 
00689         if(config.map_type == "voxel") {
00690           unsigned int z_voxels;
00691           unsigned char lethal_threshold, unknown_cost_value;
00692           unsigned int unknown_threshold, mark_threshold;
00693 
00694           z_voxels = config.z_voxels;
00695 
00696           lethal_threshold = config.lethal_cost_threshold;
00697           unknown_threshold = config.unknown_threshold;
00698           mark_threshold = config.mark_threshold;
00699 
00700           unknown_cost_value = config.unknown_cost_value;
00701 
00702           VoxelCostmap2D *new_map = new VoxelCostmap2D(size_x, size_y, z_voxels, 
00703                          resolution, config.z_resolution, origin_x, origin_y, config.origin_z, 
00704                          inscribed_radius, circumscribed_radius, config.inflation_radius, 
00705                          config.max_obstacle_range, config.raytrace_range, config.cost_scaling_factor, 
00706                          input_data_, lethal_threshold, unknown_threshold, mark_threshold, unknown_cost_value);
00707           delete costmap_;
00708           costmap_ = new_map;
00709         }
00710         else if(config.map_type == "costmap") {
00711           unsigned char lethal_threshold, unknown_cost_value;
00712 
00713           lethal_threshold = config.lethal_cost_threshold;
00714           unknown_cost_value = config.unknown_cost_value;
00715          
00716           Costmap2D *new_map = new Costmap2D(size_x, size_y, resolution, origin_x, origin_y,
00717                   inscribed_radius, circumscribed_radius, config.inflation_radius,
00718                   config.max_obstacle_range, config.max_obstacle_height, config.raytrace_range, config.cost_scaling_factor, 
00719                   input_data_, lethal_threshold, config.track_unknown_space, unknown_cost_value);
00720           delete costmap_;
00721           costmap_ = new_map;
00722         }
00723       }
00724 
00725       if(config.map_type == "voxel" && config.publish_voxel_map) {
00726         publish_voxel_ = true;
00727         if(voxel_pub_ == NULL) {
00728           ros::NodeHandle nh("~/" + name_);
00729           voxel_pub_ = nh.advertise<costmap_2d::VoxelGrid>("voxel_grid", 1);
00730         }
00731       }
00732       else {
00733         publish_voxel_ = false;
00734         config.publish_voxel_map = false;
00735       }
00736 
00737       //make sure that nothing else is modifying the costmap while we reconfigure it
00738       boost::recursive_mutex::scoped_lock lock(lock_);
00739 
00740       //reconfigure the underlying costmap 
00741       costmap_->reconfigure(config, last_config_);
00742 
00743       if(config.publish_frequency != last_config_.publish_frequency)
00744       {
00745         double map_publish_frequency = config.publish_frequency;
00746         delete costmap_publisher_;
00747         costmap_publisher_ = new Costmap2DPublisher(ros::NodeHandle("~/"+name_), map_publish_frequency, global_frame_);
00748       }
00749 
00750       //once all configuration is done, restart the map update loop
00751       delete map_update_thread_;
00752       map_update_thread_shutdown_ = false;
00753       double map_update_frequency = config.update_frequency;
00754       map_update_thread_ = new boost::thread(boost::bind(&Costmap2DROS::mapUpdateLoop, this, map_update_frequency));
00755 
00756       last_config_ = config;
00757     }
00758     else {
00759       if(setup_)
00760       {
00761         ROS_WARN("You cannot reconfigure the costmap unless the robot is stopped");
00762       }
00763       config = last_config_;
00764     }
00765   }
00766 
00767   double Costmap2DROS::distanceToLine(double pX, double pY, double x0, double y0, double x1, double y1){
00768     double A = pX - x0;
00769     double B = pY - y0;
00770     double C = x1 - x0;
00771     double D = y1 - y0;
00772 
00773     double dot = A * C + B * D;
00774     double len_sq = C * C + D * D;
00775     double param = dot / len_sq;
00776 
00777     double xx,yy;
00778 
00779     if(param < 0)
00780     {
00781       xx = x0;
00782       yy = y0;
00783     }
00784     else if(param > 1)
00785     {
00786       xx = x1;
00787       yy = y1;
00788     }
00789     else
00790     {
00791       xx = x0 + param * C;
00792       yy = y0 + param * D;
00793     }
00794 
00795     return distance(pX,pY,xx,yy);
00796   }
00797 
00798   std::vector<geometry_msgs::Point> Costmap2DROS::loadRobotFootprint(ros::NodeHandle node, double inscribed_radius, double circumscribed_radius){
00799     std::vector<geometry_msgs::Point> footprint;
00800     geometry_msgs::Point pt;
00801     double padding;
00802 
00803     std::string padding_param, footprint_param;
00804     if(!node.searchParam("footprint_padding", padding_param))
00805       padding = 0.01;
00806     else
00807       node.param(padding_param, padding, 0.01);
00808 
00809     //grab the footprint from the parameter server if possible
00810     XmlRpc::XmlRpcValue footprint_list;
00811     std::string footprint_string;
00812     std::vector<string> footstring_list;
00813     if(node.searchParam("footprint", footprint_param)){
00814       node.getParam(footprint_param, footprint_list);
00815       if(footprint_list.getType() == XmlRpc::XmlRpcValue::TypeString) {
00816         footprint_string = std::string(footprint_list);
00817 
00818         //if there's just an empty footprint up there, return
00819         if(footprint_string == "[]" || footprint_string == "")
00820           return footprint;
00821 
00822         boost::erase_all(footprint_string, " ");
00823 
00824         boost::char_separator<char> sep("[]");
00825         boost::tokenizer<boost::char_separator<char> > tokens(footprint_string, sep);
00826         footstring_list = std::vector<string>(tokens.begin(), tokens.end());
00827       }
00828       //make sure we have a list of lists
00829       if(!(footprint_list.getType() == XmlRpc::XmlRpcValue::TypeArray && footprint_list.size() > 2) && !(footprint_list.getType() == XmlRpc::XmlRpcValue::TypeString && footstring_list.size() > 5)){
00830         ROS_FATAL("The footprint must be specified as list of lists on the parameter server, %s was specified as %s", footprint_param.c_str(), std::string(footprint_list).c_str());
00831         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]]");
00832       }
00833 
00834       if(footprint_list.getType() == XmlRpc::XmlRpcValue::TypeArray) {
00835         for(int i = 0; i < footprint_list.size(); ++i){
00836           //make sure we have a list of lists of size 2
00837           XmlRpc::XmlRpcValue point = footprint_list[i];
00838           if(!(point.getType() == XmlRpc::XmlRpcValue::TypeArray && point.size() == 2)){
00839             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");
00840             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");
00841           }
00842        
00843           //make sure that the value we're looking at is either a double or an int
00844           if(!(point[0].getType() == XmlRpc::XmlRpcValue::TypeInt || point[0].getType() == XmlRpc::XmlRpcValue::TypeDouble)){
00845             ROS_FATAL("Values in the footprint specification must be numbers");
00846             throw std::runtime_error("Values in the footprint specification must be numbers");
00847           }
00848           pt.x = point[0].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(point[0]) : (double)(point[0]);
00849           pt.x += sign(pt.x) * padding;
00850        
00851           //make sure that the value we're looking at is either a double or an int
00852           if(!(point[1].getType() == XmlRpc::XmlRpcValue::TypeInt || point[1].getType() == XmlRpc::XmlRpcValue::TypeDouble)){
00853             ROS_FATAL("Values in the footprint specification must be numbers");
00854             throw std::runtime_error("Values in the footprint specification must be numbers");
00855           }
00856           pt.y = point[1].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(point[1]) : (double)(point[1]);
00857           pt.y += sign(pt.y) * padding;
00858        
00859           footprint.push_back(pt);
00860 
00861           node.deleteParam(footprint_param);
00862           ostringstream oss;
00863           bool first = true;
00864           BOOST_FOREACH(geometry_msgs::Point p, footprint) {
00865             if(first) {
00866               oss << "[[" << p.x << "," << p.y << "]";
00867               first = false;
00868             }
00869             else {
00870               oss << ",[" << p.x << "," << p.y << "]";
00871             }
00872           }
00873           oss << "]";
00874           node.setParam(footprint_param, oss.str().c_str());
00875           node.setParam("footprint", oss.str().c_str());
00876         }
00877       }
00878 
00879       else if(footprint_list.getType() == XmlRpc::XmlRpcValue::TypeString) {
00880         std::vector<geometry_msgs::Point> footprint_spec;
00881         bool valid_foot = true;
00882         BOOST_FOREACH(string t, footstring_list) {
00883           if( t != "," ) {
00884             boost::erase_all(t, " ");
00885             boost::char_separator<char> pt_sep(",");
00886             boost::tokenizer<boost::char_separator<char> > pt_tokens(t, pt_sep);
00887             std::vector<string> point(pt_tokens.begin(), pt_tokens.end());
00888 
00889             if(point.size() != 2) {
00890               ROS_WARN("Each point must have exactly 2 coordinates");
00891               valid_foot = false;
00892               break;
00893             }
00894 
00895             vector<double>tmp_pt;
00896             BOOST_FOREACH(string p, point) {
00897               istringstream iss(p);
00898               double temp;
00899               if(iss >> temp) {
00900                 tmp_pt.push_back(temp);
00901               }
00902               else {
00903                 ROS_WARN("Each coordinate must convert to a double.");
00904                 valid_foot = false;
00905                 break;
00906               }
00907             }
00908             if(!valid_foot)
00909               break;
00910 
00911             geometry_msgs::Point pt;
00912             pt.x = tmp_pt[0];
00913             pt.y = tmp_pt[1];
00914 
00915             footprint_spec.push_back(pt);
00916           }
00917         }
00918         if (valid_foot) {
00919           footprint = footprint_spec;
00920           node.setParam("footprint", footprint_string);
00921         }
00922         else {
00923           ROS_FATAL("This footprint is not vaid it must be specified as a list of lists with at least 3 points, you specified %s", footprint_string.c_str());
00924           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]]");
00925         }
00926       }
00927     }
00928     return footprint;
00929   }
00930 
00931   Costmap2DROS::~Costmap2DROS(){
00932     delete dsrv_;
00933     map_update_thread_shutdown_ = true;
00934     if(map_update_thread_ != NULL){
00935       map_update_thread_->join();
00936       delete map_update_thread_;
00937     }
00938 
00939     if(costmap_publisher_ != NULL){
00940       delete costmap_publisher_;
00941     }
00942 
00943     if(costmap_ != NULL)
00944       delete costmap_;
00945   }
00946 
00947   void Costmap2DROS::start(){
00948     //check if we're stopped or just paused
00949     if(stopped_){
00950       //if we're stopped we need to re-subscribe to topics
00951       for(unsigned int i = 0; i < observation_subscribers_.size(); ++i){
00952         if(observation_subscribers_[i] != NULL)
00953           observation_subscribers_[i]->subscribe();
00954       }
00955       stopped_ = false;
00956     }
00957     for (unsigned int i=0; i < observation_buffers_.size(); ++i){
00958       if (observation_buffers_[i])
00959         observation_buffers_[i]->resetLastUpdated();
00960     } 
00961     stop_updates_ = false;
00962 
00963     //block until the costmap is re-initialized.. meaning one update cycle has run
00964     ros::Rate r(100.0);
00965     while(ros::ok() && !initialized_)
00966       r.sleep();
00967   }
00968 
00969   void Costmap2DROS::stop(){
00970     stop_updates_ = true;
00971     //unsubscribe from topics
00972     for(unsigned int i = 0; i < observation_subscribers_.size(); ++i){
00973       if(observation_subscribers_[i] != NULL)
00974         observation_subscribers_[i]->unsubscribe();
00975     }
00976     initialized_ = false;
00977     stopped_ = true;
00978   }
00979 
00980   void Costmap2DROS::addObservationBuffer(const boost::shared_ptr<ObservationBuffer>& buffer){
00981     if(buffer)
00982       observation_buffers_.push_back(buffer);
00983   }
00984 
00985   void Costmap2DROS::laserScanCallback(const sensor_msgs::LaserScanConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer){
00986     //project the laser into a point cloud
00987     sensor_msgs::PointCloud2 cloud;
00988     cloud.header = message->header;
00989 
00990     //project the scan into a point cloud
00991     try
00992     {
00993       projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, tf_);
00994     }
00995     catch (tf::TransformException &ex)
00996     {
00997       ROS_WARN ("High fidelity enabled, but TF returned a transform exception to frame %s: %s", global_frame_.c_str (), ex.what ());
00998       projector_.projectLaser(*message, cloud);
00999     }
01000 
01001     //buffer the point cloud
01002     buffer->lock();
01003     buffer->bufferCloud(cloud);
01004     buffer->unlock();
01005   }
01006 
01007   void Costmap2DROS::pointCloudCallback(const sensor_msgs::PointCloudConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer){
01008     sensor_msgs::PointCloud2 cloud2;
01009 
01010     if(!sensor_msgs::convertPointCloudToPointCloud2(*message, cloud2)){
01011       ROS_ERROR("Failed to convert a PointCloud to a PointCloud2, dropping message");
01012       return;
01013     }
01014 
01015     //buffer the point cloud
01016     buffer->lock();
01017     buffer->bufferCloud(cloud2);
01018     buffer->unlock();
01019   }
01020 
01021   void Costmap2DROS::pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer){
01022     //buffer the point cloud
01023     buffer->lock();
01024     buffer->bufferCloud(*message);
01025     buffer->unlock();
01026   }
01027 
01028   void Costmap2DROS::mapUpdateLoop(double frequency){
01029     //the user might not want to run the loop every cycle
01030     if(frequency == 0.0)
01031       return;
01032 
01033     boost::mutex::scoped_lock ml(map_update_mutex_);
01034 
01035     ros::NodeHandle nh;
01036     ros::Rate r(frequency);
01037     while(nh.ok() && !map_update_thread_shutdown_){
01038       struct timeval start, end;
01039       double start_t, end_t, t_diff;
01040       gettimeofday(&start, NULL);
01041       if(!stop_updates_){
01042         updateMap();
01043         initialized_ = true;
01044       }
01045       gettimeofday(&end, NULL);
01046       start_t = start.tv_sec + double(start.tv_usec) / 1e6;
01047       end_t = end.tv_sec + double(end.tv_usec) / 1e6;
01048       t_diff = end_t - start_t;
01049       ROS_DEBUG("Map update time: %.9f", t_diff);
01050 
01051       r.sleep();
01052       //make sure to sleep for the remainder of our cycle time
01053       if(r.cycleTime() > ros::Duration(1 / frequency))
01054         ROS_WARN("Map update loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", frequency, r.cycleTime().toSec());
01055     }
01056   }
01057 
01058   bool Costmap2DROS::getMarkingObservations(std::vector<Observation>& marking_observations) const {
01059     bool current = true;
01060     //get the marking observations
01061     for(unsigned int i = 0; i < marking_buffers_.size(); ++i){
01062       marking_buffers_[i]->lock();
01063       marking_buffers_[i]->getObservations(marking_observations);
01064       current = marking_buffers_[i]->isCurrent() && current;
01065       marking_buffers_[i]->unlock();
01066     }
01067     return current;
01068   }
01069 
01070   bool Costmap2DROS::getClearingObservations(std::vector<Observation>& clearing_observations) const {
01071     bool current = true;
01072     //get the clearing observations
01073     for(unsigned int i = 0; i < clearing_buffers_.size(); ++i){
01074       clearing_buffers_[i]->lock();
01075       clearing_buffers_[i]->getObservations(clearing_observations);
01076       current = clearing_buffers_[i]->isCurrent() && current;
01077       clearing_buffers_[i]->unlock();
01078     }
01079     return current;
01080   }
01081 
01082 
01083   void Costmap2DROS::updateMap(){
01084     tf::Stamped<tf::Pose> global_pose;
01085     if(!getRobotPose(global_pose))
01086       return;
01087 
01088     double wx = global_pose.getOrigin().x();
01089     double wy = global_pose.getOrigin().y();
01090 
01091     bool current = true;
01092     std::vector<Observation> observations, clearing_observations;
01093 
01094     //get the marking observations
01095     current = current && getMarkingObservations(observations);
01096 
01097     //get the clearing observations
01098     current = current && getClearingObservations(clearing_observations);
01099 
01100     //update the global current status
01101     current_ = current;
01102 
01103     boost::recursive_mutex::scoped_lock uml(configuration_mutex_);
01104     boost::recursive_mutex::scoped_lock lock(lock_);
01105     //if we're using a rolling buffer costmap... we need to update the origin using the robot's position
01106     if(rolling_window_){
01107       double origin_x = wx - costmap_->getSizeInMetersX() / 2;
01108       double origin_y = wy - costmap_->getSizeInMetersY() / 2;
01109       costmap_->updateOrigin(origin_x, origin_y);
01110     }
01111     costmap_->updateWorld(wx, wy, observations, clearing_observations);
01112 
01113     //make sure to clear the robot footprint of obstacles at the end
01114     clearRobotFootprint();
01115     
01116     if(save_debug_pgm_)
01117       costmap_->saveMap(name_ + ".pgm");
01118 
01119     //if we have an active publisher... we'll update its costmap data
01120     if(costmap_publisher_->active()){
01121       std::vector<geometry_msgs::Point> oriented_footprint;
01122       getOrientedFootprint(oriented_footprint);
01123       tf::Stamped<tf::Pose> global_pose;
01124       getRobotPose(global_pose);
01125       costmap_publisher_->updateCostmapData(*costmap_, oriented_footprint, global_pose);
01126     }
01127 
01128     if(publish_voxel_){
01129       costmap_2d::VoxelGrid voxel_grid;
01130       ((VoxelCostmap2D*)costmap_)->getVoxelGridMessage(voxel_grid);
01131       voxel_grid.header.frame_id = global_frame_;
01132       voxel_grid.header.stamp = ros::Time::now();
01133       voxel_pub_.publish(voxel_grid);
01134     }
01135   }
01136 
01137   void Costmap2DROS::clearNonLethalWindow(double size_x, double size_y){
01138     tf::Stamped<tf::Pose> global_pose;
01139     if(!getRobotPose(global_pose))
01140       return;
01141 
01142     double wx = global_pose.getOrigin().x();
01143     double wy = global_pose.getOrigin().y();
01144     lock_.lock();
01145     ROS_DEBUG("Clearing map in window");
01146     costmap_->clearNonLethal(wx, wy, size_x, size_y, true);
01147     lock_.unlock();
01148 
01149     //make sure to force an update of the map to take in the latest sensor data
01150     updateMap();
01151   }
01152 
01153   void Costmap2DROS::resetMapOutsideWindow(double size_x, double size_y){
01154     tf::Stamped<tf::Pose> global_pose;
01155     if(!getRobotPose(global_pose))
01156       return;
01157 
01158     double wx = global_pose.getOrigin().x();
01159     double wy = global_pose.getOrigin().y();
01160     lock_.lock();
01161     ROS_DEBUG("Resetting map outside window");
01162     costmap_->resetMapOutsideWindow(wx, wy, size_x, size_y);
01163     lock_.unlock();
01164 
01165     //make sure to force an update of the map to take in the latest sensor data
01166     updateMap();
01167 
01168   }
01169 
01170   void Costmap2DROS::getCostmapCopy(Costmap2D& costmap) const {
01171     boost::recursive_mutex::scoped_lock lock(lock_);
01172     costmap = *costmap_;
01173   }
01174 
01175   void Costmap2DROS::incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map){
01176     if(!map_initialized_){
01177       initFromMap(*new_map);
01178       map_initialized_ = true;
01179     }
01180     else if(costmap_initialized_)
01181       updateStaticMap(*new_map);
01182   }
01183 
01184   void Costmap2DROS::initFromMap(const nav_msgs::OccupancyGrid& map){
01185     boost::recursive_mutex::scoped_lock lock(map_data_lock_);
01186 
01187     // We need to cast to unsigned chars from int
01188     unsigned int numCells = map.info.width * map.info.height;
01189     for(unsigned int i = 0; i < numCells; i++){
01190       input_data_.push_back((unsigned char) map.data[i]);
01191     }
01192 
01193     map_meta_data_ = map.info;
01194     global_frame_ = tf::resolve(tf_prefix_, map.header.frame_id);
01195   }
01196 
01197   void Costmap2DROS::updateStaticMap(const nav_msgs::OccupancyGrid& new_map){
01198     std::vector<unsigned char> new_map_data;
01199     // We need to cast to unsigned chars from int
01200     unsigned int numCells = new_map.info.width * new_map.info.height;
01201     for(unsigned int i = 0; i < numCells; i++){
01202       new_map_data.push_back((unsigned char) new_map.data[i]);
01203     }
01204 
01205     double map_width = (unsigned int)new_map.info.width;
01206     double map_height = (unsigned int)new_map.info.height;
01207     double map_resolution = new_map.info.resolution;
01208     double map_origin_x = new_map.info.origin.position.x;
01209     double map_origin_y = new_map.info.origin.position.y;
01210 
01211     if(fabs(map_resolution - costmap_->getResolution()) > 1e-6){
01212       ROS_ERROR("You cannot update a map with resolution: %.4f, with a new map that has resolution: %.4f", 
01213           costmap_->getResolution(), map_resolution);
01214       return;
01215     }
01216 
01217     if(fabs(new_map.info.origin.orientation.x) > 1e-6 
01218        && fabs(new_map.info.origin.orientation.y) > 1e-6 
01219        && fabs(new_map.info.origin.orientation.z) > 1e-6 
01220        && (fabs(new_map.info.origin.orientation.w) > 1e-6 || fabs(new_map.info.origin.orientation.w - 1.0) > 1e-6)){
01221       ROS_ERROR("The costmap does not support origins that contain rotations. The origin must be aligned with the global_frame.");
01222       return;
01223     }
01224 
01225     if(tf::resolve(tf_prefix_, new_map.header.frame_id) != tf::resolve(tf_prefix_, global_frame_)){
01226       std::string new_global_frame = tf::resolve(tf_prefix_, new_map.header.frame_id);
01227 
01228       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());
01229 
01230       //we'll update all the observation buffers we have associated with this map
01231       for(unsigned int i = 0; i < observation_buffers_.size(); ++i){
01232         observation_buffers_[i]->lock();
01233         observation_buffers_[i]->setGlobalFrame(new_global_frame);
01234         observation_buffers_[i]->unlock();
01235       }
01236 
01237       //make sure to lock the costmap
01238       boost::recursive_mutex::scoped_lock uml(configuration_mutex_);
01239       boost::recursive_mutex::scoped_lock lock(lock_);
01240 
01241       //if the map has a new global frame... we'll actually wipe the whole map rather than trying to be efficient about updating a potential window
01242       costmap_->replaceFullMap(map_origin_x, map_origin_y, map_width, map_height, new_map_data);
01243 
01244       //we'll also update the global frame id for this costmap
01245       global_frame_ = new_global_frame;
01246 
01247       return;
01248     }
01249 
01250     boost::recursive_mutex::scoped_lock lock(lock_);
01251     costmap_->updateStaticMapWindow(map_origin_x, map_origin_y, map_width, map_height, new_map_data);
01252   }
01253 
01254   void Costmap2DROS::getCostmapWindowCopy(double win_size_x, double win_size_y, Costmap2D& costmap) const {
01255     boost::recursive_mutex::scoped_lock lock(lock_);
01256     tf::Stamped<tf::Pose> global_pose;
01257     if(!getRobotPose(global_pose)){
01258       ROS_ERROR("Could not get a window of this costmap centered at the robot, because we failed to get the pose of the robot");
01259       return;
01260     }
01261     getCostmapWindowCopy(global_pose.getOrigin().x(), global_pose.getOrigin().y(), win_size_x, win_size_y, costmap);
01262   }
01263 
01264   void Costmap2DROS::getCostmapWindowCopy(double win_center_x, double win_center_y, double win_size_x, double win_size_y, Costmap2D& costmap) const {
01265     boost::recursive_mutex::scoped_lock lock(lock_);
01266 
01267     //we need to compute legal bounds for the window and shrink it if necessary
01268     double ll_x = std::min(std::max(win_center_x - win_size_x, costmap_->getOriginX()), costmap_->getSizeInMetersX());
01269     double ll_y = std::min(std::max(win_center_y - win_size_y, costmap_->getOriginY()), costmap_->getSizeInMetersY());
01270     double ur_x = std::min(std::max(win_center_x + win_size_x, costmap_->getOriginX()), costmap_->getSizeInMetersX());
01271     double ur_y = std::min(std::max(win_center_y + win_size_y, costmap_->getOriginY()), costmap_->getSizeInMetersY());
01272     double size_x = ur_x - ll_x;
01273     double size_y = ur_y - ll_y;
01274 
01275     //copy the appropriate window from our costmap into the one passed in by the user
01276     costmap.copyCostmapWindow(*costmap_, ll_x, ll_y, size_x, size_y);
01277   }
01278 
01279   unsigned int Costmap2DROS::getSizeInCellsX() const {
01280     boost::recursive_mutex::scoped_lock lock(lock_);
01281     return costmap_->getSizeInCellsX();
01282   }
01283 
01284   unsigned int Costmap2DROS::getSizeInCellsY() const {
01285     boost::recursive_mutex::scoped_lock lock(lock_);
01286     return costmap_->getSizeInCellsY();
01287   }
01288 
01289   double Costmap2DROS::getResolution() const {
01290     boost::recursive_mutex::scoped_lock lock(lock_);
01291     return costmap_->getResolution();
01292   }
01293 
01294   bool Costmap2DROS::getRobotPose(tf::Stamped<tf::Pose>& global_pose) const {
01295 
01296     global_pose.setIdentity();
01297     tf::Stamped<tf::Pose> robot_pose;
01298     robot_pose.setIdentity();
01299     robot_pose.frame_id_ = robot_base_frame_;
01300     robot_pose.stamp_ = ros::Time();
01301     ros::Time current_time = ros::Time::now(); // save time for checking tf delay later
01302 
01303     //get the global pose of the robot
01304     try{
01305       tf_.transformPose(global_frame_, robot_pose, global_pose);
01306     }
01307     catch(tf::LookupException& ex) {
01308       ROS_ERROR_THROTTLE(1.0, "No Transform available Error looking up robot pose: %s\n", ex.what());
01309       return false;
01310     }
01311     catch(tf::ConnectivityException& ex) {
01312       ROS_ERROR_THROTTLE(1.0, "Connectivity Error looking up robot pose: %s\n", ex.what());
01313       return false;
01314     }
01315     catch(tf::ExtrapolationException& ex) {
01316       ROS_ERROR_THROTTLE(1.0, "Extrapolation Error looking up robot pose: %s\n", ex.what());
01317       return false;
01318     }
01319     // check global_pose timeout
01320     if (current_time.toSec() - global_pose.stamp_.toSec() > transform_tolerance_) {
01321       ROS_WARN_THROTTLE(1.0, "Costmap2DROS transform timeout. Current time: %.4f, global_pose stamp: %.4f, tolerance: %.4f",
01322           current_time.toSec() ,global_pose.stamp_.toSec() ,transform_tolerance_);
01323       return false;
01324     }
01325 
01326     return true;
01327   }
01328 
01329   void Costmap2DROS::clearRobotFootprint(){
01330     tf::Stamped<tf::Pose> global_pose;
01331     if(!getRobotPose(global_pose))
01332       return;
01333 
01334     clearRobotFootprint(global_pose);
01335   }
01336 
01337   std::vector<geometry_msgs::Point> Costmap2DROS::getRobotFootprint() const {
01338     return footprint_spec_;
01339   }
01340 
01341   void Costmap2DROS::getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint) const {
01342     tf::Stamped<tf::Pose> global_pose;
01343     if(!getRobotPose(global_pose))
01344       return;
01345 
01346     double yaw = tf::getYaw(global_pose.getRotation());
01347 
01348     getOrientedFootprint(global_pose.getOrigin().x(), global_pose.getOrigin().y(), yaw, oriented_footprint);
01349   }
01350 
01351   void Costmap2DROS::getOrientedFootprint(double x, double y, double theta, std::vector<geometry_msgs::Point>& oriented_footprint) const {
01352     //build the oriented footprint at the robot's current location
01353     double cos_th = cos(theta);
01354     double sin_th = sin(theta);
01355     for(unsigned int i = 0; i < footprint_spec_.size(); ++i){
01356       geometry_msgs::Point new_pt;
01357       new_pt.x = x + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th);
01358       new_pt.y = y + (footprint_spec_[i].x * sin_th + footprint_spec_[i].y * cos_th);
01359       oriented_footprint.push_back(new_pt);
01360     }
01361   }
01362 
01363   bool Costmap2DROS::setConvexPolygonCost(const std::vector<geometry_msgs::Point>& polygon, unsigned char cost_value){
01364     lock_.lock();
01365     bool success = costmap_->setConvexPolygonCost(polygon, cost_value);
01366     lock_.unlock();
01367 
01368     //make sure to take our active sensor data into account
01369     updateMap();
01370 
01371     return success;
01372   }
01373 
01374   std::string Costmap2DROS::getGlobalFrameID() const {
01375     return global_frame_;
01376   }
01377 
01378   std::string Costmap2DROS::getBaseFrameID() const {
01379     return robot_base_frame_;
01380   }
01381 
01382   double Costmap2DROS::getInscribedRadius() const {
01383     boost::recursive_mutex::scoped_lock lock(lock_);
01384     return costmap_->getInscribedRadius();
01385   }
01386 
01387   double Costmap2DROS::getCircumscribedRadius() const {
01388     boost::recursive_mutex::scoped_lock lock(lock_);
01389     return costmap_->getCircumscribedRadius();
01390   }
01391 
01392   double Costmap2DROS::getInflationRadius() const {
01393     boost::recursive_mutex::scoped_lock lock(lock_);
01394     return costmap_->getInflationRadius();
01395   }
01396 
01397   void Costmap2DROS::clearRobotFootprint(const tf::Stamped<tf::Pose>& global_pose){
01398     std::vector<geometry_msgs::Point> oriented_footprint;
01399 
01400     //check if we have a circular footprint or a polygon footprint
01401     if(footprint_spec_.size() < 3){
01402       //we'll build an approximation of the circle as the footprint and clear that
01403       double angle = 0;
01404       double step = 2 * M_PI / 72;
01405       while(angle < 2 * M_PI){
01406         geometry_msgs::Point pt;
01407         pt.x = getInscribedRadius() * cos(angle) + global_pose.getOrigin().x();
01408         pt.y = getInscribedRadius() * sin(angle) + global_pose.getOrigin().y();
01409         pt.z = 0.0;
01410         oriented_footprint.push_back(pt);
01411         angle += step;
01412       }
01413     }
01414     else{
01415       double yaw = tf::getYaw(global_pose.getRotation());
01416 
01417       //get the oriented footprint of the robot
01418       double x = global_pose.getOrigin().x();
01419       double y = global_pose.getOrigin().y();
01420       double theta = yaw;
01421 
01422       //build the oriented footprint at the robot's current location
01423       getOrientedFootprint(x, y, theta, oriented_footprint);
01424     }
01425 
01426     //lock the map if necessary
01427     boost::recursive_mutex::scoped_lock lock(lock_);
01428 
01429     //set the associated costs in the cost map to be free
01430     if(!costmap_->setConvexPolygonCost(oriented_footprint, costmap_2d::FREE_SPACE))
01431       return;
01432 
01433     double max_inflation_dist = 2 * (costmap_->getInflationRadius() + costmap_->getCircumscribedRadius());
01434 
01435     //clear all non-lethal obstacles out to the maximum inflation distance of an obstacle in the robot footprint
01436     costmap_->clearNonLethal(global_pose.getOrigin().x(), global_pose.getOrigin().y(), max_inflation_dist, max_inflation_dist);
01437 
01438     //make sure to re-inflate obstacles in the affected region... plus those obstalces that could inflate to have costs in the footprint
01439     costmap_->reinflateWindow(global_pose.getOrigin().x(), global_pose.getOrigin().y(), 
01440         max_inflation_dist + 2 * costmap_->getInflationRadius(), max_inflation_dist + 2 * costmap_->getInflationRadius(), false);
01441 
01442   }
01443 
01444 };


costmap_2d
Author(s): Eitan Marder-Eppstein
autogenerated on Sat Dec 28 2013 17:13:40