add function getTypeLayer
This commit is contained in:
parent
6c682712fe
commit
ae469e3271
|
|
@ -10,6 +10,10 @@ class CriticalLayer : public StaticLayer
|
||||||
public:
|
public:
|
||||||
CriticalLayer();
|
CriticalLayer();
|
||||||
virtual ~CriticalLayer();
|
virtual ~CriticalLayer();
|
||||||
|
LayerType getType() const override
|
||||||
|
{
|
||||||
|
return LayerType::CRITICAL_LAYER;
|
||||||
|
}
|
||||||
private:
|
private:
|
||||||
unsigned char interpretValue(unsigned char value) override;
|
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;
|
void updateCosts(robot_costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j) override;
|
||||||
|
|
|
||||||
|
|
@ -13,7 +13,10 @@ namespace robot_costmap_2d
|
||||||
virtual ~DirectionalLayer();
|
virtual ~DirectionalLayer();
|
||||||
bool laneFilter(const std::vector<robot_geometry_msgs::PoseStamped> plan);
|
bool laneFilter(const std::vector<robot_geometry_msgs::PoseStamped> plan);
|
||||||
void resetMap();
|
void resetMap();
|
||||||
|
LayerType getType() const override
|
||||||
|
{
|
||||||
|
return LayerType::DIRECTIONAL_LAYER;
|
||||||
|
}
|
||||||
private:
|
private:
|
||||||
void incomingMap(const robot_nav_msgs::OccupancyGrid &new_map);
|
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);
|
bool laneFilter(std::vector<std::array<uint16_t, 2>> new_map, const robot_nav_msgs::Path path);
|
||||||
|
|
|
||||||
|
|
@ -67,6 +67,7 @@ public:
|
||||||
unsigned int index_;
|
unsigned int index_;
|
||||||
unsigned int x_, y_;
|
unsigned int x_, y_;
|
||||||
unsigned int src_x_, src_y_;
|
unsigned int src_x_, src_y_;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class InflationLayer : public Layer
|
class InflationLayer : public Layer
|
||||||
|
|
@ -120,6 +121,10 @@ public:
|
||||||
*/
|
*/
|
||||||
void setInflationParameters(double inflation_radius, double cost_scaling_factor);
|
void setInflationParameters(double inflation_radius, double cost_scaling_factor);
|
||||||
|
|
||||||
|
LayerType getType() const override
|
||||||
|
{
|
||||||
|
return LayerType::INFLATION_LAYER;
|
||||||
|
}
|
||||||
protected:
|
protected:
|
||||||
virtual void onFootprintChanged();
|
virtual void onFootprintChanged();
|
||||||
boost::recursive_mutex* inflation_access_;
|
boost::recursive_mutex* inflation_access_;
|
||||||
|
|
|
||||||
|
|
@ -45,6 +45,21 @@
|
||||||
#include <robot/node_handle.h>
|
#include <robot/node_handle.h>
|
||||||
namespace robot_costmap_2d
|
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 LayeredCostmap;
|
||||||
|
|
||||||
class Layer
|
class Layer
|
||||||
|
|
@ -79,7 +94,7 @@ public:
|
||||||
|
|
||||||
virtual void reset() {}
|
virtual void reset() {}
|
||||||
|
|
||||||
virtual ~Layer() {}
|
virtual ~Layer() = default;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Check to make sure all the data in the layer is up to date.
|
* @brief Check to make sure all the data in the layer is up to date.
|
||||||
|
|
@ -130,6 +145,8 @@ public:
|
||||||
* notified of changes to the robot's footprint. */
|
* notified of changes to the robot's footprint. */
|
||||||
virtual void onFootprintChanged() {}
|
virtual void onFootprintChanged() {}
|
||||||
|
|
||||||
|
virtual LayerType getType() const { return LayerType::UNKNOWN; }
|
||||||
|
|
||||||
template<typename T>
|
template<typename T>
|
||||||
void dataCallBack(const T& value, const std::string& topic) {
|
void dataCallBack(const T& value, const std::string& topic) {
|
||||||
handle(value, topic);
|
handle(value, topic);
|
||||||
|
|
|
||||||
|
|
@ -76,6 +76,11 @@ public:
|
||||||
void addStaticObservation(robot_costmap_2d::Observation& obs, bool marking, bool clearing);
|
void addStaticObservation(robot_costmap_2d::Observation& obs, bool marking, bool clearing);
|
||||||
void clearStaticObservations(bool marking, bool clearing);
|
void clearStaticObservations(bool marking, bool clearing);
|
||||||
|
|
||||||
|
LayerType getType() const override
|
||||||
|
{
|
||||||
|
return LayerType::OBSTACLE_LAYER;
|
||||||
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void handleImpl(const void* data,
|
void handleImpl(const void* data,
|
||||||
const std::type_info&,
|
const std::type_info&,
|
||||||
|
|
|
||||||
|
|
@ -10,6 +10,10 @@ class PreferredLayer : public StaticLayer
|
||||||
public:
|
public:
|
||||||
PreferredLayer();
|
PreferredLayer();
|
||||||
virtual ~PreferredLayer();
|
virtual ~PreferredLayer();
|
||||||
|
LayerType getType() const override
|
||||||
|
{
|
||||||
|
return LayerType::PREFERRED_LAYER;
|
||||||
|
}
|
||||||
private:
|
private:
|
||||||
unsigned char interpretValue(unsigned char value);
|
unsigned char interpretValue(unsigned char value);
|
||||||
};
|
};
|
||||||
|
|
|
||||||
|
|
@ -63,6 +63,12 @@ public:
|
||||||
virtual void updateCosts(robot_costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
|
virtual void updateCosts(robot_costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
|
||||||
|
|
||||||
virtual void matchSize();
|
virtual void matchSize();
|
||||||
|
|
||||||
|
LayerType getType() const override
|
||||||
|
{
|
||||||
|
return LayerType::STATIC_LAYER;
|
||||||
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void handleImpl(const void* data,
|
void handleImpl(const void* data,
|
||||||
const std::type_info& type,
|
const std::type_info& type,
|
||||||
|
|
|
||||||
|
|
@ -10,7 +10,10 @@ class UnPreferredLayer : public StaticLayer
|
||||||
public:
|
public:
|
||||||
UnPreferredLayer();
|
UnPreferredLayer();
|
||||||
virtual ~UnPreferredLayer();
|
virtual ~UnPreferredLayer();
|
||||||
|
LayerType getType() const override
|
||||||
|
{
|
||||||
|
return LayerType::UNPREFERRED_LAYER;
|
||||||
|
}
|
||||||
private:
|
private:
|
||||||
unsigned char interpretValue(unsigned char value);
|
unsigned char interpretValue(unsigned char value);
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -76,7 +76,10 @@ public:
|
||||||
}
|
}
|
||||||
virtual void matchSize();
|
virtual void matchSize();
|
||||||
virtual void reset();
|
virtual void reset();
|
||||||
|
LayerType getType() const override
|
||||||
|
{
|
||||||
|
return LayerType::VOXEL_LAYER;
|
||||||
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -347,7 +347,7 @@ void StaticLayer::updateCosts(robot_costmap_2d::Costmap2D& master_grid, int min_
|
||||||
tf3::TransformStampedMsg transformMsg;
|
tf3::TransformStampedMsg transformMsg;
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
transformMsg = tf_->lookupTransform(map_frame_, global_frame_, tf3::Time::now());
|
transformMsg = tf_->lookupTransform(map_frame_, global_frame_, tf3::Time());
|
||||||
}
|
}
|
||||||
catch (tf3::TransformException ex)
|
catch (tf3::TransformException ex)
|
||||||
{
|
{
|
||||||
|
|
|
||||||
|
|
@ -66,7 +66,7 @@ bool ObservationBuffer::setGlobalFrame(const std::string new_global_frame)
|
||||||
std::string tf_error;
|
std::string tf_error;
|
||||||
|
|
||||||
robot_geometry_msgs::TransformStamped transformStamped;
|
robot_geometry_msgs::TransformStamped transformStamped;
|
||||||
if (!tf3_buffer_.canTransform(new_global_frame, global_frame_, transform_time, &tf_error))
|
if (!tf3_buffer_.canTransform(new_global_frame, global_frame_, tf3::Time(), &tf_error))
|
||||||
{
|
{
|
||||||
printf("Transform between %s and %s with tolerance %.2f failed: %s.\n", new_global_frame.c_str(),
|
printf("Transform between %s and %s with tolerance %.2f failed: %s.\n", new_global_frame.c_str(),
|
||||||
global_frame_.c_str(), tf_tolerance_, tf_error.c_str());
|
global_frame_.c_str(), tf_tolerance_, tf_error.c_str());
|
||||||
|
|
@ -90,7 +90,7 @@ bool ObservationBuffer::setGlobalFrame(const std::string new_global_frame)
|
||||||
tf3::TransformStampedMsg tfm_1 = tf3_buffer_.lookupTransform(
|
tf3::TransformStampedMsg tfm_1 = tf3_buffer_.lookupTransform(
|
||||||
new_global_frame, // frame đích
|
new_global_frame, // frame đích
|
||||||
origin.header.frame_id, // frame nguồn
|
origin.header.frame_id, // frame nguồn
|
||||||
transform_time
|
tf3::Time()
|
||||||
);
|
);
|
||||||
tf3::doTransform(origin, origin, tfm_1);
|
tf3::doTransform(origin, origin, tfm_1);
|
||||||
obs.origin_ = origin.point;
|
obs.origin_ = origin.point;
|
||||||
|
|
@ -100,7 +100,7 @@ bool ObservationBuffer::setGlobalFrame(const std::string new_global_frame)
|
||||||
tf3::TransformStampedMsg tfm_2 = tf3_buffer_.lookupTransform(
|
tf3::TransformStampedMsg tfm_2 = tf3_buffer_.lookupTransform(
|
||||||
new_global_frame, // frame đích
|
new_global_frame, // frame đích
|
||||||
obs.cloud_->header.frame_id, // frame nguồn
|
obs.cloud_->header.frame_id, // frame nguồn
|
||||||
transform_time
|
tf3::Time()
|
||||||
);
|
);
|
||||||
tf3::doTransform(*(obs.cloud_), *(obs.cloud_), tfm_2);
|
tf3::doTransform(*(obs.cloud_), *(obs.cloud_), tfm_2);
|
||||||
}
|
}
|
||||||
|
|
@ -140,7 +140,7 @@ void ObservationBuffer::bufferCloud(const robot_sensor_msgs::PointCloud2& cloud)
|
||||||
tf3::TransformStampedMsg tfm_1 = tf3_buffer_.lookupTransform(
|
tf3::TransformStampedMsg tfm_1 = tf3_buffer_.lookupTransform(
|
||||||
global_frame_, // frame đích
|
global_frame_, // frame đích
|
||||||
local_origin.header.frame_id, // frame nguồn
|
local_origin.header.frame_id, // frame nguồn
|
||||||
data_convert::convertTime(local_origin.header.stamp)
|
tf3::Time()
|
||||||
);
|
);
|
||||||
tf3::doTransform(local_origin, global_origin, tfm_1);
|
tf3::doTransform(local_origin, global_origin, tfm_1);
|
||||||
|
|
||||||
|
|
@ -161,7 +161,7 @@ void ObservationBuffer::bufferCloud(const robot_sensor_msgs::PointCloud2& cloud)
|
||||||
tf3::TransformStampedMsg tfm_2 = tf3_buffer_.lookupTransform(
|
tf3::TransformStampedMsg tfm_2 = tf3_buffer_.lookupTransform(
|
||||||
global_frame_, // frame đích
|
global_frame_, // frame đích
|
||||||
cloud.header.frame_id, // frame nguồn
|
cloud.header.frame_id, // frame nguồn
|
||||||
data_convert::convertTime(cloud.header.stamp)
|
tf3::Time()
|
||||||
);
|
);
|
||||||
tf3::doTransform(cloud, global_frame_cloud, tfm_2);
|
tf3::doTransform(cloud, global_frame_cloud, tfm_2);
|
||||||
global_frame_cloud.header.stamp = cloud.header.stamp;
|
global_frame_cloud.header.stamp = cloud.header.stamp;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue
Block a user