Nav2 Navigation Stack - kilted  kilted
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 #include <memory>
47 
48 #include "geometry_msgs/msg/pose2_d.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_util/service_server.hpp"
53 
54 namespace nav2_costmap_2d
55 {
56 
61 class CostmapFilter : public Layer
62 {
63 public:
67  CostmapFilter();
72 
76  typedef std::recursive_mutex mutex_t;
81  {
82  return access_;
83  }
84 
88  void onInitialize() final;
89 
100  void updateBounds(
101  double robot_x, double robot_y, double robot_yaw,
102  double * min_x, double * min_y, double * max_x, double * max_y) final;
103 
112  void updateCosts(
113  nav2_costmap_2d::Costmap2D & master_grid,
114  int min_i, int min_j, int max_i, int max_j) final;
115 
119  void activate() final;
123  void deactivate() final;
127  void reset() final;
128 
132  bool isClearable() {return false;}
133 
139  virtual void initializeFilter(
140  const std::string & filter_info_topic) = 0;
141 
152  virtual void process(
153  nav2_costmap_2d::Costmap2D & master_grid,
154  int min_i, int min_j, int max_i, int max_j,
155  const geometry_msgs::msg::Pose2D & pose) = 0;
156 
160  virtual void resetFilter() = 0;
161 
162 protected:
169  void enableCallback(
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);
173 
182  bool transformPose(
183  const std::string global_frame,
184  const geometry_msgs::msg::Pose2D & global_pose,
185  const std::string mask_frame,
186  geometry_msgs::msg::Pose2D & mask_pose) const;
187 
198  bool worldToMask(
199  nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
200  double wx, double wy, unsigned int & mx, unsigned int & my) const;
201 
209  inline int8_t getMaskData(
210  nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
211  const unsigned int mx, const unsigned int my) const
212  {
213  return filter_mask->data[my * filter_mask->info.width + mx];
214  }
215 
223  unsigned char getMaskCost(
224  nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
225  const unsigned int mx, const unsigned int & my) const;
226 
230  std::string filter_info_topic_;
231 
235  std::string mask_topic_;
236 
240  tf2::Duration transform_tolerance_;
241 
245  nav2_util::ServiceServer<std_srvs::srv::SetBool,
246  std::shared_ptr<rclcpp_lifecycle::LifecycleNode>>::SharedPtr enable_service_;
247 
248 private:
252  geometry_msgs::msg::Pose2D latest_pose_;
253 
257  mutex_t * access_;
258 };
259 
260 } // namespace nav2_costmap_2d
261 
262 #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:69
: 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
nav2_util::ServiceServer< std_srvs::srv::SetBool, std::shared_ptr< rclcpp_lifecycle::LifecycleNode > >::SharedPtr enable_service_
: A service to enable/disable costmap filter
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.
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59
A simple wrapper on ROS2 services server.