PointCloud3< T > Class Template Reference

PointCloud3&lt; T &gt; Class Template Reference#

Beluga ROS: beluga_ros::PointCloud3< T > Class Template Reference
Beluga ROS
beluga_ros::PointCloud3< T > Class Template Reference

Thin wrapper type for 3D sensor_msgs/PointCloud2 messages. More...

#include <point_cloud.hpp>

Inheritance diagram for beluga_ros::PointCloud3< T >:
[legend]
Collaboration diagram for beluga_ros::PointCloud3< T >:
[legend]

Public Types

using Scalar = T
 PointCloud type.
 

Public Member Functions

 PointCloud3 (beluga_ros::msg::PointCloud2ConstSharedPtr cloud, Sophus::SE3d origin=Sophus::SE3d())
 Check type is float or double. More...
 
const auto & origin () const
 Get the point cloud frame origin in the filter frame.
 
auto points () const
 Get the unorganized 3D point collection as an Eigen Map<Eigen::Matrix3X>.
 

Detailed Description

template<typename T>
class beluga_ros::PointCloud3< T >

Thin wrapper type for 3D sensor_msgs/PointCloud2 messages.

Constructor & Destructor Documentation

◆ PointCloud3()

template<typename T >
beluga_ros::PointCloud3< T >::PointCloud3 ( beluga_ros::msg::PointCloud2ConstSharedPtr  cloud,
Sophus::SE3d  origin = Sophus::SE3d() 
)
inlineexplicit

Check type is float or double.

Constructor.

Parameters
cloudPoint cloud message.
originPoint cloud frame origin in the filter frame.

The documentation for this class was generated from the following file:
  • /home/runner/work/beluga/beluga/beluga_ros/include/beluga_ros/point_cloud.hpp