26#ifndef EASYNAV_SENSORS_TYPES__POINTPERCEPTIONS_HPP_
27#define EASYNAV_SENSORS_TYPES__POINTPERCEPTIONS_HPP_
33#include "tf2/LinearMath/Transform.hpp"
34#include "pcl/point_cloud.h"
35#include "pcl/point_types.h"
36#include "pcl/PointIndices.h"
38#include "sensor_msgs/msg/laser_scan.hpp"
39#include "sensor_msgs/msg/point_cloud2.hpp"
41#include "rclcpp/time.hpp"
42#include "rclcpp_lifecycle/lifecycle_node.hpp"
53struct hash<
std::tuple<int, int, int>>
58 std::size_t
operator()(
const std::tuple<int, int, int> & key)
const
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);
74 pcl::PointCloud<pcl::PointXYZ>
data;
95 return t ==
"sensor_msgs/msg/LaserScan" ||
96 t ==
"sensor_msgs/msg/PointCloud2";
101 [[maybe_unused]]
static const bool _ = [] {
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";
116 pcl::PointCloud<pcl::PointXYZ>
data;
128 data.points.resize(size);
134 return buffer.latest_ref();
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;
154 buffer.push(std::move(pending_item));
158 const std::size_t count =
buffer.size();
168 std::vector<PointPerceptionBufferType> items;
169 items.reserve(count);
171 for (std::size_t i = 0; i < count; ++i) {
176 items.push_back(std::move(item));
192 std::optional<std::size_t> newest_idx;
193 std::optional<std::size_t> newest_valid_idx;
195 for (std::size_t i = 0; i < items.size(); ++i) {
196 const auto & item = items[i];
199 if (!newest_idx || item.stamp > items[*newest_idx].stamp) {
205 has_tf = tf_buffer.canTransform(
208 tf2_ros::fromMsg(item.stamp),
209 tf2::durationFromSec(0.0));
216 if (!newest_valid_idx || item.stamp > items[*newest_valid_idx].stamp) {
217 newest_valid_idx = i;
228 if (newest_valid_idx) {
229 const auto & sel = items[*newest_valid_idx];
235 }
else if (newest_idx) {
236 const auto & sel = items[*newest_idx];
252 if (newest_valid_idx) {
254 const rclcpp::Time cutoff_stamp = items[*newest_valid_idx].stamp;
256 for (
auto & item : items) {
257 if (item.stamp >= cutoff_stamp) {
258 buffer.push(std::move(item));
263 for (
auto & item : items) {
264 buffer.push(std::move(item));
293 bool cycle_rt([[maybe_unused]] std::shared_ptr<NavState> nav_state)
override;
297 std::shared_ptr<PointPerception> perception_data_ {
nullptr};
300 rclcpp::SubscriptionBase::SharedPtr perception_sub_;
306void convert(
const sensor_msgs::msg::LaserScan & scan, pcl::PointCloud<pcl::PointXYZ> & pc);
316sensor_msgs::msg::PointCloud2
points_to_rosmsg(
const pcl::PointCloud<pcl::PointXYZ> & points);
321 std::vector<std::shared_ptr<PointPerception>>;
349 return x == other.
x &&
y == other.
y &&
z == other.
z;
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);
415 const std::vector<double> & min_bounds,
416 const std::vector<double> & max_bounds,
417 bool lazy_post_fuse =
true);
442 collapse(
const std::vector<double> & collapse_dims,
bool lazy =
true);
446 pcl::PointCloud<pcl::PointXYZ>
as_points()
const;
451 const pcl::PointCloud<pcl::PointXYZ> &
as_points(
int idx)
const;
482 const std::string & target_frame,
483 rclcpp::Time & stamp,
484 bool exact_time =
false);
502 const pcl::PointCloud<pcl::PointXYZ> points,
503 const std::string & frame,
515 std::optional<PointPerceptions> owned_;
517 std::vector<pcl::PointIndices> indices_;
520 bool has_target_frame_ {
false};
521 std::string target_frame_;
522 std::vector<tf2::Transform> tf_transforms_;
523 std::vector<bool> tf_valid_;
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};
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};
540 mutable pcl::PointCloud<pcl::PointXYZ> tmp_single_cloud_;
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