update from DuongTD
This commit is contained in:
@@ -45,6 +45,20 @@
|
||||
#include <robot/node_handle.h>
|
||||
namespace robot_costmap_2d
|
||||
{
|
||||
|
||||
enum class LayerType
|
||||
{
|
||||
UNKNOWN,
|
||||
STATIC_LAYER,
|
||||
OBSTACLE_LAYER,
|
||||
INFLATION_LAYER,
|
||||
CRITICAL_LAYER,
|
||||
DIRECTIONAL_LAYER,
|
||||
PREFERRED_LAYER,
|
||||
UNPREFERRED_LAYER,
|
||||
VOXEL_LAYER
|
||||
};
|
||||
|
||||
class LayeredCostmap;
|
||||
|
||||
class Layer
|
||||
@@ -134,6 +148,9 @@ public:
|
||||
void dataCallBack(const T& value, const std::string& topic) {
|
||||
handle(value, topic);
|
||||
}
|
||||
|
||||
virtual LayerType getType() const { return LayerType::UNKNOWN; }
|
||||
|
||||
protected:
|
||||
|
||||
// Hàm template public, dùng để gửi dữ liệu
|
||||
@@ -157,7 +174,7 @@ protected:
|
||||
bool enabled_;
|
||||
std::string name_;
|
||||
tf3::BufferCore *tf_;
|
||||
|
||||
|
||||
private:
|
||||
std::vector<robot_geometry_msgs::Point> footprint_spec_;
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user