|
Easy Navigation
|
Defines data structures and utilities for representing and processing point-based sensor perceptions. More...
#include <string>#include <vector>#include <optional>#include "tf2/LinearMath/Transform.hpp"#include "pcl/point_cloud.h"#include "pcl/point_types.h"#include "pcl/PointIndices.h"#include "sensor_msgs/msg/laser_scan.hpp"#include "sensor_msgs/msg/point_cloud2.hpp"#include "rclcpp/time.hpp"#include "rclcpp_lifecycle/lifecycle_node.hpp"#include "easynav_common/types/Perceptions.hpp"#include "easynav_common/CircularBuffer.hpp"#include "easynav_common/RTTFBuffer.hpp"

Go to the source code of this file.
Classes | |
| struct | hash< std::tuple< int, int, int > > |
Custom hash specialization for std::tuple<int,int,int>. More... | |
| class | PointPerception |
| Concrete perception class for 3D point cloud data. More... | |
| struct | PointPerceptionBufferType |
| class | PointPerceptionHandler |
| PerceptionHandler implementation for sensors producing point-based data. More... | |
| class | PointPerceptionsOpsView |
| Provides efficient, non-destructive, chainable operations over a set of point-based perceptions. More... | |
| struct | PointPerceptionsOpsView::VoxelKey |
| Discrete 3D voxel index used for downsampling. More... | |
| struct | PointPerceptionsOpsView::VoxelKeyHash |
| Hash functor for VoxelKey. More... | |
Namespaces | |
| namespace | easynav |
| namespace | std |
Typedefs | |
| using | PointPerceptions |
| Alias for a vector of shared pointers to PointPerception objects. | |
Functions | |
| void | convert (const sensor_msgs::msg::LaserScan &scan, pcl::PointCloud< pcl::PointXYZ > &pc) |
Converts a LaserScan message into a point cloud. | |
| rclcpp::Time | get_latest_point_perceptions_stamp (const PointPerceptions &perceptions) |
| Retrieves the latest timestamp among a set of point-based perceptions. | |
| PointPerceptions | get_point_perceptions (std::vector< PerceptionPtr > &perceptionptr) |
| Extracts all PointPerception objects from a heterogeneous collection. | |
| sensor_msgs::msg::PointCloud2 | perception_to_rosmsg (const PointPerception &perception) |
Converts a PointPerception into a sensor_msgs::msg::PointCloud2 message. | |
| 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. | |
Defines data structures and utilities for representing and processing point-based sensor perceptions.
This header provides:
PointPerception: a concrete class for point cloud data.PointPerceptionHandler: a handler for sensor_msgs::msg::LaserScan and sensor_msgs::msg::PointCloud2 messages.PointPerceptionsOpsView: an efficient view-based operator class for processing multiple perceptions (filtering, downsampling, fusion, and collapsing) without duplicating memory.