#include <Eigen/Core>
#include <pcl/point_cloud.h>
#include <pcl/common/transforms.h>
#include <VirtualRobot/Robot.h>
#include <RobotAPI/libraries/core/FramedPose.h>
Go to the source code of this file.
|
template<class PointCloudPtrT > |
| FramedPointCloud (PointCloudPtrT pointCloudPtr) -> FramedPointCloud< typename PointCloudPtrT::element_type::PointType > |
|
template<class PointCloudPtrT > |
| FramedPointCloud (PointCloudPtrT pointCloudPtr, const std::string &frameName) -> FramedPointCloud< typename PointCloudPtrT::element_type::PointType > |
|
template<class PointT > |
void | transformPointCloudFromTo (const pcl::PointCloud< PointT > &sourceCloud, pcl::PointCloud< PointT > &targetCloud, const std::string &sourceFrame, const std::string &targetFrame, const VirtualRobot::RobotPtr &robot) |
| Transform a point cloud from a robot frame to another. More...
|
|