-
Notifications
You must be signed in to change notification settings - Fork 1.4k
/
Copy pathpointcloud.cpp
130 lines (109 loc) · 3.95 KB
/
pointcloud.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
// Copyright (c) 2022 Samsung R&D Institute Russia
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "nav2_collision_monitor/pointcloud.hpp"
#include <functional>
#include "sensor_msgs/point_cloud2_iterator.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/robot_utils.hpp"
namespace nav2_collision_monitor
{
PointCloud::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)
: Source(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
transform_tolerance, source_timeout),
data_(nullptr)
{
RCLCPP_INFO(logger_, "[%s]: Creating PointCloud", source_name_.c_str());
}
PointCloud::~PointCloud()
{
RCLCPP_INFO(logger_, "[%s]: Destroying PointCloud", source_name_.c_str());
data_sub_.reset();
}
void PointCloud::configure()
{
auto node = node_.lock();
if (!node) {
throw std::runtime_error{"Failed to lock node"};
}
std::string source_topic;
getParameters(source_topic);
rclcpp::QoS pointcloud_qos = rclcpp::SensorDataQoS(); // set to default
data_sub_ = node->create_subscription<sensor_msgs::msg::PointCloud2>(
source_topic, pointcloud_qos,
std::bind(&PointCloud::dataCallback, this, std::placeholders::_1));
}
void PointCloud::getData(
const rclcpp::Time & curr_time,
std::vector<Point> & data) const
{
// Ignore data from the source if it is not being published yet or
// not published for a long time
if (data_ == nullptr) {
return;
}
if (!sourceValid(data_->header.stamp, curr_time)) {
return;
}
// Obtaining the transform to get data from source frame and time where it was received
// to the base frame and current time
tf2::Transform tf_transform;
if (
!nav2_util::getTransform(
data_->header.frame_id, data_->header.stamp,
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
}
sensor_msgs::PointCloud2ConstIterator<float> iter_x(*data_, "x");
sensor_msgs::PointCloud2ConstIterator<float> iter_y(*data_, "y");
sensor_msgs::PointCloud2ConstIterator<float> iter_z(*data_, "z");
// Refill data array with PointCloud points in base frame
for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
// Transform point coordinates from source frame -> to base frame
tf2::Vector3 p_v3_s(*iter_x, *iter_y, *iter_z);
tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
// Refill data array
if (p_v3_b.z() >= min_height_ && p_v3_b.z() <= max_height_) {
data.push_back({p_v3_b.x(), p_v3_b.y()});
}
}
}
void PointCloud::getParameters(std::string & source_topic)
{
auto node = node_.lock();
if (!node) {
throw std::runtime_error{"Failed to lock node"};
}
getCommonParameters(source_topic);
nav2_util::declare_parameter_if_not_declared(
node, source_name_ + ".min_height", rclcpp::ParameterValue(0.05));
min_height_ = node->get_parameter(source_name_ + ".min_height").as_double();
nav2_util::declare_parameter_if_not_declared(
node, source_name_ + ".max_height", rclcpp::ParameterValue(0.5));
max_height_ = node->get_parameter(source_name_ + ".max_height").as_double();
}
void PointCloud::dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
{
data_ = msg;
}
} // namespace nav2_collision_monitor