Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
pointcloud.cpp
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 #include "nav2_collision_monitor/pointcloud.hpp"
16 
17 #include <functional>
18 
19 #include "sensor_msgs/point_cloud2_iterator.hpp"
20 #include "tf2/transform_datatypes.h"
21 
22 #include "nav2_util/node_utils.hpp"
23 #include "nav2_util/robot_utils.hpp"
24 
25 namespace nav2_collision_monitor
26 {
27 
29  const nav2_util::LifecycleNode::WeakPtr & node,
30  const std::string & source_name,
31  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
32  const std::string & base_frame_id,
33  const std::string & global_frame_id,
34  const tf2::Duration & transform_tolerance,
35  const rclcpp::Duration & source_timeout,
36  const bool base_shift_correction)
37 : Source(
38  node, source_name, tf_buffer, base_frame_id, global_frame_id,
39  transform_tolerance, source_timeout, base_shift_correction),
40  data_(nullptr)
41 {
42  RCLCPP_INFO(logger_, "[%s]: Creating PointCloud", source_name_.c_str());
43 }
44 
46 {
47  RCLCPP_INFO(logger_, "[%s]: Destroying PointCloud", source_name_.c_str());
48  data_sub_.reset();
49 }
50 
52 {
54  auto node = node_.lock();
55  if (!node) {
56  throw std::runtime_error{"Failed to lock node"};
57  }
58 
59  std::string source_topic;
60 
61  getParameters(source_topic);
62 
63  rclcpp::QoS pointcloud_qos = rclcpp::SensorDataQoS(); // set to default
64  data_sub_ = node->create_subscription<sensor_msgs::msg::PointCloud2>(
65  source_topic, pointcloud_qos,
66  std::bind(&PointCloud::dataCallback, this, std::placeholders::_1));
67 }
68 
70  const rclcpp::Time & curr_time,
71  std::vector<Point> & data)
72 {
73  // Ignore data from the source if it is not being published yet or
74  // not published for a long time
75  if (data_ == nullptr) {
76  return false;
77  }
78  if (!sourceValid(data_->header.stamp, curr_time)) {
79  return false;
80  }
81 
82  tf2::Transform tf_transform;
83  if (!getTransform(curr_time, data_->header, tf_transform)) {
84  return false;
85  }
86 
87  sensor_msgs::PointCloud2ConstIterator<float> iter_x(*data_, "x");
88  sensor_msgs::PointCloud2ConstIterator<float> iter_y(*data_, "y");
89  sensor_msgs::PointCloud2ConstIterator<float> iter_z(*data_, "z");
90 
91  // Refill data array with PointCloud points in base frame
92  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
93  // Transform point coordinates from source frame -> to base frame
94  tf2::Vector3 p_v3_s(*iter_x, *iter_y, *iter_z);
95 
96  // Check range from sensor origin before transformation
97  double range = p_v3_s.length();
98  if (range < min_range_) {
99  continue;
100  }
101 
102  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
103 
104  // Refill data array
105  if (p_v3_b.z() >= min_height_ && p_v3_b.z() <= max_height_) {
106  data.push_back({p_v3_b.x(), p_v3_b.y()});
107  }
108  }
109  return true;
110 }
111 
112 void PointCloud::getParameters(std::string & source_topic)
113 {
114  auto node = node_.lock();
115  if (!node) {
116  throw std::runtime_error{"Failed to lock node"};
117  }
118 
119  getCommonParameters(source_topic);
120 
121  nav2_util::declare_parameter_if_not_declared(
122  node, source_name_ + ".min_height", rclcpp::ParameterValue(0.05));
123  min_height_ = node->get_parameter(source_name_ + ".min_height").as_double();
124  nav2_util::declare_parameter_if_not_declared(
125  node, source_name_ + ".max_height", rclcpp::ParameterValue(0.5));
126  max_height_ = node->get_parameter(source_name_ + ".max_height").as_double();
127  nav2_util::declare_parameter_if_not_declared(
128  node, source_name_ + ".min_range", rclcpp::ParameterValue(0.0));
129  min_range_ = node->get_parameter(source_name_ + ".min_range").as_double();
130 }
131 
132 void PointCloud::dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
133 {
134  data_ = msg;
135 }
136 
137 } // namespace nav2_collision_monitor
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
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
Definition: source.hpp:146
bool getTransform(const rclcpp::Time &curr_time, const std_msgs::msg::Header &data_header, tf2::Transform &tf_transform) const
Obtain the transform to get data from source frame and time where it was received to the base frame a...
Definition: source.cpp:135
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 source_name_
Name of data source.
Definition: source.hpp:152
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: source.hpp:144
bool sourceValid(const rclcpp::Time &source_time, const rclcpp::Time &curr_time) const
Checks whether the source data might be considered as valid.
Definition: source.cpp:81