Template Class SparsePointCloud3

Inheritance Relationships

Base Type

  • public beluga::BaseSparsePointCloud< SparsePointCloud3< T > >

Class Documentation

template<typename T>
class SparsePointCloud3 : public beluga::BaseSparsePointCloud<SparsePointCloud3<T>>

Thin wrapper type for 3D sensor_msgs/PointCloud2 messages. Assumes an XYZ… type message. XYZ datafields must be the same type (float or double). Other datafields can be different types.

Public Types

using Scalar = T

PointCloud type.

Public Functions

inline explicit SparsePointCloud3(beluga_ros::msg::PointCloud2ConstSharedPtr cloud, Sophus::SE3d origin = Sophus::SE3d())

Check type is float or double.

Constructor.

Parameters:
  • cloud – Point cloud message.

  • origin – Point cloud frame origin in the filter frame.

inline const auto &origin() const

Get the point cloud frame origin in the filter frame.

inline auto points() const

Get the unorganized 3D point collection as an Eigen Map<Eigen::Vector3>.