base
Public Member Functions | Public Attributes | List of all members
base::samples::PoseWithCovariance Class Reference

#include <PoseWithCovariance.hpp>

Public Member Functions

 PoseWithCovariance ()
 
 PoseWithCovariance (const base::TransformWithCovariance &transform)
 
 PoseWithCovariance (const base::samples::RigidBodyState &rbs)
 
PoseWithCovariance operator* (const PoseWithCovariance &pose) const
 
void setTransform (const base::TransformWithCovariance &transform)
 
void setTransform (const Eigen::Affine3d &transform)
 
const base::TransformWithCovariancegetTransformWithCovariance () const
 
Eigen::Affine3d getTransform () const
 
const base::TransformWithCovariance::CovariancegetCovariance () const
 
base::samples::RigidBodyState toRigidBodyState () const
 

Public Attributes

base::Time time
 
std::string frame_id
 
std::string object_frame_id
 
base::TransformWithCovariance transform
 

Detailed Description

Represents a 3D pose with uncertainty of the frame 'object_frame_id' in the frame 'frame_id'. A frame ID shall be globally unique and correspond to a coordinate system. Following the Rock's conventions coordinate systems are right handed with X forward, Y left and Z up.

The pose $ ^{reference}_{object}T $ in this structure transforms a vector $ v_{object} $ from the object frame to the reference frame: $ v_{reference} = ^{reference}_{object}T \cdot v_{object} $ Example of a transformation chain: $ ^{world}_{sensor}T = ^{world}_{body}T \cdot ^{body}_{sensor}T $

Constructor & Destructor Documentation

◆ PoseWithCovariance() [1/3]

base::samples::PoseWithCovariance::PoseWithCovariance ( )

Default constructor

◆ PoseWithCovariance() [2/3]

base::samples::PoseWithCovariance::PoseWithCovariance ( const base::TransformWithCovariance transform)
explicit

Initializes type from a TransformWithCovariance

◆ PoseWithCovariance() [3/3]

base::samples::PoseWithCovariance::PoseWithCovariance ( const base::samples::RigidBodyState rbs)
explicit

Initializes type from a RigidBodyState

Member Function Documentation

◆ getCovariance()

const TransformWithCovariance::Covariance & base::samples::PoseWithCovariance::getCovariance ( ) const

Returns the 6x6 covariance matrix

◆ getTransform()

Eigen::Affine3d base::samples::PoseWithCovariance::getTransform ( ) const

Returns transformation as Eigen::Affine3d

◆ getTransformWithCovariance()

const TransformWithCovariance & base::samples::PoseWithCovariance::getTransformWithCovariance ( ) const

Returns transformation as TransformWithCovariance

◆ operator*()

PoseWithCovariance base::samples::PoseWithCovariance::operator* ( const PoseWithCovariance pose) const

Performs a composition of this pose with a given pose. The result is another pose with result = this * pose. The frame ID's will be set accordingly (e.g. a_in_b = c_in_b * a_in_c). Note that this method doesn't check if the composition is frame wise valid.

◆ setTransform() [1/2]

void base::samples::PoseWithCovariance::setTransform ( const base::TransformWithCovariance transform)

Sets the transformation as TransformWithCovariance

◆ setTransform() [2/2]

void base::samples::PoseWithCovariance::setTransform ( const Eigen::Affine3d transform)

Sets the transformation as Eigen::Affine3d

◆ toRigidBodyState()

RigidBodyState base::samples::PoseWithCovariance::toRigidBodyState ( ) const

Converts the type to a RigidBodyState. Note that the cross-covariances will be lost, since the RigidBodyState does not store them.

Member Data Documentation

◆ frame_id

std::string base::samples::PoseWithCovariance::frame_id

ID of the reference frame where this pose is expressed in

◆ object_frame_id

std::string base::samples::PoseWithCovariance::object_frame_id

ID of the object frame defined by this pose

◆ time

base::Time base::samples::PoseWithCovariance::time

Reference timestamp of the pose sample

◆ transform

base::TransformWithCovariance base::samples::PoseWithCovariance::transform

Pose of the object frame in the reference frame


The documentation for this class was generated from the following files: