15 #ifndef NAV2_COLLISION_MONITOR__POLYGON_HPP_
16 #define NAV2_COLLISION_MONITOR__POLYGON_HPP_
22 #include "rclcpp/rclcpp.hpp"
23 #include "geometry_msgs/msg/polygon_stamped.hpp"
24 #include "geometry_msgs/msg/polygon.hpp"
27 #include "tf2_ros/buffer.h"
29 #include "nav2_util/lifecycle_node.hpp"
30 #include "nav2_costmap_2d/footprint_subscriber.hpp"
32 #include "nav2_collision_monitor/types.hpp"
34 namespace nav2_collision_monitor
54 const nav2_util::LifecycleNode::WeakPtr & node,
55 const std::string & polygon_name,
56 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
57 const std::string & base_frame_id,
58 const tf2::Duration & transform_tolerance);
116 virtual void getPolygon(std::vector<Point> & poly)
const;
140 const std::vector<Point> & collision_points,
162 virtual bool getParameters(std::string & polygon_pub_topic, std::string & footprint_topic);
175 std::vector<rclcpp::Parameter> parameters);
177 bool isPointInside(
const Point & point)
const;
182 nav2_util::LifecycleNode::WeakPtr
node_;
184 rclcpp::Logger
logger_{rclcpp::get_logger(
"collision_monitor")};
220 rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
polygon_pub_;
Basic polygon shape class. For STOP/SLOWDOWN model it represents zone around the robot while for APPR...
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
double getTimeBeforeCollision() const
Obtains required time before collision for current polygon. Applicable for APPROACH model.
int max_points_
Maximum number of data readings within a zone to not trigger the action.
bool getCommonParameters(std::string &polygon_pub_topic)
Supporting routine obtaining ROS-parameters common for all shapes.
virtual int getPointsInside(const std::vector< Point > &points) const
Gets number of points inside given polygon.
double time_before_collision_
Time before collision in seconds.
bool enabled_
Whether polygon is enabled.
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
ActionType action_type_
Action type for the polygon.
double getCollisionTime(const std::vector< Point > &collision_points, const Velocity &velocity) const
Obtains estimated (simulated) time before a collision. Applicable for APPROACH model.
int getMaxPoints() const
Obtains polygon maximum points to enter inside polygon causing no action.
void publish() const
Publishes polygon message into a its own topic.
void updatePolygon()
Updates polygon from footprint subscriber (if any)
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
double simulation_time_step_
Time step for robot movement simulation.
void activate()
Activates polygon lifecycle publisher.
bool configure()
Shape configuration routine. Obtains ROS-parameters related to shape object and creates polygon lifec...
geometry_msgs::msg::Polygon polygon_
Polygon points stored for later publishing.
std::string getName() const
Returns the name of polygon.
virtual void getPolygon(std::vector< Point > &poly) const
Gets polygon points.
tf2::Duration transform_tolerance_
Transform tolerance.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
ActionType getActionType() const
Obtains polygon action type.
std::vector< Point > poly_
Polygon points (vertices)
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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Checks if point is inside polygon.
void deactivate()
Deactivates polygon lifecycle publisher.
std::unique_ptr< nav2_costmap_2d::FootprintSubscriber > footprint_sub_
Footprint subscriber.
double getSlowdownRatio() const
Obtains speed slowdown ratio for current polygon. Applicable for SLOWDOWN model.
std::string polygon_name_
Name of polygon.
virtual ~Polygon()
Polygon destructor.
bool getEnabled() const
Obtains polygon enabled state.
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_pub_
Polygon publisher for visualization purposes.
bool visualize_
Whether to publish the polygon.
std::string base_frame_id_
Base frame ID.
virtual bool getParameters(std::string &polygon_pub_topic, std::string &footprint_topic)
Supporting routine obtaining polygon-specific ROS-parameters.
double slowdown_ratio_
Robot slowdown (share of its actual speed)
Velocity for 2D model of motion.