15 #ifndef NAV2_COLLISION_MONITOR__VELOCITY_POLYGON_HPP_
16 #define NAV2_COLLISION_MONITOR__VELOCITY_POLYGON_HPP_
22 #include "geometry_msgs/msg/polygon_stamped.hpp"
23 #include "nav2_collision_monitor/polygon.hpp"
24 #include "nav2_collision_monitor/types.hpp"
25 #include "nav2_ros_common/lifecycle_node.hpp"
26 #include "rclcpp/rclcpp.hpp"
27 #include "tf2_ros/buffer.hpp"
29 namespace nav2_collision_monitor
46 const nav2::LifecycleNode::WeakPtr & node,
const std::string & polygon_name,
47 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
const std::string & base_frame_id,
48 const tf2::Duration & transform_tolerance);
62 std::string & , std::string & polygon_pub_topic,
63 std::string & )
override;
85 std::vector<Point> poly_;
86 std::string velocity_polygon_name_;
91 double direction_end_angle_;
92 double direction_start_angle_;
104 rclcpp::Clock::SharedPtr clock_;
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
Velocity polygon class. This class contains all the points of the polygon and the expected condition ...
std::vector< SubPolygonParameter > sub_polygons_
Vector to store the parameters of the sub-polygon.
bool getParameters(std::string &, std::string &polygon_pub_topic, std::string &) override
Overridden getParameters function for VelocityPolygon parameters.
bool isInRange(const Velocity &cmd_vel_in, const SubPolygonParameter &sub_polygon_param)
Check if the velocities and direction is in expected range.
virtual ~VelocityPolygon()
VelocityPolygon destructor.
VelocityPolygon(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)
VelocityPolygon constructor.
void updatePolygon(const Velocity &cmd_vel_in) override
Overridden updatePolygon function for VelocityPolygon.
bool holonomic_
Flag to indicate if the robot is holonomic.
Custom struct to store the parameters of the sub-polygon.
Velocity for 2D model of motion.