15 #include "nav2_collision_monitor/circle.hpp"
21 #include "nav2_ros_common/node_utils.hpp"
23 namespace nav2_collision_monitor
27 const nav2::LifecycleNode::WeakPtr & node,
28 const std::string & polygon_name,
29 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
30 const std::string & base_frame_id,
31 const tf2::Duration & transform_tolerance)
32 :
Polygon::
Polygon(node, polygon_name, tf_buffer, base_frame_id, transform_tolerance)
45 const double polygon_edges = 16;
47 double angle_increment = 2 * M_PI / polygon_edges;
54 for (
double angle = 0.0; angle < 2 * M_PI; angle += angle_increment) {
55 p.x =
radius_ * std::cos(angle);
56 p.y =
radius_ * std::sin(angle);
64 for (
Point point : points) {
83 std::string & polygon_sub_topic,
84 std::string & polygon_pub_topic,
85 std::string & footprint_topic)
87 auto node =
node_.lock();
89 throw std::runtime_error{
"Failed to lock node"};
93 polygon_sub_topic.clear();
95 bool use_dynamic_sub =
true;
98 nav2::declare_parameter_if_not_declared(
102 use_dynamic_sub =
false;
103 }
catch (
const rclcpp::exceptions::ParameterUninitializedException &) {
106 "[%s]: Polygon circle radius is not defined. Using dynamic subscription instead.",
112 polygon_sub_topic, polygon_pub_topic, footprint_topic, use_dynamic_sub))
114 if (use_dynamic_sub && polygon_sub_topic.empty()) {
117 "[%s]: Error while getting circle parameters: static radius and sub topic both not defined",
124 footprint_topic.clear();
131 auto node =
node_.lock();
133 throw std::runtime_error{
"Failed to lock node"};
136 if (!polygon_sub_topic.empty()) {
139 "[%s]: Subscribing on %s topic for polygon",
143 polygon_qos.transient_local();
145 radius_sub_ = node->create_subscription<std_msgs::msg::Float32>(
159 std::vector<Point> poly;
162 for (
const Point & p : poly) {
163 geometry_msgs::msg::Point32 p_s;
167 polygon_.polygon.points.push_back(p_s);
175 "[%s]: Polygon circle radius update has been arrived",
A QoS profile for standard reliable topics with a history of 10 messages.
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.
nav2::Subscription< std_msgs::msg::Float32 >::SharedPtr radius_sub_
Radius subscription.
Circle(const nav2::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.
void updatePolygon(double radius)
Updates polygon from radius value.
~Circle()
Circle class destructor.
double radius_
Radius of the circle.
void createSubscription(std::string &polygon_sub_topic) override
Creates polygon or radius topic subscription.
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
bool getCommonParameters(std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic, bool use_dynamic_sub=false)
Supporting routine obtaining ROS-parameters common for all shapes.
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
geometry_msgs::msg::PolygonStamped polygon_
Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message.
bool polygon_subscribe_transient_local_
Whether the subscription to polygon topic has transient local QoS durability.
std::string polygon_name_
Name of polygon.
nav2::LifecycleNode::WeakPtr node_
Collision Monitor node.