15 #include "nav2_collision_monitor/polygon_source.hpp"
20 #include "geometry_msgs/msg/polygon_stamped.hpp"
21 #include "tf2/transform_datatypes.hpp"
23 #include "nav2_util/node_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
27 namespace nav2_collision_monitor
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)
40 node, source_name, tf_buffer, base_frame_id, global_frame_id,
41 transform_tolerance, source_timeout, base_shift_correction)
53 auto node =
node_.lock();
55 throw std::runtime_error{
"Failed to lock node"};
58 std::string source_topic;
62 rclcpp::QoS qos = rclcpp::SensorDataQoS();
63 data_sub_ = node->create_subscription<geometry_msgs::msg::PolygonInstanceStamped>(
69 const rclcpp::Time & curr_time,
70 std::vector<Point> & data)
82 [
this, curr_time](
const geometry_msgs::msg::PolygonInstanceStamped & polygon_stamped) {
83 return curr_time - rclcpp::Time(polygon_stamped.header.stamp) > source_timeout_;
86 tf2::Stamped<tf2::Transform> tf_transform;
87 for (
const auto & polygon_instance :
data_) {
92 !nav2_util::getTransform(
93 polygon_instance.header.frame_id, polygon_instance.header.stamp,
104 !nav2_util::getTransform(
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);
122 const geometry_msgs::msg::PolygonStamped & polygon, std::vector<Point> & data)
const
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()];
133 double segment_length =
134 std::hypot(next_point.x - current_point.x, next_point.y - current_point.y);
137 int num_points_in_segment =
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;
145 for (
int j = 0; j <= num_points_in_segment; ++j) {
147 p.x = current_point.x + j * dx;
148 p.y = current_point.y + j * dy;
156 auto node =
node_.lock();
158 throw std::runtime_error{
"Failed to lock node"};
163 nav2_util::declare_parameter_if_not_declared(
164 node,
source_name_ +
".sampling_distance", rclcpp::ParameterValue(0.1));
170 auto node =
node_.lock();
172 throw std::runtime_error{
"Failed to lock node"};
174 auto curr_time = node->now();
177 for (
auto & polygon_stamped :
data_) {
178 if (msg->polygon.id == polygon_stamped.polygon.id) {
179 polygon_stamped = *msg;
183 data_.push_back(*msg);
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.
std::string base_frame_id_
Robot base frame ID.
tf2::Duration transform_tolerance_
Transform tolerance.
void getCommonParameters(std::string &source_topic)
Supporting routine obtaining ROS-parameters common for all data sources.
bool configure()
Source configuration routine.
std::string global_frame_id_
Global frame ID for correct transform calculation.
std::string source_name_
Name of data source.
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
bool base_shift_correction_
Whether to correct source data towards to base frame movement, considering the difference between cur...