Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
costmap_filter.cpp
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 #include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"
42 
43 #include <exception>
44 
45 #include "nav2_util/geometry_utils.hpp"
46 #include "geometry_msgs/msg/point_stamped.hpp"
47 
48 #include "nav2_costmap_2d/cost_values.hpp"
49 #include "nav2_util/occ_grid_values.hpp"
50 
51 namespace nav2_costmap_2d
52 {
53 
55 : filter_info_topic_(""), mask_topic_("")
56 {
57  access_ = new mutex_t();
58 }
59 
61 {
62  delete access_;
63 }
64 
66 {
67  nav2::LifecycleNode::SharedPtr node = node_.lock();
68  if (!node) {
69  throw std::runtime_error{"Failed to lock node"};
70  }
71 
72  try {
73  // Declare common for all costmap filters parameters
74  declareParameter("enabled", rclcpp::ParameterValue(true));
75  declareParameter("filter_info_topic", rclcpp::PARAMETER_STRING);
76  declareParameter("transform_tolerance", rclcpp::ParameterValue(0.1));
77 
78  // Get parameters
79  node->get_parameter(name_ + "." + "enabled", enabled_);
80  filter_info_topic_ = node->get_parameter(name_ + "." + "filter_info_topic").as_string();
81  double transform_tolerance {};
82  node->get_parameter(name_ + "." + "transform_tolerance", transform_tolerance);
83  transform_tolerance_ = tf2::durationFromSec(transform_tolerance);
84 
85  // Costmap Filter enabling service
86  enable_service_ = node->create_service<std_srvs::srv::SetBool>(
87  name_ + "/toggle_filter",
88  std::bind(&CostmapFilter::enableCallback, this, std::placeholders::_1,
89  std::placeholders::_2, std::placeholders::_3));
90  } catch (const std::exception & ex) {
91  RCLCPP_ERROR(logger_, "Parameter problem: %s", ex.what());
92  throw ex;
93  }
94 }
95 
97 {
99 }
100 
102 {
103  resetFilter();
104 }
105 
107 {
108  resetFilter();
110  current_ = false;
111 }
112 
114  double robot_x, double robot_y, double robot_yaw,
115  double * /*min_x*/, double * /*min_y*/, double * /*max_x*/, double * /*max_y*/)
116 {
117  if (!enabled_) {
118  return;
119  }
120 
121  latest_pose_.position.x = robot_x;
122  latest_pose_.position.y = robot_y;
123  latest_pose_.position.z = 0.0;
124  latest_pose_.orientation = nav2_util::geometry_utils::orientationAroundZAxis(robot_yaw);
125 }
126 
128  nav2_costmap_2d::Costmap2D & master_grid,
129  int min_i, int min_j, int max_i, int max_j)
130 {
131  if (!enabled_) {
132  return;
133  }
134 
135  process(master_grid, min_i, min_j, max_i, max_j, latest_pose_);
136  current_ = true;
137 }
138 
140  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
141  const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
142  std::shared_ptr<std_srvs::srv::SetBool::Response> response)
143 {
144  enabled_ = request->data;
145  response->success = true;
146  if (enabled_) {
147  response->message = "Enabled";
148  } else {
149  response->message = "Disabled";
150  }
151 }
152 
154  const std::string global_frame,
155  const geometry_msgs::msg::Pose & global_pose,
156  const std::string mask_frame,
157  geometry_msgs::msg::Pose & mask_pose) const
158 {
159  if (mask_frame != global_frame) {
160  // Filter mask and current layer are in different frames:
161  // Transform (global_pose.position.x, global_pose.position.y) point from current layer frame
162  // to mask_pose in mask_frame
163  geometry_msgs::msg::TransformStamped transform;
164  geometry_msgs::msg::PointStamped in, out;
165  in.header.stamp = clock_->now();
166  in.header.frame_id = global_frame;
167  in.point.x = global_pose.position.x;
168  in.point.y = global_pose.position.y;
169  in.point.z = 0.0;
170 
171  try {
172  tf_->transform(in, out, mask_frame, transform_tolerance_);
173  } catch (tf2::TransformException & ex) {
174  RCLCPP_ERROR(
175  logger_,
176  "CostmapFilter: failed to get costmap frame (%s) "
177  "transformation to mask frame (%s) with error: %s",
178  global_frame.c_str(), mask_frame.c_str(), ex.what());
179  return false;
180  }
181 
182  mask_pose = global_pose;
183  mask_pose.position.x = out.point.x;
184  mask_pose.position.y = out.point.y;
185  // mask_pose.position.z is kept as-is (0 or original)
186  // orientation is preserved
187  } else {
188  // Filter mask and current layer are in the same frame:
189  // Just use global_pose
190  mask_pose = global_pose;
191  }
192 
193  return true;
194 }
195 
197  nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
198  double wx, double wy, unsigned int & mx, unsigned int & my) const
199 {
200  const double origin_x = filter_mask->info.origin.position.x;
201  const double origin_y = filter_mask->info.origin.position.y;
202  const double resolution = filter_mask->info.resolution;
203  const unsigned int size_x = filter_mask->info.width;
204  const unsigned int size_y = filter_mask->info.height;
205 
206  if (wx < origin_x || wy < origin_y) {
207  return false;
208  }
209 
210  mx = static_cast<unsigned int>((wx - origin_x) / resolution);
211  my = static_cast<unsigned int>((wy - origin_y) / resolution);
212  if (mx >= size_x || my >= size_y) {
213  return false;
214  }
215 
216  return true;
217 }
218 
220  nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
221  const unsigned int mx, const unsigned int & my) const
222 {
223  const unsigned int index = my * filter_mask->info.width + mx;
224 
225  const char data = filter_mask->data[index];
226  if (data == nav2_util::OCC_GRID_UNKNOWN) {
227  return NO_INFORMATION;
228  } else {
229  // Linear conversion from OccupancyGrid data range [OCC_GRID_FREE..OCC_GRID_OCCUPIED]
230  // to costmap data range [FREE_SPACE..LETHAL_OBSTACLE]
231  return std::round(
232  static_cast<double>(data) * (LETHAL_OBSTACLE - FREE_SPACE) /
233  (nav2_util::OCC_GRID_OCCUPIED - nav2_util::OCC_GRID_FREE));
234  }
235 }
236 
237 } // namespace nav2_costmap_2d
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
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
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
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
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.
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.
void declareParameter(const std::string &param_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:76