|
|
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... | |
A point cloud which keeps track of its reference coordinate frame and allows changing frames using armarx::FramedPose.
Definition at line 56 of file PointCloudFilter.h.
| using PointCloudPtrT = typename PointCloudT::Ptr |
Definition at line 40 of file FramedPointCloud.h.
| using PointCloudT = pcl::PointCloud<PointT> |
Definition at line 39 of file FramedPointCloud.h.
| using PointT = _PointT |
Definition at line 38 of file FramedPointCloud.h.
|
default |
Construct an empty point cloud in global frame.
|
inline |
Construct an empty point cloud residing in given frame.
Definition at line 47 of file FramedPointCloud.h.
|
inline |
Construct a framed point cloud managing given point cloud in global frame.
Definition at line 52 of file FramedPointCloud.h.
|
inline |
Construct a framed point cloud managing given point cloud residing in given frame.
Definition at line 57 of file FramedPointCloud.h.
|
inline |
Transform the point cloud from the current frame to the new frame using the given reference robot.
Definition at line 97 of file FramedPointCloud.h.
Here is the caller graph for this function:
|
inline |
Get the current frame.
Definition at line 64 of file FramedPointCloud.h.
Here is the caller graph for this function:
|
inline |
Get the current pose as FramedPose.
Definition at line 77 of file FramedPointCloud.h.
Here is the call graph for this function:
Here is the caller graph for this function:
|
inline |
|
inline |
Get the current global pose.
Definition at line 90 of file FramedPointCloud.h.
Here is the call graph for this function:
Here is the caller graph for this function:
|
inline |
|
inline |
Definition at line 104 of file FramedPointCloud.h.
Here is the call graph for this function:
Here is the caller graph for this function:| PointCloudPtrT cloud {new PointCloudT()} |
The point cloud.
Definition at line 111 of file FramedPointCloud.h.