26#ifndef EASYNAV_COMMON_TYPES__POINTPERCEPTIONS_HPP_
27#define EASYNAV_COMMON_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";
100 pcl::PointCloud<pcl::PointXYZ>
data;
112 data.points.resize(size);
118 return buffer.latest_ref();
125 auto & tf_buffer = *tf_buffer_ptr;
126 const auto tf_info = tf_buffer.get_tf_info();
127 const std::string & robot_frame = tf_info.robot_frame;
138 buffer.push(std::move(pending_item));
142 const std::size_t count =
buffer.size();
152 std::vector<PointPerceptionBufferType> items;
153 items.reserve(count);
155 for (std::size_t i = 0; i < count; ++i) {
160 items.push_back(std::move(item));
176 std::optional<std::size_t> newest_idx;
177 std::optional<std::size_t> newest_valid_idx;
179 for (std::size_t i = 0; i < items.size(); ++i) {
180 const auto & item = items[i];
183 if (!newest_idx || item.stamp > items[*newest_idx].stamp) {
189 has_tf = tf_buffer.canTransform(
192 tf2_ros::fromMsg(item.stamp),
193 tf2::durationFromSec(0.0));
200 if (!newest_valid_idx || item.stamp > items[*newest_valid_idx].stamp) {
201 newest_valid_idx = i;
212 if (newest_valid_idx) {
213 const auto & sel = items[*newest_valid_idx];
219 }
else if (newest_idx) {
220 const auto & sel = items[*newest_idx];
236 if (newest_valid_idx) {
238 const rclcpp::Time cutoff_stamp = items[*newest_valid_idx].stamp;
240 for (
auto & item : items) {
241 if (item.stamp >= cutoff_stamp) {
242 buffer.push(std::move(item));
247 for (
auto & item : items) {
248 buffer.push(std::move(item));
267 std::string
group()
const override {
return "points";}
272 std::shared_ptr<PerceptionBase>
create(
const std::string &)
override
274 return std::make_shared<PointPerception>();
290 rclcpp_lifecycle::LifecycleNode & node,
291 const std::string & topic,
292 const std::string & type,
293 std::shared_ptr<PerceptionBase> target,
294 rclcpp::CallbackGroup::SharedPtr cb_group)
override;
300void convert(
const sensor_msgs::msg::LaserScan & scan, pcl::PointCloud<pcl::PointXYZ> & pc);
310sensor_msgs::msg::PointCloud2
points_to_rosmsg(
const pcl::PointCloud<pcl::PointXYZ> & points);
315 std::vector<std::shared_ptr<PointPerception>>;
348 return x == other.
x &&
y == other.
y &&
z == other.
z;
361 std::size_t h1 = std::hash<int>{}(key.
x);
362 std::size_t h2 = std::hash<int>{}(key.
y);
363 std::size_t h3 = std::hash<int>{}(key.
z);
364 return h1 ^ (h2 << 1) ^ (h3 << 2);
414 const std::vector<double> & min_bounds,
415 const std::vector<double> & max_bounds,
416 bool lazy_post_fuse =
true);
441 collapse(
const std::vector<double> & collapse_dims,
bool lazy =
true);
445 pcl::PointCloud<pcl::PointXYZ>
as_points()
const;
450 const pcl::PointCloud<pcl::PointXYZ> &
as_points(
int idx)
const;
481 const std::string & target_frame,
482 rclcpp::Time & stamp,
483 bool exact_time =
true);
501 const pcl::PointCloud<pcl::PointXYZ> points,
502 const std::string & frame,
514 std::optional<PointPerceptions> owned_;
516 std::vector<pcl::PointIndices> indices_;
519 bool has_target_frame_ {
false};
520 std::string target_frame_;
521 std::vector<tf2::Transform> tf_transforms_;
522 std::vector<bool> tf_valid_;
525 bool collapse_x_ {
false};
526 bool collapse_y_ {
false};
527 bool collapse_z_ {
false};
528 float collapse_val_x_ {0.0f};
529 float collapse_val_y_ {0.0f};
530 float collapse_val_z_ {0.0f};
532 bool has_post_filter_ {
false};
533 double post_min_[3] {0.0, 0.0, 0.0};
534 double post_max_[3] {0.0, 0.0, 0.0};
535 bool use_post_min_[3] {
false,
false,
false};
536 bool use_post_max_[3] {
false,
false,
false};
539 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
Abstract base class for representing a single sensor perception.
Definition Perceptions.hpp:40
bool valid
Whether the perception contains valid data.
Definition Perceptions.hpp:51
rclcpp::Time stamp
Timestamp of the perception (ROS time).
Definition Perceptions.hpp:45
bool new_data
Whether the data has changed since the last observation.
Definition Perceptions.hpp:54
std::string frame_id
Coordinate frame associated with the perception.
Definition Perceptions.hpp:48
Abstract base interface for group-specific perception handlers.
Definition Perceptions.hpp:116
PerceptionHandler implementation for sensors producing point-based data.
Definition PointPerception.hpp:263
std::shared_ptr< PerceptionBase > create(const std::string &) override
Creates a new PointPerception instance.
Definition PointPerception.hpp:272
std::string group() const override
Returns the sensor group handled by this handler.
Definition PointPerception.hpp:267
rclcpp::SubscriptionBase::SharedPtr create_subscription(rclcpp_lifecycle::LifecycleNode &node, const std::string &topic, const std::string &type, std::shared_ptr< PerceptionBase > target, rclcpp::CallbackGroup::SharedPtr cb_group) override
Creates a subscription to LaserScan or PointCloud2 messages and updates the perception.
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:103
static bool supports_msg_type(std::string_view t)
Checks if a ROS message type is supported by this perception.
Definition PointPerception.hpp:93
CircularBuffer< PointPerceptionBufferType > buffer
Definition PointPerception.hpp:254
static constexpr std::string_view default_group_
Group identifier for point perceptions.
Definition PointPerception.hpp:88
std::string pending_frame_
Definition PointPerception.hpp:104
bool pending_available_
Definition PointPerception.hpp:102
pcl::PointCloud< pcl::PointXYZ > data
The 3D point cloud data associated with this perception.
Definition PointPerception.hpp:100
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:116
rclcpp::Time pending_stamp_
Definition PointPerception.hpp:105
void resize(std::size_t size)
Resizes the internal point cloud storage.
Definition PointPerception.hpp:110
void integrate_pending_perceptions()
Definition PointPerception.hpp:121
PointPerceptionsOpsView & downsample(double resolution)
Downsamples each perception using a voxel grid.
Definition PointPerception.cpp:356
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:674
PointPerceptionsOpsView & fuse(const std::string &target_frame, bool exact_time=true)
Configures fusion of all perceptions into a common frame.
Definition PointPerception.cpp:598
PointPerceptionsOpsView(PointPerceptionsOpsView &&)=default
const PointPerceptions & get_perceptions() const
Provides a constant reference to the underlying perceptions container.
Definition PointPerception.hpp:507
pcl::PointCloud< pcl::PointXYZ > as_points() const
Retrieves all selected points across perceptions as a single concatenated cloud.
Definition PointPerception.cpp:468
PointPerceptionsOpsView(const PointPerceptions &perceptions)
Constructs a view over an external container of perceptions.
Definition PointPerception.cpp:192
rclcpp::Time get_latest_stamp() const
Retrieves the latest timestamp across all perceptions.
Definition PointPerception.cpp:728
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:407
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:252
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:713
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:184
sensor_msgs::msg::PointCloud2 perception_to_rosmsg(const PointPerception &perception)
Converts a PointPerception into a sensor_msgs::msg::PointCloud2 message.
Definition PointPerception.cpp:174
void convert(const sensor_msgs::msg::LaserScan &scan, pcl::PointCloud< pcl::PointXYZ > &pc)
Converts a LaserScan message into a point cloud.
Definition PointPerception.cpp:142
std::vector< std::shared_ptr< PointPerception > > PointPerceptions
Alias for a vector of shared pointers to PointPerception objects.
Definition PointPerception.hpp:314
PointPerceptions get_point_perceptions(std::vector< PerceptionPtr > &perceptionptr)
Extracts all PointPerception objects from a heterogeneous collection.
Definition PointPerception.cpp:708
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:355
std::size_t operator()(const VoxelKey &key) const
Computes the hash value.
Definition PointPerception.hpp:359
Discrete 3D voxel index used for downsampling.
Definition PointPerception.hpp:339
int y
Definition PointPerception.hpp:341
int z
Definition PointPerception.hpp:341
int x
Discrete coordinates (voxel indices).
Definition PointPerception.hpp:341
bool operator==(const VoxelKey &other) const
Equality comparison.
Definition PointPerception.hpp:346
std::size_t operator()(const std::tuple< int, int, int > &key) const
Computes the hash value.
Definition PointPerception.hpp:58