Class Circle

Inheritance Relationships

Base Type

Class Documentation

class Circle : public nav2_collision_monitor::Polygon

Circle shape implementaiton. For STOP/SLOWDOWN model it represents zone around the robot while for APPROACH model it represents robot footprint.

Public 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.

Parameters:
  • 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

~Circle()

Circle class destructor.

virtual void getPolygon(std::vector<Point> &poly) const override

Gets polygon points, approximated to the circle. To be used in visualization purposes.

Parameters:

poly – Output polygon points (vertices)

virtual int getPointsInside(const std::vector<Point> &points) const override

Gets number of points inside circle.

Parameters:

points – Input array of points to be checked

Returns:

Number of points inside circle. If there are no points, returns zero value.

Protected Functions

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

Supporting routine obtaining polygon-specific ROS-parameters.

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.

Returns:

True if all parameters were obtained or false in failure case

Protected Attributes

double radius_

Radius of the circle.

double radius_squared_

(radius * radius) value. Stored for optimization.