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

Class to define Cartesian pose in Cartesian space as 3D position and quaternion based orientation. More...

#include <CartesianPose.hpp>

Inheritance diagram for state_representation::CartesianPose:
state_representation::CartesianState state_representation::SpatialState state_representation::State

Public Member Functions

const Eigen::Vector3d & get_linear_velocity () const =delete
 
const Eigen::Vector3d & get_angular_velocity () const =delete
 
Eigen::Matrix< double, 6, 1 > get_twist () const =delete
 
const Eigen::Vector3d & get_linear_acceleration () const =delete
 
const Eigen::Vector3d & get_angular_acceleration () const =delete
 
Eigen::Matrix< double, 6, 1 > get_acceleration () const =delete
 
const Eigen::Vector3d & get_force () const =delete
 
const Eigen::Vector3d & get_torque () const =delete
 
Eigen::Matrix< double, 6, 1 > get_wrench () const =delete
 
void set_linear_velocity (const Eigen::Vector3d &linear_velocity)=delete
 
void set_linear_velocity (const std::vector< double > &linear_velocity)=delete
 
void set_linear_velocity (const double &x, const double &y, const double &z)=delete
 
void set_angular_velocity (const Eigen::Vector3d &angular_velocity)=delete
 
void set_angular_velocity (const std::vector< double > &angular_velocity)=delete
 
void set_angular_velocity (const double &x, const double &y, const double &z)=delete
 
void set_twist (const Eigen::Matrix< double, 6, 1 > &twist)=delete
 
void set_twist (const std::vector< double > &twist)=delete
 
void set_linear_acceleration (const Eigen::Vector3d &linear_acceleration)=delete
 
void set_linear_acceleration (const std::vector< double > &linear_acceleration)=delete
 
void set_linear_acceleration (const double &x, const double &y, const double &z)=delete
 
void set_angular_acceleration (const Eigen::Vector3d &angular_acceleration)=delete
 
void set_angular_acceleration (const std::vector< double > &angular_acceleration)=delete
 
void set_angular_acceleration (const double &x, const double &y, const double &z)=delete
 
void set_acceleration (const Eigen::Matrix< double, 6, 1 > &acceleration)=delete
 
void set_acceleration (const std::vector< double > &acceleration)=delete
 
void set_force (const Eigen::Vector3d &force)=delete
 
void set_force (const std::vector< double > &force)=delete
 
void set_force (const double &x, const double &y, const double &z)=delete
 
void set_torque (const Eigen::Vector3d &torque)=delete
 
void set_torque (const std::vector< double > &torque)=delete
 
void set_torque (const double &x, const double &y, const double &z)=delete
 
void set_wrench (const Eigen::Matrix< double, 6, 1 > &wrench)=delete
 
void set_wrench (const std::vector< double > &wrench)=delete
 
CartesianPoseoperator*= (const CartesianTwist &twist)=delete
 
CartesianPoseoperator*= (const CartesianAcceleration &acceleration)=delete
 
CartesianPoseoperator*= (const CartesianWrench &wrench)=delete
 
CartesianStateoperator+= (const CartesianTwist &twist)=delete
 
CartesianStateoperator+= (const CartesianAcceleration &acceleration)=delete
 
CartesianStateoperator+= (const CartesianWrench &wrench)=delete
 
CartesianState operator+ (const CartesianTwist &twist) const =delete
 
CartesianState operator+ (const CartesianAcceleration &acceleration) const =delete
 
CartesianState operator+ (const CartesianWrench &wrench) const =delete
 
CartesianStateoperator-= (const CartesianTwist &twist)=delete
 
CartesianStateoperator-= (const CartesianAcceleration &acceleration)=delete
 
CartesianStateoperator-= (const CartesianWrench &wrench)=delete
 
CartesianState operator- (const CartesianTwist &twist) const =delete
 
CartesianState operator- (const CartesianAcceleration &acceleration) const =delete
 
CartesianState operator- (const CartesianWrench &wrench) const =delete
 
 CartesianPose ()
 Empty constructor.
 
 CartesianPose (const std::string &name, const std::string &reference="world")
 Constructor with name and reference frame provided.
 
 CartesianPose (const CartesianPose &pose)
 Copy constructor.
 
 CartesianPose (const CartesianState &state)
 Copy constructor from a Cartesian state.
 
 CartesianPose (const CartesianTwist &twist)
 Copy constructor from a Cartesian twist by considering that it is a displacement over 1 second.
 
 CartesianPose (const std::string &name, const Eigen::Vector3d &position, const std::string &reference="world")
 Constructor of a Cartesian pose from a position given as a vector of coordinates.
 
 CartesianPose (const std::string &name, double x, double y, double z, const std::string &reference="world")
 Constructor of a Cartesian pose from a position given as three scalar coordinates.
 
 CartesianPose (const std::string &name, const Eigen::Quaterniond &orientation, const std::string &reference="world")
 Constructor of a Cartesian pose from a quaternion.
 
 CartesianPose (const std::string &name, const Eigen::Vector3d &position, const Eigen::Quaterniond &orientation, const std::string &reference="world")
 Constructor of a Cartesian pose from a position given as a vector of coordinates and a quaternion.
 
CartesianPoseoperator= (const CartesianPose &pose)=default
 Copy assignment operator that has to be defined to the custom assignment operator.
 
Eigen::VectorXd data () const override
 Returns the pose data as an Eigen vector.
 
void set_data (const Eigen::VectorXd &data) override
 Set the pose data from an Eigen vector.
 
void set_data (const std::vector< double > &data) override
 Set the pose data from a std vector.
 
CartesianPose copy () const
 Return a copy of the Cartesian pose.
 
CartesianPose inverse () const
 Compute the inverse of the current Cartesian pose.
 
CartesianPose normalized (const CartesianStateVariable &state_variable_type=CartesianStateVariable::POSE) const
 Compute the normalized pose at the state variable given in argument (default is full pose)
 
std::vector< double > norms (const CartesianStateVariable &state_variable_type=CartesianStateVariable::POSE) const override
 Compute the norms of the state variable specified by the input type (default is full pose)
 
CartesianPoseoperator*= (const CartesianState &state)
 Transform inplace a Cartesian state into the current reference frame.
 
CartesianPoseoperator*= (const CartesianPose &pose)
 Transform inplace a Cartesian pose into the current reference frame.
 
CartesianState operator* (const CartesianState &state) const
 Transform a Cartesian state into the pose reference frame.
 
CartesianPose operator* (const CartesianPose &pose) const
 Transform a Cartesian pose into the left operand pose reference frame.
 
CartesianTwist operator* (const CartesianTwist &twist) const
 Transform a Cartesian twist into the pose reference frame.
 
CartesianAcceleration operator* (const CartesianAcceleration &acceleration) const
 Transform a Cartesian acceleration into the pose reference frame.
 
CartesianWrench operator* (const CartesianWrench &wrench) const
 Transform a Cartesian wrench into the pose reference frame.
 
CartesianPoseoperator*= (double lambda)
 Scale inplace by a scalar.
 
CartesianPose operator* (double lambda) const
 Scale a Cartesian pose by a scalar.
 
CartesianPoseoperator/= (double lambda)
 Scale inplace by a scalar.
 
CartesianPose operator/ (double lambda) const
 Scale a Cartesian pose by a scalar.
 
CartesianTwist operator/ (const std::chrono::nanoseconds &dt) const
 Differentiate a Cartesian pose over a time period.
 
CartesianPoseoperator+= (const CartesianPose &pose)
 Add inplace another Cartesian pose.
 
CartesianPoseoperator+= (const CartesianState &state)
 Add inplace another pose from a Cartesian state.
 
CartesianPose operator+ (const CartesianPose &pose) const
 Add another Cartesian pose.
 
CartesianState operator+ (const CartesianState &state) const
 Add another Cartesian state.
 
CartesianPose operator- () const
 Negate a Cartesian pose.
 
CartesianPoseoperator-= (const CartesianPose &pose)
 Compute inplace the difference with another Cartesian pose.
 
CartesianPoseoperator-= (const CartesianState &state)
 Compute inplace the difference with another Cartesian state.
 
CartesianPose operator- (const CartesianPose &pose) const
 Compute the difference with another Cartesian pose.
 
CartesianState operator- (const CartesianState &state) const
 Compute the difference with a Cartesian state.
 
- Public Member Functions inherited from state_representation::CartesianState
 CartesianState ()
 Empty constructor.
 
 CartesianState (const std::string &name, const std::string &reference="world")
 Constructor with name and reference frame provided.
 
 CartesianState (const CartesianState &state)
 Copy constructor of a Cartesian state.
 
CartesianStateoperator= (const CartesianState &state)
 Copy assignment operator that has to be defined to the custom assignment operator.
 
const Eigen::Vector3d & get_position () const
 Getter of the position attribute.
 
const Eigen::Quaterniond & get_orientation () const
 Getter of the orientation attribute.
 
Eigen::Vector4d get_orientation_coefficients () const
 Getter of the orientation attribute as Vector4d of coefficients.
 
Eigen::Matrix< double, 7, 1 > get_pose () const
 Getter of the pose from position and orientation attributes.
 
Eigen::Matrix4d get_transformation_matrix () const
 Getter of a pose from position and orientation attributes.
 
const Eigen::Vector3d & get_linear_velocity () const
 Getter of the linear velocity attribute.
 
const Eigen::Vector3d & get_angular_velocity () const
 Getter of the angular velocity attribute.
 
Eigen::Matrix< double, 6, 1 > get_twist () const
 Getter of the 6d twist from linear and angular velocity attributes.
 
const Eigen::Vector3d & get_linear_acceleration () const
 Getter of the linear acceleration attribute.
 
const Eigen::Vector3d & get_angular_acceleration () const
 Getter of the angular acceleration attribute.
 
Eigen::Matrix< double, 6, 1 > get_acceleration () const
 Getter of the 6d acceleration from linear and angular acceleration attributes.
 
const Eigen::Vector3d & get_force () const
 Getter of the force attribute.
 
const Eigen::Vector3d & get_torque () const
 Getter of the torque attribute.
 
Eigen::Matrix< double, 6, 1 > get_wrench () const
 Getter of the 6d wrench from force and torque attributes.
 
Eigen::ArrayXd array () const
 Return the data vector as an Eigen Array.
 
std::vector< double > to_std_vector () const
 Return the state as a std vector.
 
void set_position (const Eigen::Vector3d &position)
 Setter of the position.
 
void set_position (const std::vector< double > &position)
 Setter of the position from a std vector.
 
void set_position (const double &x, const double &y, const double &z)
 Setter of the position from three scalar coordinates.
 
void set_orientation (const Eigen::Quaterniond &orientation)
 Setter of the orientation.
 
void set_orientation (const Eigen::Vector4d &orientation)
 Setter of the orientation from a 4d vector.
 
void set_orientation (const std::vector< double > &orientation)
 Setter of the orientation from a std vector.
 
void set_orientation (const double &w, const double &x, const double &y, const double &z)
 Setter of the orientation from four scalar coefficients (w, x, y, z)
 
void set_pose (const Eigen::Vector3d &position, const Eigen::Quaterniond &orientation)
 Setter of the pose from both position and orientation.
 
void set_pose (const Eigen::Matrix< double, 7, 1 > &pose)
 Setter of the pose from both position and orientation as Eigen 7d vector.
 
void set_pose (const std::vector< double > &pose)
 Setter of the pose from both position and orientation as std vector.
 
void set_linear_velocity (const Eigen::Vector3d &linear_velocity)
 Setter of the linear velocity attribute.
 
void set_linear_velocity (const std::vector< double > &linear_velocity)
 Setter of the linear velocity from a std vector.
 
void set_linear_velocity (const double &x, const double &y, const double &z)
 Setter of the linear velocity from three scalar coordinates.
 
void set_angular_velocity (const Eigen::Vector3d &angular_velocity)
 Setter of the angular velocity attribute.
 
void set_angular_velocity (const std::vector< double > &angular_velocity)
 Setter of the angular velocity from a std vector.
 
void set_angular_velocity (const double &x, const double &y, const double &z)
 Setter of the angular velocity from three scalar coordinates.
 
void set_twist (const Eigen::Matrix< double, 6, 1 > &twist)
 Setter of the linear and angular velocities from a 6d twist vector.
 
void set_twist (const std::vector< double > &twist)
 Setter of the linear and angular velocities from a std vector.
 
void set_linear_acceleration (const Eigen::Vector3d &linear_acceleration)
 Setter of the linear acceleration attribute.
 
void set_linear_acceleration (const std::vector< double > &linear_acceleration)
 Setter of the linear acceleration from a std vector.
 
void set_linear_acceleration (const double &x, const double &y, const double &z)
 Setter of the linear acceleration from three scalar coordinates.
 
void set_angular_acceleration (const Eigen::Vector3d &angular_acceleration)
 Setter of the angular velocity attribute.
 
void set_angular_acceleration (const std::vector< double > &angular_acceleration)
 Setter of the angular acceleration from a std vector.
 
void set_angular_acceleration (const double &x, const double &y, const double &z)
 Setter of the angular acceleration from three scalar coordinates.
 
void set_acceleration (const Eigen::Matrix< double, 6, 1 > &acceleration)
 Setter of the linear and angular acceleration from a 6d acceleration vector.
 
void set_acceleration (const std::vector< double > &acceleration)
 Setter of the linear and angular acceleration from a std vector.
 
void set_force (const Eigen::Vector3d &force)
 Setter of the force attribute.
 
void set_force (const std::vector< double > &force)
 Setter of the force from a std vector.
 
void set_force (const double &x, const double &y, const double &z)
 Setter of the force from three scalar coordinates.
 
void set_torque (const Eigen::Vector3d &torque)
 Setter of the torque attribute.
 
void set_torque (const std::vector< double > &torque)
 Setter of the torque from a std vector.
 
void set_torque (const double &x, const double &y, const double &z)
 Setter of the torque from three scalar coordinates.
 
void set_wrench (const Eigen::Matrix< double, 6, 1 > &wrench)
 Setter of the force and torque from a 6d wrench vector.
 
void set_wrench (const std::vector< double > &wrench)
 Setter of the force and torque from a std vector.
 
void set_zero ()
 Set the State to a zero value.
 
void clamp_state_variable (double max_norm, const CartesianStateVariable &state_variable_type, double noise_ratio=0)
 Clamp inplace the norm of the a specific state variable.
 
CartesianState copy () const
 Return a copy of the Cartesian state.
 
double dist (const CartesianState &state, const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL) const
 Compute the distance to another state as the sum of distances between each features.
 
void reset () override
 Reset the object to a post-construction state.
 
CartesianState inverse () const
 Compute the inverse of the current Cartesian state.
 
void normalize (const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL)
 Normalize inplace the state at the state variable given in argument. Default is full state.
 
CartesianState normalized (const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL) const
 Compute the normalized state at the state variable given in argument. Default is full state.
 
CartesianStateoperator*= (const CartesianState &state)
 Transform inplace a Cartesian state into the current reference frame.
 
CartesianState operator* (const CartesianState &state) const
 Transform a Cartesian state into the left operand state reference frame.
 
CartesianStateoperator*= (double lambda)
 Scale inplace by a scalar.
 
CartesianState operator* (double lambda) const
 Scale a Cartesian pose by a scalar.
 
Eigen::Vector3d operator* (const Eigen::Vector3d &vector) const
 Transform a vector into the state reference frame.
 
CartesianStateoperator/= (double lambda)
 Scale inplace by a scalar.
 
CartesianState operator/ (double lambda) const
 Scale a Cartesian state by a scalar.
 
CartesianStateoperator+= (const CartesianState &state)
 Add inplace another Cartesian state.
 
CartesianState operator+ (const CartesianState &state) const
 Add another Cartesian state.
 
CartesianState operator- () const
 Negate a Cartesian state.
 
CartesianStateoperator-= (const CartesianState &state)
 Compute inplace the difference with another Cartesian state.
 
CartesianState operator- (const CartesianState &state) const
 Compute the difference with another Cartesian state.
 
- Public Member Functions inherited from state_representation::SpatialState
 SpatialState ()
 Empty constructor.
 
 SpatialState (const std::string &name, const std::string &reference_frame="world")
 Constructor with name and reference frame specification.
 
 SpatialState (const SpatialState &state)
 Copy constructor from another spatial state.
 
SpatialStateoperator= (const SpatialState &state)
 Copy assignment operator that has to be defined to the custom assignment operator.
 
const std::string & get_reference_frame () const
 Getter of the reference frame as const reference.
 
virtual void set_reference_frame (const std::string &reference_frame)
 Setter of the reference frame.
 
bool is_incompatible (const State &state) const override
 Check if the spatial state is incompatible for operations with the state given as argument.
 
- Public Member Functions inherited from state_representation::State
 State ()
 Empty constructor.
 
 State (const std::string &name)
 Constructor with name specification.
 
 State (const State &state)
 Copy constructor from another state.
 
virtual ~State ()=default
 Virtual destructor.
 
Stateoperator= (const State &state)
 Copy assignment operator that has to be defined to the custom assignment operator.
 
const StateTypeget_type () const
 Getter of the type attribute.
 
const std::string & get_name () const
 Getter of the name attribute.
 
bool is_empty () const
 Getter of the empty attribute.
 
const std::chrono::time_point< std::chrono::steady_clock > & get_timestamp () const
 Getter of the timestamp attribute.
 
virtual void set_name (const std::string &name)
 Setter of the name attribute.
 
void reset_timestamp ()
 Reset the timestamp attribute to now.
 
virtual void set_data (const Eigen::MatrixXd &data)
 Set the data of the state from an Eigen matrix.
 
double get_age () const
 Get the age of the state, i.e. the time since the last modification.
 
bool is_deprecated (double time_delay) const
 Check if the state is deprecated given a certain time delay.
 
template<typename DurationT >
bool is_deprecated (const std::chrono::duration< int64_t, DurationT > &time_delay) const
 Check if the state is deprecated given a certain time delay.
 
 operator bool () const noexcept
 Boolean operator for the truthiness of a state.
 

Static Public Member Functions

static CartesianPose Identity (const std::string &name, const std::string &reference="world")
 Constructor for the identity pose.
 
static CartesianPose Random (const std::string &name, const std::string &reference="world")
 Constructor for a random pose.
 
- Static Public Member Functions inherited from state_representation::CartesianState
static CartesianState Identity (const std::string &name, const std::string &reference="world")
 Constructor for the identity Cartesian state (identity pose and 0 for the rest)
 
static CartesianState Random (const std::string &name, const std::string &reference="world")
 Constructor for a random Cartesian state.
 

Friends

CartesianPose operator* (double lambda, const CartesianPose &pose)
 Scale a Cartesian pose by a scalar.
 
std::ostream & operator<< (std::ostream &os, const CartesianPose &pose)
 Overload the ostream operator for printing.
 

Additional Inherited Members

- Protected Member Functions inherited from state_representation::CartesianState
Eigen::VectorXd get_state_variable (const CartesianStateVariable &state_variable_type) const
 Getter of the variable value corresponding to the input.
 
void set_state_variable (const Eigen::VectorXd &new_value, const CartesianStateVariable &state_variable_type)
 Setter of the variable value corresponding to the input.
 
void set_state_variable (const std::vector< double > &new_value, const CartesianStateVariable &state_variable_type)
 Setter of the variable value corresponding to the input.
 
std::string to_string () const override
 Convert the state to its string representation.
 
- Protected Member Functions inherited from state_representation::SpatialState
std::string to_string () const override
 Convert the state to its string representation.
 
- Protected Member Functions inherited from state_representation::State
void set_type (const StateType &type)
 Setter of the state type attribute.
 
void set_empty (bool empty=true)
 Setter of the empty attribute.
 
void assert_not_empty () const
 Throw an exception if the state is empty.
 

Detailed Description

Class to define Cartesian pose in Cartesian space as 3D position and quaternion based orientation.

Definition at line 18 of file CartesianPose.hpp.

Constructor & Destructor Documentation

◆ CartesianPose() [1/9]

state_representation::CartesianPose::CartesianPose ( )
explicit

Empty constructor.

Definition at line 9 of file CartesianPose.cpp.

◆ CartesianPose() [2/9]

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

Constructor with name and reference frame provided.

Parameters
nameThe name of the state
referenceThe name of the reference frame (default is "world")

Definition at line 13 of file CartesianPose.cpp.

◆ CartesianPose() [3/9]

state_representation::CartesianPose::CartesianPose ( const CartesianPose pose)

Copy constructor.

Definition at line 54 of file CartesianPose.cpp.

◆ CartesianPose() [4/9]

state_representation::CartesianPose::CartesianPose ( const CartesianState state)

Copy constructor from a Cartesian state.

Definition at line 46 of file CartesianPose.cpp.

◆ CartesianPose() [5/9]

state_representation::CartesianPose::CartesianPose ( const CartesianTwist twist)

Copy constructor from a Cartesian twist by considering that it is a displacement over 1 second.

Definition at line 56 of file CartesianPose.cpp.

◆ CartesianPose() [6/9]

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

Constructor of a Cartesian pose from a position given as a vector of coordinates.

Parameters
nameThe name of the state
positionThe position data given as Eigen vector
referenceThe name of the reference frame (default is "world")

Definition at line 17 of file CartesianPose.cpp.

◆ CartesianPose() [7/9]

state_representation::CartesianPose::CartesianPose ( const std::string &  name,
double  x,
double  y,
double  z,
const std::string &  reference = "world" 
)
explicit

Constructor of a Cartesian pose from a position given as three scalar coordinates.

Parameters
nameThe name of the state
xThe x coordinate of the position
yThe y coordinate of the position
zThe z coordinate of the position
referenceThe name of the reference frame (default is "world")

Definition at line 23 of file CartesianPose.cpp.

◆ CartesianPose() [8/9]

state_representation::CartesianPose::CartesianPose ( const std::string &  name,
const Eigen::Quaterniond &  orientation,
const std::string &  reference = "world" 
)
explicit

Constructor of a Cartesian pose from a quaternion.

Parameters
nameThe name of the state
orientationThe orientation given as Eigen quaternion
referenceThe name of the reference frame (default is "world")

Definition at line 30 of file CartesianPose.cpp.

◆ CartesianPose() [9/9]

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

Constructor of a Cartesian pose from a position given as a vector of coordinates and a quaternion.

Parameters
nameThe name of the state
positionThe position data given as Eigen vector
orientationThe orientation given as Eigen quaternion
referenceThe name of the reference frame (default is "world")

Definition at line 37 of file CartesianPose.cpp.

Member Function Documentation

◆ copy()

CartesianPose state_representation::CartesianPose::copy ( ) const

Return a copy of the Cartesian pose.

Definition at line 82 of file CartesianPose.cpp.

◆ data()

Eigen::VectorXd state_representation::CartesianPose::data ( ) const
overridevirtual

Returns the pose data as an Eigen vector.

Reimplemented from state_representation::CartesianState.

Definition at line 66 of file CartesianPose.cpp.

◆ Identity()

CartesianPose state_representation::CartesianPose::Identity ( const std::string &  name,
const std::string &  reference = "world" 
)
static

Constructor for the identity pose.

Parameters
nameThe name of the state
referenceThe name of the reference frame (default is "world")
Returns
Cartesian identity pose

Definition at line 58 of file CartesianPose.cpp.

◆ inverse()

CartesianPose state_representation::CartesianPose::inverse ( ) const

Compute the inverse of the current Cartesian pose.

Returns
The inverse corresponding to b_S_f (assuming this is f_S_b)

Definition at line 87 of file CartesianPose.cpp.

◆ normalized()

CartesianPose state_representation::CartesianPose::normalized ( const CartesianStateVariable &  state_variable_type = CartesianStateVariable::POSE) const

Compute the normalized pose at the state variable given in argument (default is full pose)

Parameters
state_variable_typeThe type of state variable to compute the norms on
Returns
The normalized pose FIXME: state variable type doesnt make sense here

Definition at line 91 of file CartesianPose.cpp.

◆ norms()

std::vector< double > state_representation::CartesianPose::norms ( const CartesianStateVariable &  state_variable_type = CartesianStateVariable::POSE) const
overridevirtual

Compute the norms of the state variable specified by the input type (default is full pose)

Parameters
state_variable_typeThe type of state variable to compute the norms on
Returns
The norms of the state variables as a vector

Reimplemented from state_representation::CartesianState.

Definition at line 95 of file CartesianPose.cpp.

◆ operator*() [1/6]

CartesianAcceleration state_representation::CartesianPose::operator* ( const CartesianAcceleration acceleration) const

Transform a Cartesian acceleration into the pose reference frame.

: For a pose A expressed in reference frame W multiplied with an acceleration B expressed in reference frame A, the result of the transformation is an acceleration B expressed in reference frame W.

Parameters
accelerationA Cartesian acceleration expressed in the pose frame
Returns
The transformed acceleration expressed in the pose reference frame

Definition at line 121 of file CartesianPose.cpp.

◆ operator*() [2/6]

CartesianPose state_representation::CartesianPose::operator* ( const CartesianPose pose) const

Transform a Cartesian pose into the left operand pose reference frame.

: For a pose A expressed in reference frame W multiplied with a pose B expressed in reference frame A, the result of the transformation is a pose B expressed in reference frame W.

Parameters
poseA Cartesian pose expressed in the left operand pose frame
Returns
The transformed pose expressed in the left operand pose reference frame

Definition at line 113 of file CartesianPose.cpp.

◆ operator*() [3/6]

CartesianState state_representation::CartesianPose::operator* ( const CartesianState state) const

Transform a Cartesian state into the pose reference frame.

: For a pose A expressed in reference frame W multiplied with a state B expressed in reference frame A, the result of the transformation is a state B expressed in reference frame W.

Parameters
stateA Cartesian state expressed in the pose frame
Returns
The transformed state expressed in the pose reference frame

Definition at line 109 of file CartesianPose.cpp.

◆ operator*() [4/6]

CartesianTwist state_representation::CartesianPose::operator* ( const CartesianTwist twist) const

Transform a Cartesian twist into the pose reference frame.

: For a pose A expressed in reference frame W multiplied with a twist B expressed in reference frame A, the result of the transformation is a twist B expressed in reference frame W.

Parameters
twistA Cartesian twist expressed in the pose frame
Returns
The transformed twist expressed in the pose reference frame

Definition at line 117 of file CartesianPose.cpp.

◆ operator*() [5/6]

CartesianWrench state_representation::CartesianPose::operator* ( const CartesianWrench wrench) const

Transform a Cartesian wrench into the pose reference frame.

: For a pose A expressed in reference frame W multiplied with a wrench B expressed in reference frame A, the result of the transformation is a wrench B expressed in reference frame W.

Parameters
wrenchA Cartesian wrench expressed in the pose frame
Returns
The transformed wrench expressed in the pose reference frame

Definition at line 125 of file CartesianPose.cpp.

◆ operator*() [6/6]

CartesianPose state_representation::CartesianPose::operator* ( double  lambda) const

Scale a Cartesian pose by a scalar.

: All state variables in all their dimensions are scaled by the same factor.

Parameters
lambdaThe scaling factor
Returns
The reference to the scaled Cartesian state
Parameters
lambdaThe scaling factor
Returns
The scaled Cartesian pose

Definition at line 134 of file CartesianPose.cpp.

◆ operator*=() [1/3]

CartesianPose & state_representation::CartesianPose::operator*= ( const CartesianPose pose)

Transform inplace a Cartesian pose into the current reference frame.

: For a pose A expressed in reference frame W multiplied with a pose B expressed in reference frame A, the result of the transformation is a pose B expressed in reference frame W.

Parameters
poseA Cartesian pose expressed in the current pose frame
Returns
The transformed pose expressed in the original reference frame

Definition at line 104 of file CartesianPose.cpp.

◆ operator*=() [2/3]

CartesianPose & state_representation::CartesianPose::operator*= ( const CartesianState state)

Transform inplace a Cartesian state into the current reference frame.

: For a pose A expressed in reference frame W multiplied with a state B expressed in reference frame A, the result of the transformation is a pose B expressed in reference frame W.

Parameters
stateA Cartesian state expressed in the current pose frame
Returns
The transformed pose expressed in the original reference frame

Definition at line 99 of file CartesianPose.cpp.

◆ operator*=() [3/3]

CartesianPose & state_representation::CartesianPose::operator*= ( double  lambda)

Scale inplace by a scalar.

: All state variables in all their dimensions are scaled by the same factor.

Parameters
lambdaThe scaling factor
Returns
The reference to the scaled Cartesian state
Parameters
lambdaThe scaling factor
Returns
The reference to the scaled Cartesian pose

Definition at line 129 of file CartesianPose.cpp.

◆ operator+() [1/2]

CartesianPose state_representation::CartesianPose::operator+ ( const CartesianPose pose) const

Add another Cartesian pose.

Parameters
poseA Cartesian pose in the same reference frame
Returns
The combined Cartesian pose

Definition at line 175 of file CartesianPose.cpp.

◆ operator+() [2/2]

CartesianState state_representation::CartesianPose::operator+ ( const CartesianState state) const

Add another Cartesian state.

Parameters
stateA Cartesian state in the same reference frame
Returns
The combined Cartesian state

Definition at line 179 of file CartesianPose.cpp.

◆ operator+=() [1/2]

CartesianPose & state_representation::CartesianPose::operator+= ( const CartesianPose pose)

Add inplace another Cartesian pose.

Parameters
poseA Cartesian pose in the same reference frame
Returns
The reference to the combined Cartesian pose

Definition at line 165 of file CartesianPose.cpp.

◆ operator+=() [2/2]

CartesianPose & state_representation::CartesianPose::operator+= ( const CartesianState state)

Add inplace another pose from a Cartesian state.

Parameters
stateA Cartesian state in the same reference frame
Returns
The reference to the combined Cartesian pose

Definition at line 170 of file CartesianPose.cpp.

◆ operator-() [1/3]

CartesianPose state_representation::CartesianPose::operator- ( ) const

Negate a Cartesian pose.

Returns
The negative value of the Cartesian pose

Definition at line 183 of file CartesianPose.cpp.

◆ operator-() [2/3]

CartesianPose state_representation::CartesianPose::operator- ( const CartesianPose pose) const

Compute the difference with another Cartesian pose.

Parameters
poseA Cartesian pose in the same reference frame
Returns
The difference in pose

Definition at line 197 of file CartesianPose.cpp.

◆ operator-() [3/3]

CartesianState state_representation::CartesianPose::operator- ( const CartesianState state) const

Compute the difference with a Cartesian state.

Parameters
stateA Cartesian state in the same reference frame
Returns
The difference in all the state variables

Definition at line 201 of file CartesianPose.cpp.

◆ operator-=() [1/2]

CartesianPose & state_representation::CartesianPose::operator-= ( const CartesianPose pose)

Compute inplace the difference with another Cartesian pose.

Parameters
poseA Cartesian pose in the same reference frame
Returns
The reference to the difference in pose

Definition at line 187 of file CartesianPose.cpp.

◆ operator-=() [2/2]

CartesianPose & state_representation::CartesianPose::operator-= ( const CartesianState state)

Compute inplace the difference with another Cartesian state.

Parameters
stateA Cartesian state in the same reference frame
Returns
The reference to the difference in pose

Definition at line 192 of file CartesianPose.cpp.

◆ operator/() [1/2]

CartesianTwist state_representation::CartesianPose::operator/ ( const std::chrono::nanoseconds &  dt) const

Differentiate a Cartesian pose over a time period.

Parameters
dtThe time period used for derivation
Returns
The resulting Cartesian twist after derivation

Definition at line 151 of file CartesianPose.cpp.

◆ operator/() [2/2]

CartesianPose state_representation::CartesianPose::operator/ ( double  lambda) const

Scale a Cartesian pose by a scalar.

: All state variables in all their dimensions are scaled by the same factor.

Parameters
lambdaThe scaling factor
Returns
The reference to the scaled Cartesian state
Parameters
lambdaThe scaling factor
Returns
The scaled Cartesian acceleration

Definition at line 147 of file CartesianPose.cpp.

◆ operator/=()

CartesianPose & state_representation::CartesianPose::operator/= ( double  lambda)

Scale inplace by a scalar.

: All state variables in all their dimensions are scaled by the same factor.

Parameters
lambdaThe scaling factor
Returns
The reference to the scaled Cartesian state
Parameters
lambdaThe scaling factor
Returns
The reference to the scaled Cartesian pose

Definition at line 142 of file CartesianPose.cpp.

◆ operator=()

CartesianPose & state_representation::CartesianPose::operator= ( const CartesianPose pose)
default

Copy assignment operator that has to be defined to the custom assignment operator.

Parameters
poseThe pose with value to assign
Returns
Reference to the current pose with new values

◆ Random()

CartesianPose state_representation::CartesianPose::Random ( const std::string &  name,
const std::string &  reference = "world" 
)
static

Constructor for a random pose.

Parameters
nameThe name of the state
referenceThe name of the reference frame (default is "world")
Returns
Cartesian random pose

Definition at line 62 of file CartesianPose.cpp.

◆ set_data() [1/2]

void state_representation::CartesianPose::set_data ( const Eigen::VectorXd &  data)
overridevirtual

Set the pose data from an Eigen vector.

Reimplemented from state_representation::CartesianState.

Definition at line 70 of file CartesianPose.cpp.

◆ set_data() [2/2]

void state_representation::CartesianPose::set_data ( const std::vector< double > &  data)
overridevirtual

Set the pose data from a std vector.

Reimplemented from state_representation::CartesianState.

Definition at line 78 of file CartesianPose.cpp.

Friends And Related Symbol Documentation

◆ operator*

CartesianPose operator* ( double  lambda,
const CartesianPose pose 
)
friend

Scale a Cartesian pose by a scalar.

: All state variables in all their dimensions are scaled by the same factor.

Parameters
lambdaThe scaling factor
Returns
The reference to the scaled Cartesian state
Parameters
lambdaThe scaling factor
poseThe Cartesian pose to be scaled
Returns
The scaled Cartesian pose

Definition at line 138 of file CartesianPose.cpp.

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const CartesianPose pose 
)
friend

Overload the ostream operator for printing.

Parameters
osThe ostream to append the string representing the Cartesian pose to
CartesianPoseThe Cartesian pose to print
Returns
The appended ostream

Definition at line 205 of file CartesianPose.cpp.


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