Pose.h
Go to the documentation of this file.
1 
18 #pragma once
19 
20 // Global includes
21 #include <cmath>
22 #include <vector>
23 
24 // Package includes
25 #include <Eigen/Core>
26 #include <Eigen/Geometry>
27 
28 #include <boost/shared_ptr.hpp>
29 
30 #include <asr_msgs/AsrObject.h>
31 
32 #include <geometry_msgs/Pose.h>
33 
34 #include <trainer/source/Object.h>
35 
36 namespace ResourcesForPsm {
37 
44  class Pose {
45  public:
46 
50  Pose();
51 
57  Pose(const asr_msgs::AsrObject pObject);
58 
64  Pose(const geometry_msgs::Pose pPose);
65 
71  Pose(const boost::shared_ptr<SceneModel::Object> pObject);
72 
76  ~Pose();
77 
84  void convertPoseIntoFrame(const boost::shared_ptr<Pose>& pFrame, boost::shared_ptr<Pose>& pResult);
85 
89  Eigen::Vector3d getPosition();
90 
94  Eigen::Quaternion<double> getOrientation();
95 
96  private:
97 
101  boost::shared_ptr<Eigen::Vector3d> mPosition;
102 
106  boost::shared_ptr<Eigen::Quaternion<double> > mOrientation;
107  };
108 }
Eigen::Quaternion< double > getOrientation()
Definition: Pose.cpp:92
boost::shared_ptr< Eigen::Vector3d > mPosition
Definition: Pose.h:101
Eigen::Vector3d getPosition()
Definition: Pose.cpp:87
void convertPoseIntoFrame(const boost::shared_ptr< Pose > &pFrame, boost::shared_ptr< Pose > &pResult)
Definition: Pose.cpp:73
boost::shared_ptr< Eigen::Quaternion< double > > mOrientation
Definition: Pose.h:106


asr_resources_for_psm
Author(s): Gehrung Joachim, Meißner Pascal
autogenerated on Fri Nov 8 2019 03:42:23