Nav2 Navigation Stack - humble  humble
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 "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
46 #include "geometry_msgs/msg/point_stamped.hpp"
47 
48 namespace nav2_costmap_2d
49 {
50 
52 : filter_info_topic_(""), mask_topic_("")
53 {
54  access_ = new mutex_t();
55 }
56 
58 {
59  delete access_;
60 }
61 
63 {
64  rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock();
65  if (!node) {
66  throw std::runtime_error{"Failed to lock node"};
67  }
68 
69  try {
70  // Declare common for all costmap filters parameters
71  declareParameter("enabled", rclcpp::ParameterValue(true));
72  declareParameter("filter_info_topic", rclcpp::PARAMETER_STRING);
73  declareParameter("transform_tolerance", rclcpp::ParameterValue(0.1));
74 
75  // Get parameters
76  node->get_parameter(name_ + "." + "enabled", enabled_);
77  filter_info_topic_ = node->get_parameter(name_ + "." + "filter_info_topic").as_string();
78  double transform_tolerance {};
79  node->get_parameter(name_ + "." + "transform_tolerance", transform_tolerance);
80  transform_tolerance_ = tf2::durationFromSec(transform_tolerance);
81 
82  // Costmap Filter enabling service
83  enable_service_ = node->create_service<std_srvs::srv::SetBool>(
84  name_ + "/toggle_filter",
85  std::bind(
87  std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
88  } catch (const std::exception & ex) {
89  RCLCPP_ERROR(logger_, "Parameter problem: %s", ex.what());
90  throw ex;
91  }
92 }
93 
95 {
97 }
98 
100 {
101  resetFilter();
102 }
103 
105 {
106  resetFilter();
108  current_ = false;
109 }
110 
112  double robot_x, double robot_y, double robot_yaw,
113  double * /*min_x*/, double * /*min_y*/, double * /*max_x*/, double * /*max_y*/)
114 {
115  if (!enabled_) {
116  return;
117  }
118 
119  latest_pose_.x = robot_x;
120  latest_pose_.y = robot_y;
121  latest_pose_.theta = robot_yaw;
122 }
123 
125  nav2_costmap_2d::Costmap2D & master_grid,
126  int min_i, int min_j, int max_i, int max_j)
127 {
128  if (!enabled_) {
129  return;
130  }
131 
132  process(master_grid, min_i, min_j, max_i, max_j, latest_pose_);
133  current_ = true;
134 }
135 
137  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
138  const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
139  std::shared_ptr<std_srvs::srv::SetBool::Response> response)
140 {
141  enabled_ = request->data;
142  response->success = true;
143  if (enabled_) {
144  response->message = "Enabled";
145  } else {
146  response->message = "Disabled";
147  }
148 }
149 
151  const std::string global_frame,
152  const geometry_msgs::msg::Pose2D & global_pose,
153  const std::string mask_frame,
154  geometry_msgs::msg::Pose2D & mask_pose) const
155 {
156  if (mask_frame != global_frame) {
157  // Filter mask and current layer are in different frames:
158  // Transform (global_pose.x, global_pose.y) point from current layer frame (global_frame)
159  // to mask_pose point in mask_frame
160  geometry_msgs::msg::TransformStamped transform;
161  geometry_msgs::msg::PointStamped in, out;
162  in.header.stamp = clock_->now();
163  in.header.frame_id = global_frame;
164  in.point.x = global_pose.x;
165  in.point.y = global_pose.y;
166  in.point.z = 0;
167 
168  try {
169  tf_->transform(in, out, mask_frame, transform_tolerance_);
170  } catch (tf2::TransformException & ex) {
171  RCLCPP_ERROR(
172  logger_,
173  "CostmapFilter: failed to get costmap frame (%s) "
174  "transformation to mask frame (%s) with error: %s",
175  global_frame.c_str(), mask_frame.c_str(), ex.what());
176  return false;
177  }
178  mask_pose.x = out.point.x;
179  mask_pose.y = out.point.y;
180  } else {
181  // Filter mask and current layer are in the same frame:
182  // Just use global_pose coordinates
183  mask_pose = global_pose;
184  }
185 
186  return true;
187 }
188 
190  nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
191  double wx, double wy, unsigned int & mx, unsigned int & my) const
192 {
193  const double origin_x = filter_mask->info.origin.position.x;
194  const double origin_y = filter_mask->info.origin.position.y;
195  const double resolution = filter_mask->info.resolution;
196  const unsigned int size_x = filter_mask->info.width;
197  const unsigned int size_y = filter_mask->info.height;
198 
199  if (wx < origin_x || wy < origin_y) {
200  return false;
201  }
202 
203  mx = static_cast<unsigned int>((wx - origin_x) / resolution);
204  my = static_cast<unsigned int>((wy - origin_y) / resolution);
205  if (mx >= size_x || my >= size_y) {
206  return false;
207  }
208 
209  return true;
210 }
211 
212 } // namespace nav2_costmap_2d
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
void activate() final
Activate the layer.
std::recursive_mutex mutex_t
: Provide a typedef to ease future code maintenance
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
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
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