Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
polygon_source.hpp
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 #ifndef NAV2_COLLISION_MONITOR__POLYGON_SOURCE_HPP_
16 #define NAV2_COLLISION_MONITOR__POLYGON_SOURCE_HPP_
17 
18 #include <memory>
19 #include <vector>
20 #include <string>
21 
22 #include "geometry_msgs/msg/polygon_instance_stamped.hpp"
23 #include "geometry_msgs/msg/polygon_stamped.hpp"
24 
25 #include "nav2_collision_monitor/source.hpp"
26 
27 namespace nav2_collision_monitor
28 {
29 
33 class PolygonSource : public Source
34 {
35 public:
49  const nav2_util::LifecycleNode::WeakPtr & node,
50  const std::string & source_name,
51  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
52  const std::string & base_frame_id,
53  const std::string & global_frame_id,
54  const tf2::Duration & transform_tolerance,
55  const rclcpp::Duration & source_timeout,
56  const bool base_shift_correction);
61 
66  void configure();
67 
75  bool getData(
76  const rclcpp::Time & curr_time,
77  std::vector<Point> & data);
78 
85  const geometry_msgs::msg::PolygonStamped & polygon,
86  std::vector<Point> & data) const;
87 
88 protected:
93  void getParameters(std::string & source_topic);
94 
99  void dataCallback(geometry_msgs::msg::PolygonInstanceStamped::ConstSharedPtr msg);
100 
101  // ----- Variables -----
102 
104  rclcpp::Subscription<geometry_msgs::msg::PolygonInstanceStamped>::SharedPtr data_sub_;
105 
107  std::vector<geometry_msgs::msg::PolygonInstanceStamped> data_;
108 
111 }; // class PolygonSource
112 
113 } // namespace nav2_collision_monitor
114 
115 #endif // NAV2_COLLISION_MONITOR__POLYGON_SOURCE_HPP_
Implementation for polygon source.
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