update
This commit is contained in:
@@ -55,18 +55,18 @@
|
||||
|
||||
#include <robot/node_handle.h>
|
||||
#include <robot/plugin_loader_helper.h>
|
||||
class SuperValue : public robot::XmlRpc::XmlRpcValue
|
||||
class SuperValue : public robot_xmlrpcpp::XmlRpcValue
|
||||
{
|
||||
public:
|
||||
void setStruct(robot::XmlRpc::XmlRpcValue::ValueStruct* a)
|
||||
void setStruct(robot_xmlrpcpp::XmlRpcValue::ValueStruct* a)
|
||||
{
|
||||
_type = TypeStruct;
|
||||
_value.asStruct = new robot::XmlRpc::XmlRpcValue::ValueStruct(*a);
|
||||
_value.asStruct = new robot_xmlrpcpp::XmlRpcValue::ValueStruct(*a);
|
||||
}
|
||||
void setArray(robot::XmlRpc::XmlRpcValue::ValueArray* a)
|
||||
void setArray(robot_xmlrpcpp::XmlRpcValue::ValueArray* a)
|
||||
{
|
||||
_type = TypeArray;
|
||||
_value.asArray = new std::vector<robot::XmlRpc::XmlRpcValue>(*a);
|
||||
_value.asArray = new std::vector<robot_xmlrpcpp::XmlRpcValue>(*a);
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
@@ -10,10 +10,6 @@ class CriticalLayer : public StaticLayer
|
||||
public:
|
||||
CriticalLayer();
|
||||
virtual ~CriticalLayer();
|
||||
LayerType getType() const override
|
||||
{
|
||||
return LayerType::CRITICAL_LAYER;
|
||||
}
|
||||
private:
|
||||
unsigned char interpretValue(unsigned char value) override;
|
||||
void updateCosts(robot_costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j) override;
|
||||
|
||||
@@ -13,10 +13,7 @@ namespace robot_costmap_2d
|
||||
virtual ~DirectionalLayer();
|
||||
bool laneFilter(const std::vector<robot_geometry_msgs::PoseStamped> plan);
|
||||
void resetMap();
|
||||
LayerType getType() const override
|
||||
{
|
||||
return LayerType::DIRECTIONAL_LAYER;
|
||||
}
|
||||
|
||||
private:
|
||||
void incomingMap(const robot_nav_msgs::OccupancyGrid &new_map);
|
||||
bool laneFilter(std::vector<std::array<uint16_t, 2>> new_map, const robot_nav_msgs::Path path);
|
||||
|
||||
@@ -136,7 +136,7 @@ std::vector<robot_geometry_msgs::Point> makeFootprintFromParams(robot::NodeHandl
|
||||
* @param full_param_name this is the full name of the rosparam from
|
||||
* which the footprint_xmlrpc value came. It is used only for
|
||||
* reporting errors. */
|
||||
std::vector<robot_geometry_msgs::Point> makeFootprintFromXMLRPC(robot::XmlRpc::XmlRpcValue& footprint_xmlrpc,
|
||||
std::vector<robot_geometry_msgs::Point> makeFootprintFromXMLRPC(robot_xmlrpcpp::XmlRpcValue& footprint_xmlrpc,
|
||||
const std::string& full_param_name);
|
||||
|
||||
// /** @brief Write the current unpadded_footprint_ to the "footprint"
|
||||
|
||||
@@ -67,7 +67,6 @@ public:
|
||||
unsigned int index_;
|
||||
unsigned int x_, y_;
|
||||
unsigned int src_x_, src_y_;
|
||||
|
||||
};
|
||||
|
||||
class InflationLayer : public Layer
|
||||
@@ -121,10 +120,6 @@ public:
|
||||
*/
|
||||
void setInflationParameters(double inflation_radius, double cost_scaling_factor);
|
||||
|
||||
LayerType getType() const override
|
||||
{
|
||||
return LayerType::INFLATION_LAYER;
|
||||
}
|
||||
protected:
|
||||
virtual void onFootprintChanged();
|
||||
boost::recursive_mutex* inflation_access_;
|
||||
|
||||
@@ -45,21 +45,6 @@
|
||||
#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
|
||||
@@ -94,7 +79,7 @@ public:
|
||||
|
||||
virtual void reset() {}
|
||||
|
||||
virtual ~Layer() = default;
|
||||
virtual ~Layer() {}
|
||||
|
||||
/**
|
||||
* @brief Check to make sure all the data in the layer is up to date.
|
||||
@@ -145,8 +130,6 @@ public:
|
||||
* notified of changes to the robot's footprint. */
|
||||
virtual void onFootprintChanged() {}
|
||||
|
||||
virtual LayerType getType() const { return LayerType::UNKNOWN; }
|
||||
|
||||
template<typename T>
|
||||
void dataCallBack(const T& value, const std::string& topic) {
|
||||
handle(value, topic);
|
||||
|
||||
@@ -76,11 +76,6 @@ public:
|
||||
void addStaticObservation(robot_costmap_2d::Observation& obs, bool marking, bool clearing);
|
||||
void clearStaticObservations(bool marking, bool clearing);
|
||||
|
||||
LayerType getType() const override
|
||||
{
|
||||
return LayerType::OBSTACLE_LAYER;
|
||||
}
|
||||
|
||||
protected:
|
||||
void handleImpl(const void* data,
|
||||
const std::type_info&,
|
||||
|
||||
@@ -10,10 +10,6 @@ class PreferredLayer : public StaticLayer
|
||||
public:
|
||||
PreferredLayer();
|
||||
virtual ~PreferredLayer();
|
||||
LayerType getType() const override
|
||||
{
|
||||
return LayerType::PREFERRED_LAYER;
|
||||
}
|
||||
private:
|
||||
unsigned char interpretValue(unsigned char value);
|
||||
};
|
||||
|
||||
@@ -63,12 +63,6 @@ public:
|
||||
virtual void updateCosts(robot_costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
|
||||
|
||||
virtual void matchSize();
|
||||
|
||||
LayerType getType() const override
|
||||
{
|
||||
return LayerType::STATIC_LAYER;
|
||||
}
|
||||
|
||||
protected:
|
||||
void handleImpl(const void* data,
|
||||
const std::type_info& type,
|
||||
|
||||
@@ -10,10 +10,7 @@ class UnPreferredLayer : public StaticLayer
|
||||
public:
|
||||
UnPreferredLayer();
|
||||
virtual ~UnPreferredLayer();
|
||||
LayerType getType() const override
|
||||
{
|
||||
return LayerType::UNPREFERRED_LAYER;
|
||||
}
|
||||
|
||||
private:
|
||||
unsigned char interpretValue(unsigned char value);
|
||||
|
||||
|
||||
@@ -76,10 +76,7 @@ public:
|
||||
}
|
||||
virtual void matchSize();
|
||||
virtual void reset();
|
||||
LayerType getType() const override
|
||||
{
|
||||
return LayerType::VOXEL_LAYER;
|
||||
}
|
||||
|
||||
|
||||
protected:
|
||||
|
||||
|
||||
Reference in New Issue
Block a user