Nav2 Navigation Stack - rolling  main
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 #include "point_cloud_transport/point_cloud_transport.hpp"
24 
25 #include "nav2_collision_monitor/source.hpp"
26 
27 namespace nav2_collision_monitor
28 {
29 
33 class PointCloud : public Source
34 {
35 public:
48  PointCloud(
49  const nav2::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);
60  ~PointCloud();
61 
66  void configure();
67 
75  bool getData(
76  const rclcpp::Time & curr_time,
77  std::vector<Point> & data);
78 
79 protected:
84  void getParameters(std::string & source_topic);
85 
90  void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
91 
96  rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
97  std::vector<rclcpp::Parameter> parameters);
98 
99  // ----- Variables -----
100 
102  #if RCLCPP_VERSION_GTE(30, 0, 0)
103  std::shared_ptr<point_cloud_transport::PointCloudTransport> pct_;
104  point_cloud_transport::Subscriber data_sub_;
105  #else
106  nav2::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr data_sub_;
107  #endif
108 
109  // Transport type used for PointCloud messages (e.g., raw or compressed)
110  std::string transport_type_;
111 
112  // Minimum and maximum height of PointCloud projected to 2D space
113  double min_height_, max_height_;
114  // Minimum range from sensor origin to filter out close points
115  double min_range_;
116 
118  sensor_msgs::msg::PointCloud2::ConstSharedPtr data_;
119 }; // class PointCloud
120 
121 } // namespace nav2_collision_monitor
122 
123 #endif // NAV2_COLLISION_MONITOR__POINTCLOUD_HPP_
Implementation for pointcloud source.
Definition: pointcloud.hpp:34
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
Definition: pointcloud.cpp:130
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_
Latest data obtained from pointcloud.
Definition: pointcloud.hpp:118
void configure()
Data source configuration routine. Obtains pointcloud related ROS-parameters and creates pointcloud s...
Definition: pointcloud.cpp:55
nav2::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr data_sub_
PointCloud data subscriber.
Definition: pointcloud.hpp:106
void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
PointCloud data callback.
Definition: pointcloud.cpp:153
PointCloud(const nav2::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
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Definition: pointcloud.cpp:159
~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:87
Basic data source class.
Definition: source.hpp:38