Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
polygon_source.cpp
1 // Copyright (c) 2023 Pixel Robotics GmbH
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/polygon_source.hpp"
16 
17 #include <cmath>
18 #include <functional>
19 
20 #include "geometry_msgs/msg/polygon_stamped.hpp"
21 #include "tf2/transform_datatypes.h"
22 
23 #include "nav2_util/node_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
25 
26 
27 namespace nav2_collision_monitor
28 {
29 
31  const nav2_util::LifecycleNode::WeakPtr & node,
32  const std::string & source_name,
33  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
34  const std::string & base_frame_id,
35  const std::string & global_frame_id,
36  const tf2::Duration & transform_tolerance,
37  const rclcpp::Duration & source_timeout,
38  const bool base_shift_correction)
39 : Source(
40  node, source_name, tf_buffer, base_frame_id, global_frame_id,
41  transform_tolerance, source_timeout, base_shift_correction)
42 {
43 }
44 
46 {
47  data_sub_.reset();
48 }
49 
51 {
53  auto node = node_.lock();
54  if (!node) {
55  throw std::runtime_error{"Failed to lock node"};
56  }
57 
58  std::string source_topic;
59 
60  getParameters(source_topic);
61 
62  rclcpp::QoS qos = rclcpp::SensorDataQoS(); // set to default
63  data_sub_ = node->create_subscription<geometry_msgs::msg::PolygonInstanceStamped>(
64  source_topic, qos,
65  std::bind(&PolygonSource::dataCallback, this, std::placeholders::_1));
66 }
67 
69  const rclcpp::Time & curr_time,
70  std::vector<Point> & data)
71 {
72  // Ignore data from the source if it is not being published yet or
73  // not published for a long time
74  if (data_.empty()) {
75  return false;
76  }
77 
78  // Remove stale data
79  data_.erase(
80  std::remove_if(
81  data_.begin(), data_.end(),
82  [this, curr_time](const geometry_msgs::msg::PolygonInstanceStamped & polygon_stamped) {
83  return curr_time - rclcpp::Time(polygon_stamped.header.stamp) > source_timeout_;
84  }), data_.end());
85 
86  tf2::Stamped<tf2::Transform> tf_transform;
87  for (const auto & polygon_instance : data_) {
89  // Obtaining the transform to get data from source frame and time where it was received
90  // to the base frame and current time
91  if (
92  !nav2_util::getTransform(
93  polygon_instance.header.frame_id, polygon_instance.header.stamp,
94  base_frame_id_, curr_time, global_frame_id_,
95  transform_tolerance_, tf_buffer_, tf_transform))
96  {
97  return false;
98  }
99  } else {
100  // Obtaining the transform to get data from source frame to base frame without time shift
101  // considered. Less accurate but much more faster option not dependent on state estimation
102  // frames.
103  if (
104  !nav2_util::getTransform(
105  polygon_instance.header.frame_id, base_frame_id_,
106  transform_tolerance_, tf_buffer_, tf_transform))
107  {
108  return false;
109  }
110  }
111  geometry_msgs::msg::PolygonStamped poly_out, polygon_stamped;
112  geometry_msgs::msg::TransformStamped tf = tf2::toMsg(tf_transform);
113  polygon_stamped.header = polygon_instance.header;
114  polygon_stamped.polygon = polygon_instance.polygon.polygon;
115  tf2::doTransform(polygon_stamped, poly_out, tf);
116  convertPolygonStampedToPoints(poly_out, data);
117  }
118  return true;
119 }
120 
122  const geometry_msgs::msg::PolygonStamped & polygon, std::vector<Point> & data) const
123 {
124  /* Full function generated by GPT */
125 
126  // Iterate over the vertices of the polygon
127  for (size_t i = 0; i < polygon.polygon.points.size(); ++i) {
128  const auto & current_point = polygon.polygon.points[i];
129  const auto & next_point =
130  polygon.polygon.points[(i + 1) % polygon.polygon.points.size()];
131 
132  // Calculate the distance between the current and next points
133  double segment_length =
134  std::hypot(next_point.x - current_point.x, next_point.y - current_point.y);
135 
136  // Calculate the number of points to sample in the current segment
137  int num_points_in_segment =
138  std::max(static_cast<int>(std::ceil(segment_length / sampling_distance_)), 1);
139 
140  // Calculate the step size for each pair of vertices
141  const double dx = (next_point.x - current_point.x) / num_points_in_segment;
142  const double dy = (next_point.y - current_point.y) / num_points_in_segment;
143 
144  // Sample the points with equal spacing
145  for (int j = 0; j <= num_points_in_segment; ++j) {
146  Point p;
147  p.x = current_point.x + j * dx;
148  p.y = current_point.y + j * dy;
149  data.push_back(p);
150  }
151  }
152 }
153 
154 void PolygonSource::getParameters(std::string & source_topic)
155 {
156  auto node = node_.lock();
157  if (!node) {
158  throw std::runtime_error{"Failed to lock node"};
159  }
160 
161  getCommonParameters(source_topic);
162 
163  nav2_util::declare_parameter_if_not_declared(
164  node, source_name_ + ".sampling_distance", rclcpp::ParameterValue(0.1));
165  sampling_distance_ = node->get_parameter(source_name_ + ".sampling_distance").as_double();
166 }
167 
168 void PolygonSource::dataCallback(geometry_msgs::msg::PolygonInstanceStamped::ConstSharedPtr msg)
169 {
170  auto node = node_.lock();
171  if (!node) {
172  throw std::runtime_error{"Failed to lock node"};
173  }
174  auto curr_time = node->now();
175 
176  // check if older similar polygon exists already and replace it with the new one
177  for (auto & polygon_stamped : data_) {
178  if (msg->polygon.id == polygon_stamped.polygon.id) {
179  polygon_stamped = *msg;
180  return;
181  }
182  }
183  data_.push_back(*msg);
184 }
185 
186 } // namespace nav2_collision_monitor
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
void dataCallback(geometry_msgs::msg::PolygonInstanceStamped::ConstSharedPtr msg)
PolygonSource data callback.
void configure()
Data source configuration routine. Obtains ROS-parameters and creates subscriber.
PolygonSource(const nav2_util::LifecycleNode::WeakPtr &node, const std::string &source_name, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::string &base_frame_id, const std::string &global_frame_id, const tf2::Duration &transform_tolerance, const rclcpp::Duration &source_timeout, const bool base_shift_correction)
PolygonSource constructor.
bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)
Adds latest data from polygon source to the data array.
rclcpp::Subscription< geometry_msgs::msg::PolygonInstanceStamped >::SharedPtr data_sub_
PolygonSource data subscriber.
void convertPolygonStampedToPoints(const geometry_msgs::msg::PolygonStamped &polygon, std::vector< Point > &data) const
Converts a PolygonInstanceStamped to a std::vector<Point>
~PolygonSource()
PolygonSource destructor.
double sampling_distance_
distance between sampled points on polygon edges
std::vector< geometry_msgs::msg::PolygonInstanceStamped > data_
Latest data obtained.
Basic data source class.
Definition: source.hpp:38
std::string base_frame_id_
Robot base frame ID.
Definition: source.hpp:158
tf2::Duration transform_tolerance_
Transform tolerance.
Definition: source.hpp:162
void getCommonParameters(std::string &source_topic)
Supporting routine obtaining ROS-parameters common for all data sources.
Definition: source.cpp:58
bool configure()
Source configuration routine.
Definition: source.cpp:47
std::string global_frame_id_
Global frame ID for correct transform calculation.
Definition: source.hpp:160
std::string source_name_
Name of data source.
Definition: source.hpp:152
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: source.hpp:144
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
Definition: source.hpp:156
bool base_shift_correction_
Whether to correct source data towards to base frame movement, considering the difference between cur...
Definition: source.hpp:167