FramedPointCloud.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <Eigen/Core>
4 
5 #include <pcl/common/transforms.h>
6 #include <pcl/point_cloud.h>
7 
8 #include <VirtualRobot/Robot.h>
9 
11 
12 namespace visionx
13 {
14 
15  /**
16  * @brief Transform a point cloud from a robot frame to another.
17  * @param sourceCloud The source point cloud.
18  * @param targetCloud The target point cloud (may be same as `sourceCloud`).
19  * @param sourceFrame The current frame of `sourceCloud`.
20  * @param targetFrame The current frame to transform to.
21  * @param robot The reference robot to use for transformation.
22  */
23  template <class PointT>
24  void transformPointCloudFromTo(const pcl::PointCloud<PointT>& sourceCloud,
25  pcl::PointCloud<PointT>& targetCloud,
26  const std::string& sourceFrame,
27  const std::string& targetFrame,
28  const VirtualRobot::RobotPtr& robot);
29 
30  /**
31  * @brief A point cloud which keeps track of its reference coordinate frame
32  * and allows changing frames using `armarx::FramedPose`.
33  */
34  template <class _PointT>
35  class FramedPointCloud
36  {
37  public:
38  using PointT = _PointT;
39  using PointCloudT = pcl::PointCloud<PointT>;
40  using PointCloudPtrT = typename PointCloudT::Ptr;
41 
42  public:
43  /// Construct an empty point cloud in global frame.
44  FramedPointCloud() = default;
45 
46  /// Construct an empty point cloud residing in given frame.
47  FramedPointCloud(const std::string& frameName) : frame(frameName)
48  {
49  }
50 
51  /// Construct a framed point cloud managing given point cloud in global frame.
52  FramedPointCloud(PointCloudPtrT pointCloudPtr) : cloud(pointCloudPtr)
53  {
54  }
55 
56  /// Construct a framed point cloud managing given point cloud residing in given frame.
57  FramedPointCloud(PointCloudPtrT pointCloudPtr, const std::string& frameName) :
58  cloud(pointCloudPtr), frame(frameName)
59  {
60  }
61 
62  /// Get the current frame.
63  std::string
64  getFrame() const
65  {
66  return frame;
67  }
68 
69  void
70  setFrameWithoutTransformation(const std::string& f)
71  {
72  frame = f;
73  }
74 
75  /// Get the current pose as `FramedPose`.
77  getFramedPose(const std::string& agentName) const
78  {
79  return armarx::FramedPose(Eigen::Matrix4f::Identity(), frame, agentName);
80  }
81 
84  {
85  return getFramedPose(robot->getName());
86  }
87 
88  /// Get the current global pose.
91  {
92  return getFramedPose(robot).toGlobalEigen(robot);
93  }
94 
95  /// Transform the point cloud from the current frame to the new frame using the given reference robot.
96  void
97  changeFrame(const std::string& newFrame, const VirtualRobot::RobotPtr& robot)
98  {
99  transformPointCloudFromTo<PointT>(*cloud, *cloud, frame, newFrame, robot);
100  this->frame = newFrame;
101  }
102 
103  void
105  {
106  pcl::transformPointCloud(*cloud, *cloud, transform);
107  }
108 
109  public:
110  /// The point cloud.
112 
113 
114  private:
115  /// The current frame.
116  std::string frame = armarx::GlobalFrame;
117  };
118 
119 
120  // Template deduction guidelines for PointT from PointCloudPtrT.
121  template <class PointCloudPtrT>
122  FramedPointCloud(PointCloudPtrT pointCloudPtr)
123  -> FramedPointCloud<typename PointCloudPtrT::element_type::PointType>;
124 
125  template <class PointCloudPtrT>
126  FramedPointCloud(PointCloudPtrT pointCloudPtr, const std::string& frameName)
127  -> FramedPointCloud<typename PointCloudPtrT::element_type::PointType>;
128 
129 } // namespace visionx
130 
131 template <class PointT>
132 void
133 visionx::transformPointCloudFromTo(const pcl::PointCloud<PointT>& sourceCloud,
134  pcl::PointCloud<PointT>& targetCloud,
135  const std::string& sourceFrame,
136  const std::string& targetFrame,
137  const VirtualRobot::RobotPtr& robot)
138 {
139  if (sourceFrame != targetFrame)
140  {
141  armarx::FramedPose framedPose(Eigen::Matrix4f::Identity(), sourceFrame, robot->getName());
142  framedPose.changeFrame(robot, targetFrame);
143  const Eigen::Matrix4f sourceToTarget = framedPose.toEigen();
144  pcl::transformPointCloud(sourceCloud, targetCloud, sourceToTarget);
145  }
146 }
visionx::FramedPointCloud::getFramedPose
armarx::FramedPose getFramedPose(const std::string &agentName) const
Get the current pose as FramedPose.
Definition: FramedPointCloud.h:77
visionx
ArmarX headers.
Definition: OpenPoseStressTest.h:38
armarx::FramedPose
The FramedPose class.
Definition: FramedPose.h:280
armarx::VariantType::FramedPose
const VariantTypeId FramedPose
Definition: FramedPose.h:36
visionx::transformPointCloudFromTo
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.
Definition: FramedPointCloud.h:133
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:650
armarx::GlobalFrame
const std::string GlobalFrame
Definition: FramedPose.h:65
visionx::FramedPointCloud::getGlobalPose
Eigen::Matrix4f getGlobalPose(const VirtualRobot::RobotPtr &robot) const
Get the current global pose.
Definition: FramedPointCloud.h:90
visionx::FramedPointCloud::getFramedPose
armarx::FramedPose getFramedPose(const VirtualRobot::RobotPtr &robot) const
Definition: FramedPointCloud.h:83
visionx::FramedPointCloud::setFrameWithoutTransformation
void setFrameWithoutTransformation(const std::string &f)
Definition: FramedPointCloud.h:70
visionx::FramedPointCloud::PointT
_PointT PointT
Definition: FramedPointCloud.h:38
visionx::FramedPointCloud::getFrame
std::string getFrame() const
Get the current frame.
Definition: FramedPointCloud.h:64
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:570
armarx::FramedPose::toGlobalEigen
Eigen::Matrix4f toGlobalEigen(const SharedRobotInterfacePrx &referenceRobot) const
Definition: FramedPose.cpp:598
FramedPose.h
visionx::FramedPointCloud::FramedPointCloud
FramedPointCloud()=default
Construct an empty point cloud in global frame.
visionx::FramedPointCloud::cloud
PointCloudPtrT cloud
The point cloud.
Definition: FramedPointCloud.h:111
armarx::Pose::toEigen
virtual Eigen::Matrix4f toEigen() const
Definition: Pose.cpp:334
visionx::FramedPointCloud::FramedPointCloud
FramedPointCloud(const std::string &frameName)
Construct an empty point cloud residing in given frame.
Definition: FramedPointCloud.h:47
visionx::FramedPointCloud::PointCloudPtrT
typename PointCloudT::Ptr PointCloudPtrT
Definition: FramedPointCloud.h:40
visionx::FramedPointCloud::changeFrame
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.
Definition: FramedPointCloud.h:97
visionx::FramedPointCloud::PointCloudT
pcl::PointCloud< PointT > PointCloudT
Definition: FramedPointCloud.h:39
armarx::transform
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...
Definition: algorithm.h:351
visionx::FramedPointCloud::FramedPointCloud
FramedPointCloud(PointCloudPtrT pointCloudPtr)
Construct a framed point cloud managing given point cloud in global frame.
Definition: FramedPointCloud.h:52
visionx::FramedPointCloud::transformBy
void transformBy(const Eigen::Matrix4f &transform)
Definition: FramedPointCloud.h:104
visionx::FramedPointCloud
FramedPointCloud(PointCloudPtrT pointCloudPtr) -> FramedPointCloud< typename PointCloudPtrT::element_type::PointType >
visionx::FramedPointCloud::FramedPointCloud
FramedPointCloud(PointCloudPtrT pointCloudPtr, const std::string &frameName)
Construct a framed point cloud managing given point cloud residing in given frame.
Definition: FramedPointCloud.h:57
armarx::FramedPose::changeFrame
void changeFrame(const SharedRobotInterfacePrx &referenceRobot, const std::string &newFrame)
Definition: FramedPose.cpp:469
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:19