38 #ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__SPEED_FILTER_HPP_
39 #define NAV2_COSTMAP_2D__COSTMAP_FILTERS__SPEED_FILTER_HPP_
44 #include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"
46 #include "nav2_msgs/msg/costmap_filter_info.hpp"
47 #include "nav2_msgs/msg/speed_limit.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::Pose2D & pose);
93 void filterInfoCallback(
const nav2_msgs::msg::CostmapFilterInfo::SharedPtr msg);
97 void maskCallback(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
99 rclcpp::Subscription<nav2_msgs::msg::CostmapFilterInfo>::SharedPtr filter_info_sub_;
100 rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr mask_sub_;
102 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::SpeedLimit>::SharedPtr speed_limit_pub_;
104 nav_msgs::msg::OccupancyGrid::SharedPtr filter_mask_;
106 std::string mask_frame_;
107 std::string global_frame_;
109 double base_, multiplier_;
111 double speed_limit_, speed_limit_prev_;
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 speed restriction mask and enables a robot to dynamically adjust speed based on pose in ma...
void initializeFilter(const std::string &filter_info_topic)
Initialize the filter and subscribe to the info topic.
void resetFilter()
Reset the costmap filter / topic / info.
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)
Process the keepout layer at the current pose / bounds / grid.
SpeedFilter()
A constructor.
bool isActive()
If this filter is active.