Easy Navigation
Loading...
Searching...
No Matches
PointPerception.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
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
25
26#ifndef EASYNAV_SENSORS_TYPES__POINTPERCEPTIONS_HPP_
27#define EASYNAV_SENSORS_TYPES__POINTPERCEPTIONS_HPP_
28
29#include <string>
30#include <vector>
31#include <optional>
32
33#include "tf2/LinearMath/Transform.hpp"
34#include "pcl/point_cloud.h"
35#include "pcl/point_types.h"
36#include "pcl/PointIndices.h"
37
38#include "sensor_msgs/msg/laser_scan.hpp"
39#include "sensor_msgs/msg/point_cloud2.hpp"
40
41#include "rclcpp/time.hpp"
42#include "rclcpp_lifecycle/lifecycle_node.hpp"
43
47
48namespace std
49{
50
52template<>
53struct hash<std::tuple<int, int, int>>
54{
58 std::size_t operator()(const std::tuple<int, int, int> & key) const
59 {
60 std::size_t h1 = std::hash<int>()(std::get<0>(key));
61 std::size_t h2 = std::hash<int>()(std::get<1>(key));
62 std::size_t h3 = std::hash<int>()(std::get<2>(key));
63 return h1 ^ (h2 << 1) ^ (h3 << 2);
64 }
65};
66
67} // namespace std
68
69namespace easynav
70{
71
73{
74 pcl::PointCloud<pcl::PointXYZ> data;
75 std::string frame;
76 rclcpp::Time stamp;
77};
78
85{
86public:
88 static constexpr std::string_view default_group_ = "points";
89
93 static inline bool supports_msg_type(std::string_view t)
94 {
95 return t == "sensor_msgs/msg/LaserScan" ||
96 t == "sensor_msgs/msg/PointCloud2";
97 }
98
100 {
101 [[maybe_unused]] static const bool _ = [] {
103 [](const PointPerception & perception) {
104 std::ostringstream ret;
105 ret << "{ " << perception.stamp.seconds()
106 << " } PointPerception with " << perception.data.size()
107 << " points in frame [" << perception.frame_id
108 << "] with ts " << perception.stamp.seconds() << "\n";
109 return ret.str();
110 });
111 return true;
112 }();
113 }
114
116 pcl::PointCloud<pcl::PointXYZ> data;
117
119 pcl::PointCloud<pcl::PointXYZ> pending_cloud_;
120 std::string pending_frame_;
121 rclcpp::Time pending_stamp_;
122
123
126 void resize(std::size_t size)
127 {
128 data.points.resize(size);
129 }
130
133 {
134 return buffer.latest_ref();
135 }
136
138 {
139 // Access TF buffer singleton (already initialized somewhere with a clock)
140 auto tf_buffer_ptr = RTTFBuffer::getInstance();
141 auto & tf_buffer = *tf_buffer_ptr;
142 const auto tf_info = tf_buffer.get_tf_info();
143 const std::string & robot_frame = tf_info.robot_frame;
144
145 // ------------------------------------------------------------------
146 // 1. Push pending perception into the circular buffer exactly once.
147 // ------------------------------------------------------------------
148 if (pending_available_) {
149 PointPerceptionBufferType pending_item;
150 pending_item.data = std::move(pending_cloud_); // avoid deep copy
151 pending_item.frame = pending_frame_;
152 pending_item.stamp = pending_stamp_;
153
154 buffer.push(std::move(pending_item));
155 pending_available_ = false;
156 }
157
158 const std::size_t count = buffer.size();
159 if (count == 0) {
160 // No candidates at all: keep current visible state as is.
161 return;
162 }
163
164 // ------------------------------------------------------------------
165 // 2. Drain the circular buffer into a temporary vector so we can
166 // inspect all items and then rebuild the buffer.
167 // ------------------------------------------------------------------
168 std::vector<PointPerceptionBufferType> items;
169 items.reserve(count);
170
171 for (std::size_t i = 0; i < count; ++i) {
173 if (!buffer.pop(item)) {
174 break; // Defensive guard if pop() fails unexpectedly.
175 }
176 items.push_back(std::move(item));
177 }
178
179 if (items.empty()) {
180 // Nothing recovered from buffer: keep visible state untouched.
181 return;
182 }
183
184 // ------------------------------------------------------------------
185 // 3. Find indices:
186 // - newest_idx: newest perception by timestamp (regardless of TF),
187 // - newest_valid_idx: newest perception that has a valid TF.
188 //
189 // IMPORTANT: store only indices to avoid copying point clouds
190 // during the scan.
191 // ------------------------------------------------------------------
192 std::optional<std::size_t> newest_idx;
193 std::optional<std::size_t> newest_valid_idx;
194
195 for (std::size_t i = 0; i < items.size(); ++i) {
196 const auto & item = items[i];
197
198 // Track newest item overall (used when no TF is valid).
199 if (!newest_idx || item.stamp > items[*newest_idx].stamp) {
200 newest_idx = i;
201 }
202
203 bool has_tf = false;
204 try {
205 has_tf = tf_buffer.canTransform(
206 robot_frame,
207 item.frame,
208 tf2_ros::fromMsg(item.stamp),
209 tf2::durationFromSec(0.0));
210 } catch (...) {
211 // Any TF exception is treated as "no valid TF" for this item.
212 has_tf = false;
213 }
214
215 if (has_tf) {
216 if (!newest_valid_idx || item.stamp > items[*newest_valid_idx].stamp) {
217 newest_valid_idx = i;
218 }
219 }
220 }
221
222 // ------------------------------------------------------------------
223 // 4. Update visible state BEFORE moving items back into the buffer.
224 // This guarantees that `data` corresponds to:
225 // - the newest TF-valid item if any exists, otherwise
226 // - the newest item overall.
227 // ------------------------------------------------------------------
228 if (newest_valid_idx) {
229 const auto & sel = items[*newest_valid_idx];
230 data = sel.data; // single deep copy (intentional)
231 frame_id = sel.frame;
232 stamp = sel.stamp;
233 valid = true; // "valid" means "usable / not too old", not "TF ok"
234 new_data = true;
235 } else if (newest_idx) {
236 const auto & sel = items[*newest_idx];
237 data = sel.data; // single deep copy (intentional)
238 frame_id = sel.frame;
239 stamp = sel.stamp;
240 valid = true;
241 new_data = true;
242 } else {
243 // Defensive: should not happen because items is non-empty.
244 return;
245 }
246
247 // ------------------------------------------------------------------
248 // 5. Rebuild the circular buffer from scratch (move-only, no copies).
249 // ------------------------------------------------------------------
250 buffer.clear();
251
252 if (newest_valid_idx) {
253 // Keep the newest TF-valid item and any newer items (even if TF is not yet available).
254 const rclcpp::Time cutoff_stamp = items[*newest_valid_idx].stamp;
255
256 for (auto & item : items) {
257 if (item.stamp >= cutoff_stamp) {
258 buffer.push(std::move(item));
259 }
260 }
261 } else {
262 // No TF-valid items: keep everything in case TF arrives later.
263 for (auto & item : items) {
264 buffer.push(std::move(item));
265 }
266 }
267 }
268
269protected:
271};
272
279{
280public:
284 void on_initialize() override;
285
293 bool cycle_rt([[maybe_unused]] std::shared_ptr<NavState> nav_state) override;
294
295private:
297 std::shared_ptr<PointPerception> perception_data_ {nullptr};
298
300 rclcpp::SubscriptionBase::SharedPtr perception_sub_;
301};
302
306void convert(const sensor_msgs::msg::LaserScan & scan, pcl::PointCloud<pcl::PointXYZ> & pc);
307
311sensor_msgs::msg::PointCloud2 perception_to_rosmsg(const PointPerception & perception);
312
316sensor_msgs::msg::PointCloud2 points_to_rosmsg(const pcl::PointCloud<pcl::PointXYZ> & points);
317
321 std::vector<std::shared_ptr<PointPerception>>;
322
326rclcpp::Time get_latest_point_perceptions_stamp(const PointPerceptions & perceptions);
327
335{
336public:
339 struct VoxelKey
340 {
342 int x, y, z;
343
347 bool operator==(const VoxelKey & other) const
348 {
349 return x == other.x && y == other.y && z == other.z;
350 }
351 };
352
356 {
360 std::size_t operator()(const VoxelKey & key) const
361 {
362 std::size_t h1 = std::hash<int>{}(key.x);
363 std::size_t h2 = std::hash<int>{}(key.y);
364 std::size_t h3 = std::hash<int>{}(key.z);
365 return h1 ^ (h2 << 1) ^ (h3 << 2);
366 }
367 };
368
371 explicit PointPerceptionsOpsView(const PointPerceptions & perceptions);
372
379 explicit PointPerceptionsOpsView(const PointPerception & perception);
380
383 explicit PointPerceptionsOpsView(PointPerceptions && perceptions);
384
387
389
415 const std::vector<double> & min_bounds,
416 const std::vector<double> & max_bounds,
417 bool lazy_post_fuse = true);
418
422 PointPerceptionsOpsView & downsample(double resolution);
423
442 collapse(const std::vector<double> & collapse_dims, bool lazy = true);
443
446 pcl::PointCloud<pcl::PointXYZ> as_points() const;
447
451 const pcl::PointCloud<pcl::PointXYZ> & as_points(int idx) const;
452
464 PointPerceptionsOpsView & fuse(const std::string & target_frame, bool exact_time = false);
465
482 const std::string & target_frame,
483 rclcpp::Time & stamp,
484 bool exact_time = false);
485
501 add(
502 const pcl::PointCloud<pcl::PointXYZ> points,
503 const std::string & frame,
504 rclcpp::Time stamp);
505
508 const PointPerceptions & get_perceptions() const {return perceptions_;}
509
512 rclcpp::Time get_latest_stamp() const;
513
514private:
515 std::optional<PointPerceptions> owned_;
516 const PointPerceptions & perceptions_;
517 std::vector<pcl::PointIndices> indices_;
518
519 // Lazy fusion state
520 bool has_target_frame_ {false};
521 std::string target_frame_;
522 std::vector<tf2::Transform> tf_transforms_;
523 std::vector<bool> tf_valid_;
524
525 // Lazy collapse state
526 bool collapse_x_ {false};
527 bool collapse_y_ {false};
528 bool collapse_z_ {false};
529 float collapse_val_x_ {0.0f};
530 float collapse_val_y_ {0.0f};
531 float collapse_val_z_ {0.0f};
532
533 bool has_post_filter_ {false};
534 double post_min_[3] {0.0, 0.0, 0.0};
535 double post_max_[3] {0.0, 0.0, 0.0};
536 bool use_post_min_[3] {false, false, false};
537 bool use_post_max_[3] {false, false, false};
538
539 // Temporary storage for as_points(int)
540 mutable pcl::PointCloud<pcl::PointXYZ> tmp_single_cloud_;
541};
542
543} // namespace easynav
544
545#endif // EASYNAV_SENSORS_TYPES__POINTPERCEPTIONS_HPP_
Defines data structures and utilities for representing and processing sensor perceptions.
Fixed-size circular buffer, thread-safe (mutex-based), copyable.
Definition CircularBuffer.hpp:33
static void register_printer(std::function< std::string(const T &)> printer)
Registers a pretty-printer for type T used by debug_string().
Definition NavState.hpp:384
Abstract base class for representing a single sensor perception.
Definition Perceptions.hpp:44
bool valid
Whether the perception contains valid data.
Definition Perceptions.hpp:56
rclcpp::Time stamp
Timestamp of the perception (ROS time).
Definition Perceptions.hpp:49
bool new_data
Whether the data has changed since the last observation.
Definition Perceptions.hpp:59
std::string frame_id
Coordinate frame associated with the perception.
Definition Perceptions.hpp:52
Abstract base class for pluginlib-based sensor perception handlers.
Definition Perceptions.hpp:108
PerceptionHandler implementation for sensors producing point-based data.
Definition PointPerception.hpp:279
bool cycle_rt(std::shared_ptr< NavState > nav_state) override
Run one real-time sensor processing cycle.
Definition PointPerception.cpp:150
void on_initialize() override
Optional post-initialization hook for subclasses.
Definition PointPerception.cpp:92
Concrete perception class for 3D point cloud data.
Definition PointPerception.hpp:85
pcl::PointCloud< pcl::PointXYZ > pending_cloud_
Definition PointPerception.hpp:119
static bool supports_msg_type(std::string_view t)
Checks if a ROS message type is supported by this perception.
Definition PointPerception.hpp:93
PointPerception()
Definition PointPerception.hpp:99
CircularBuffer< PointPerceptionBufferType > buffer
Definition PointPerception.hpp:270
static constexpr std::string_view default_group_
Group identifier for point perceptions.
Definition PointPerception.hpp:88
std::string pending_frame_
Definition PointPerception.hpp:120
bool pending_available_
Definition PointPerception.hpp:118
pcl::PointCloud< pcl::PointXYZ > data
The 3D point cloud data associated with this perception.
Definition PointPerception.hpp:116
const PointPerceptionBufferType & get_last_perception() const
Retrieves the most recent buffered perception (independently of it has a valid TF) without removing i...
Definition PointPerception.hpp:132
rclcpp::Time pending_stamp_
Definition PointPerception.hpp:121
void resize(std::size_t size)
Resizes the internal point cloud storage.
Definition PointPerception.hpp:126
void integrate_pending_perceptions()
Definition PointPerception.hpp:137
PointPerceptionsOpsView & downsample(double resolution)
Downsamples each perception using a voxel grid.
Definition PointPerception.cpp:375
PointPerceptionsOpsView & add(const pcl::PointCloud< pcl::PointXYZ > points, const std::string &frame, rclcpp::Time stamp)
Adds a new perception to the current view.
Definition PointPerception.cpp:756
PointPerceptionsOpsView & fuse(const std::string &target_frame, bool exact_time=false)
Configures fusion of all perceptions into a common frame.
Definition PointPerception.cpp:617
PointPerceptionsOpsView(PointPerceptionsOpsView &&)=default
const PointPerceptions & get_perceptions() const
Provides a constant reference to the underlying perceptions container.
Definition PointPerception.hpp:508
pcl::PointCloud< pcl::PointXYZ > as_points() const
Retrieves all selected points across perceptions as a single concatenated cloud.
Definition PointPerception.cpp:487
PointPerceptionsOpsView(const PointPerceptions &perceptions)
Constructs a view over an external container of perceptions.
Definition PointPerception.cpp:211
rclcpp::Time get_latest_stamp() const
Retrieves the latest timestamp across all perceptions.
Definition PointPerception.cpp:812
PointPerceptionsOpsView & collapse(const std::vector< double > &collapse_dims, bool lazy=true)
Collapses dimensions to fixed values (for example, projection onto a plane).
Definition PointPerception.cpp:426
PointPerceptionsOpsView(const PointPerceptionsOpsView &)=delete
PointPerceptionsOpsView & operator=(const PointPerceptionsOpsView &)=delete
PointPerceptionsOpsView & filter(const std::vector< double > &min_bounds, const std::vector< double > &max_bounds, bool lazy_post_fuse=true)
Filters all point clouds by axis-aligned bounds.
Definition PointPerception.cpp:271
static RTTFBuffer * getInstance(Args &&... args)
Definition Singleton.hpp:31
Definition CircularBuffer.hpp:23
rclcpp::Time get_latest_point_perceptions_stamp(const PointPerceptions &perceptions)
Retrieves the latest timestamp among a set of point-based perceptions.
Definition PointPerception.cpp:789
sensor_msgs::msg::PointCloud2 points_to_rosmsg(const pcl::PointCloud< pcl::PointXYZ > &points)
Converts a PCL point cloud into a sensor_msgs::msg::PointCloud2 message.
Definition PointPerception.cpp:203
sensor_msgs::msg::PointCloud2 perception_to_rosmsg(const PointPerception &perception)
Converts a PointPerception into a sensor_msgs::msg::PointCloud2 message.
Definition PointPerception.cpp:193
void convert(const sensor_msgs::msg::LaserScan &scan, pcl::PointCloud< pcl::PointXYZ > &pc)
Converts a LaserScan message into a point cloud.
Definition PointPerception.cpp:161
std::vector< std::shared_ptr< PointPerception > > PointPerceptions
Alias for a vector of shared pointers to PointPerception objects.
Definition PointPerception.hpp:320
Definition PointPerception.hpp:49
Definition PointPerception.hpp:73
rclcpp::Time stamp
Definition PointPerception.hpp:76
pcl::PointCloud< pcl::PointXYZ > data
Definition PointPerception.hpp:74
std::string frame
Definition PointPerception.hpp:75
Hash functor for VoxelKey.
Definition PointPerception.hpp:356
std::size_t operator()(const VoxelKey &key) const
Computes the hash value.
Definition PointPerception.hpp:360
Discrete 3D voxel index used for downsampling.
Definition PointPerception.hpp:340
int y
Definition PointPerception.hpp:342
int z
Definition PointPerception.hpp:342
int x
Discrete coordinates (voxel indices).
Definition PointPerception.hpp:342
bool operator==(const VoxelKey &other) const
Equality comparison.
Definition PointPerception.hpp:347
std::size_t operator()(const std::tuple< int, int, int > &key) const
Computes the hash value.
Definition PointPerception.hpp:58