15 #ifndef NAV2_COLLISION_MONITOR__CIRCLE_HPP_
16 #define NAV2_COLLISION_MONITOR__CIRCLE_HPP_
22 #include "std_msgs/msg/float32.hpp"
24 #include "nav2_collision_monitor/polygon.hpp"
26 namespace nav2_collision_monitor
46 const nav2_util::LifecycleNode::WeakPtr & node,
47 const std::string & polygon_name,
48 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
49 const std::string & base_frame_id,
50 const tf2::Duration & transform_tolerance);
61 void getPolygon(std::vector<Point> & poly)
const override;
87 std::string & polygon_sub_topic,
88 std::string & polygon_pub_topic,
89 std::string & footprint_topic)
override;
118 rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr
radius_sub_;
Circle shape implementaiton. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while ...
int getPointsInside(const std::vector< Point > &points) const override
Gets number of points inside circle.
bool getParameters(std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic) override
Supporting routine obtaining polygon-specific ROS-parameters.
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.
void radiusCallback(std_msgs::msg::Float32::ConstSharedPtr msg)
Dynamic circle radius callback.
bool isShapeSet() override
Returns true if circle radius is set. Otherwise, prints a warning and returns false.
void updatePolygon(double radius)
Updates polygon from radius value.
~Circle()
Circle class destructor.
double radius_
Radius of the circle.
rclcpp::Subscription< std_msgs::msg::Float32 >::SharedPtr radius_sub_
Radius subscription.
void createSubscription(std::string &polygon_sub_topic) override
Creates polygon or radius topic subscription.
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/LIMIT model it represents zone around the robot while fo...