38 #ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__KEEPOUT_FILTER_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_FILTERS__KEEPOUT_FILTER_HPP_
44 #include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"
46 #include "rclcpp/rclcpp.hpp"
47 #include "nav2_msgs/msg/costmap_filter_info.hpp"
69 const std::string & filter_info_topic);
82 double robot_x,
double robot_y,
double robot_yaw,
83 double * min_x,
double * min_y,
double * max_x,
double * max_y)
override;
90 int min_i,
int min_j,
int max_i,
int max_j,
91 const geometry_msgs::msg::Pose & pose);
107 void filterInfoCallback(
const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg);
111 void maskCallback(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
113 nav2::Subscription<nav2_msgs::msg::CostmapFilterInfo>::SharedPtr filter_info_sub_;
114 nav2::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr mask_sub_;
116 nav_msgs::msg::OccupancyGrid::SharedPtr filter_mask_;
118 std::string global_frame_;
120 bool override_lethal_cost_{
false};
121 unsigned char lethal_override_cost_{252};
122 bool last_pose_lethal_{
false};
123 bool is_pose_lethal_{
false};
124 double lethal_state_update_min_x_, lethal_state_update_min_y_;
125 double lethal_state_update_max_x_, lethal_state_update_max_y_;
129 unsigned int width_{0};
130 unsigned int height_{0};
131 bool has_updated_data_{
false};
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...
Reads in a keepout mask and marks keepout regions in the map to prevent planning or control in restri...
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.
KeepoutFilter()
A constructor.
void resetFilter()
Reset the costmap filter / topic / info.
void initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
bool isActive()
If this filter is active.
void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) override
Update the bounds of the master costmap by this layer's update dimensions.