Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
pointcloud.hpp
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 #ifndef NAV2_COLLISION_MONITOR__POINTCLOUD_HPP_
16 #define NAV2_COLLISION_MONITOR__POINTCLOUD_HPP_
17 
18 #include <memory>
19 #include <vector>
20 #include <string>
21 
22 #include "sensor_msgs/msg/point_cloud2.hpp"
23 
24 #include "nav2_collision_monitor/source.hpp"
25 
26 namespace nav2_collision_monitor
27 {
28 
32 class PointCloud : public Source
33 {
34 public:
47  PointCloud(
48  const nav2_util::LifecycleNode::WeakPtr & node,
49  const std::string & source_name,
50  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
51  const std::string & base_frame_id,
52  const std::string & global_frame_id,
53  const tf2::Duration & transform_tolerance,
54  const rclcpp::Duration & source_timeout,
55  const bool base_shift_correction);
59  ~PointCloud();
60 
65  void configure();
66 
74  bool getData(
75  const rclcpp::Time & curr_time,
76  std::vector<Point> & data);
77 
78 protected:
83  void getParameters(std::string & source_topic);
84 
89  void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
90 
91  // ----- Variables -----
92 
94  rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr data_sub_;
95 
96  // Minimum and maximum height of PointCloud projected to 2D space
97  double min_height_, max_height_;
98  // Minimum range from sensor origin to filter out close points
99  double min_range_;
100 
102  sensor_msgs::msg::PointCloud2::ConstSharedPtr data_;
103 }; // class PointCloud
104 
105 } // namespace nav2_collision_monitor
106 
107 #endif // NAV2_COLLISION_MONITOR__POINTCLOUD_HPP_
Implementation for pointcloud source.
Definition: pointcloud.hpp:33
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
Definition: pointcloud.cpp:112
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_
Latest data obtained from pointcloud.
Definition: pointcloud.hpp:102
void configure()
Data source configuration routine. Obtains pointcloud related ROS-parameters and creates pointcloud s...
Definition: pointcloud.cpp:51
void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
PointCloud data callback.
Definition: pointcloud.cpp:132
rclcpp::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr data_sub_
PointCloud data subscriber.
Definition: pointcloud.hpp:94
PointCloud(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)
PointCloud constructor.
Definition: pointcloud.cpp:28
~PointCloud()
PointCloud destructor.
Definition: pointcloud.cpp:45
bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)
Adds latest data from pointcloud source to the data array.
Definition: pointcloud.cpp:69
Basic data source class.
Definition: source.hpp:38