Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
Abstract class for layered costmap plugin implementations. More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp>
Public Member Functions | |
Layer () | |
A constructor. | |
virtual | ~Layer () |
A destructor. | |
void | initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf, const nav2::LifecycleNode::WeakPtr &node, rclcpp::CallbackGroup::SharedPtr callback_group) |
Initialization process of layer on startup. | |
virtual void | deactivate () |
Stop publishers. | |
virtual void | activate () |
Restart publishers if they've been stopped. | |
virtual void | reset ()=0 |
Reset this costmap. | |
virtual bool | isClearable ()=0 |
If clearing operations should be processed on this layer or not. | |
virtual void | updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)=0 |
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to update. Each layer can increase the size of this bounds. More... | |
virtual void | updateCosts (Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)=0 |
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds(). | |
virtual void | matchSize () |
Implement this to make this layer match the size of the parent costmap. | |
virtual void | onFootprintChanged () |
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint. | |
std::string | getName () const |
Get the name of the costmap layer. | |
bool | isCurrent () const |
Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know. More... | |
bool | isEnabled () const |
Gets whether the layer is enabled. | |
const std::vector< geometry_msgs::msg::Point > & | getFootprint () const |
Convenience function for layered_costmap_->getFootprint(). | |
void | declareParameter (const std::string ¶m_name, const rclcpp::ParameterValue &value) |
Convenience functions for declaring ROS parameters. | |
void | declareParameter (const std::string ¶m_name, const rclcpp::ParameterType ¶m_type) |
Convenience functions for declaring ROS parameters. | |
bool | hasParameter (const std::string ¶m_name) |
Convenience functions for declaring ROS parameters. | |
std::string | getFullName (const std::string ¶m_name) |
Convenience functions for declaring ROS parameters. | |
std::string | joinWithParentNamespace (const std::string &topic) |
Protected Member Functions | |
virtual void | onInitialize () |
This is called at the end of initialize(). Override to implement subclass-specific initialization. More... | |
Protected Attributes | |
LayeredCostmap * | layered_costmap_ |
std::string | name_ |
tf2_ros::Buffer * | tf_ |
rclcpp::CallbackGroup::SharedPtr | callback_group_ |
nav2::LifecycleNode::WeakPtr | node_ |
rclcpp::Clock::SharedPtr | clock_ |
rclcpp::Logger | logger_ {rclcpp::get_logger("nav2_costmap_2d")} |
bool | current_ |
bool | enabled_ |
std::unordered_set< std::string > | local_params_ |
|
inline |
Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know.
A layer's current state should be managed by the protected variable current_.
std::string nav2_costmap_2d::Layer::joinWithParentNamespace | ( | const std::string & | topic | ) |
Joins the specified topic with the parent namespace of the layer node. If the topic has an absolute path, it is returned instead.
This is necessary for user defined relative topics to work as expected since costmap layers add an additional costmap_name
namespace to the topic. For example:
tb4
.scan
./tb4/global_costmap
./tb4/global_costmap/scan
./tb4/scan
. Use global topic /scan
if you do not wish the node namespace to applytopic | the topic to parse |
Definition at line 121 of file layer.cpp.
Referenced by nav2_costmap_2d::StaticLayer::getParameters(), nav2_costmap_2d::KeepoutFilter::initializeFilter(), nav2_costmap_2d::SpeedFilter::initializeFilter(), and nav2_costmap_2d::ObstacleLayer::onInitialize().
|
inlineprotectedvirtual |
This is called at the end of initialize(). Override to implement subclass-specific initialization.
tf_, name_, and layered_costmap_ will all be set already when this is called.
Reimplemented in nav2_costmap_2d::InflationLayer, nav2_costmap_2d::DenoiseLayer, nav2_costmap_2d::CostmapFilter, nav2_costmap_2d::VoxelLayer, nav2_costmap_2d::StaticLayer, nav2_costmap_2d::RangeSensorLayer, nav2_costmap_2d::PluginContainerLayer, and nav2_costmap_2d::ObstacleLayer.
Definition at line 196 of file layer.hpp.
Referenced by initialize().
|
pure virtual |
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to update. Each layer can increase the size of this bounds.
For more details, see "Layered Costmaps for Context-Sensitive Navigation", by Lu et. Al, IROS 2014.
Implemented in nav2_costmap_2d::InflationLayer, nav2_costmap_2d::DenoiseLayer, nav2_costmap_2d::CostmapFilter, nav2_costmap_2d::VoxelLayer, nav2_costmap_2d::StaticLayer, nav2_costmap_2d::RangeSensorLayer, nav2_costmap_2d::PluginContainerLayer, and nav2_costmap_2d::ObstacleLayer.