PointCloud3< T, Strict > Class Template Reference

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

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

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

#include <point_cloud.hpp>

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

Public Types

using Scalar = T
 Expected PointCloud2 fields type.
 

Public Member Functions

 PointCloud3 (sensor_msgs::msg::PointCloud2::ConstSharedPtr cloud, Sophus::SE3d origin=Sophus::SE3d())
 
const auto & origin () const
 Get the point cloud frame origin in the filter frame.
 
auto points () const
 Get cartesian points in the point cloud as a matrix.
 

Detailed Description

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

Thin wrapper type for 3D sensor_msgs/PointCloud2 messages with dense layouts.

The layout of the point cloud message must include exactly three (3) fields: x, y, and z, all of the same floating point datatype, representing cartesian coordinates for 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

◆ PointCloud3()

template<typename T , bool Strict = true>
beluga_ros::PointCloud3< T, Strict >::PointCloud3 ( sensor_msgs::msg::PointCloud2::ConstSharedPtr  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:
  • /home/runner/work/beluga/beluga/beluga_ros/include/beluga_ros/point_cloud.hpp