Nav2 Navigation Stack - rolling  main
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_ros_common/node_utils.hpp"
18 
19 namespace nav2_collision_monitor
20 {
21 
23  const nav2::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  std::vector<std::string> velocity_polygons =
54  node->declare_or_get_parameter<std::vector<std::string>>(
55  polygon_name_ + ".velocity_polygons");
56 
57  // holonomic param
58  holonomic_ = node->declare_or_get_parameter(
59  polygon_name_ + ".holonomic", false);
60 
61  for (std::string velocity_polygon_name : velocity_polygons) {
62  // polygon points parameter
63  std::vector<Point> poly;
64  std::string poly_string =
65  node->declare_or_get_parameter<std::string>(
66  polygon_name_ + "." + velocity_polygon_name + ".points");
67 
68  if (!getPolygonFromString(poly_string, poly)) {
69  return false;
70  }
71 
72  // linear_min param
73  double linear_min = node->declare_or_get_parameter<double>(
74  polygon_name_ + "." + velocity_polygon_name + ".linear_min");
75 
76  // linear_max param
77  double linear_max = node->declare_or_get_parameter<double>(
78  polygon_name_ + "." + velocity_polygon_name + ".linear_max");
79 
80  // theta_min param
81  double theta_min = node->declare_or_get_parameter<double>(
82  polygon_name_ + "." + velocity_polygon_name + ".theta_min");
83 
84  // theta_max param
85  double theta_max = node->declare_or_get_parameter<double>(
86  polygon_name_ + "." + velocity_polygon_name + ".theta_max");
87 
88  // direction_end_angle param and direction_start_angle param
89  double direction_end_angle = 0.0;
90  double direction_start_angle = 0.0;
91  if (holonomic_) {
92  direction_end_angle = node->declare_or_get_parameter(
93  polygon_name_ + "." + velocity_polygon_name + ".direction_end_angle", M_PI);
94 
95  direction_start_angle = node->declare_or_get_parameter(
96  polygon_name_ + "." + velocity_polygon_name + ".direction_start_angle", -M_PI);
97  }
98 
99  SubPolygonParameter sub_polygon = {
100  poly, velocity_polygon_name, linear_min, linear_max, theta_min,
101  theta_max, direction_end_angle, direction_start_angle};
102  sub_polygons_.push_back(sub_polygon);
103  }
104  } catch (const std::exception & ex) {
105  RCLCPP_ERROR(
106  logger_, "[%s]: Error while getting polygon parameters: %s", polygon_name_.c_str(),
107  ex.what());
108  return false;
109  }
110  return true;
111 }
112 
113 void VelocityPolygon::updatePolygon(const Velocity & cmd_vel_in)
114 {
115  for (auto & sub_polygon : sub_polygons_) {
116  if (isInRange(cmd_vel_in, sub_polygon)) {
117  // Set the polygon that is within the speed range
118  poly_ = sub_polygon.poly_;
119 
120  // Update visualization polygon
121  polygon_.polygon.points.clear();
122  for (const Point & p : poly_) {
123  geometry_msgs::msg::Point32 p_s;
124  p_s.x = p.x;
125  p_s.y = p.y;
126  // p_s.z will remain 0.0
127  polygon_.polygon.points.push_back(p_s);
128  }
129  return;
130  }
131  }
132 
133  // Log for uncovered velocity
134  RCLCPP_WARN_THROTTLE(
135  logger_, *clock_, 2.0,
136  "Velocity is not covered by any of the velocity polygons. x: %.3f y: %.3f tw: %.3f ",
137  cmd_vel_in.x, cmd_vel_in.y, cmd_vel_in.tw);
138  return;
139 }
140 
142  const Velocity & cmd_vel_in, const SubPolygonParameter & sub_polygon)
143 {
144  bool in_range =
145  (cmd_vel_in.x <= sub_polygon.linear_max_ && cmd_vel_in.x >= sub_polygon.linear_min_ &&
146  cmd_vel_in.tw <= sub_polygon.theta_max_ && cmd_vel_in.tw >= sub_polygon.theta_min_);
147 
148  if (holonomic_) {
149  // Additionally check if moving direction in angle range(start -> end) for holonomic case
150  const double direction = std::atan2(cmd_vel_in.y, cmd_vel_in.x);
151  if (sub_polygon.direction_start_angle_ <= sub_polygon.direction_end_angle_) {
152  in_range &=
153  (direction >= sub_polygon.direction_start_angle_ &&
154  direction <= sub_polygon.direction_end_angle_);
155  } else {
156  in_range &=
157  (direction >= sub_polygon.direction_start_angle_ ||
158  direction <= sub_polygon.direction_end_angle_);
159  }
160  }
161 
162  return in_range;
163 }
164 
165 } // 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
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:255
geometry_msgs::msg::PolygonStamped polygon_
Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message.
Definition: polygon.hpp:301
std::vector< Point > poly_
Polygon points (vertices) in a base_frame_id_.
Definition: polygon.hpp:306
std::string polygon_name_
Name of polygon.
Definition: polygon.hpp:261
nav2::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: polygon.hpp:253
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:573
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.
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.
VelocityPolygon(const nav2::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.
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