base
PoseWithCovariance.hpp
Go to the documentation of this file.
1 #ifndef BASE_SAMPLES_POSE_WITH_COVARIANCE_HPP
2 #define BASE_SAMPLES_POSE_WITH_COVARIANCE_HPP
3 
4 #include <string>
5 #include <base/Time.hpp>
6 #include <base/TransformWithCovariance.hpp>
7 #include <base/samples/RigidBodyState.hpp>
8 
9 namespace base { namespace samples {
10 
24 {
25 public:
28 
30  std::string frame_id;
31 
33  std::string object_frame_id;
34 
37 
38 public:
41 
43  explicit PoseWithCovariance(const base::TransformWithCovariance& transform);
44 
47 
55 
57  void setTransform(const base::TransformWithCovariance& transform);
58 
60  void setTransform(const Eigen::Affine3d& transform);
61 
64 
67 
70 
76 };
77 
78 }}
79 
80 #endif
base::Time time
Definition: PoseWithCovariance.hpp:27
void setTransform(const base::TransformWithCovariance &transform)
Definition: PoseWithCovariance.cpp:34
const base::TransformWithCovariance & getTransformWithCovariance() const
Definition: PoseWithCovariance.cpp:44
std::string object_frame_id
Definition: PoseWithCovariance.hpp:33
Eigen::Affine3d getTransform() const
Definition: PoseWithCovariance.cpp:49
const base::TransformWithCovariance::Covariance & getCovariance() const
Definition: PoseWithCovariance.cpp:54
base::Matrix6d Covariance
Definition: TransformWithCovariance.hpp:24
Definition: Time.hpp:11
base::samples::RigidBodyState toRigidBodyState() const
Definition: PoseWithCovariance.cpp:59
PoseWithCovariance operator*(const PoseWithCovariance &pose) const
Definition: PoseWithCovariance.cpp:23
PoseWithCovariance()
Definition: PoseWithCovariance.cpp:5
Definition: LinearAngular6DCommand.hpp:8
Definition: TransformWithCovariance.hpp:20
std::string frame_id
Definition: PoseWithCovariance.hpp:30
Definition: RigidBodyState.hpp:31
Definition: PoseWithCovariance.hpp:23
Eigen::Transform< double, 3, Eigen::Affine > Affine3d
Definition: Eigen.cpp:20
base::TransformWithCovariance transform
Definition: PoseWithCovariance.hpp:36