Class VelocityPolygon
Defined in File velocity_polygon.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public nav2_collision_monitor::Polygon
(Class Polygon)
Class Documentation
Velocity polygon class. This class contains all the points of the polygon and the expected condition of the velocity based polygon.
Public Functions
VelocityPolygon constructor.
- Parameters:
node – Collision Monitor node pointer
polygon_name – Name of main polygon
VelocityPolygon destructor.
Overriden getParameters function for VelocityPolygon parameters.
- Parameters:
polygon_sub_topic – Not used in VelocityPolygon
polygon_pub_topic – Output name of polygon publishing topic
footprint_topic – Not used in VelocityPolygon
- Returns:
True if all parameters were obtained or false in failure case
Overriden updatePolygon function for VelocityPolygon.
- Parameters:
cmd_vel_in – Robot twist command input
Protected Functions
Check if the velocities and direction is in expected range.
- Parameters:
cmd_vel_in – Robot twist command input
sub_polygon_param – Sub polygon parameters
- Returns:
True if speed and direction is within the condition
Protected Attributes
Flag to indicate if the robot is holonomic.
Vector to store the parameters of the sub-polygon.
Custom struc to store the parameters of the sub-polygon.
- Param poly_:
The points of the sub-polygon
- Param velocity_polygon_name_:
The name of the sub-polygon
- Param linear_min_:
The minimum linear velocity
- Param linear_max_:
The maximum linear velocity
- Param theta_min_:
The minimum angular velocity
- Param theta_max_:
The maximum angular velocity
- Param direction_end_angle_:
The end angle of the direction(For holonomic robot only)
- Param direction_start_angle_:
The start angle of the direction(For holonomic robot only)
Public Members