Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef NAV_CORE2_COSTMAP_H
00036 #define NAV_CORE2_COSTMAP_H
00037
00038 #include <nav_grid/nav_grid.h>
00039 #include <nav_core2/common.h>
00040 #include <nav_core2/bounds.h>
00041 #include <boost/thread.hpp>
00042 #include <string>
00043
00044 namespace nav_core2
00045 {
00046
00047 class Costmap : public nav_grid::NavGrid<unsigned char>
00048 {
00049 public:
00050 static const unsigned char NO_INFORMATION = 255;
00051 static const unsigned char LETHAL_OBSTACLE = 254;
00052 static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
00053 static const unsigned char FREE_SPACE = 0;
00054
00055 using Ptr = std::shared_ptr<Costmap>;
00056
00060 virtual ~Costmap() {}
00061
00072 virtual void initialize(const ros::NodeHandle& parent, const std::string& name, TFListenerPtr tf) {}
00073
00074 inline unsigned char getCost(const unsigned int x, const unsigned int y)
00075 {
00076 return getValue(x, y);
00077 }
00078
00079 inline unsigned char getCost(const nav_grid::Index& index)
00080 {
00081 return getValue(index.x, index.y);
00082 }
00083
00084 inline void setCost(const unsigned int x, const unsigned int y, const unsigned char cost)
00085 {
00086 setValue(x, y, cost);
00087 }
00088
00089 inline void setCost(const nav_grid::Index& index, const unsigned char cost)
00090 {
00091 setValue(index, cost);
00092 }
00093
00101 virtual void update() {}
00102
00103 using mutex_t = boost::recursive_mutex;
00107 virtual mutex_t* getMutex() = 0;
00108
00112 virtual bool canTrackChanges() { return false; }
00113
00137 virtual UIntBounds getChangeBounds(const std::string& ns)
00138 {
00139 if (!canTrackChanges())
00140 {
00141 throw std::runtime_error("You called 'getChangeBounds()' on a derived Costmap type that is not capable of "
00142 "tracking changes (i.e. canTrackChanges() returns false). You shouldn't do that.");
00143 }
00144 else
00145 {
00146 throw std::runtime_error("You called 'getChangeBounds()' on a derived Costmap type that is capable of tracking "
00147 "changes but has not properly implemented this function. You should yell at the author "
00148 "of the derived Costmap.");
00149 }
00150 return UIntBounds();
00151 }
00152 };
00153 }
00154
00155 #endif // NAV_CORE2_COSTMAP_H