FramedPointCloud< _PointT > Class Template Reference

A point cloud which keeps track of its reference coordinate frame and allows changing frames using armarx::FramedPose. More...

#include <VisionX/components/pointcloud_processor/PointCloudFilter/PointCloudFilter.h>

Public Types

using PointCloudPtrT = typename PointCloudT::Ptr
 
using PointCloudT = pcl::PointCloud< PointT >
 
using PointT = _PointT
 

Public Member Functions

void changeFrame (const std::string &newFrame, const VirtualRobot::RobotPtr &robot)
 Transform the point cloud from the current frame to the new frame using the given reference robot. More...
 
 FramedPointCloud ()=default
 Construct an empty point cloud in global frame. More...
 
 FramedPointCloud (const std::string &frameName)
 Construct an empty point cloud residing in given frame. More...
 
 FramedPointCloud (PointCloudPtrT pointCloudPtr)
 Construct a framed point cloud managing given point cloud in global frame. More...
 
 FramedPointCloud (PointCloudPtrT pointCloudPtr, const std::string &frameName)
 Construct a framed point cloud managing given point cloud residing in given frame. More...
 
std::string getFrame () const
 Get the current frame. More...
 
armarx::FramedPose getFramedPose (const std::string &agentName) const
 Get the current pose as FramedPose. More...
 
armarx::FramedPose getFramedPose (const VirtualRobot::RobotPtr &robot) const
 
Eigen::Matrix4f getGlobalPose (const VirtualRobot::RobotPtr &robot) const
 Get the current global pose. More...
 
void setFrameWithoutTransformation (const std::string &f)
 
void transformBy (const Eigen::Matrix4f &transform)
 

Public Attributes

PointCloudPtrT cloud { new PointCloudT() }
 The point cloud. More...
 

Detailed Description

template<class _PointT>
class visionx::FramedPointCloud< _PointT >

A point cloud which keeps track of its reference coordinate frame and allows changing frames using armarx::FramedPose.

Definition at line 59 of file PointCloudFilter.h.

Member Typedef Documentation

◆ PointCloudPtrT

using PointCloudPtrT = typename PointCloudT::Ptr

Definition at line 42 of file FramedPointCloud.h.

◆ PointCloudT

using PointCloudT = pcl::PointCloud<PointT>

Definition at line 41 of file FramedPointCloud.h.

◆ PointT

using PointT = _PointT

Definition at line 40 of file FramedPointCloud.h.

Constructor & Destructor Documentation

◆ FramedPointCloud() [1/4]

FramedPointCloud ( )
default

Construct an empty point cloud in global frame.

◆ FramedPointCloud() [2/4]

FramedPointCloud ( const std::string &  frameName)
inline

Construct an empty point cloud residing in given frame.

Definition at line 50 of file FramedPointCloud.h.

◆ FramedPointCloud() [3/4]

FramedPointCloud ( PointCloudPtrT  pointCloudPtr)
inline

Construct a framed point cloud managing given point cloud in global frame.

Definition at line 55 of file FramedPointCloud.h.

◆ FramedPointCloud() [4/4]

FramedPointCloud ( PointCloudPtrT  pointCloudPtr,
const std::string &  frameName 
)
inline

Construct a framed point cloud managing given point cloud residing in given frame.

Definition at line 60 of file FramedPointCloud.h.

Member Function Documentation

◆ changeFrame()

void changeFrame ( const std::string &  newFrame,
const VirtualRobot::RobotPtr robot 
)
inline

Transform the point cloud from the current frame to the new frame using the given reference robot.

Definition at line 92 of file FramedPointCloud.h.

+ Here is the caller graph for this function:

◆ getFrame()

std::string getFrame ( ) const
inline

Get the current frame.

Definition at line 66 of file FramedPointCloud.h.

+ Here is the caller graph for this function:

◆ getFramedPose() [1/2]

armarx::FramedPose getFramedPose ( const std::string &  agentName) const
inline

Get the current pose as FramedPose.

Definition at line 76 of file FramedPointCloud.h.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ getFramedPose() [2/2]

armarx::FramedPose getFramedPose ( const VirtualRobot::RobotPtr robot) const
inline

Definition at line 80 of file FramedPointCloud.h.

+ Here is the call graph for this function:

◆ getGlobalPose()

Eigen::Matrix4f getGlobalPose ( const VirtualRobot::RobotPtr robot) const
inline

Get the current global pose.

Definition at line 86 of file FramedPointCloud.h.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ setFrameWithoutTransformation()

void setFrameWithoutTransformation ( const std::string &  f)
inline

Definition at line 70 of file FramedPointCloud.h.

+ Here is the caller graph for this function:

◆ transformBy()

void transformBy ( const Eigen::Matrix4f &  transform)
inline

Definition at line 98 of file FramedPointCloud.h.

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

Member Data Documentation

◆ cloud

PointCloudPtrT cloud { new PointCloudT() }

The point cloud.

Definition at line 105 of file FramedPointCloud.h.


The documentation for this class was generated from the following files: