Control Libraries 6.3.4
Loading...
Searching...
No Matches
Public Member Functions | Friends | List of all members
state_representation::DualQuaternionPose Class Reference

Class to represent a Pose in Dual Quaternion space. More...

#include <DualQuaternionPose.hpp>

Inheritance diagram for state_representation::DualQuaternionPose:
state_representation::DualQuaternionState state_representation::SpatialState state_representation::State

Public Member Functions

 DualQuaternionPose (const std::string &name, const std::string &reference="world")
 Constructor with name and reference frame provided. More...
 
 DualQuaternionPose (const DualQuaternionPose &state)
 Copy constructor of a DualQuaternionPose. More...
 
 DualQuaternionPose (const DualQuaternionState &state)
 Copy constructor of a DualQuaternionPose from a DualQuaternionState. More...
 
 DualQuaternionPose (const std::string &name, const Eigen::Vector3d &position, const Eigen::Quaterniond &rotation, const std::string &reference="world")
 Construct a DualQuaternionPose from a position given as a vector of coordinates and a quaternion. More...
 
const Eigen::Vector3d get_position () const
 Getter of the position attribute. More...
 
const Eigen::Quaterniond & get_orientation () const
 Getter of the orientation from the primary. More...
 
void set_orientation (const Eigen::Quaterniond &orientation)
 Setter of the orientation. More...
 
void set_position (const Eigen::Vector3d &position)
 Setter of the psotion from a vector. More...
 
void set_position (const Eigen::Quaterniond &dual)
 Setter of the position from a dual. More...
 
const DualQuaternionPose conjugate () const
 compute the conjugate of the current DualQuaternionPose More...
 
const DualQuaternionPose inverse () const
 compute the inverse of the current DualQuaternionPose More...
 
DualQuaternionPoseoperator*= (const DualQuaternionPose &q)
 Overload the *= operator. More...
 
const DualQuaternionPose operator* (const DualQuaternionPose &p) const
 Overload the * operator. More...
 
DualQuaternionPoseoperator*= (const DualQuaternionState &s)
 Overload the *= operator. More...
 
const DualQuaternionPose operator* (const DualQuaternionState &s) const
 Overload the * operator. More...
 
void operator= (const DualQuaternionState &s)
 Overload the = operator with a DualQuaternionState. More...
 
void initialize ()
 Initialize the DualQuaternionPose to a zero value. More...
 
const DualQuaternionPose copy () const
 Return a copy of the DualQuaternionPose. More...
 
- Public Member Functions inherited from state_representation::DualQuaternionState
 DualQuaternionState ()
 Empty constructor. More...
 
 DualQuaternionState (const std::string &name, const std::string &reference="world")
 Constructor with name and reference frame provided. More...
 
 DualQuaternionState (const DualQuaternionState &state)
 Copy constructor. More...
 
 DualQuaternionState (const std::string &name, const Eigen::Quaterniond &primary, const Eigen::Quaterniond &dual, const std::string &reference="world")
 Construct a DualQuaternion from two quaternions. More...
 
const Eigen::Quaterniond & get_primary () const
 Getter of the primary attribute. More...
 
const Eigen::Quaterniond & get_dual () const
 Getter of the dual attribute. More...
 
void set_primary (const Eigen::Quaterniond &primary)
 Setter of the primary attribute. More...
 
void set_dual (const Eigen::Quaterniond &dual)
 Setter of the dual attribute. More...
 
DualQuaternionStateoperator*= (const DualQuaternionState &q)
 Overload the *= operator. More...
 
const DualQuaternionState operator* (const DualQuaternionState &p) const
 Overload the * operator. More...
 
const DualQuaternionState conjugate () const
 compute the conjugate of the current DualQuaternion More...
 
virtual void initialize ()
 Initialize the DualQuaternionState to a zero value. More...
 
const DualQuaternionState copy () const
 Return a copy of the DualQuaternionState. More...
 
- Public Member Functions inherited from state_representation::SpatialState
 SpatialState ()
 Empty constructor. More...
 
 SpatialState (const StateType &type)
 Empty constructor with a specific state type. More...
 
 SpatialState (const StateType &type, const std::string &name, const std::string &reference_frame="world", const bool &empty=true)
 Constructor with name and reference frame specification. More...
 
 SpatialState (const SpatialState &state)=default
 Copy constructor from another SpatialState.
 
SpatialStateoperator= (const SpatialState &state)
 Copy assignment operator that have to be defined to the custom assignment operator. More...
 
const std::string & get_reference_frame () const
 Getter of the reference frame as const reference. More...
 
virtual void set_reference_frame (const std::string &reference_frame)
 Setter of the reference frame. More...
 
virtual bool is_compatible (const State &state) const override
 Check if the state is compatible for operations with the state given as argument. More...
 
- Public Member Functions inherited from state_representation::State
 State ()
 Empty constructor. More...
 
 State (const StateType &type)
 Constructor only specifying the type of the state from the StateType enumeration. More...
 
 State (const StateType &type, const std::string &name, const bool &empty=true)
 Constructor with name specification. More...
 
 State (const State &state)
 Copy constructor from another State. More...
 
virtual ~State ()=default
 Virtual destructor.
 
Stateoperator= (const State &state)
 Copy assignment operator that have to be defined to the custom assignment operator. More...
 
const StateTypeget_type () const
 Getter of the type attribute. More...
 
bool is_empty () const
 Getter of the empty attribute. More...
 
void set_empty (bool empty=true)
 Setter of the empty attribute. More...
 
void set_filled ()
 Setter of the empty attribute to false and also reset the timestamp. More...
 
const std::chrono::time_point< std::chrono::steady_clock > & get_timestamp () const
 Getter of the timestamp attribute. More...
 
void set_timestamp (const std::chrono::time_point< std::chrono::steady_clock > &timepoint)
 Setter of the timestamp attribute. More...
 
void reset_timestamp ()
 Reset the timestamp attribute to now. More...
 
const std::string & get_name () const
 Getter of the name as const reference. More...
 
virtual void set_name (const std::string &name)
 Setter of the name. More...
 
template<typename DurationT >
bool is_deprecated (const std::chrono::duration< int64_t, DurationT > &time_delay)
 Check if the state is deprecated given a certain time delay. More...
 
virtual bool is_compatible (const State &state) const
 Check if the state is compatible for operations with the state given as argument. More...
 
virtual void initialize ()
 Initialize the State to a zero value. More...
 
virtual void set_data (const Eigen::VectorXd &data)
 Set the data of the state from a single Eigen vector. More...
 
virtual void set_data (const std::vector< double > &data)
 Set the data of the state from a single std vector. More...
 
virtual void set_data (const Eigen::MatrixXd &data)
 Set the data of the state from an Eigen matrix. More...
 
 operator bool () const noexcept
 Boolean operator for the truthiness of a state. More...
 

Friends

const DualQuaternionState log (const DualQuaternionPose &state)
 Calculate the log of a dual quaternion. More...
 
std::ostream & operator<< (std::ostream &os, const DualQuaternionPose &state)
 Overload the ostream operator for printing. More...
 

Additional Inherited Members

- Protected Member Functions inherited from state_representation::State
void set_type (const StateType &type)
 Override the state type. More...
 

Detailed Description

Class to represent a Pose in Dual Quaternion space.

Definition at line 10 of file DualQuaternionPose.hpp.

Constructor & Destructor Documentation

◆ DualQuaternionPose() [1/4]

state_representation::DualQuaternionPose::DualQuaternionPose ( const std::string &  name,
const std::string &  reference = "world" 
)
explicit

Constructor with name and reference frame provided.

name the name of the state

reference the name of the reference frame

Definition at line 4 of file DualQuaternionPose.cpp.

◆ DualQuaternionPose() [2/4]

state_representation::DualQuaternionPose::DualQuaternionPose ( const DualQuaternionPose state)

Copy constructor of a DualQuaternionPose.

Definition at line 9 of file DualQuaternionPose.cpp.

◆ DualQuaternionPose() [3/4]

state_representation::DualQuaternionPose::DualQuaternionPose ( const DualQuaternionState state)

Copy constructor of a DualQuaternionPose from a DualQuaternionState.

Definition at line 12 of file DualQuaternionPose.cpp.

◆ DualQuaternionPose() [4/4]

state_representation::DualQuaternionPose::DualQuaternionPose ( const std::string &  name,
const Eigen::Vector3d &  position,
const Eigen::Quaterniond &  rotation,
const std::string &  reference = "world" 
)
explicit

Construct a DualQuaternionPose from a position given as a vector of coordinates and a quaternion.

Definition at line 17 of file DualQuaternionPose.cpp.

Member Function Documentation

◆ conjugate()

const DualQuaternionPose state_representation::DualQuaternionPose::conjugate ( ) const

compute the conjugate of the current DualQuaternionPose

Returns
the conjugate

Definition at line 27 of file DualQuaternionPose.cpp.

◆ copy()

const DualQuaternionPose state_representation::DualQuaternionPose::copy ( ) const

Return a copy of the DualQuaternionPose.

Returns
the copy

Definition at line 89 of file DualQuaternionPose.cpp.

◆ get_orientation()

const Eigen::Quaterniond & state_representation::DualQuaternionPose::get_orientation ( ) const
inline

Getter of the orientation from the primary.

Definition at line 142 of file DualQuaternionPose.hpp.

◆ get_position()

const Eigen::Vector3d state_representation::DualQuaternionPose::get_position ( ) const
inline

Getter of the position attribute.

Definition at line 138 of file DualQuaternionPose.hpp.

◆ initialize()

void state_representation::DualQuaternionPose::initialize ( )
virtual

Initialize the DualQuaternionPose to a zero value.

Reimplemented from state_representation::DualQuaternionState.

Definition at line 84 of file DualQuaternionPose.cpp.

◆ inverse()

const DualQuaternionPose state_representation::DualQuaternionPose::inverse ( ) const

compute the inverse of the current DualQuaternionPose

Returns
the inverse

Definition at line 31 of file DualQuaternionPose.cpp.

◆ operator*() [1/2]

const DualQuaternionPose state_representation::DualQuaternionPose::operator* ( const DualQuaternionPose p) const

Overload the * operator.

Parameters
pDualQuaternionState to multiply with
Returns
the current DualQuaternionState multiply by the DualQuaternionState given in argument

Definition at line 52 of file DualQuaternionPose.cpp.

◆ operator*() [2/2]

const DualQuaternionPose state_representation::DualQuaternionPose::operator* ( const DualQuaternionState s) const

Overload the * operator.

Parameters
pDualQuaternionState to multiply with
Returns
the current DualQuaternionState multiply by the DualQuaternionState given in argument

Definition at line 70 of file DualQuaternionPose.cpp.

◆ operator*=() [1/2]

DualQuaternionPose & state_representation::DualQuaternionPose::operator*= ( const DualQuaternionPose q)

Overload the *= operator.

Parameters
qDualQuaternion to multiply with
Returns
the current DualQuaternion multiply by the DualQuaternion given in argument

Definition at line 41 of file DualQuaternionPose.cpp.

◆ operator*=() [2/2]

DualQuaternionPose & state_representation::DualQuaternionPose::operator*= ( const DualQuaternionState s)

Overload the *= operator.

Parameters
qDualQuaternion to multiply with
Returns
the current DualQuaternion multiply by the DualQuaternion given in argument

Definition at line 58 of file DualQuaternionPose.cpp.

◆ operator=()

void state_representation::DualQuaternionPose::operator= ( const DualQuaternionState s)

Overload the = operator with a DualQuaternionState.

Parameters
sDualQuaternion to copy values from

Definition at line 76 of file DualQuaternionPose.cpp.

◆ set_orientation()

void state_representation::DualQuaternionPose::set_orientation ( const Eigen::Quaterniond &  orientation)
inline

Setter of the orientation.

Definition at line 146 of file DualQuaternionPose.hpp.

◆ set_position() [1/2]

void state_representation::DualQuaternionPose::set_position ( const Eigen::Quaterniond &  dual)
inline

Setter of the position from a dual.

Definition at line 170 of file DualQuaternionPose.hpp.

◆ set_position() [2/2]

void state_representation::DualQuaternionPose::set_position ( const Eigen::Vector3d &  position)
inline

Setter of the psotion from a vector.

Definition at line 162 of file DualQuaternionPose.hpp.

Friends And Related Function Documentation

◆ log

const DualQuaternionState log ( const DualQuaternionPose state)
friend

Calculate the log of a dual quaternion.

Parameters
statethe dual quaternion to calcualte the log on
Returns
the log of the dual quaternion

Definition at line 94 of file DualQuaternionPose.cpp.

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const DualQuaternionPose state 
)
friend

Overload the ostream operator for printing.

Parameters
osthe ostream to happend the string representing the state to
statethe state to print
Returns
the appended ostream

Definition at line 104 of file DualQuaternionPose.cpp.


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