SparsePointCloud3< T, Strict > Class Template Reference

SparsePointCloud3&lt; T, Strict &gt; Class Template Reference#

Beluga ROS: beluga_ros::SparsePointCloud3< T, Strict > Class Template Reference
Beluga ROS
beluga_ros::SparsePointCloud3< T, Strict > Class Template Reference

Thin wrapper for 3D sensor_msgs/PointCloud2 messages with potentially sparse layouts. More...

#include <sparse_point_cloud.hpp>

Inheritance diagram for beluga_ros::SparsePointCloud3< T, Strict >:
[legend]
Collaboration diagram for beluga_ros::SparsePointCloud3< T, Strict >:
[legend]

Public Types

using Scalar = T
 Expected PointCloud2 fields type.
 

Public Member Functions

 SparsePointCloud3 (beluga_ros::msg::PointCloud2ConstSharedPtr cloud, Sophus::SE3d origin=Sophus::SE3d())
 
std::size_t size () const
 Get the point cloud size.
 
const auto & origin () const
 Get the point cloud frame origin in the filter frame.
 
auto points () const
 Get the range of cartesian points in the point cloud.
 

Detailed Description

template<typename T, bool Strict = true>
class beluga_ros::SparsePointCloud3< T, Strict >

Thin wrapper for 3D sensor_msgs/PointCloud2 messages with potentially sparse layouts.

The layout of the point cloud message is only required to include at least three (3) fields: x, y, and z, all of the same floating point datatype, representing cartesian coordinates for each point. These fields must be at the beginning of each point.

Template Parameters
TScalar type for point coordinates. Must be floating point.
StrictIf true, xyz fields' datatypes must match the expected scalar type or the wrapper will throw on construction. If false, the wrapper will cast as necessary.

Constructor & Destructor Documentation

◆ SparsePointCloud3()

template<typename T , bool Strict = true>
beluga_ros::SparsePointCloud3< T, Strict >::SparsePointCloud3 ( beluga_ros::msg::PointCloud2ConstSharedPtr  cloud,
Sophus::SE3d  origin = Sophus::SE3d() 
)
inlineexplicit

Constructor.

Parameters
cloudPoint cloud message.
originPoint cloud frame origin in the filter frame.
Exceptions
std::invalid_argumentif cloud does not meet expectations.

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