Class PointPerception

Inheritance Relationships

Base Type

Class Documentation

class PointPerception : public easynav::PerceptionBase

Concrete perception class for 3D point cloud data.

Stores a point cloud of type pcl::PointCloud<pcl::PointXYZ> and the common metadata inherited from PerceptionBase.

Public Functions

inline void resize(std::size_t size)

Resizes the internal point cloud storage.

Parameters:

size – Number of points to allocate in data.

inline const PointPerceptionBufferType &get_last_perception() const

Retrieves the most recent buffered perception (independently of it has a valid TF) without removing it from the buffer.

inline void integrate_pending_perceptions()

Public Members

pcl::PointCloud<pcl::PointXYZ> data

The 3D point cloud data associated with this perception.

bool pending_available_ = {false}
pcl::PointCloud<pcl::PointXYZ> pending_cloud_
std::string pending_frame_
rclcpp::Time pending_stamp_

Public Static Functions

static inline bool supports_msg_type(std::string_view t)

Checks if a ROS message type is supported by this perception.

Parameters:

t – Fully-qualified ROS 2 message type name (e.g., "sensor_msgs/msg/PointCloud2").

Returns:

true if t is sensor_msgs/msg/LaserScan or sensor_msgs/msg/PointCloud2, otherwise false.

Public Static Attributes

static constexpr std::string_view default_group_ = "points"

Group identifier for point perceptions.

Protected Attributes

CircularBuffer<PointPerceptionBufferType> buffer = {10}