Class VelocityPolygon

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class VelocityPolygon : public nav2_collision_monitor::Polygon

Velocity polygon class. This class contains all the points of the polygon and the expected condition of the velocity based polygon.

Public Functions

VelocityPolygon(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)

VelocityPolygon constructor.

Parameters:
  • node – Collision Monitor node pointer

  • polygon_name – Name of main polygon

virtual ~VelocityPolygon()

VelocityPolygon destructor.

virtual bool getParameters(std::string&, std::string &polygon_pub_topic, std::string&) override

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

virtual void updatePolygon(const Velocity &cmd_vel_in) override

Overriden updatePolygon function for VelocityPolygon.

Parameters:

cmd_vel_in – Robot twist command input

Protected Functions

bool isInRange(const Velocity &cmd_vel_in, const SubPolygonParameter &sub_polygon_param)

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

rclcpp::Clock::SharedPtr clock_
bool holonomic_

Flag to indicate if the robot is holonomic.

std::vector<SubPolygonParameter> sub_polygons_

Vector to store the parameters of the sub-polygon.

struct SubPolygonParameter

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

std::vector<Point> poly_
std::string velocity_polygon_name_
double linear_min_
double linear_max_
double theta_min_
double theta_max_
double direction_end_angle_
double direction_start_angle_