costmap_2d_ros.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, 2013, 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 Willow Garage, Inc. 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  *         David V. Lu!!
00037  *********************************************************************/
00038 #include <costmap_2d/layered_costmap.h>
00039 #include <costmap_2d/costmap_2d_ros.h>
00040 #include <cstdio>
00041 #include <string>
00042 #include <algorithm>
00043 #include <vector>
00044 
00045 
00046 using namespace std;
00047 
00048 namespace costmap_2d
00049 {
00050 
00051 void move_parameter(ros::NodeHandle& old_h, ros::NodeHandle& new_h, std::string name, bool should_delete = true)
00052 {
00053   if (!old_h.hasParam(name))
00054     return;
00055 
00056   XmlRpc::XmlRpcValue value;
00057   old_h.getParam(name, value);
00058   new_h.setParam(name, value);
00059   if (should_delete) old_h.deleteParam(name);
00060 }
00061 
00062 Costmap2DROS::Costmap2DROS(std::string name, tf::TransformListener& tf) :
00063     layered_costmap_(NULL), name_(name), tf_(tf), stop_updates_(false), initialized_(true), stopped_(false),
00064     robot_stopped_(false), map_update_thread_(NULL), last_publish_(0),
00065     plugin_loader_("costmap_2d", "costmap_2d::Layer"), publisher_(NULL)
00066 {
00067   ros::NodeHandle private_nh("~/" + name);
00068   ros::NodeHandle g_nh;
00069 
00070   // get our tf prefix
00071   ros::NodeHandle prefix_nh;
00072   std::string tf_prefix = tf::getPrefixParam(prefix_nh);
00073 
00074   // get two frames
00075   private_nh.param("global_frame", global_frame_, std::string("/map"));
00076   private_nh.param("robot_base_frame", robot_base_frame_, std::string("base_link"));
00077 
00078   // make sure that we set the frames appropriately based on the tf_prefix
00079   global_frame_ = tf::resolve(tf_prefix, global_frame_);
00080   robot_base_frame_ = tf::resolve(tf_prefix, robot_base_frame_);
00081 
00082   ros::Time last_error = ros::Time::now();
00083   std::string tf_error;
00084   // we need to make sure that the transform between the robot base frame and the global frame is available
00085   while (ros::ok()
00086       && !tf_.waitForTransform(global_frame_, robot_base_frame_, ros::Time(), ros::Duration(0.1), ros::Duration(0.01),
00087                                &tf_error))
00088   {
00089     ros::spinOnce();
00090     if (last_error + ros::Duration(5.0) < ros::Time::now())
00091     {
00092       ROS_WARN("Timed out waiting for transform from %s to %s to become available before running costmap, tf error: %s",
00093                robot_base_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());
00094       last_error = ros::Time::now();
00095     }
00096     // The error string will accumulate and errors will typically be the same, so the last
00097     // will do for the warning above. Reset the string here to avoid accumulation.
00098     tf_error.clear();
00099   }
00100 
00101   // check if we want a rolling window version of the costmap
00102   bool rolling_window, track_unknown_space, always_send_full_costmap;
00103   private_nh.param("rolling_window", rolling_window, false);
00104   private_nh.param("track_unknown_space", track_unknown_space, false);
00105   private_nh.param("always_send_full_costmap", always_send_full_costmap, false);
00106 
00107   layered_costmap_ = new LayeredCostmap(global_frame_, rolling_window, track_unknown_space);
00108 
00109   if (!private_nh.hasParam("plugins"))
00110   {
00111     resetOldParameters(private_nh);
00112   }
00113 
00114   if (private_nh.hasParam("plugins"))
00115   {
00116     XmlRpc::XmlRpcValue my_list;
00117     private_nh.getParam("plugins", my_list);
00118     for (int32_t i = 0; i < my_list.size(); ++i)
00119     {
00120       std::string pname = static_cast<std::string>(my_list[i]["name"]);
00121       std::string type = static_cast<std::string>(my_list[i]["type"]);
00122       ROS_INFO("Using plugin \"%s\"", pname.c_str());
00123 
00124       boost::shared_ptr<Layer> plugin = plugin_loader_.createInstance(type);
00125       layered_costmap_->addPlugin(plugin);
00126       plugin->initialize(layered_costmap_, name + "/" + pname, &tf_);
00127     }
00128   }
00129 
00130   // subscribe to the footprint topic
00131   std::string topic_param, topic;
00132   if (!private_nh.searchParam("footprint_topic", topic_param))
00133   {
00134     topic_param = "footprint_topic";
00135   }
00136 
00137   private_nh.param(topic_param, topic, std::string("footprint"));
00138   footprint_sub_ = private_nh.subscribe(topic, 1, &Costmap2DROS::setUnpaddedRobotFootprintPolygon, this);
00139 
00140   if (!private_nh.searchParam("published_footprint_topic", topic_param))
00141   {
00142     topic_param = "published_footprint";
00143   }
00144 
00145   private_nh.param(topic_param, topic, std::string("oriented_footprint"));
00146   footprint_pub_ = private_nh.advertise<geometry_msgs::PolygonStamped>("footprint", 1);
00147 
00148   setUnpaddedRobotFootprint(makeFootprintFromParams(private_nh));
00149 
00150   publisher_ = new Costmap2DPublisher(&private_nh, layered_costmap_->getCostmap(), global_frame_, "costmap",
00151                                       always_send_full_costmap);
00152 
00153   // create a thread to handle updating the map
00154   stop_updates_ = false;
00155   initialized_ = true;
00156   stopped_ = false;
00157 
00158   // Create a timer to check if the robot is moving
00159   robot_stopped_ = false;
00160   double pose_update_frequency;
00161   private_nh.param("pose_update_frequency", pose_update_frequency, 10.0);
00162   timer_ = private_nh.createTimer(ros::Duration(1 / pose_update_frequency),
00163                                   &Costmap2DROS::movementCB, this);
00164 
00165   dsrv_ = new dynamic_reconfigure::Server<Costmap2DConfig>(ros::NodeHandle("~/" + name));
00166   dynamic_reconfigure::Server<Costmap2DConfig>::CallbackType cb = boost::bind(&Costmap2DROS::reconfigureCB, this, _1,
00167                                                                               _2);
00168   dsrv_->setCallback(cb);
00169 }
00170 
00171 void Costmap2DROS::setUnpaddedRobotFootprintPolygon(const geometry_msgs::Polygon& footprint)
00172 {
00173   setUnpaddedRobotFootprint(toPointVector(footprint));
00174 }
00175 
00176 Costmap2DROS::~Costmap2DROS()
00177 {
00178   map_update_thread_shutdown_ = true;
00179   if (map_update_thread_ != NULL)
00180   {
00181     map_update_thread_->join();
00182     delete map_update_thread_;
00183   }
00184   if (publisher_ != NULL)
00185     delete publisher_;
00186 
00187   delete layered_costmap_;
00188   delete dsrv_;
00189 }
00190 
00191 void Costmap2DROS::resetOldParameters(ros::NodeHandle& nh)
00192 {
00193   ROS_INFO("Loading from pre-hydro parameter style");
00194   bool flag;
00195   std::string s;
00196   std::vector < XmlRpc::XmlRpcValue > plugins;
00197 
00198   XmlRpc::XmlRpcValue::ValueStruct map;
00199   SuperValue super_map;
00200   SuperValue super_array;
00201 
00202   if (nh.getParam("static_map", flag) && flag)
00203   {
00204     map["name"] = XmlRpc::XmlRpcValue("static_layer");
00205     map["type"] = XmlRpc::XmlRpcValue("costmap_2d::StaticLayer");
00206     super_map.setStruct(&map);
00207     plugins.push_back(super_map);
00208 
00209     ros::NodeHandle map_layer(nh, "static_layer");
00210     move_parameter(nh, map_layer, "map_topic");
00211     move_parameter(nh, map_layer, "unknown_cost_value");
00212     move_parameter(nh, map_layer, "lethal_cost_threshold");
00213     move_parameter(nh, map_layer, "track_unknown_space", false);
00214   }
00215 
00216   ros::NodeHandle obstacles(nh, "obstacle_layer");
00217   if (nh.getParam("map_type", s) && s == "voxel")
00218   {
00219     map["name"] = XmlRpc::XmlRpcValue("obstacle_layer");
00220     map["type"] = XmlRpc::XmlRpcValue("costmap_2d::VoxelLayer");
00221     super_map.setStruct(&map);
00222     plugins.push_back(super_map);
00223 
00224     move_parameter(nh, obstacles, "origin_z");
00225     move_parameter(nh, obstacles, "z_resolution");
00226     move_parameter(nh, obstacles, "z_voxels");
00227     move_parameter(nh, obstacles, "mark_threshold");
00228     move_parameter(nh, obstacles, "unknown_threshold");
00229     move_parameter(nh, obstacles, "publish_voxel_map");
00230   }
00231   else
00232   {
00233     map["name"] = XmlRpc::XmlRpcValue("obstacle_layer");
00234     map["type"] = XmlRpc::XmlRpcValue("costmap_2d::ObstacleLayer");
00235     super_map.setStruct(&map);
00236     plugins.push_back(super_map);
00237   }
00238 
00239   move_parameter(nh, obstacles, "max_obstacle_height");
00240   move_parameter(nh, obstacles, "raytrace_range");
00241   move_parameter(nh, obstacles, "obstacle_range");
00242   move_parameter(nh, obstacles, "track_unknown_space", true);
00243   nh.param("observation_sources", s, std::string(""));
00244   std::stringstream ss(s);
00245   std::string source;
00246   while (ss >> source)
00247   {
00248     move_parameter(nh, obstacles, source);
00249   }
00250   move_parameter(nh, obstacles, "observation_sources");
00251 
00252   ros::NodeHandle inflation(nh, "inflation_layer");
00253   move_parameter(nh, inflation, "cost_scaling_factor");
00254   move_parameter(nh, inflation, "inflation_radius");
00255   map["name"] = XmlRpc::XmlRpcValue("inflation_layer");
00256   map["type"] = XmlRpc::XmlRpcValue("costmap_2d::InflationLayer");
00257   super_map.setStruct(&map);
00258   plugins.push_back(super_map);
00259 
00260   super_array.setArray(&plugins);
00261   nh.setParam("plugins", super_array);
00262 }
00263 
00264 void Costmap2DROS::reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level)
00265 {
00266   transform_tolerance_ = config.transform_tolerance;
00267   if (map_update_thread_ != NULL)
00268   {
00269     map_update_thread_shutdown_ = true;
00270     map_update_thread_->join();
00271     delete map_update_thread_;
00272   }
00273   map_update_thread_shutdown_ = false;
00274   double map_update_frequency = config.update_frequency;
00275 
00276   double map_publish_frequency = config.publish_frequency;
00277   if (map_publish_frequency > 0)
00278     publish_cycle = ros::Duration(1 / map_publish_frequency);
00279   else
00280     publish_cycle = ros::Duration(-1);
00281 
00282   // find size parameters
00283   double map_width_meters = config.width, map_height_meters = config.height, resolution = config.resolution, origin_x =
00284              config.origin_x,
00285          origin_y = config.origin_y;
00286 
00287   if (!layered_costmap_->isSizeLocked())
00288   {
00289     layered_costmap_->resizeMap((unsigned int)(map_width_meters / resolution),
00290                                 (unsigned int)(map_height_meters / resolution), resolution, origin_x, origin_y);
00291   }
00292 
00293   // If the padding has changed, call setUnpaddedRobotFootprint() to
00294   // re-apply the padding.
00295   if (footprint_padding_ != config.footprint_padding)
00296   {
00297     footprint_padding_ = config.footprint_padding;
00298     setUnpaddedRobotFootprint(unpadded_footprint_);
00299   }
00300 
00301   readFootprintFromConfig(config, old_config_);
00302 
00303   old_config_ = config;
00304 
00305   map_update_thread_ = new boost::thread(boost::bind(&Costmap2DROS::mapUpdateLoop, this, map_update_frequency));
00306 }
00307 
00308 void Costmap2DROS::readFootprintFromConfig(const costmap_2d::Costmap2DConfig &new_config,
00309                                            const costmap_2d::Costmap2DConfig &old_config)
00310 {
00311   // Only change the footprint if footprint or robot_radius has
00312   // changed.  Otherwise we might overwrite a footprint sent on a
00313   // topic by a dynamic_reconfigure call which was setting some other
00314   // variable.
00315   if (new_config.footprint == old_config.footprint &&
00316       new_config.robot_radius == old_config.robot_radius)
00317   {
00318     return;
00319   }
00320 
00321   if (new_config.footprint != "" && new_config.footprint != "[]")
00322   {
00323     std::vector<geometry_msgs::Point> new_footprint;
00324     if (makeFootprintFromString(new_config.footprint, new_footprint))
00325     {
00326         setUnpaddedRobotFootprint(new_footprint);
00327     }
00328     else
00329     {
00330         ROS_ERROR("Invalid footprint string from dynamic reconfigure");
00331     }
00332   }
00333   else
00334   {
00335     // robot_radius may be 0, but that must be intended at this point.
00336     setUnpaddedRobotFootprint(makeFootprintFromRadius(new_config.robot_radius));
00337   }
00338 }
00339 
00340 void Costmap2DROS::setUnpaddedRobotFootprint(const std::vector<geometry_msgs::Point>& points)
00341 {
00342   unpadded_footprint_ = points;
00343   padded_footprint_ = points;
00344   padFootprint(padded_footprint_, footprint_padding_);
00345 
00346   layered_costmap_->setFootprint(padded_footprint_);
00347 }
00348 
00349 void Costmap2DROS::movementCB(const ros::TimerEvent &event)
00350 {
00351   // don't allow configuration to happen while this check occurs
00352   // boost::recursive_mutex::scoped_lock mcl(configuration_mutex_);
00353 
00354   tf::Stamped < tf::Pose > new_pose;
00355 
00356   if (!getRobotPose(new_pose))
00357   {
00358     ROS_WARN_THROTTLE(1.0, "Could not get robot pose, cancelling pose reconfiguration");
00359     robot_stopped_ = false;
00360   }
00361   // make sure that the robot is not moving
00362   else if (fabs((old_pose_.getOrigin() - new_pose.getOrigin()).length()) < 1e-3
00363       && fabs(old_pose_.getRotation().angle(new_pose.getRotation())) < 1e-3)
00364   {
00365     old_pose_ = new_pose;
00366     robot_stopped_ = true;
00367   }
00368   else
00369   {
00370     old_pose_ = new_pose;
00371     robot_stopped_ = false;
00372   }
00373 }
00374 
00375 void Costmap2DROS::mapUpdateLoop(double frequency)
00376 {
00377   // the user might not want to run the loop every cycle
00378   if (frequency == 0.0)
00379     return;
00380 
00381   ros::NodeHandle nh;
00382   ros::Rate r(frequency);
00383   while (nh.ok() && !map_update_thread_shutdown_)
00384   {
00385     struct timeval start, end;
00386     double start_t, end_t, t_diff;
00387     gettimeofday(&start, NULL);
00388 
00389     updateMap();
00390 
00391     gettimeofday(&end, NULL);
00392     start_t = start.tv_sec + double(start.tv_usec) / 1e6;
00393     end_t = end.tv_sec + double(end.tv_usec) / 1e6;
00394     t_diff = end_t - start_t;
00395     ROS_DEBUG("Map update time: %.9f", t_diff);
00396     if (publish_cycle.toSec() > 0 && layered_costmap_->isInitialized())
00397     {
00398       unsigned int x0, y0, xn, yn;
00399       layered_costmap_->getBounds(&x0, &xn, &y0, &yn);
00400       publisher_->updateBounds(x0, xn, y0, yn);
00401 
00402       ros::Time now = ros::Time::now();
00403       if (last_publish_ + publish_cycle < now)
00404       {
00405         publisher_->publishCostmap();
00406         last_publish_ = now;
00407       }
00408     }
00409     r.sleep();
00410     // make sure to sleep for the remainder of our cycle time
00411     if (r.cycleTime() > ros::Duration(1 / frequency))
00412       ROS_WARN("Map update loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", frequency,
00413                r.cycleTime().toSec());
00414   }
00415 }
00416 
00417 void Costmap2DROS::updateMap()
00418 {
00419   if (!stop_updates_)
00420   {
00421     // get global pose
00422     tf::Stamped < tf::Pose > pose;
00423     if (getRobotPose (pose))
00424     {
00425       double x = pose.getOrigin().x(),
00426              y = pose.getOrigin().y(),
00427              yaw = tf::getYaw(pose.getRotation());
00428 
00429       layered_costmap_->updateMap(x, y, yaw);
00430 
00431       geometry_msgs::PolygonStamped footprint;
00432       footprint.header.frame_id = global_frame_;
00433       footprint.header.stamp = ros::Time::now();
00434       transformFootprint(x, y, yaw, padded_footprint_, footprint);
00435       footprint_pub_.publish(footprint);
00436 
00437       initialized_ = true;
00438     }
00439   }
00440 }
00441 
00442 void Costmap2DROS::start()
00443 {
00444   std::vector < boost::shared_ptr<Layer> > *plugins = layered_costmap_->getPlugins();
00445   // check if we're stopped or just paused
00446   if (stopped_)
00447   {
00448     // if we're stopped we need to re-subscribe to topics
00449     for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins->begin(); plugin != plugins->end();
00450         ++plugin)
00451     {
00452       (*plugin)->activate();
00453     }
00454     stopped_ = false;
00455   }
00456   stop_updates_ = false;
00457 
00458   // block until the costmap is re-initialized.. meaning one update cycle has run
00459   ros::Rate r(100.0);
00460   while (ros::ok() && !initialized_)
00461     r.sleep();
00462 }
00463 
00464 void Costmap2DROS::stop()
00465 {
00466   stop_updates_ = true;
00467   std::vector < boost::shared_ptr<Layer> > *plugins = layered_costmap_->getPlugins();
00468   // unsubscribe from topics
00469   for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins->begin(); plugin != plugins->end();
00470       ++plugin)
00471   {
00472     (*plugin)->deactivate();
00473   }
00474   initialized_ = false;
00475   stopped_ = true;
00476 }
00477 
00478 void Costmap2DROS::pause()
00479 {
00480   stop_updates_ = true;
00481   initialized_ = false;
00482 }
00483 
00484 void Costmap2DROS::resume()
00485 {
00486   stop_updates_ = false;
00487 
00488   // block until the costmap is re-initialized.. meaning one update cycle has run
00489   ros::Rate r(100.0);
00490   while (!initialized_)
00491     r.sleep();
00492 }
00493 
00494 
00495 void Costmap2DROS::resetLayers()
00496 {
00497   Costmap2D* top = layered_costmap_->getCostmap();
00498   top->resetMap(0, 0, top->getSizeInCellsX(), top->getSizeInCellsY());
00499   std::vector < boost::shared_ptr<Layer> > *plugins = layered_costmap_->getPlugins();
00500   for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins->begin(); plugin != plugins->end();
00501       ++plugin)
00502   {
00503     (*plugin)->reset();
00504   }
00505 }
00506 
00507 bool Costmap2DROS::getRobotPose(tf::Stamped<tf::Pose>& global_pose) const
00508 {
00509   global_pose.setIdentity();
00510   tf::Stamped < tf::Pose > robot_pose;
00511   robot_pose.setIdentity();
00512   robot_pose.frame_id_ = robot_base_frame_;
00513   robot_pose.stamp_ = ros::Time();
00514   ros::Time current_time = ros::Time::now();  // save time for checking tf delay later
00515 
00516   // get the global pose of the robot
00517   try
00518   {
00519     tf_.transformPose(global_frame_, robot_pose, global_pose);
00520   }
00521   catch (tf::LookupException& ex)
00522   {
00523     ROS_ERROR_THROTTLE(1.0, "No Transform available Error looking up robot pose: %s\n", ex.what());
00524     return false;
00525   }
00526   catch (tf::ConnectivityException& ex)
00527   {
00528     ROS_ERROR_THROTTLE(1.0, "Connectivity Error looking up robot pose: %s\n", ex.what());
00529     return false;
00530   }
00531   catch (tf::ExtrapolationException& ex)
00532   {
00533     ROS_ERROR_THROTTLE(1.0, "Extrapolation Error looking up robot pose: %s\n", ex.what());
00534     return false;
00535   }
00536   // check global_pose timeout
00537   if (current_time.toSec() - global_pose.stamp_.toSec() > transform_tolerance_)
00538   {
00539     ROS_WARN_THROTTLE(1.0,
00540                       "Costmap2DROS transform timeout. Current time: %.4f, global_pose stamp: %.4f, tolerance: %.4f",
00541                       current_time.toSec(), global_pose.stamp_.toSec(), transform_tolerance_);
00542     return false;
00543   }
00544 
00545   return true;
00546 }
00547 
00548 void Costmap2DROS::getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint) const
00549 {
00550   tf::Stamped<tf::Pose> global_pose;
00551   if (!getRobotPose(global_pose))
00552     return;
00553 
00554   double yaw = tf::getYaw(global_pose.getRotation());
00555   transformFootprint(global_pose.getOrigin().x(), global_pose.getOrigin().y(), yaw,
00556                      padded_footprint_, oriented_footprint);
00557 }
00558 
00559 }  // namespace costmap_2d


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Wed Aug 2 2017 03:12:21