38 #ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__BINARY_FILTER_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_FILTERS__BINARY_FILTER_HPP_
44 #include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"
46 #include "std_msgs/msg/bool.hpp"
47 #include "nav2_msgs/msg/costmap_filter_info.hpp"
69 const std::string & filter_info_topic);
76 int min_i,
int min_j,
int max_i,
int max_j,
77 const geometry_msgs::msg::Pose & pose);
93 void filterInfoCallback(
const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg);
97 void maskCallback(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
102 void changeState(
const bool state);
105 nav2::Subscription<nav2_msgs::msg::CostmapFilterInfo>::SharedPtr filter_info_sub_;
106 nav2::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr mask_sub_;
108 nav2::Publisher<std_msgs::msg::Bool>::SharedPtr binary_state_pub_;
110 nav_msgs::msg::OccupancyGrid::SharedPtr filter_mask_;
112 std::string global_frame_;
114 double base_, multiplier_;
117 double flip_threshold_;
Reads in a speed restriction mask and enables a robot to dynamically adjust speed based on pose in ma...
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 initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
BinaryFilter()
A constructor.
bool isActive()
If this filter is active.
void resetFilter()
Reset the costmap filter / topic / info.
A 2D costmap provides a mapping between points in the world and their associated "costs".
: CostmapFilter basic class. It is inherited from Layer in order to avoid hidden problems when the sh...