Go to the documentation of this file.
5 #include <pcl/common/transforms.h>
6 #include <pcl/point_cloud.h>
8 #include <VirtualRobot/Robot.h>
23 template <
class Po
intT>
25 pcl::PointCloud<PointT>& targetCloud,
26 const std::string& sourceFrame,
27 const std::string& targetFrame,
34 template <
class _Po
intT>
58 cloud(pointCloudPtr), frame(frameName)
99 transformPointCloudFromTo<PointT>(*
cloud, *
cloud, frame, newFrame, robot);
100 this->frame = newFrame;
121 template <
class Po
intCloudPtrT>
123 -> FramedPointCloud<typename PointCloudPtrT::element_type::PointType>;
125 template <
class Po
intCloudPtrT>
126 FramedPointCloud(PointCloudPtrT pointCloudPtr,
const std::string& frameName)
127 -> FramedPointCloud<typename PointCloudPtrT::element_type::PointType>;
131 template <
class Po
intT>
134 pcl::PointCloud<PointT>& targetCloud,
135 const std::string& sourceFrame,
136 const std::string& targetFrame,
139 if (sourceFrame != targetFrame)
144 pcl::transformPointCloud(sourceCloud, targetCloud, sourceToTarget);
armarx::FramedPose getFramedPose(const std::string &agentName) const
Get the current pose as FramedPose.
const VariantTypeId FramedPose
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.
MatrixXX< 4, 4, float > Matrix4f
const std::string GlobalFrame
Eigen::Matrix4f getGlobalPose(const VirtualRobot::RobotPtr &robot) const
Get the current global pose.
armarx::FramedPose getFramedPose(const VirtualRobot::RobotPtr &robot) const
void setFrameWithoutTransformation(const std::string &f)
std::string getFrame() const
Get the current frame.
void Identity(MatrixXX< N, N, T > *a)
Eigen::Matrix4f toGlobalEigen(const SharedRobotInterfacePrx &referenceRobot) const
FramedPointCloud()=default
Construct an empty point cloud in global frame.
PointCloudPtrT cloud
The point cloud.
virtual Eigen::Matrix4f toEigen() const
FramedPointCloud(const std::string &frameName)
Construct an empty point cloud residing in given frame.
typename PointCloudT::Ptr PointCloudPtrT
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.
pcl::PointCloud< PointT > PointCloudT
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT >>
Convenience function (with less typing) to transform a container of type InputT into the same contain...
FramedPointCloud(PointCloudPtrT pointCloudPtr)
Construct a framed point cloud managing given point cloud in global frame.
void transformBy(const Eigen::Matrix4f &transform)
FramedPointCloud(PointCloudPtrT pointCloudPtr) -> FramedPointCloud< typename PointCloudPtrT::element_type::PointType >
FramedPointCloud(PointCloudPtrT pointCloudPtr, const std::string &frameName)
Construct a framed point cloud managing given point cloud residing in given frame.
void changeFrame(const SharedRobotInterfacePrx &referenceRobot, const std::string &newFrame)
std::shared_ptr< class Robot > RobotPtr