|
Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while for APPROACH model it represents robot footprint. More...
#include <nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp>


Public Member Functions | |
| 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. More... | |
| virtual | ~Polygon () |
| Polygon destructor. | |
| bool | configure () |
| Shape configuration routine. Obtains ROS-parameters related to shape object and creates polygon lifecycle publisher. More... | |
| void | activate () |
| Activates polygon lifecycle publisher. | |
| void | deactivate () |
| Deactivates polygon lifecycle publisher. | |
| std::string | getName () const |
| Returns the name of polygon. More... | |
| ActionType | getActionType () const |
| Obtains polygon action type. More... | |
| bool | getEnabled () const |
| Obtains polygon enabled state. More... | |
| int | getMinPoints () const |
| Obtains polygon minimum points to enter inside polygon causing the action. More... | |
| double | getSlowdownRatio () const |
| Obtains speed slowdown ratio for current polygon. Applicable for SLOWDOWN model. More... | |
| double | getLinearLimit () const |
| Obtains speed linear limit for current polygon. Applicable for LIMIT model. More... | |
| double | getAngularLimit () const |
| Obtains speed angular z limit for current polygon. Applicable for LIMIT model. More... | |
| double | getTimeBeforeCollision () const |
| Obtains required time before collision for current polygon. Applicable for APPROACH model. More... | |
| virtual void | getPolygon (std::vector< Point > &poly) const |
| Gets polygon points. More... | |
| std::vector< std::string > | getSourcesNames () const |
| Obtains the name of the observation sources for current polygon. More... | |
| virtual bool | isShapeSet () |
| Returns true if polygon points were set. Otherwise, prints a warning and returns false. | |
| virtual void | updatePolygon (const Velocity &) |
| Updates polygon from footprint subscriber (if any) | |
| virtual int | getPointsInside (const std::vector< Point > &points) const |
| Gets number of points inside given polygon. More... | |
| virtual int | getPointsInside (const std::unordered_map< std::string, std::vector< Point >> &sources_collision_points_map) const |
| Gets number of points inside given polygon. More... | |
| 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. More... | |
| void | publish () |
| Publishes polygon message into a its own topic. | |
Protected Member Functions | |
| 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. More... | |
| virtual bool | getParameters (std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic) |
| Supporting routine obtaining polygon-specific ROS-parameters. More... | |
| virtual void | createSubscription (std::string &polygon_sub_topic) |
| Creates polygon or radius topic subscription. More... | |
| void | updatePolygon (geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg) |
| Updates polygon from geometry_msgs::msg::PolygonStamped message. More... | |
| void | polygonCallback (geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg) |
| Dynamic polygon callback. More... | |
| rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
| Callback executed when a parameter change is detected. More... | |
| bool | isPointInside (const Point &point) const |
| Checks if point is inside polygon. More... | |
| 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]...]. More... | |
Protected Attributes | |
| nav2_util::LifecycleNode::WeakPtr | node_ |
| Collision Monitor node. | |
| rclcpp::Logger | logger_ {rclcpp::get_logger("collision_monitor")} |
| Collision monitor node logger stored for further usage. | |
| rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
| Dynamic parameters handler. | |
| std::string | polygon_name_ |
| Name of polygon. | |
| ActionType | action_type_ |
| Action type for the polygon. | |
| int | min_points_ |
| Minimum number of data readings within a zone to trigger the action. | |
| double | slowdown_ratio_ |
| Robot slowdown (share of its actual speed) | |
| double | linear_limit_ |
| Robot linear limit. | |
| double | angular_limit_ |
| Robot angular limit. | |
| double | time_before_collision_ |
| Time before collision in seconds. | |
| double | simulation_time_step_ |
| Time step for robot movement simulation. | |
| bool | enabled_ |
| Whether polygon is enabled. | |
| bool | polygon_subscribe_transient_local_ |
| Wether the subscription to polygon topic has transient local QoS durability. | |
| rclcpp::Subscription< geometry_msgs::msg::PolygonStamped >::SharedPtr | polygon_sub_ |
| Polygon subscription. | |
| std::unique_ptr< nav2_costmap_2d::FootprintSubscriber > | footprint_sub_ |
| Footprint subscriber. | |
| std::vector< std::string > | sources_names_ |
| Name of the observation sources to check for polygon. | |
| std::shared_ptr< tf2_ros::Buffer > | tf_buffer_ |
| TF buffer. | |
| std::string | base_frame_id_ |
| Base frame ID. | |
| tf2::Duration | transform_tolerance_ |
| Transform tolerance. | |
| bool | visualize_ |
| Whether to publish the polygon. | |
| geometry_msgs::msg::PolygonStamped | polygon_ |
| Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message. | |
| rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::PolygonStamped >::SharedPtr | polygon_pub_ |
| Polygon publisher for visualization purposes. | |
| std::vector< Point > | poly_ |
| Polygon points (vertices) in a base_frame_id_. | |
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while for APPROACH model it represents robot footprint.
Definition at line 42 of file polygon.hpp.
| nav2_collision_monitor::Polygon::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.
| node | Collision Monitor node pointer |
| polygon_name | Name of polygon |
| tf_buffer | Shared pointer to a TF buffer |
| base_frame_id | Robot base frame ID |
| transform_tolerance | Transform tolerance |
Definition at line 33 of file polygon.cpp.
References logger_, and polygon_name_.
| bool nav2_collision_monitor::Polygon::configure | ( | ) |
Shape configuration routine. Obtains ROS-parameters related to shape object and creates polygon lifecycle publisher.
Definition at line 56 of file polygon.cpp.
References base_frame_id_, createSubscription(), dyn_params_handler_, dynamicParametersCallback(), footprint_sub_, getParameters(), getPolygon(), logger_, node_, polygon_, polygon_name_, polygon_pub_, tf_buffer_, transform_tolerance_, and visualize_.

|
protectedvirtual |
Creates polygon or radius topic subscription.
| polygon_sub_topic | Output name of polygon or radius subscription topic. Empty, if no polygon subscription. |
Reimplemented in nav2_collision_monitor::Circle.
Definition at line 509 of file polygon.cpp.
References logger_, node_, polygon_name_, polygon_sub_, polygon_subscribe_transient_local_, and polygonCallback().
Referenced by configure().


|
protected |
Callback executed when a parameter change is detected.
| event | ParameterEvent message |
Definition at line 570 of file polygon.cpp.
References enabled_, and polygon_name_.
Referenced by configure().

| ActionType nav2_collision_monitor::Polygon::getActionType | ( | ) | const |
Obtains polygon action type.
Definition at line 125 of file polygon.cpp.
References action_type_.
| double nav2_collision_monitor::Polygon::getAngularLimit | ( | ) | const |
Obtains speed angular z limit for current polygon. Applicable for LIMIT model.
Definition at line 150 of file polygon.cpp.
References angular_limit_.
| double nav2_collision_monitor::Polygon::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.
| sources_collision_points_map | Map containing source name as key, and input array of source's 2D obstacle points as value |
| velocity | Simulated robot velocity |
Definition at line 255 of file polygon.cpp.
References getPointsInside(), getSourcesNames(), min_points_, simulation_time_step_, and time_before_collision_.

|
protected |
Supporting routine obtaining ROS-parameters common for all shapes.
| polygon_pub_topic | Output name of polygon or radius subscription topic. Empty, if no polygon subscription. |
| polygon_sub_topic | Output name of polygon publishing topic |
| footprint_topic | Output name of footprint topic. Empty, if no footprint subscription. |
| use_dynamic_sub | If false, the parameter polygon_sub_topic or footprint_topic will not be declared |
Definition at line 318 of file polygon.cpp.
References action_type_, angular_limit_, enabled_, getName(), linear_limit_, logger_, min_points_, node_, polygon_name_, polygon_subscribe_transient_local_, simulation_time_step_, slowdown_ratio_, sources_names_, time_before_collision_, and visualize_.
Referenced by nav2_collision_monitor::VelocityPolygon::getParameters(), getParameters(), and nav2_collision_monitor::Circle::getParameters().


| bool nav2_collision_monitor::Polygon::getEnabled | ( | ) | const |
Obtains polygon enabled state.
Definition at line 130 of file polygon.cpp.
References enabled_.
| double nav2_collision_monitor::Polygon::getLinearLimit | ( | ) | const |
Obtains speed linear limit for current polygon. Applicable for LIMIT model.
Definition at line 145 of file polygon.cpp.
References linear_limit_.
| int nav2_collision_monitor::Polygon::getMinPoints | ( | ) | const |
Obtains polygon minimum points to enter inside polygon causing the action.
Definition at line 135 of file polygon.cpp.
References min_points_.
| std::string nav2_collision_monitor::Polygon::getName | ( | ) | const |
Returns the name of polygon.
Definition at line 120 of file polygon.cpp.
References polygon_name_.
Referenced by getCommonParameters().

|
protectedvirtual |
Supporting routine obtaining polygon-specific ROS-parameters.
| polygon_sub_topic | Output name of polygon or radius subscription topic. Empty, if no polygon subscription. |
| polygon_pub_topic | Output name of polygon publishing topic |
| footprint_topic | Output name of footprint topic. Empty, if no footprint subscription. |
Reimplemented in nav2_collision_monitor::Circle, and nav2_collision_monitor::VelocityPolygon.
Definition at line 463 of file polygon.cpp.
References getCommonParameters(), getPolygonFromString(), logger_, node_, poly_, and polygon_name_.
Referenced by configure().


|
virtual |
Gets number of points inside given polygon.
| sources_collision_points_map | Map containing source name as key, and input array of source's points to be checked as value |
Definition at line 237 of file polygon.cpp.
References getPointsInside(), and getSourcesNames().

|
virtual |
Gets number of points inside given polygon.
| points | Input array of points to be checked |
Reimplemented in nav2_collision_monitor::Circle.
Definition at line 226 of file polygon.cpp.
References isPointInside().
Referenced by getCollisionTime(), and getPointsInside().


|
virtual |
Gets polygon points.
| poly | Output polygon points (vertices) |
Reimplemented in nav2_collision_monitor::Circle.
Definition at line 165 of file polygon.cpp.
References poly_.
Referenced by configure().

|
protected |
Extracts Polygon points from a string with of the form [[x1,y1],[x2,y2],[x3,y3]...].
| poly_string | Input String containing the verteceis of the polygon |
| polygon | Output Point vector with all the vertecies of the polygon |
Definition at line 630 of file polygon.cpp.
References logger_.
Referenced by nav2_collision_monitor::VelocityPolygon::getParameters(), and getParameters().

| double nav2_collision_monitor::Polygon::getSlowdownRatio | ( | ) | const |
Obtains speed slowdown ratio for current polygon. Applicable for SLOWDOWN model.
Definition at line 140 of file polygon.cpp.
References slowdown_ratio_.
| std::vector< std::string > nav2_collision_monitor::Polygon::getSourcesNames | ( | ) | const |
Obtains the name of the observation sources for current polygon.
Definition at line 160 of file polygon.cpp.
References sources_names_.
Referenced by getCollisionTime(), and getPointsInside().

| double nav2_collision_monitor::Polygon::getTimeBeforeCollision | ( | ) | const |
Obtains required time before collision for current polygon. Applicable for APPROACH model.
Definition at line 155 of file polygon.cpp.
References time_before_collision_.
|
inlineprotected |
Checks if point is inside polygon.
| point | Given point to check |
Definition at line 598 of file polygon.cpp.
References poly_.
Referenced by getPointsInside().

|
protected |
Dynamic polygon callback.
| msg | Shared pointer to the polygon message |
Definition at line 589 of file polygon.cpp.
References logger_, polygon_name_, and updatePolygon().
Referenced by createSubscription().


|
protected |
Updates polygon from geometry_msgs::msg::PolygonStamped message.
| msg | Message to update polygon from |
Definition at line 531 of file polygon.cpp.
References base_frame_id_, logger_, poly_, polygon_, polygon_name_, tf_buffer_, and transform_tolerance_.