Template Class SparsePointCloud3
Defined in File sparse_point_cloud.hpp
Inheritance Relationships
Base Type
public beluga::BaseSparsePointCloud< SparsePointCloud3< T > >
Class Documentation
-
template<typename T, bool Strict = true>
class SparsePointCloud3 : public beluga::BaseSparsePointCloud<SparsePointCloud3<T>> 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:
T – Scalar type for point coordinates. Must be floating point.
Strict – If 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.
Public Functions
Constructor.
- Parameters:
cloud – Point cloud message.
origin – Point cloud frame origin in the filter frame.
- Throws:
std::invalid_argument – if
cloud
does not meet expectations.
-
inline std::size_t size() const
Get the point cloud size.
-
inline const auto &origin() const
Get the point cloud frame origin in the filter frame.
-
inline auto points() const
Get the range of cartesian points in the point cloud.