gtsam_points
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
gtsam_points::PointCloudCPU Struct Reference

Point cloud frame on CPU memory. More...

#include <point_cloud_cpu.hpp>

Inheritance diagram for gtsam_points::PointCloudCPU:
Inheritance graph
[legend]
Collaboration diagram for gtsam_points::PointCloudCPU:
Collaboration graph
[legend]

Public Types

using Ptr = std::shared_ptr< PointCloudCPU >
 
using ConstPtr = std::shared_ptr< const PointCloudCPU >
 
- Public Types inherited from gtsam_points::PointCloud
using Ptr = std::shared_ptr< PointCloud >
 
using ConstPtr = std::shared_ptr< const PointCloud >
 

Public Member Functions

template<typename T , int D>
 PointCloudCPU (const Eigen::Matrix< T, D, 1 > *points, int num_points)
 Constructor.
 
template<typename T , int D, typename Alloc >
 PointCloudCPU (const std::vector< Eigen::Matrix< T, D, 1 >, Alloc > &points)
 Constructor.
 
 PointCloudCPU (const PointCloudCPU &points)=delete
 
PointCloudCPUoperator= (PointCloudCPU const &)=delete
 
template<typename T >
void add_times (const T *times, int num_points)
 
template<typename T >
void add_times (const std::vector< T > &times)
 
template<typename T , int D>
void add_points (const Eigen::Matrix< T, D, 1 > *points, int num_points)
 
template<typename T , int D, typename Alloc >
void add_points (const std::vector< Eigen::Matrix< T, D, 1 >, Alloc > &points)
 
template<typename T , int D>
void add_normals (const Eigen::Matrix< T, D, 1 > *normals, int num_points)
 
template<typename T , int D, typename Alloc >
void add_normals (const std::vector< Eigen::Matrix< T, D, 1 >, Alloc > &normals)
 
template<typename T , int D>
void add_covs (const Eigen::Matrix< T, D, D > *covs, int num_points)
 
template<typename T , int D, typename Alloc >
void add_covs (const std::vector< Eigen::Matrix< T, D, D >, Alloc > &covs)
 
template<typename T >
void add_intensities (const T *intensities, int num_points)
 
template<typename T >
void add_intensities (const std::vector< T > &intensities)
 
template<typename T >
void add_aux_attribute (const std::string &attrib_name, const T *values, int num_points)
 
template<typename T , typename Alloc >
void add_aux_attribute (const std::string &attrib_name, const std::vector< T, Alloc > &values)
 
size_t memory_usage () const
 Memory usage in bytes.
 
- Public Member Functions inherited from gtsam_points::PointCloud
 PointCloud (const PointCloud &)=delete
 
PointCloudoperator= (PointCloud const &)=delete
 
size_t size () const
 Number of points.
 
bool has_times () const
 Check if the point cloud has per-point timestamps.
 
bool has_points () const
 Check if the point cloud has points.
 
bool has_normals () const
 Check if the point cloud has point normals.
 
bool has_covs () const
 Check if the point cloud has point covariances.
 
bool has_intensities () const
 Check if the point cloud has point intensities.
 
bool check_times () const
 Warn if the point cloud doesn't have times.
 
bool check_points () const
 Warn if the point cloud doesn't have points.
 
bool check_normals () const
 Warn if the point cloud doesn't have normals.
 
bool check_covs () const
 Warn if the point cloud doesn't have covs.
 
bool check_intensities () const
 Warn if the point cloud doesn't have intensities.
 
bool has_times_gpu () const
 Check if the point cloud has per-point timestamps on GPU.
 
bool has_points_gpu () const
 Check if the point cloud has points on GPU.
 
bool has_normals_gpu () const
 Check if the point cloud has point normals on GPU.
 
bool has_covs_gpu () const
 Check if the point cloud has point covariances on GPU.
 
bool has_intensities_gpu () const
 Check if the point cloud has point intensities on GPU.
 
bool check_times_gpu () const
 Warn if the point cloud doesn't have times on GPU.
 
bool check_points_gpu () const
 Warn if the point cloud doesn't have points on GPU.
 
bool check_normals_gpu () const
 Warn if the point cloud doesn't have normals on GPU.
 
bool check_covs_gpu () const
 Warn if the point cloud doesn't have covs on GPU.
 
bool check_intensities_gpu () const
 Warn if the point cloud doesn't have intensities on GPU.
 
template<typename T >
const T * aux_attribute (const std::string &attrib) const
 Get the pointer to an aux attribute.
 
void save (const std::string &path) const
 Save the point cloud data.
 
void save_compact (const std::string &path) const
 Save the point cloud data with a compact representation without unnecessary fields (e.g., the last element of homogeneous coordinates).
 

Static Public Member Functions

static PointCloudCPU::Ptr clone (const PointCloud &points)
 Deep copy.
 
static PointCloudCPU::Ptr load (const std::string &path)
 

Public Attributes

std::vector< double > times_storage
 
std::vector< Eigen::Vector4d > points_storage
 
std::vector< Eigen::Vector4d > normals_storage
 
std::vector< Eigen::Matrix4d > covs_storage
 
std::vector< double > intensities_storage
 
std::unordered_map< std::string, std::shared_ptr< void > > aux_attributes_storage
 
- Public Attributes inherited from gtsam_points::PointCloud
size_t num_points
 Number of points.
 
double * times
 Per-point timestamp w.r.t. the first point (should be sorted)
 
Eigen::Vector4d * points
 Point coordinates (x, y, z, 1)
 
Eigen::Vector4d * normals
 Point normals (nx, ny, nz, 0)
 
Eigen::Matrix4d * covs
 Point covariances cov(3, 3) = 0.
 
double * intensities
 Point intensities.
 
std::unordered_map< std::string, std::pair< size_t, void * > > aux_attributes
 Aux attributes <attribute_name, pair<element_size, data_ptr>>
 
float * times_gpu
 Per-point timestamp on GPU.
 
Eigen::Vector3f * points_gpu
 Point coordinates on GPU.
 
Eigen::Vector3f * normals_gpu
 Point normals on GPU.
 
Eigen::Matrix3f * covs_gpu
 Point covariances on GPU.
 
float * intensities_gpu
 Point intensities on GPU.
 

Detailed Description

Point cloud frame on CPU memory.

Constructor & Destructor Documentation

◆ PointCloudCPU() [1/2]

template<typename T , int D>
gtsam_points::PointCloudCPU::PointCloudCPU ( const Eigen::Matrix< T, D, 1 > *  points,
int  num_points 
)

Constructor.

Parameters
pointsPointer to point data
num_pointsNumber of points

◆ PointCloudCPU() [2/2]

template<typename T , int D, typename Alloc >
gtsam_points::PointCloudCPU::PointCloudCPU ( const std::vector< Eigen::Matrix< T, D, 1 >, Alloc > &  points)
inline

Constructor.

Parameters
pointsPoints

The documentation for this struct was generated from the following file: