Template Class PointCloud3

Inheritance Relationships

Base Type

  • public beluga::BasePointCloud< PointCloud3< T > >

Class Documentation

template<typename T>
class PointCloud3 : public beluga::BasePointCloud<PointCloud3<T>>

Thin wrapper type for 3D sensor_msgs/PointCloud2 messages.

Public Types

using Scalar = T

PointCloud type.

Public Functions

inline explicit PointCloud3(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::Matrix3X>.