|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
Circle shape implementaiton. For STOP/SLOWDOWN model it represents zone around the robot while for APPROACH model it represents robot footprint. More...
#include <nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp>


Public Member Functions | |
| Circle (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) | |
| Circle class constructor. More... | |
| ~Circle () | |
| Circle class destructor. | |
| void | getPolygon (std::vector< Point > &poly) const override |
| Gets polygon points, approximated to the circle. To be used in visualization purposes. More... | |
| int | getPointsInside (const std::vector< Point > &points) const override |
| Gets number of points inside circle. More... | |
Public Member Functions inherited from 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. 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 | getMaxPoints () const |
| Obtains polygon maximum points to enter inside polygon causing no action. More... | |
| double | getSlowdownRatio () const |
| Obtains speed slowdown ratio for current polygon. Applicable for SLOWDOWN model. More... | |
| double | getTimeBeforeCollision () const |
| Obtains required time before collision for current polygon. Applicable for APPROACH model. More... | |
| void | updatePolygon () |
| Updates polygon from footprint subscriber (if any) | |
| double | getCollisionTime (const std::vector< Point > &collision_points, const Velocity &velocity) const |
| Obtains estimated (simulated) time before a collision. Applicable for APPROACH model. More... | |
| void | publish () const |
| Publishes polygon message into a its own topic. | |
Protected Member Functions | |
| bool | getParameters (std::string &polygon_pub_topic, std::string &footprint_topic) override |
| Supporting routine obtaining polygon-specific ROS-parameters. More... | |
Protected Member Functions inherited from nav2_collision_monitor::Polygon | |
| bool | getCommonParameters (std::string &polygon_pub_topic) |
| Supporting routine obtaining ROS-parameters common for all shapes. More... | |
| rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
| Checks if point is inside polygon. More... | |
| bool | isPointInside (const Point &point) const |
Protected Attributes | |
| double | radius_ |
| Radius of the circle. | |
| double | radius_squared_ |
| (radius * radius) value. Stored for optimization. | |
Protected Attributes inherited from nav2_collision_monitor::Polygon | |
| 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 | max_points_ |
| Maximum number of data readings within a zone to not trigger the action. | |
| double | slowdown_ratio_ |
| Robot slowdown (share of its actual speed) | |
| double | time_before_collision_ |
| Time before collision in seconds. | |
| double | simulation_time_step_ |
| Time step for robot movement simulation. | |
| std::unique_ptr< nav2_costmap_2d::FootprintSubscriber > | footprint_sub_ |
| Footprint subscriber. | |
| bool | enabled_ |
| Whether polygon is enabled. | |
| 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::Polygon | polygon_ |
| Polygon points stored for later publishing. | |
| rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::PolygonStamped >::SharedPtr | polygon_pub_ |
| Polygon publisher for visualization purposes. | |
| std::vector< Point > | poly_ |
| Polygon points (vertices) | |
Circle shape implementaiton. For STOP/SLOWDOWN model it represents zone around the robot while for APPROACH model it represents robot footprint.
Definition at line 32 of file circle.hpp.
| nav2_collision_monitor::Circle::Circle | ( | 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 | ||
| ) |
Circle class constructor.
| node | Collision Monitor node pointer |
| polygon_name | Name of circle |
| tf_buffer | Shared pointer to a TF buffer |
| base_frame_id | Robot base frame ID |
| transform_tolerance | Transform tolerance |
Definition at line 26 of file circle.cpp.
References nav2_collision_monitor::Polygon::logger_, and nav2_collision_monitor::Polygon::polygon_name_.
|
overrideprotectedvirtual |
Supporting routine obtaining polygon-specific ROS-parameters.
| polygon_pub_topic | Output name of polygon publishing topic |
| footprint_topic | Output name of footprint topic. For Circle returns empty string, there is no footprint subscription in this class. |
Reimplemented from nav2_collision_monitor::Polygon.
Definition at line 73 of file circle.cpp.
References nav2_collision_monitor::Polygon::getCommonParameters(), nav2_collision_monitor::Polygon::logger_, nav2_collision_monitor::Polygon::node_, nav2_collision_monitor::Polygon::polygon_name_, radius_, and radius_squared_.

|
overridevirtual |
Gets number of points inside circle.
| points | Input array of points to be checked |
Reimplemented from nav2_collision_monitor::Polygon.
Definition at line 61 of file circle.cpp.
References radius_squared_.
|
overridevirtual |
Gets polygon points, approximated to the circle. To be used in visualization purposes.
| poly | Output polygon points (vertices) |
Reimplemented from nav2_collision_monitor::Polygon.
Definition at line 42 of file circle.cpp.
References radius_.