Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
Reads in a speed restriction mask and enables a robot to dynamically adjust speed based on pose in map to slow in dangerous areas. Done via absolute speed setting or percentage of maximum speed. More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/binary_filter.hpp>
Public Member Functions | |
BinaryFilter () | |
A constructor. | |
void | initializeFilter (const std::string &filter_info_topic) |
Initialize the filter and subscribe to the info topic. | |
void | process (nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j, const geometry_msgs::msg::Pose &pose) |
Process the keepout layer at the current pose / bounds / grid. | |
void | resetFilter () |
Reset the costmap filter / topic / info. | |
bool | isActive () |
If this filter is active. | |
![]() | |
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. | |
![]() | |
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 | 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) |
Additional Inherited Members | |
![]() | |
typedef std::recursive_mutex | mutex_t |
: Provide a typedef to ease future code maintenance | |
![]() | |
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::Pose &global_pose, const std::string mask_frame, geometry_msgs::msg::Pose &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... | |
![]() | |
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::ServiceServer< std_srvs::srv::SetBool >::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_ |
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_ |
Reads in a speed restriction mask and enables a robot to dynamically adjust speed based on pose in map to slow in dangerous areas. Done via absolute speed setting or percentage of maximum speed.
Definition at line 57 of file binary_filter.hpp.