Nav2 Navigation Stack - rolling  main
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.hpp"
21 
22 #include "nav2_ros_common/node_utils.hpp"
23 #include "nav2_util/robot_utils.hpp"
24 
25 namespace nav2_collision_monitor
26 {
27 
29  const nav2::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  #if RCLCPP_VERSION_GTE(30, 0, 0)
49  data_sub_.shutdown();
50  #else
51  data_sub_.reset();
52  #endif
53 }
54 
56 {
58  auto node = node_.lock();
59  if (!node) {
60  throw std::runtime_error{"Failed to lock node"};
61  }
62 
63  std::string source_topic;
64 
65  getParameters(source_topic);
66 
67  #if RCLCPP_VERSION_GTE(30, 0, 0)
68  const point_cloud_transport::TransportHints hint(transport_type_);
69  pct_ = std::make_shared<point_cloud_transport::PointCloudTransport>(*node);
70  data_sub_ = pct_->subscribe(
71  source_topic, nav2::qos::SensorDataQoS(),
72  std::bind(&PointCloud::dataCallback, this, std::placeholders::_1),
73  {}, &hint
74  );
75  #else
76  data_sub_ = node->create_subscription<sensor_msgs::msg::PointCloud2>(
77  source_topic,
78  std::bind(&PointCloud::dataCallback, this, std::placeholders::_1),
80  #endif
81 
82  // Add callback for dynamic parameters
83  dyn_params_handler_ = node->add_on_set_parameters_callback(
84  std::bind(&PointCloud::dynamicParametersCallback, this, std::placeholders::_1));
85 }
86 
88  const rclcpp::Time & curr_time,
89  std::vector<Point> & data)
90 {
91  // Ignore data from the source if it is not being published yet or
92  // not published for a long time
93  if (data_ == nullptr) {
94  return false;
95  }
96  if (!sourceValid(data_->header.stamp, curr_time)) {
97  return false;
98  }
99 
100  tf2::Transform tf_transform;
101  if (!getTransform(curr_time, data_->header, tf_transform)) {
102  return false;
103  }
104 
105  sensor_msgs::PointCloud2ConstIterator<float> iter_x(*data_, "x");
106  sensor_msgs::PointCloud2ConstIterator<float> iter_y(*data_, "y");
107  sensor_msgs::PointCloud2ConstIterator<float> iter_z(*data_, "z");
108 
109  bool height_present = false;
110  for (const auto & field : data_->fields) {
111  if (field.name == "height") {
112  height_present = true;
113  }
114  }
115 
116 // Reference height field
117  std::string height_field{"z"};
118  if (use_global_height_ && height_present) {
119  height_field = "height";
120  } else if (use_global_height_) {
121  RCLCPP_ERROR(logger_, "[%s]: 'use_global_height' parameter true but height field not in cloud",
122  source_name_.c_str());
123  return false;
124  }
125  sensor_msgs::PointCloud2ConstIterator<float> iter_height(*data_, height_field);
126 
127  // Refill data array with PointCloud points in base frame
128  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
129  // Transform point coordinates from source frame -> to base frame
130  tf2::Vector3 p_v3_s(*iter_x, *iter_y, *iter_z);
131 
132  double data_height = *iter_z;
133  if (use_global_height_) {
134  data_height = *iter_height;
135  ++iter_height;
136  }
137 
138  // Check range from sensor origin before transformation
139  double range = p_v3_s.length();
140  if (range < min_range_) {
141  continue;
142  }
143 
144  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
145 
146  // Refill data array
147  if (data_height >= min_height_ && data_height <= max_height_) {
148  data.push_back({p_v3_b.x(), p_v3_b.y()});
149  }
150  }
151  return true;
152 }
153 
154 void PointCloud::getParameters(std::string & source_topic)
155 {
156  auto node = node_.lock();
157  if (!node) {
158  throw std::runtime_error{"Failed to lock node"};
159  }
160 
161  getCommonParameters(source_topic);
162 
163  min_height_ = node->declare_or_get_parameter(source_name_ + ".min_height", 0.05);
164  max_height_ = node->declare_or_get_parameter(source_name_ + ".max_height", 0.5);
165  min_range_ = node->declare_or_get_parameter(source_name_ + ".min_range", 0.0);
166  use_global_height_ = node->declare_or_get_parameter(
167  source_name_ + ".use_global_height", false);
168  transport_type_ = node->declare_or_get_parameter(
169  source_name_ + ".transport_type", std::string("raw"));
170 }
171 
172 void PointCloud::dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
173 {
174  data_ = msg;
175 }
176 
177 rcl_interfaces::msg::SetParametersResult
179  std::vector<rclcpp::Parameter> parameters)
180 {
181  rcl_interfaces::msg::SetParametersResult result;
182 
183  for (auto parameter : parameters) {
184  const auto & param_type = parameter.get_type();
185  const auto & param_name = parameter.get_name();
186  if(param_name.find(source_name_ + ".") != 0) {
187  continue;
188  }
189  if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
190  if (param_name == source_name_ + "." + "min_height") {
191  min_height_ = parameter.as_double();
192  } else if (param_name == source_name_ + "." + "max_height") {
193  max_height_ = parameter.as_double();
194  } else if (param_name == source_name_ + "." + "min_range") {
195  min_range_ = parameter.as_double();
196  }
197  } else if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
198  if (param_name == source_name_ + "." + "enabled") {
199  enabled_ = parameter.as_bool();
200  } else if (param_name == source_name_ + "." + "use_global_height") {
201  use_global_height_ = parameter.as_bool();
202  }
203  }
204  }
205  result.successful = true;
206  return result;
207 }
208 
209 } // namespace nav2_collision_monitor
A QoS profile for best-effort sensor data with a history of 10 messages.
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
Definition: pointcloud.cpp:154
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_
Latest data obtained from pointcloud.
Definition: pointcloud.hpp:122
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:172
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:178
~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
nav2::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: source.hpp:144
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:133
bool enabled_
Whether source is enabled.
Definition: source.hpp:169
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
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:77
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
Definition: source.hpp:148