Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
polygon.cpp
1 // Copyright (c) 2022 Samsung R&D Institute Russia
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/polygon.hpp"
16 
17 #include <exception>
18 #include <utility>
19 
20 #include "geometry_msgs/msg/point.hpp"
21 #include "geometry_msgs/msg/point32.hpp"
22 #include "tf2/transform_datatypes.h"
23 
24 #include "nav2_util/node_utils.hpp"
25 #include "nav2_util/robot_utils.hpp"
26 #include "nav2_util/array_parser.hpp"
27 
28 #include "nav2_collision_monitor/kinematics.hpp"
29 
30 namespace nav2_collision_monitor
31 {
32 
34  const nav2_util::LifecycleNode::WeakPtr & node,
35  const std::string & polygon_name,
36  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
37  const std::string & base_frame_id,
38  const tf2::Duration & transform_tolerance)
39 : node_(node), polygon_name_(polygon_name), action_type_(DO_NOTHING),
40  slowdown_ratio_(0.0), linear_limit_(0.0), angular_limit_(0.0),
41  footprint_sub_(nullptr), tf_buffer_(tf_buffer),
42  base_frame_id_(base_frame_id), transform_tolerance_(transform_tolerance)
43 {
44  RCLCPP_INFO(logger_, "[%s]: Creating Polygon", polygon_name_.c_str());
45 }
46 
48 {
49  RCLCPP_INFO(logger_, "[%s]: Destroying Polygon", polygon_name_.c_str());
50  polygon_sub_.reset();
51  polygon_pub_.reset();
52  poly_.clear();
53  dyn_params_handler_.reset();
54 }
55 
57 {
58  auto node = node_.lock();
59  if (!node) {
60  throw std::runtime_error{"Failed to lock node"};
61  }
62 
63  std::string polygon_sub_topic, polygon_pub_topic, footprint_topic;
64 
65  if (!getParameters(polygon_sub_topic, polygon_pub_topic, footprint_topic)) {
66  return false;
67  }
68 
69  createSubscription(polygon_sub_topic);
70 
71  if (!footprint_topic.empty()) {
72  RCLCPP_INFO(
73  logger_,
74  "[%s]: Making footprint subscriber on %s topic",
75  polygon_name_.c_str(), footprint_topic.c_str());
76  footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
77  node, footprint_topic, *tf_buffer_,
78  base_frame_id_, tf2::durationToSec(transform_tolerance_));
79  }
80 
81  if (visualize_) {
82  // Fill polygon_ for future usage
83  polygon_.header.frame_id = base_frame_id_;
84  std::vector<Point> poly;
85  getPolygon(poly);
86  for (const Point & p : poly) {
87  geometry_msgs::msg::Point32 p_s;
88  p_s.x = p.x;
89  p_s.y = p.y;
90  // p_s.z will remain 0.0
91  polygon_.polygon.points.push_back(p_s);
92  }
93 
94  rclcpp::QoS polygon_qos = rclcpp::SystemDefaultsQoS(); // set to default
95  polygon_pub_ = node->create_publisher<geometry_msgs::msg::PolygonStamped>(
96  polygon_pub_topic, polygon_qos);
97  }
98 
99  // Add callback for dynamic parameters
100  dyn_params_handler_ = node->add_on_set_parameters_callback(
101  std::bind(&Polygon::dynamicParametersCallback, this, std::placeholders::_1));
102 
103  return true;
104 }
105 
107 {
108  if (visualize_) {
109  polygon_pub_->on_activate();
110  }
111 }
112 
114 {
115  if (visualize_) {
116  polygon_pub_->on_deactivate();
117  }
118 }
119 
120 std::string Polygon::getName() const
121 {
122  return polygon_name_;
123 }
124 
125 ActionType Polygon::getActionType() const
126 {
127  return action_type_;
128 }
129 
131 {
132  return enabled_;
133 }
134 
136 {
137  return min_points_;
138 }
139 
141 {
142  return slowdown_ratio_;
143 }
144 
146 {
147  return linear_limit_;
148 }
149 
151 {
152  return angular_limit_;
153 }
154 
156 {
157  return time_before_collision_;
158 }
159 
160 std::vector<std::string> Polygon::getSourcesNames() const
161 {
162  return sources_names_;
163 }
164 
165 void Polygon::getPolygon(std::vector<Point> & poly) const
166 {
167  poly = poly_;
168 }
169 
171 {
172  if (poly_.empty()) {
173  RCLCPP_WARN(logger_, "[%s]: Polygon shape is not set yet", polygon_name_.c_str());
174  return false;
175  }
176  return true;
177 }
178 
179 void Polygon::updatePolygon(const Velocity & /*cmd_vel_in*/)
180 {
181  if (footprint_sub_ != nullptr) {
182  // Get latest robot footprint from footprint subscriber
183  std::vector<geometry_msgs::msg::Point> footprint_vec;
184  std_msgs::msg::Header footprint_header;
185  footprint_sub_->getFootprintInRobotFrame(footprint_vec, footprint_header);
186 
187  std::size_t new_size = footprint_vec.size();
188  poly_.resize(new_size);
189  polygon_.header.frame_id = base_frame_id_;
190  polygon_.polygon.points.resize(new_size);
191 
192  geometry_msgs::msg::Point32 p_s;
193  for (std::size_t i = 0; i < new_size; i++) {
194  poly_[i] = {footprint_vec[i].x, footprint_vec[i].y};
195  p_s.x = footprint_vec[i].x;
196  p_s.y = footprint_vec[i].y;
197  polygon_.polygon.points[i] = p_s;
198  }
199  } else if (!polygon_.header.frame_id.empty() && polygon_.header.frame_id != base_frame_id_) {
200  // Polygon is published in another frame: correct poly_ vertices to the latest frame state
201  std::size_t new_size = polygon_.polygon.points.size();
202 
203  // Get the transform from PolygonStamped frame to base_frame_id_
204  tf2::Stamped<tf2::Transform> tf_transform;
205  if (
206  !nav2_util::getTransform(
207  polygon_.header.frame_id, base_frame_id_,
208  transform_tolerance_, tf_buffer_, tf_transform))
209  {
210  return;
211  }
212 
213  // Correct main poly_ vertices
214  poly_.resize(new_size);
215  for (std::size_t i = 0; i < new_size; i++) {
216  // Transform point coordinates from PolygonStamped frame -> to base frame
217  tf2::Vector3 p_v3_s(polygon_.polygon.points[i].x, polygon_.polygon.points[i].y, 0.0);
218  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
219 
220  // Fill poly_ array
221  poly_[i] = {p_v3_b.x(), p_v3_b.y()};
222  }
223  }
224 }
225 
226 int Polygon::getPointsInside(const std::vector<Point> & points) const
227 {
228  int num = 0;
229  for (const Point & point : points) {
230  if (isPointInside(point)) {
231  num++;
232  }
233  }
234  return num;
235 }
236 
238  const std::unordered_map<std::string,
239  std::vector<Point>> & sources_collision_points_map) const
240 {
241  int num = 0;
242  std::vector<std::string> polygon_sources_names = getSourcesNames();
243 
244  // Sum the number of points from all sources associated with current polygon
245  for (const auto & source_name : polygon_sources_names) {
246  const auto & iter = sources_collision_points_map.find(source_name);
247  if (iter != sources_collision_points_map.end()) {
248  num += getPointsInside(iter->second);
249  }
250  }
251 
252  return num;
253 }
254 
256  const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
257  const Velocity & velocity) const
258 {
259  // Initial robot pose is {0,0} in base_footprint coordinates
260  Pose pose = {0.0, 0.0, 0.0};
261  Velocity vel = velocity;
262 
263  std::vector<std::string> polygon_sources_names = getSourcesNames();
264  std::vector<Point> collision_points;
265 
266  // Save all points coming from the sources associated with current polygon
267  for (const auto & source_name : polygon_sources_names) {
268  const auto & iter = sources_collision_points_map.find(source_name);
269  if (iter != sources_collision_points_map.end()) {
270  collision_points.insert(collision_points.end(), iter->second.begin(), iter->second.end());
271  }
272  }
273 
274  // Array of points transformed to the frame concerned with pose on each simulation step
275  std::vector<Point> points_transformed = collision_points;
276 
277  // Check static polygon
278  if (getPointsInside(collision_points) >= min_points_) {
279  return 0.0;
280  }
281 
282  // Robot movement simulation
283  for (double time = 0.0; time <= time_before_collision_; time += simulation_time_step_) {
284  // Shift the robot pose towards to the vel during simulation_time_step_ time interval
285  // NOTE: vel is changing during the simulation
286  projectState(simulation_time_step_, pose, vel);
287  // Transform collision_points to the frame concerned with current robot pose
288  points_transformed = collision_points;
289  transformPoints(pose, points_transformed);
290  // If the collision occurred on this stage, return the actual time before a collision
291  // as if robot was moved with given velocity
292  if (getPointsInside(points_transformed) >= min_points_) {
293  return time;
294  }
295  }
296 
297  // There is no collision
298  return -1.0;
299 }
300 
302 {
303  if (!visualize_) {
304  return;
305  }
306 
307  auto node = node_.lock();
308  if (!node) {
309  throw std::runtime_error{"Failed to lock node"};
310  }
311 
312  // Actualize the time to current and publish the polygon
313  polygon_.header.stamp = node->now();
314  auto msg = std::make_unique<geometry_msgs::msg::PolygonStamped>(polygon_);
315  polygon_pub_->publish(std::move(msg));
316 }
317 
319  std::string & polygon_sub_topic,
320  std::string & polygon_pub_topic,
321  std::string & footprint_topic,
322  bool use_dynamic_sub_topic)
323 {
324  auto node = node_.lock();
325  if (!node) {
326  throw std::runtime_error{"Failed to lock node"};
327  }
328 
329  try {
330  // Get action type.
331  // Leave it not initialized: the will cause an error if it will not set.
332  nav2_util::declare_parameter_if_not_declared(
333  node, polygon_name_ + ".action_type", rclcpp::PARAMETER_STRING);
334  const std::string at_str =
335  node->get_parameter(polygon_name_ + ".action_type").as_string();
336  if (at_str == "stop") {
337  action_type_ = STOP;
338  } else if (at_str == "slowdown") {
339  action_type_ = SLOWDOWN;
340  } else if (at_str == "limit") {
341  action_type_ = LIMIT;
342  } else if (at_str == "approach") {
343  action_type_ = APPROACH;
344  } else if (at_str == "none") {
345  action_type_ = DO_NOTHING;
346  } else { // Error if something else
347  RCLCPP_ERROR(logger_, "[%s]: Unknown action type: %s", polygon_name_.c_str(), at_str.c_str());
348  return false;
349  }
350 
351  nav2_util::declare_parameter_if_not_declared(
352  node, polygon_name_ + ".enabled", rclcpp::ParameterValue(true));
353  enabled_ = node->get_parameter(polygon_name_ + ".enabled").as_bool();
354 
355  nav2_util::declare_parameter_if_not_declared(
356  node, polygon_name_ + ".min_points", rclcpp::ParameterValue(4));
357  min_points_ = node->get_parameter(polygon_name_ + ".min_points").as_int();
358 
359  try {
360  nav2_util::declare_parameter_if_not_declared(
361  node, polygon_name_ + ".max_points", rclcpp::PARAMETER_INTEGER);
362  min_points_ = node->get_parameter(polygon_name_ + ".max_points").as_int() + 1;
363  RCLCPP_WARN(
364  logger_,
365  "[%s]: \"max_points\" parameter was deprecated. Use \"min_points\" instead to specify "
366  "the minimum number of data readings within a zone to trigger the action",
367  polygon_name_.c_str());
368  } catch (const std::exception &) {
369  // This is normal situation: max_points parameter should not being declared
370  }
371 
372  if (action_type_ == SLOWDOWN) {
373  nav2_util::declare_parameter_if_not_declared(
374  node, polygon_name_ + ".slowdown_ratio", rclcpp::ParameterValue(0.5));
375  slowdown_ratio_ = node->get_parameter(polygon_name_ + ".slowdown_ratio").as_double();
376  }
377 
378  if (action_type_ == LIMIT) {
379  nav2_util::declare_parameter_if_not_declared(
380  node, polygon_name_ + ".linear_limit", rclcpp::ParameterValue(0.5));
381  linear_limit_ = node->get_parameter(polygon_name_ + ".linear_limit").as_double();
382  nav2_util::declare_parameter_if_not_declared(
383  node, polygon_name_ + ".angular_limit", rclcpp::ParameterValue(0.5));
384  angular_limit_ = node->get_parameter(polygon_name_ + ".angular_limit").as_double();
385  }
386 
387  if (action_type_ == APPROACH) {
388  nav2_util::declare_parameter_if_not_declared(
389  node, polygon_name_ + ".time_before_collision", rclcpp::ParameterValue(2.0));
391  node->get_parameter(polygon_name_ + ".time_before_collision").as_double();
392  nav2_util::declare_parameter_if_not_declared(
393  node, polygon_name_ + ".simulation_time_step", rclcpp::ParameterValue(0.1));
395  node->get_parameter(polygon_name_ + ".simulation_time_step").as_double();
396  }
397 
398  nav2_util::declare_parameter_if_not_declared(
399  node, polygon_name_ + ".visualize", rclcpp::ParameterValue(false));
400  visualize_ = node->get_parameter(polygon_name_ + ".visualize").as_bool();
401  if (visualize_) {
402  // Get polygon topic parameter in case if it is going to be published
403  nav2_util::declare_parameter_if_not_declared(
404  node, polygon_name_ + ".polygon_pub_topic", rclcpp::ParameterValue(polygon_name_));
405  polygon_pub_topic = node->get_parameter(polygon_name_ + ".polygon_pub_topic").as_string();
406  }
407 
408  nav2_util::declare_parameter_if_not_declared(
409  node, polygon_name_ + ".polygon_subscribe_transient_local", rclcpp::ParameterValue(false));
411  node->get_parameter(polygon_name_ + ".polygon_subscribe_transient_local").as_bool();
412 
413  if (use_dynamic_sub_topic) {
414  if (action_type_ != APPROACH) {
415  // Get polygon sub topic
416  nav2_util::declare_parameter_if_not_declared(
417  node, polygon_name_ + ".polygon_sub_topic", rclcpp::PARAMETER_STRING);
418  polygon_sub_topic =
419  node->get_parameter(polygon_name_ + ".polygon_sub_topic").as_string();
420  } else {
421  // Obtain the footprint topic to make a footprint subscription for approach polygon
422  nav2_util::declare_parameter_if_not_declared(
423  node, polygon_name_ + ".footprint_topic",
424  rclcpp::ParameterValue("local_costmap/published_footprint"));
425  footprint_topic =
426  node->get_parameter(polygon_name_ + ".footprint_topic").as_string();
427  }
428  }
429 
430  // By default, use all observation sources for polygon
431  nav2_util::declare_parameter_if_not_declared(
432  node, "observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
433  const std::vector<std::string> observation_sources =
434  node->get_parameter("observation_sources").as_string_array();
435  nav2_util::declare_parameter_if_not_declared(
436  node, polygon_name_ + ".sources_names", rclcpp::ParameterValue(observation_sources));
437  sources_names_ = node->get_parameter(polygon_name_ + ".sources_names").as_string_array();
438 
439  // Check the observation sources configured for polygon are defined
440  for (auto source_name : sources_names_) {
441  if (std::find(observation_sources.begin(), observation_sources.end(), source_name) ==
442  observation_sources.end())
443  {
444  RCLCPP_ERROR_STREAM(
445  logger_,
446  "Observation source [" << source_name <<
447  "] configured for polygon [" << getName() <<
448  "] is not defined as one of the node's observation_source!");
449  return false;
450  }
451  }
452  } catch (const std::exception & ex) {
453  RCLCPP_ERROR(
454  logger_,
455  "[%s]: Error while getting common polygon parameters: %s",
456  polygon_name_.c_str(), ex.what());
457  return false;
458  }
459 
460  return true;
461 }
462 
464  std::string & polygon_sub_topic,
465  std::string & polygon_pub_topic,
466  std::string & footprint_topic)
467 {
468  auto node = node_.lock();
469  if (!node) {
470  throw std::runtime_error{"Failed to lock node"};
471  }
472 
473  // Clear the subscription topics. They will be set later, if necessary.
474  polygon_sub_topic.clear();
475  footprint_topic.clear();
476 
477  bool use_dynamic_sub = true; // if getting parameter points fails, use dynamic subscription
478  try {
479  // Leave it uninitialized: it will throw an inner exception if the parameter is not set
480  nav2_util::declare_parameter_if_not_declared(
481  node, polygon_name_ + ".points", rclcpp::PARAMETER_STRING);
482  std::string poly_string =
483  node->get_parameter(polygon_name_ + ".points").as_string();
484 
485  use_dynamic_sub = !getPolygonFromString(poly_string, poly_);
486  } catch (const rclcpp::exceptions::ParameterUninitializedException &) {
487  RCLCPP_INFO(
488  logger_,
489  "[%s]: Polygon points are not defined. Using dynamic subscription instead.",
490  polygon_name_.c_str());
491  }
492 
493  if (!getCommonParameters(
494  polygon_sub_topic, polygon_pub_topic, footprint_topic, use_dynamic_sub))
495  {
496  if (use_dynamic_sub && polygon_sub_topic.empty() && footprint_topic.empty()) {
497  RCLCPP_ERROR(
498  logger_,
499  "[%s]: Error while getting polygon parameters:"
500  " static points and sub topic both not defined",
501  polygon_name_.c_str());
502  }
503  return false;
504  }
505 
506  return true;
507 }
508 
509 void Polygon::createSubscription(std::string & polygon_sub_topic)
510 {
511  auto node = node_.lock();
512  if (!node) {
513  throw std::runtime_error{"Failed to lock node"};
514  }
515 
516  if (!polygon_sub_topic.empty()) {
517  RCLCPP_INFO(
518  logger_,
519  "[%s]: Subscribing on %s topic for polygon",
520  polygon_name_.c_str(), polygon_sub_topic.c_str());
521  rclcpp::QoS polygon_qos = rclcpp::SystemDefaultsQoS(); // set to default
523  polygon_qos.transient_local();
524  }
525  polygon_sub_ = node->create_subscription<geometry_msgs::msg::PolygonStamped>(
526  polygon_sub_topic, polygon_qos,
527  std::bind(&Polygon::polygonCallback, this, std::placeholders::_1));
528  }
529 }
530 
531 void Polygon::updatePolygon(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg)
532 {
533  std::size_t new_size = msg->polygon.points.size();
534 
535  if (new_size < 3) {
536  RCLCPP_ERROR(
537  logger_,
538  "[%s]: Polygon should have at least 3 points",
539  polygon_name_.c_str());
540  return;
541  }
542 
543  // Get the transform from PolygonStamped frame to base_frame_id_
544  tf2::Stamped<tf2::Transform> tf_transform;
545  if (
546  !nav2_util::getTransform(
547  msg->header.frame_id, base_frame_id_,
548  transform_tolerance_, tf_buffer_, tf_transform))
549  {
550  return;
551  }
552 
553  // Set main poly_ vertices first time
554  poly_.resize(new_size);
555  for (std::size_t i = 0; i < new_size; i++) {
556  // Transform point coordinates from PolygonStamped frame -> to base frame
557  tf2::Vector3 p_v3_s(msg->polygon.points[i].x, msg->polygon.points[i].y, 0.0);
558  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
559 
560  // Fill poly_ array
561  poly_[i] = {p_v3_b.x(), p_v3_b.y()};
562  }
563 
564  // Store incoming polygon for further (possible) poly_ vertices corrections
565  // from PolygonStamped frame -> to base frame
566  polygon_ = *msg;
567 }
568 
569 rcl_interfaces::msg::SetParametersResult
571  std::vector<rclcpp::Parameter> parameters)
572 {
573  rcl_interfaces::msg::SetParametersResult result;
574 
575  for (auto parameter : parameters) {
576  const auto & param_type = parameter.get_type();
577  const auto & param_name = parameter.get_name();
578 
579  if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
580  if (param_name == polygon_name_ + "." + "enabled") {
581  enabled_ = parameter.as_bool();
582  }
583  }
584  }
585  result.successful = true;
586  return result;
587 }
588 
589 void Polygon::polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg)
590 {
591  RCLCPP_INFO(
592  logger_,
593  "[%s]: Polygon shape update has been arrived",
594  polygon_name_.c_str());
595  updatePolygon(msg);
596 }
597 
598 inline bool Polygon::isPointInside(const Point & point) const
599 {
600  // Adaptation of Shimrat, Moshe. "Algorithm 112: position of point relative to polygon."
601  // Communications of the ACM 5.8 (1962): 434.
602  // Implementation of ray crossings algorithm for point in polygon task solving.
603  // Y coordinate is fixed. Moving the ray on X+ axis starting from given point.
604  // Odd number of intersections with polygon boundaries means the point is inside polygon.
605  const int poly_size = poly_.size();
606  int i, j; // Polygon vertex iterators
607  bool res = false; // Final result, initialized with already inverted value
608 
609  // Starting from the edge where the last point of polygon is connected to the first
610  i = poly_size - 1;
611  for (j = 0; j < poly_size; j++) {
612  // Checking the edge only if given point is between edge boundaries by Y coordinates.
613  // One of the condition should contain equality in order to exclude the edges
614  // parallel to X+ ray.
615  if ((point.y <= poly_[i].y) == (point.y > poly_[j].y)) {
616  // Calculating the intersection coordinate of X+ ray
617  const double x_inter = poly_[i].x +
618  (point.y - poly_[i].y) * (poly_[j].x - poly_[i].x) /
619  (poly_[j].y - poly_[i].y);
620  // If intersection with checked edge is greater than point.x coordinate, inverting the result
621  if (x_inter > point.x) {
622  res = !res;
623  }
624  }
625  i = j;
626  }
627  return res;
628 }
629 
631  std::string & poly_string,
632  std::vector<Point> & polygon)
633 {
634  std::string error;
635  std::vector<std::vector<float>> vvf = nav2_util::parseVVF(poly_string, error);
636 
637  if (error != "") {
638  RCLCPP_ERROR(
639  logger_, "Error parsing polygon parameter %s: '%s'",
640  poly_string.c_str(), error.c_str());
641  return false;
642  }
643 
644  // Check for minimum 4 points
645  if (vvf.size() <= 3) {
646  RCLCPP_ERROR(
647  logger_,
648  "Polygon must have at least three points.");
649  return false;
650  }
651  for (unsigned int i = 0; i < vvf.size(); i++) {
652  if (vvf[i].size() == 2) {
653  Point point;
654  point.x = vvf[i][0];
655  point.y = vvf[i][1];
656  polygon.push_back(point);
657  } else {
658  RCLCPP_ERROR(
659  logger_,
660  "Points in the polygon specification must be pairs of numbers"
661  "Found a point with %d numbers.",
662  static_cast<int>(vvf[i].size()));
663  polygon.clear();
664  return false;
665  }
666  }
667 
668  return true;
669 }
670 
671 } // namespace nav2_collision_monitor
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: polygon.hpp:260
virtual bool getParameters(std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic)
Supporting routine obtaining polygon-specific ROS-parameters.
Definition: polygon.cpp:463
int getMinPoints() const
Obtains polygon minimum points to enter inside polygon causing the action.
Definition: polygon.cpp:135
double getTimeBeforeCollision() const
Obtains required time before collision for current polygon. Applicable for APPROACH model.
Definition: polygon.cpp:155
virtual void updatePolygon(const Velocity &)
Updates polygon from footprint subscriber (if any)
Definition: polygon.cpp:179
virtual int getPointsInside(const std::vector< Point > &points) const
Gets number of points inside given polygon.
Definition: polygon.cpp:226
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:318
double time_before_collision_
Time before collision in seconds.
Definition: polygon.hpp:280
bool enabled_
Whether polygon is enabled.
Definition: polygon.hpp:284
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
Definition: polygon.hpp:262
ActionType action_type_
Action type for the polygon.
Definition: polygon.hpp:270
geometry_msgs::msg::PolygonStamped polygon_
Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message.
Definition: polygon.hpp:306
rclcpp::Subscription< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_sub_
Polygon subscription.
Definition: polygon.hpp:288
virtual void createSubscription(std::string &polygon_sub_topic)
Creates polygon or radius topic subscription.
Definition: polygon.cpp:509
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
Definition: polygon.hpp:264
bool polygon_subscribe_transient_local_
Wether the subscription to polygon topic has transient local QoS durability.
Definition: polygon.hpp:286
virtual bool isShapeSet()
Returns true if polygon points were set. Otherwise, prints a warning and returns false.
Definition: polygon.cpp:170
double simulation_time_step_
Time step for robot movement simulation.
Definition: polygon.hpp:282
void activate()
Activates polygon lifecycle publisher.
Definition: polygon.cpp:106
bool configure()
Shape configuration routine. Obtains ROS-parameters related to shape object and creates polygon lifec...
Definition: polygon.cpp:56
bool isPointInside(const Point &point) const
Checks if point is inside polygon.
Definition: polygon.cpp:598
double getLinearLimit() const
Obtains speed linear limit for current polygon. Applicable for LIMIT model.
Definition: polygon.cpp:145
std::string getName() const
Returns the name of polygon.
Definition: polygon.cpp:120
virtual void getPolygon(std::vector< Point > &poly) const
Gets polygon points.
Definition: polygon.cpp:165
tf2::Duration transform_tolerance_
Transform tolerance.
Definition: polygon.hpp:300
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
Definition: polygon.hpp:296
ActionType getActionType() const
Obtains polygon action type.
Definition: polygon.cpp:125
int min_points_
Minimum number of data readings within a zone to trigger the action.
Definition: polygon.hpp:272
std::vector< Point > poly_
Polygon points (vertices) in a base_frame_id_.
Definition: polygon.hpp:311
Polygon(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)
Polygon constructor.
Definition: polygon.cpp:33
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Definition: polygon.cpp:570
std::vector< std::string > sources_names_
Name of the observation sources to check for polygon.
Definition: polygon.hpp:292
void deactivate()
Deactivates polygon lifecycle publisher.
Definition: polygon.cpp:113
std::unique_ptr< nav2_costmap_2d::FootprintSubscriber > footprint_sub_
Footprint subscriber.
Definition: polygon.hpp:290
void polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg)
Dynamic polygon callback.
Definition: polygon.cpp:589
double getSlowdownRatio() const
Obtains speed slowdown ratio for current polygon. Applicable for SLOWDOWN model.
Definition: polygon.cpp:140
double getAngularLimit() const
Obtains speed angular z limit for current polygon. Applicable for LIMIT model.
Definition: polygon.cpp:150
double getCollisionTime(const std::unordered_map< std::string, std::vector< Point >> &sources_collision_points_map, const Velocity &velocity) const
Obtains estimated (simulated) time before a collision. Applicable for APPROACH model.
Definition: polygon.cpp:255
std::string polygon_name_
Name of polygon.
Definition: polygon.hpp:268
double linear_limit_
Robot linear limit.
Definition: polygon.hpp:276
virtual ~Polygon()
Polygon destructor.
Definition: polygon.cpp:47
bool getEnabled() const
Obtains polygon enabled state.
Definition: polygon.cpp:130
double angular_limit_
Robot angular limit.
Definition: polygon.hpp:278
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:630
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_pub_
Polygon publisher for visualization purposes.
Definition: polygon.hpp:308
bool visualize_
Whether to publish the polygon.
Definition: polygon.hpp:304
std::vector< std::string > getSourcesNames() const
Obtains the name of the observation sources for current polygon.
Definition: polygon.cpp:160
std::string base_frame_id_
Base frame ID.
Definition: polygon.hpp:298
double slowdown_ratio_
Robot slowdown (share of its actual speed)
Definition: polygon.hpp:274
void publish()
Publishes polygon message into a its own topic.
Definition: polygon.cpp:301
Velocity for 2D model of motion.
Definition: types.hpp:25