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