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
00036
00037 #ifndef COSTMAP_2D_LAYER_H_
00038 #define COSTMAP_2D_LAYER_H_
00039
00040 #include <costmap_2d/costmap_2d.h>
00041 #include <costmap_2d/layered_costmap.h>
00042 #include <string>
00043 #include <tf/tf.h>
00044 #include <tf/transform_listener.h>
00045
00046 namespace costmap_2d
00047 {
00048 class LayeredCostmap;
00049
00050 class Layer
00051 {
00052 public:
00053 Layer();
00054
00055 void initialize(LayeredCostmap* parent, std::string name, tf::TransformListener *tf);
00056
00065 virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
00066 double* max_x, double* max_y) {}
00067
00072 virtual void updateCosts(Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j) {}
00073
00075 virtual void deactivate() {}
00076
00078 virtual void activate() {}
00079
00080 virtual void reset() {}
00081
00082 virtual ~Layer() {}
00083
00094 bool isCurrent() const
00095 {
00096 return current_;
00097 }
00098
00100 virtual void matchSize() {}
00101
00102 std::string getName() const
00103 {
00104 return name_;
00105 }
00106
00108 const std::vector<geometry_msgs::Point>& getFootprint() const;
00109
00113 virtual void onFootprintChanged() {}
00114
00115 protected:
00120 virtual void onInitialize() {}
00121
00122 LayeredCostmap* layered_costmap_;
00123 bool current_;
00124 bool enabled_;
00125 std::string name_;
00126 tf::TransformListener* tf_;
00127
00128 private:
00129 std::vector<geometry_msgs::Point> footprint_spec_;
00130 };
00131
00132 }
00133
00134 #endif // COSTMAP_2D_LAYER_H_
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:15