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  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  data_sub_ = node->create_subscription<sensor_msgs::msg::PointCloud2>(
64  source_topic,
65  std::bind(&PointCloud::dataCallback, this, std::placeholders::_1),
67 
68  // Add callback for dynamic parameters
69  dyn_params_handler_ = node->add_on_set_parameters_callback(
70  std::bind(&PointCloud::dynamicParametersCallback, this, std::placeholders::_1));
71 }
72 
74  const rclcpp::Time & curr_time,
75  std::vector<Point> & data)
76 {
77  // Ignore data from the source if it is not being published yet or
78  // not published for a long time
79  if (data_ == nullptr) {
80  return false;
81  }
82  if (!sourceValid(data_->header.stamp, curr_time)) {
83  return false;
84  }
85 
86  tf2::Transform tf_transform;
87  if (!getTransform(curr_time, data_->header, tf_transform)) {
88  return false;
89  }
90 
91  sensor_msgs::PointCloud2ConstIterator<float> iter_x(*data_, "x");
92  sensor_msgs::PointCloud2ConstIterator<float> iter_y(*data_, "y");
93  sensor_msgs::PointCloud2ConstIterator<float> iter_z(*data_, "z");
94 
95  // Refill data array with PointCloud points in base frame
96  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
97  // Transform point coordinates from source frame -> to base frame
98  tf2::Vector3 p_v3_s(*iter_x, *iter_y, *iter_z);
99 
100  // Check range from sensor origin before transformation
101  double range = p_v3_s.length();
102  if (range < min_range_) {
103  continue;
104  }
105 
106  tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
107 
108  // Refill data array
109  if (p_v3_b.z() >= min_height_ && p_v3_b.z() <= max_height_) {
110  data.push_back({p_v3_b.x(), p_v3_b.y()});
111  }
112  }
113  return true;
114 }
115 
116 void PointCloud::getParameters(std::string & source_topic)
117 {
118  auto node = node_.lock();
119  if (!node) {
120  throw std::runtime_error{"Failed to lock node"};
121  }
122 
123  getCommonParameters(source_topic);
124 
125  nav2::declare_parameter_if_not_declared(
126  node, source_name_ + ".min_height", rclcpp::ParameterValue(0.05));
127  min_height_ = node->get_parameter(source_name_ + ".min_height").as_double();
128  nav2::declare_parameter_if_not_declared(
129  node, source_name_ + ".max_height", rclcpp::ParameterValue(0.5));
130  max_height_ = node->get_parameter(source_name_ + ".max_height").as_double();
131  nav2::declare_parameter_if_not_declared(
132  node, source_name_ + ".min_range", rclcpp::ParameterValue(0.0));
133  min_range_ = node->get_parameter(source_name_ + ".min_range").as_double();
134 }
135 
136 void PointCloud::dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
137 {
138  data_ = msg;
139 }
140 
141 rcl_interfaces::msg::SetParametersResult
143  std::vector<rclcpp::Parameter> parameters)
144 {
145  rcl_interfaces::msg::SetParametersResult result;
146 
147  for (auto parameter : parameters) {
148  const auto & param_type = parameter.get_type();
149  const auto & param_name = parameter.get_name();
150  if(param_name.find(source_name_ + ".") != 0) {
151  continue;
152  }
153  if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
154  if (param_name == source_name_ + "." + "min_height") {
155  min_height_ = parameter.as_double();
156  } else if (param_name == source_name_ + "." + "max_height") {
157  max_height_ = parameter.as_double();
158  } else if (param_name == source_name_ + "." + "min_range") {
159  min_range_ = parameter.as_double();
160  }
161  } else if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
162  if (param_name == source_name_ + "." + "enabled") {
163  enabled_ = parameter.as_bool();
164  }
165  }
166  }
167  result.successful = true;
168  return result;
169 }
170 
171 } // 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:116
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_
Latest data obtained from pointcloud.
Definition: pointcloud.hpp:109
void configure()
Data source configuration routine. Obtains pointcloud related ROS-parameters and creates pointcloud s...
Definition: pointcloud.cpp:51
nav2::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr data_sub_
PointCloud data subscriber.
Definition: pointcloud.hpp:101
void dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
PointCloud data callback.
Definition: pointcloud.cpp:136
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:142
~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:73
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:137
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:81
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
Definition: source.hpp:148