Concrete perception class for 3D point cloud data.
More...
#include <PointPerception.hpp>
|
| static bool | supports_msg_type (std::string_view t) |
| | Checks if a ROS message type is supported by this perception.
|
| |
|
| 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_ |
| |
| std::string | frame_id |
| | Coordinate frame associated with the perception.
|
| |
| bool | new_data = false |
| | Whether the data has changed since the last observation.
|
| |
| rclcpp::Time | stamp |
| | Timestamp of the perception (ROS time).
|
| |
| bool | valid = false |
| | Whether the perception contains valid data.
|
| |
|
| static constexpr std::string_view | default_group_ = "points" |
| | Group identifier for point perceptions.
|
| |
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.
◆ get_last_perception()
Retrieves the most recent buffered perception (independently of it has a valid TF) without removing it from the buffer.
◆ integrate_pending_perceptions()
| void integrate_pending_perceptions |
( |
| ) |
|
◆ resize()
| void resize |
( |
std::size_t | size | ) |
|
Resizes the internal point cloud storage.
- Parameters
-
| size | Number of points to allocate in data. |
◆ supports_msg_type()
| static bool supports_msg_type |
( |
std::string_view | t | ) |
|
|
static |
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.
◆ buffer
◆ data
| pcl::PointCloud<pcl::PointXYZ> data |
The 3D point cloud data associated with this perception.
◆ default_group_
| std::string_view default_group_ = "points" |
|
staticconstexpr |
Group identifier for point perceptions.
◆ pending_available_
| bool pending_available_ {false} |
◆ pending_cloud_
| pcl::PointCloud<pcl::PointXYZ> pending_cloud_ |
◆ pending_frame_
| std::string pending_frame_ |
◆ pending_stamp_
| rclcpp::Time pending_stamp_ |
The documentation for this class was generated from the following file: