15 #ifndef NAV2_COLLISION_MONITOR__CIRCLE_HPP_
16 #define NAV2_COLLISION_MONITOR__CIRCLE_HPP_
22 #include "nav2_collision_monitor/polygon.hpp"
24 namespace nav2_collision_monitor
44 const nav2_util::LifecycleNode::WeakPtr & node,
45 const std::string & polygon_name,
46 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
47 const std::string & base_frame_id,
48 const tf2::Duration & transform_tolerance);
59 void getPolygon(std::vector<Point> & poly)
const override;
77 bool getParameters(std::string & polygon_pub_topic, std::string & footprint_topic)
override;
Circle shape implementaiton. For STOP/SLOWDOWN model it represents zone around the robot while for AP...
int getPointsInside(const std::vector< Point > &points) const override
Gets number of points inside circle.
void getPolygon(std::vector< Point > &poly) const override
Gets polygon points, approximated to the circle. To be used in visualization purposes.
double radius_squared_
(radius * radius) value. Stored for optimization.
bool getParameters(std::string &polygon_pub_topic, std::string &footprint_topic) override
Supporting routine obtaining polygon-specific ROS-parameters.
~Circle()
Circle class destructor.
double radius_
Radius of the circle.
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.
Basic polygon shape class. For STOP/SLOWDOWN model it represents zone around the robot while for APPR...