41 #ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__COSTMAP_FILTER_HPP_
42 #define NAV2_COSTMAP_2D__COSTMAP_FILTERS__COSTMAP_FILTER_HPP_
48 #include "geometry_msgs/msg/pose.hpp"
49 #include "std_srvs/srv/set_bool.hpp"
50 #include "nav2_costmap_2d/layer.hpp"
51 #include "nav_msgs/msg/occupancy_grid.hpp"
52 #include "nav2_ros_common/service_server.hpp"
101 double robot_x,
double robot_y,
double robot_yaw,
102 double * min_x,
double * min_y,
double * max_x,
double * max_y) final;
114 int min_i,
int min_j,
int max_i,
int max_j) final;
140 const std::string & filter_info_topic) = 0;
154 int min_i,
int min_j,
int max_i,
int max_j,
155 const geometry_msgs::msg::Pose & pose) = 0;
170 const std::shared_ptr<rmw_request_id_t> request_header,
171 const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
172 std::shared_ptr<std_srvs::srv::SetBool::Response> response);
183 const std::string global_frame,
184 const geometry_msgs::msg::Pose & global_pose,
185 const std::string mask_frame,
186 geometry_msgs::msg::Pose & mask_pose)
const;
199 nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
200 double wx,
double wy,
unsigned int & mx,
unsigned int & my)
const;
210 nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
211 const unsigned int mx,
const unsigned int my)
const
213 return filter_mask->data[my * filter_mask->info.width + mx];
224 nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
225 const unsigned int mx,
const unsigned int & my)
const;
251 geometry_msgs::msg::Pose latest_pose_;
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...
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::Pose &pose)=0
: An algorithm for how to use that map's information. Fills the Costmap2D with calculated data and ma...
void activate() final
Activate the layer.
std::recursive_mutex mutex_t
: Provide a typedef to ease future code maintenance
bool isClearable()
If clearing operations should be processed on this layer or not.
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.
nav2::ServiceServer< std_srvs::srv::SetBool >::SharedPtr enable_service_
: A service to enable/disable costmap filter
void deactivate() final
Deactivate the layer.
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 w...
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
void reset() final
Reset the layer.
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.
virtual void initializeFilter(const std::string &filter_info_topic)=0
: Initializes costmap filter. Creates subscriptions to filter-related topics
CostmapFilter()
A constructor.
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.
std::string filter_info_topic_
: Name of costmap filter info topic
std::string mask_topic_
: Name of filter mask topic
virtual void resetFilter()=0
: Resets costmap filter. Stops all subscriptions
tf2::Duration transform_tolerance_
: mask_frame->global_frame_ transform tolerance
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.
mutex_t * getMutex()
: returns pointer to a mutex
void onInitialize() final
Initialization process of layer on startup.
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.
~CostmapFilter()
A destructor.
Abstract class for layered costmap plugin implementations.