Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
circle.cpp
1 // Copyright (c) 2022 Samsung R&D Institute Russia
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_collision_monitor/circle.hpp"
16 
17 #include <math.h>
18 #include <cmath>
19 #include <exception>
20 
21 #include "nav2_ros_common/node_utils.hpp"
22 
23 namespace nav2_collision_monitor
24 {
25 
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)
33 {
34  RCLCPP_INFO(logger_, "[%s]: Creating Circle", polygon_name_.c_str());
35 }
36 
38 {
39  RCLCPP_INFO(logger_, "[%s]: Destroying Circle", polygon_name_.c_str());
40 }
41 
42 void Circle::getPolygon(std::vector<Point> & poly) const
43 {
44  // Number of polygon points. More edges means better approximation.
45  const double polygon_edges = 16;
46  // Increment of angle during points position calculation
47  double angle_increment = 2 * M_PI / polygon_edges;
48 
49  // Clear polygon before filling
50  poly.clear();
51 
52  // Making new polygon looks like a circle
53  Point p;
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);
57  poly.push_back(p);
58  }
59 }
60 
61 int Circle::getPointsInside(const std::vector<Point> & points) const
62 {
63  int num = 0;
64  for (Point point : points) {
65  if (point.x * point.x + point.y * point.y < radius_squared_) {
66  num++;
67  }
68  }
69 
70  return num;
71 }
72 
74 {
75  if (radius_squared_ == -1.0) {
76  RCLCPP_WARN(logger_, "[%s]: Circle radius is not set yet", polygon_name_.c_str());
77  return false;
78  }
79  return true;
80 }
81 
83  std::string & polygon_sub_topic,
84  std::string & polygon_pub_topic,
85  std::string & footprint_topic)
86 {
87  auto node = node_.lock();
88  if (!node) {
89  throw std::runtime_error{"Failed to lock node"};
90  }
91 
92  // Clear the polygon subscription topic. It will be set later, if necessary.
93  polygon_sub_topic.clear();
94 
95  bool use_dynamic_sub = true; // if getting parameter radius fails, use dynamic subscription
96  try {
97  // Leave it not initialized: the will cause an error if it will not set
98  nav2::declare_parameter_if_not_declared(
99  node, polygon_name_ + ".radius", rclcpp::PARAMETER_DOUBLE);
100  radius_ = node->get_parameter(polygon_name_ + ".radius").as_double();
102  use_dynamic_sub = false;
103  } catch (const rclcpp::exceptions::ParameterUninitializedException &) {
104  RCLCPP_INFO(
105  logger_,
106  "[%s]: Polygon circle radius is not defined. Using dynamic subscription instead.",
107  polygon_name_.c_str());
108  }
109 
110  bool ret = true;
111  if (!getCommonParameters(
112  polygon_sub_topic, polygon_pub_topic, footprint_topic, use_dynamic_sub))
113  {
114  if (use_dynamic_sub && polygon_sub_topic.empty()) {
115  RCLCPP_ERROR(
116  logger_,
117  "[%s]: Error while getting circle parameters: static radius and sub topic both not defined",
118  polygon_name_.c_str());
119  }
120  ret = false;
121  }
122 
123  // There is no footprint subscription for the Circle. Thus, set string as empty.
124  footprint_topic.clear();
125 
126  return ret;
127 }
128 
129 void Circle::createSubscription(std::string & polygon_sub_topic)
130 {
131  auto node = node_.lock();
132  if (!node) {
133  throw std::runtime_error{"Failed to lock node"};
134  }
135 
136  if (!polygon_sub_topic.empty()) {
137  RCLCPP_INFO(
138  logger_,
139  "[%s]: Subscribing on %s topic for polygon",
140  polygon_name_.c_str(), polygon_sub_topic.c_str());
141  rclcpp::QoS polygon_qos = nav2::qos::StandardTopicQoS(); // set to default
143  polygon_qos.transient_local();
144  }
145  radius_sub_ = node->create_subscription<std_msgs::msg::Float32>(
146  polygon_sub_topic,
147  std::bind(&Circle::radiusCallback, this, std::placeholders::_1),
148  polygon_qos);
149  }
150 }
151 
152 void Circle::updatePolygon(double radius)
153 {
154  // Update circle radius
155  radius_ = radius;
157 
158  // Create a polygon from radius and store it
159  std::vector<Point> poly;
160  getPolygon(poly);
161  polygon_.polygon.points.clear(); // clear polygon points
162  for (const Point & p : poly) {
163  geometry_msgs::msg::Point32 p_s;
164  p_s.x = p.x;
165  p_s.y = p.y;
166  // p_s.z will remain 0.0
167  polygon_.polygon.points.push_back(p_s); // add new points
168  }
169 }
170 
171 void Circle::radiusCallback(std_msgs::msg::Float32::ConstSharedPtr msg)
172 {
173  RCLCPP_INFO(
174  logger_,
175  "[%s]: Polygon circle radius update has been arrived",
176  polygon_name_.c_str());
177  updatePolygon(msg->data);
178 }
179 
180 } // namespace nav2_collision_monitor
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.
Definition: circle.cpp:61
bool getParameters(std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic) override
Supporting routine obtaining polygon-specific ROS-parameters.
Definition: circle.cpp:82
void getPolygon(std::vector< Point > &poly) const override
Gets polygon points, approximated to the circle. To be used in visualization purposes.
Definition: circle.cpp:42
double radius_squared_
(radius * radius) value. Stored for optimization.
Definition: circle.hpp:116
void radiusCallback(std_msgs::msg::Float32::ConstSharedPtr msg)
Dynamic circle radius callback.
Definition: circle.cpp:171
bool isShapeSet() override
Returns true if circle radius is set. Otherwise, prints a warning and returns false.
Definition: circle.cpp:73
nav2::Subscription< std_msgs::msg::Float32 >::SharedPtr radius_sub_
Radius subscription.
Definition: circle.hpp:118
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.
Definition: circle.cpp:26
void updatePolygon(double radius)
Updates polygon from radius value.
Definition: circle.cpp:152
~Circle()
Circle class destructor.
Definition: circle.cpp:37
double radius_
Radius of the circle.
Definition: circle.hpp:114
void createSubscription(std::string &polygon_sub_topic) override
Creates polygon or radius topic subscription.
Definition: circle.cpp:129
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
Definition: polygon.hpp:43
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.
Definition: polygon.cpp:320
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
Definition: polygon.hpp:262
geometry_msgs::msg::PolygonStamped polygon_
Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message.
Definition: polygon.hpp:308
bool polygon_subscribe_transient_local_
Whether the subscription to polygon topic has transient local QoS durability.
Definition: polygon.hpp:286
std::string polygon_name_
Name of polygon.
Definition: polygon.hpp:268
nav2::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: polygon.hpp:260