Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
costmap_filter.hpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * Copyright (c) 2020 Samsung Research Russia
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the <ORGANIZATION> nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Eitan Marder-Eppstein
37  * David V. Lu!!
38  * Alexey Merzlyakov
39  *********************************************************************/
40 
41 #ifndef NAV2_COSTMAP_2D__COSTMAP_FILTERS__COSTMAP_FILTER_HPP_
42 #define NAV2_COSTMAP_2D__COSTMAP_FILTERS__COSTMAP_FILTER_HPP_
43 
44 #include <string>
45 #include <mutex>
46 
47 #include "geometry_msgs/msg/pose2_d.hpp"
48 #include "std_srvs/srv/set_bool.hpp"
49 #include "nav2_costmap_2d/layer.hpp"
50 #include "nav_msgs/msg/occupancy_grid.hpp"
51 
52 namespace nav2_costmap_2d
53 {
54 
59 class CostmapFilter : public Layer
60 {
61 public:
65  CostmapFilter();
70 
74  typedef std::recursive_mutex mutex_t;
79  {
80  return access_;
81  }
82 
86  void onInitialize() final;
87 
98  void updateBounds(
99  double robot_x, double robot_y, double robot_yaw,
100  double * min_x, double * min_y, double * max_x, double * max_y) final;
101 
110  void updateCosts(
111  nav2_costmap_2d::Costmap2D & master_grid,
112  int min_i, int min_j, int max_i, int max_j) final;
113 
117  void activate() final;
121  void deactivate() final;
125  void reset() final;
126 
130  bool isClearable() {return false;}
131 
137  virtual void initializeFilter(
138  const std::string & filter_info_topic) = 0;
139 
150  virtual void process(
151  nav2_costmap_2d::Costmap2D & master_grid,
152  int min_i, int min_j, int max_i, int max_j,
153  const geometry_msgs::msg::Pose2D & pose) = 0;
154 
158  virtual void resetFilter() = 0;
159 
160 protected:
167  void enableCallback(
168  const std::shared_ptr<rmw_request_id_t> request_header,
169  const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
170  std::shared_ptr<std_srvs::srv::SetBool::Response> response);
171 
180  bool transformPose(
181  const std::string global_frame,
182  const geometry_msgs::msg::Pose2D & global_pose,
183  const std::string mask_frame,
184  geometry_msgs::msg::Pose2D & mask_pose) const;
185 
196  bool worldToMask(
197  nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
198  double wx, double wy, unsigned int & mx, unsigned int & my) const;
199 
207  inline int8_t getMaskData(
208  nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
209  const unsigned int mx, const unsigned int my) const
210  {
211  return filter_mask->data[my * filter_mask->info.width + mx];
212  }
213 
217  std::string filter_info_topic_;
218 
222  std::string mask_topic_;
223 
227  tf2::Duration transform_tolerance_;
228 
232  rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr enable_service_;
233 
234 private:
238  geometry_msgs::msg::Pose2D latest_pose_;
239 
243  mutex_t * access_;
244 };
245 
246 } // namespace nav2_costmap_2d
247 
248 #endif // NAV2_COSTMAP_2D__COSTMAP_FILTERS__COSTMAP_FILTER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
: CostmapFilter basic class. It is inherited from Layer in order to avoid hidden problems when the sh...
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.
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...
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::Pose2D &pose)=0
: An algorithm for how to use that map's information. Fills the Costmap2D with calculated data and ma...
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.
bool transformPose(const std::string global_frame, const geometry_msgs::msg::Pose2D &global_pose, const std::string mask_frame, geometry_msgs::msg::Pose2D &mask_pose) const
: Transforms robot pose from current layer frame to mask frame
virtual void initializeFilter(const std::string &filter_info_topic)=0
: Initializes costmap filter. Creates subscriptions to filter-related topics
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
rclcpp::Service< std_srvs::srv::SetBool >::SharedPtr enable_service_
: A service to enable/disable costmap filter
virtual void resetFilter()=0
: Resets costmap filter. Stops all subscriptions
tf2::Duration transform_tolerance_
: mask_frame_->global_frame_ transform tolerance
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.
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59