costmap_2d_ros.h
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 #ifndef COSTMAP_COSTMAP_2D_ROS_H_
00039 #define COSTMAP_COSTMAP_2D_ROS_H_
00040 
00041 #include <costmap_2d/layered_costmap.h>
00042 #include <costmap_2d/layer.h>
00043 #include <costmap_2d/costmap_2d_publisher.h>
00044 #include <costmap_2d/Costmap2DConfig.h>
00045 #include <costmap_2d/footprint.h>
00046 #include <geometry_msgs/Polygon.h>
00047 #include <dynamic_reconfigure/server.h>
00048 #include <pluginlib/class_loader.h>
00049 
00050 class SuperValue : public XmlRpc::XmlRpcValue
00051 {
00052 public:
00053   void setStruct(XmlRpc::XmlRpcValue::ValueStruct* a)
00054   {
00055     _type = TypeStruct;
00056     _value.asStruct = new XmlRpc::XmlRpcValue::ValueStruct(*a);
00057   }
00058   void setArray(XmlRpc::XmlRpcValue::ValueArray* a)
00059   {
00060     _type = TypeArray;
00061     _value.asArray = new std::vector<XmlRpc::XmlRpcValue>(*a);
00062   }
00063 };
00064 
00065 namespace costmap_2d
00066 {
00067 
00071 class Costmap2DROS
00072 {
00073 public:
00079   Costmap2DROS(std::string name, tf::TransformListener& tf);
00080   ~Costmap2DROS();
00081 
00087   void start();
00088 
00092   void stop();
00093 
00097   void pause();
00098 
00102   void resume();
00103 
00104   void updateMap();
00105 
00109   void resetLayers();
00110 
00112   bool isCurrent()
00113     {
00114       return layered_costmap_->isCurrent();
00115     }
00116 
00122   bool getRobotPose(tf::Stamped<tf::Pose>& global_pose) const;
00123 
00127   Costmap2D* getCostmap()
00128     {
00129       return layered_costmap_->getCostmap();
00130     }
00131 
00136   std::string getGlobalFrameID()
00137     {
00138       return global_frame_;
00139     }
00140 
00145   std::string getBaseFrameID()
00146     {
00147       return robot_base_frame_;
00148     }
00149   LayeredCostmap* getLayeredCostmap()
00150     {
00151       return layered_costmap_;
00152     }
00153 
00155   geometry_msgs::Polygon getRobotFootprintPolygon()
00156   {
00157     return costmap_2d::toPolygon( padded_footprint_ );
00158   }
00159 
00168   std::vector<geometry_msgs::Point> getRobotFootprint()
00169   {
00170     return padded_footprint_;
00171   }
00172 
00180   std::vector<geometry_msgs::Point> getUnpaddedRobotFootprint()
00181   {
00182     return unpadded_footprint_;
00183   }
00184 
00192   void getOrientedFootprint(double x, double y, double theta, std::vector<geometry_msgs::Point>& oriented_footprint) const;
00193 
00198   void getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint) const;
00199 
00210   void setUnpaddedRobotFootprint( const std::vector<geometry_msgs::Point>& points );
00211 
00222   void setUnpaddedRobotFootprintPolygon( const geometry_msgs::Polygon& footprint );
00223 
00224 protected:
00225   LayeredCostmap* layered_costmap_;
00226   std::string name_;
00227   tf::TransformListener& tf_;  
00228   std::string global_frame_;  
00229   std::string robot_base_frame_;  
00230   double transform_tolerance_; 
00231 
00232 private:
00237   bool readFootprintFromString( const std::string& footprint_string );
00238 
00243   void readFootprintFromConfig( const costmap_2d::Costmap2DConfig &new_config,
00244                                 const costmap_2d::Costmap2DConfig &old_config );
00245 
00247   void setFootprintFromRadius( double radius );
00248   
00253   void readFootprintFromParams( ros::NodeHandle& nh );
00254 
00265   void readFootprintFromXMLRPC( XmlRpc::XmlRpcValue& footprint_xmlrpc,
00266                                 const std::string& full_param_name );
00267 
00271   void writeFootprintToParam( ros::NodeHandle& nh );
00272 
00273   void resetOldParameters(ros::NodeHandle& nh);
00274   void reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level);
00275   void movementCB(const ros::TimerEvent &event);
00276   void mapUpdateLoop(double frequency);
00277   bool map_update_thread_shutdown_;
00278   bool stop_updates_, initialized_, stopped_, robot_stopped_;
00279   boost::thread* map_update_thread_;  
00280   ros::Timer timer_;
00281   ros::Time last_publish_;
00282   ros::Duration publish_cycle;
00283   pluginlib::ClassLoader<Layer> plugin_loader_;
00284   tf::Stamped<tf::Pose> old_pose_;
00285   Costmap2DPublisher* publisher_;
00286   dynamic_reconfigure::Server<costmap_2d::Costmap2DConfig> *dsrv_;
00287 
00288   boost::recursive_mutex configuration_mutex_;
00289 
00290   ros::Subscriber footprint_sub_;
00291   bool got_footprint_;
00292   std::vector<geometry_msgs::Point> unpadded_footprint_;
00293   std::vector<geometry_msgs::Point> padded_footprint_;
00294   float footprint_padding_;
00295   costmap_2d::Costmap2DConfig old_config_;
00296 };
00297 // class Costmap2DROS
00298 }// namespace costmap_2d
00299 
00300 #endif


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55