Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
: CostmapFilter basic class. It is inherited from Layer in order to avoid hidden problems when the shared handling of costmap_ resource (PR #1936) More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/costmap_filter.hpp>
Public Types | |
typedef std::recursive_mutex | mutex_t |
: Provide a typedef to ease future code maintenance | |
Public Member Functions | |
CostmapFilter () | |
A constructor. | |
~CostmapFilter () | |
A destructor. | |
mutex_t * | getMutex () |
: returns pointer to a mutex | |
void | onInitialize () final |
Initialization process of layer on startup. | |
void | updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) final |
Update the bounds of the master costmap by this layer's update dimensions. More... | |
void | updateCosts (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) final |
Update the costs in the master costmap in the window. More... | |
void | activate () final |
Activate the layer. | |
void | deactivate () final |
Deactivate the layer. | |
void | reset () final |
Reset the layer. | |
bool | isClearable () |
If clearing operations should be processed on this layer or not. | |
virtual void | initializeFilter (const std::string &filter_info_topic)=0 |
: Initializes costmap filter. Creates subscriptions to filter-related topics More... | |
virtual void | process (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j, const geometry_msgs::msg::Pose2D &pose)=0 |
: An algorithm for how to use that map's information. Fills the Costmap2D with calculated data and makes an action based on processed data More... | |
virtual void | resetFilter ()=0 |
: Resets costmap filter. Stops all subscriptions | |
![]() | |
Layer () | |
A constructor. | |
virtual | ~Layer () |
A destructor. | |
void | initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf, const nav2_util::LifecycleNode::WeakPtr &node, rclcpp::CallbackGroup::SharedPtr callback_group) |
Initialization process of layer on startup. | |
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 | |
void | enableCallback (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< std_srvs::srv::SetBool::Request > request, std::shared_ptr< std_srvs::srv::SetBool::Response > response) |
Costmap filter enabling/disabling callback. More... | |
bool | transformPose (const std::string global_frame, const geometry_msgs::msg::Pose2D &global_pose, const std::string mask_frame, geometry_msgs::msg::Pose2D &mask_pose) const |
: Transforms robot pose from current layer frame to mask frame More... | |
bool | worldToMask (nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, double wx, double wy, unsigned int &mx, unsigned int &my) const |
: Convert from world coordinates to mask coordinates. Similar to Costmap2D::worldToMap() method but works directly with OccupancyGrid-s. More... | |
int8_t | getMaskData (nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, const unsigned int mx, const unsigned int my) const |
Get the data of a cell in the filter mask. More... | |
unsigned char | getMaskCost (nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, const unsigned int mx, const unsigned int &my) const |
Get the cost of a cell in the filter mask. More... | |
Protected Attributes | |
std::string | filter_info_topic_ |
: Name of costmap filter info topic | |
std::string | mask_topic_ |
: Name of filter mask topic | |
tf2::Duration | transform_tolerance_ |
: mask_frame->global_frame_ transform tolerance | |
nav2_util::ServiceServer< std_srvs::srv::SetBool, std::shared_ptr< rclcpp_lifecycle::LifecycleNode > >::SharedPtr | enable_service_ |
: A service to enable/disable costmap filter | |
![]() | |
LayeredCostmap * | layered_costmap_ |
std::string | name_ |
tf2_ros::Buffer * | tf_ |
rclcpp::CallbackGroup::SharedPtr | callback_group_ |
rclcpp_lifecycle::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_ |
: CostmapFilter basic class. It is inherited from Layer in order to avoid hidden problems when the shared handling of costmap_ resource (PR #1936)
Definition at line 61 of file costmap_filter.hpp.
|
protected |
Costmap filter enabling/disabling callback.
request_header | Service request header |
request | Service request |
response | Service response |
Definition at line 140 of file costmap_filter.cpp.
Referenced by onInitialize().
|
protected |
Get the cost of a cell in the filter mask.
filter_mask | Filter mask to get the cost from |
mx | The x coordinate of the cell |
my | The y coordinate of the cell |
Definition at line 216 of file costmap_filter.cpp.
Referenced by nav2_costmap_2d::KeepoutFilter::process().
|
inlineprotected |
Get the data of a cell in the filter mask.
filter_mask | Filter mask to get the data from |
mx | The x coordinate of the cell |
my | The y coordinate of the cell |
Definition at line 209 of file costmap_filter.hpp.
Referenced by nav2_costmap_2d::BinaryFilter::process(), and nav2_costmap_2d::SpeedFilter::process().
|
pure virtual |
: Initializes costmap filter. Creates subscriptions to filter-related topics
CostmapFilter API
Name of costmap filter info topic |
Implemented in nav2_costmap_2d::SpeedFilter, nav2_costmap_2d::KeepoutFilter, and nav2_costmap_2d::BinaryFilter.
Referenced by activate(), and reset().
|
pure virtual |
: An algorithm for how to use that map's information. Fills the Costmap2D with calculated data and makes an action based on processed data
Reference to a master costmap2d | |
Low window map boundary OX | |
Low window map boundary OY | |
High window map boundary OX | |
High window map boundary OY | |
Robot 2D-pose |
Implemented in nav2_costmap_2d::SpeedFilter, nav2_costmap_2d::KeepoutFilter, and nav2_costmap_2d::BinaryFilter.
Referenced by updateCosts().
|
protected |
: Transforms robot pose from current layer frame to mask frame
global_frame Costmap frame to transform from | |
global_pose Robot pose in costmap frame | |
mask_frame Filter mask frame to transform to | |
mask_pose Output robot pose in mask frame |
Definition at line 154 of file costmap_filter.cpp.
References transform_tolerance_.
Referenced by nav2_costmap_2d::BinaryFilter::process(), nav2_costmap_2d::KeepoutFilter::process(), and nav2_costmap_2d::SpeedFilter::process().
|
finalvirtual |
Update the bounds of the master costmap by this layer's update dimensions.
robot_x | X pose of robot |
robot_y | Y pose of robot |
robot_yaw | Robot orientation |
min_x | X min map coord of the window to update |
min_y | Y min map coord of the window to update |
max_x | X max map coord of the window to update |
max_y | Y max map coord of the window to update |
Implements nav2_costmap_2d::Layer.
Definition at line 115 of file costmap_filter.cpp.
|
finalvirtual |
Update the costs in the master costmap in the window.
master_grid | The master costmap grid to update |
min_x | X min map coord of the window to update |
min_y | Y min map coord of the window to update |
max_x | X max map coord of the window to update |
max_y | Y max map coord of the window to update |
Implements nav2_costmap_2d::Layer.
Definition at line 128 of file costmap_filter.cpp.
References process().
|
protected |
: Convert from world coordinates to mask coordinates. Similar to Costmap2D::worldToMap() method but works directly with OccupancyGrid-s.
filter_mask | Filter mask on which to convert |
wx | The x world coordinate |
wy | The y world coordinate |
mx | Will be set to the associated mask x coordinate |
my | Will be set to the associated mask y coordinate |
Definition at line 193 of file costmap_filter.cpp.
Referenced by nav2_costmap_2d::BinaryFilter::process(), nav2_costmap_2d::KeepoutFilter::process(), and nav2_costmap_2d::SpeedFilter::process().