Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
velocity_polygon.cpp
1 // Copyright (c) 2023 Dexory
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_collision_monitor/velocity_polygon.hpp"
16 
17 #include "nav2_util/node_utils.hpp"
18 
19 namespace nav2_collision_monitor
20 {
21 
23  const nav2_util::LifecycleNode::WeakPtr & node, const std::string & polygon_name,
24  const std::shared_ptr<tf2_ros::Buffer> tf_buffer, const std::string & base_frame_id,
25  const tf2::Duration & transform_tolerance)
26 : Polygon::Polygon(node, polygon_name, tf_buffer, base_frame_id, transform_tolerance)
27 {
28  RCLCPP_INFO(logger_, "[%s]: Creating VelocityPolygon", polygon_name_.c_str());
29 }
30 
32 {
33  RCLCPP_INFO(logger_, "[%s]: Destroying VelocityPolygon", polygon_name_.c_str());
34 }
35 
37  std::string & polygon_sub_topic,
38  std::string & polygon_pub_topic,
39  std::string & footprint_topic)
40 {
41  auto node = node_.lock();
42  if (!node) {
43  throw std::runtime_error{"Failed to lock node"};
44  }
45  clock_ = node->get_clock();
46 
47  if (!getCommonParameters(polygon_sub_topic, polygon_pub_topic, footprint_topic, false)) {
48  return false;
49  }
50 
51  try {
52  // Get velocity_polygons parameter
53  nav2_util::declare_parameter_if_not_declared(
54  node, polygon_name_ + ".velocity_polygons", rclcpp::PARAMETER_STRING_ARRAY);
55  std::vector<std::string> velocity_polygons =
56  node->get_parameter(polygon_name_ + ".velocity_polygons").as_string_array();
57 
58  // holonomic param
59  nav2_util::declare_parameter_if_not_declared(
60  node, polygon_name_ + ".holonomic", rclcpp::ParameterValue(false));
61  holonomic_ = node->get_parameter(polygon_name_ + ".holonomic").as_bool();
62 
63  for (std::string velocity_polygon_name : velocity_polygons) {
64  // polygon points parameter
65  std::vector<Point> poly;
66  nav2_util::declare_parameter_if_not_declared(
67  node, polygon_name_ + "." + velocity_polygon_name + ".points", rclcpp::PARAMETER_STRING);
68  std::string poly_string =
69  node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".points").as_string();
70 
71  if (!getPolygonFromString(poly_string, poly)) {
72  return false;
73  }
74 
75  // linear_min param
76  double linear_min;
77  nav2_util::declare_parameter_if_not_declared(
78  node, polygon_name_ + "." + velocity_polygon_name + ".linear_min",
79  rclcpp::PARAMETER_DOUBLE);
80  linear_min = node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".linear_min")
81  .as_double();
82 
83  // linear_max param
84  double linear_max;
85  nav2_util::declare_parameter_if_not_declared(
86  node, polygon_name_ + "." + velocity_polygon_name + ".linear_max",
87  rclcpp::PARAMETER_DOUBLE);
88  linear_max = node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".linear_max")
89  .as_double();
90 
91  // theta_min param
92  double theta_min;
93  nav2_util::declare_parameter_if_not_declared(
94  node, polygon_name_ + "." + velocity_polygon_name + ".theta_min",
95  rclcpp::PARAMETER_DOUBLE);
96  theta_min =
97  node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".theta_min").as_double();
98 
99  // theta_max param
100  double theta_max;
101  nav2_util::declare_parameter_if_not_declared(
102  node, polygon_name_ + "." + velocity_polygon_name + ".theta_max",
103  rclcpp::PARAMETER_DOUBLE);
104  theta_max =
105  node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".theta_max").as_double();
106 
107  // direction_end_angle param and direction_start_angle param
108  double direction_end_angle = 0.0;
109  double direction_start_angle = 0.0;
110  if (holonomic_) {
111  nav2_util::declare_parameter_if_not_declared(
112  node, polygon_name_ + "." + velocity_polygon_name + ".direction_end_angle",
113  rclcpp::ParameterValue(M_PI));
114  direction_end_angle =
115  node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".direction_end_angle")
116  .as_double();
117 
118  nav2_util::declare_parameter_if_not_declared(
119  node, polygon_name_ + "." + velocity_polygon_name + ".direction_start_angle",
120  rclcpp::ParameterValue(-M_PI));
121  direction_start_angle =
122  node
123  ->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".direction_start_angle")
124  .as_double();
125  }
126 
127  SubPolygonParameter sub_polygon = {
128  poly, velocity_polygon_name, linear_min, linear_max, theta_min,
129  theta_max, direction_end_angle, direction_start_angle};
130  sub_polygons_.push_back(sub_polygon);
131  }
132  } catch (const std::exception & ex) {
133  RCLCPP_ERROR(
134  logger_, "[%s]: Error while getting polygon parameters: %s", polygon_name_.c_str(),
135  ex.what());
136  return false;
137  }
138  return true;
139 }
140 
141 void VelocityPolygon::updatePolygon(const Velocity & cmd_vel_in)
142 {
143  for (auto & sub_polygon : sub_polygons_) {
144  if (isInRange(cmd_vel_in, sub_polygon)) {
145  // Set the polygon that is within the speed range
146  poly_ = sub_polygon.poly_;
147 
148  // Update visualization polygon
149  polygon_.polygon.points.clear();
150  for (const Point & p : poly_) {
151  geometry_msgs::msg::Point32 p_s;
152  p_s.x = p.x;
153  p_s.y = p.y;
154  // p_s.z will remain 0.0
155  polygon_.polygon.points.push_back(p_s);
156  }
157  return;
158  }
159  }
160 
161  // Log for uncovered velocity
162  RCLCPP_WARN_THROTTLE(
163  logger_, *clock_, 2.0,
164  "Velocity is not covered by any of the velocity polygons. x: %.3f y: %.3f tw: %.3f ",
165  cmd_vel_in.x, cmd_vel_in.y, cmd_vel_in.tw);
166  return;
167 }
168 
170  const Velocity & cmd_vel_in, const SubPolygonParameter & sub_polygon)
171 {
172  bool in_range =
173  (cmd_vel_in.x <= sub_polygon.linear_max_ && cmd_vel_in.x >= sub_polygon.linear_min_ &&
174  cmd_vel_in.tw <= sub_polygon.theta_max_ && cmd_vel_in.tw >= sub_polygon.theta_min_);
175 
176  if (holonomic_) {
177  // Additionally check if moving direction in angle range(start -> end) for holonomic case
178  const double direction = std::atan2(cmd_vel_in.y, cmd_vel_in.x);
179  if (sub_polygon.direction_start_angle_ <= sub_polygon.direction_end_angle_) {
180  in_range &=
181  (direction >= sub_polygon.direction_start_angle_ &&
182  direction <= sub_polygon.direction_end_angle_);
183  } else {
184  in_range &=
185  (direction >= sub_polygon.direction_start_angle_ ||
186  direction <= sub_polygon.direction_end_angle_);
187  }
188  }
189 
190  return in_range;
191 }
192 
193 } // namespace nav2_collision_monitor
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
Definition: polygon.hpp:43
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: polygon.hpp:260
bool getCommonParameters(std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic, bool use_dynamic_sub=false)
Supporting routine obtaining ROS-parameters common for all shapes.
Definition: polygon.cpp:321
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
Definition: polygon.hpp:262
geometry_msgs::msg::PolygonStamped polygon_
Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message.
Definition: polygon.hpp:308
std::vector< Point > poly_
Polygon points (vertices) in a base_frame_id_.
Definition: polygon.hpp:313
std::string polygon_name_
Name of polygon.
Definition: polygon.hpp:268
bool getPolygonFromString(std::string &poly_string, std::vector< Point > &polygon)
Extracts Polygon points from a string with of the form [[x1,y1],[x2,y2],[x3,y3]......
Definition: polygon.cpp:637
std::vector< SubPolygonParameter > sub_polygons_
Vector to store the parameters of the sub-polygon.
bool getParameters(std::string &, std::string &polygon_pub_topic, std::string &) override
Overridden getParameters function for VelocityPolygon parameters.
VelocityPolygon(const nav2_util::LifecycleNode::WeakPtr &node, const std::string &polygon_name, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::string &base_frame_id, const tf2::Duration &transform_tolerance)
VelocityPolygon constructor.
bool isInRange(const Velocity &cmd_vel_in, const SubPolygonParameter &sub_polygon_param)
Check if the velocities and direction is in expected range.
virtual ~VelocityPolygon()
VelocityPolygon destructor.
void updatePolygon(const Velocity &cmd_vel_in) override
Overridden updatePolygon function for VelocityPolygon.
bool holonomic_
Flag to indicate if the robot is holonomic.
Custom struct to store the parameters of the sub-polygon.
Velocity for 2D model of motion.
Definition: types.hpp:25