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

Class to represent a state in Cartesian space. More...

#include <CartesianState.hpp>

Inheritance diagram for state_representation::CartesianState:
state_representation::SpatialState state_representation::State state_representation::CartesianAcceleration state_representation::CartesianPose state_representation::CartesianTwist state_representation::CartesianWrench

Public Member Functions

 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.
 
virtual Eigen::VectorXd data () const
 Return the data as the concatenation of all the state variables in a single vector.
 
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.
 
virtual void set_data (const Eigen::VectorXd &data) override
 Set the data of the state from all the state variables in a single Eigen vector.
 
virtual void set_data (const std::vector< double > &data) override
 Set the data of the state from all the state variables in a single 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.
 
virtual std::vector< double > norms (const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL) const
 Compute the norms of the state variable specified by the input type. 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 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.
 

Protected Member Functions

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.
 

Friends

void swap (CartesianState &state1, CartesianState &state2)
 Swap the values of two Cartesian states.
 
double dist (const CartesianState &s1, const CartesianState &s2, const CartesianStateVariable &state_variable_type)
 Compute the distance between two Cartesian states.
 
CartesianState operator* (double lambda, const CartesianState &state)
 Scale a Cartesian state by a scalar.
 
std::ostream & operator<< (std::ostream &os, const CartesianState &state)
 Overload the ostream operator for printing.
 

Detailed Description

Class to represent a state in Cartesian space.

Definition at line 48 of file CartesianState.hpp.

Constructor & Destructor Documentation

◆ CartesianState() [1/3]

state_representation::CartesianState::CartesianState ( )

Empty constructor.

Definition at line 43 of file CartesianState.cpp.

◆ CartesianState() [2/3]

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

Constructor with name and reference frame provided.

Definition at line 56 of file CartesianState.cpp.

◆ CartesianState() [3/3]

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

Copy constructor of a Cartesian state.

Definition at line 61 of file CartesianState.cpp.

Member Function Documentation

◆ array()

Eigen::ArrayXd state_representation::CartesianState::array ( ) const

Return the data vector as an Eigen Array.

Definition at line 210 of file CartesianState.cpp.

◆ clamp_state_variable()

void state_representation::CartesianState::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.

Parameters
max_normThe maximum norm of the state variable
state_variable_typeName of the variable from the CartesianStateVariable structure to clamp
noise_ratioIf provided, this value will be used to apply a dead zone under which the norm of the state variable will be set to 0

Definition at line 449 of file CartesianState.cpp.

◆ copy()

CartesianState state_representation::CartesianState::copy ( ) const

Return a copy of the Cartesian state.

Definition at line 467 of file CartesianState.cpp.

◆ data()

Eigen::VectorXd state_representation::CartesianState::data ( ) const
virtual

Return the data as the concatenation of all the state variables in a single vector.

Reimplemented in state_representation::CartesianAcceleration, state_representation::CartesianPose, state_representation::CartesianTwist, and state_representation::CartesianWrench.

Definition at line 206 of file CartesianState.cpp.

◆ dist()

double state_representation::CartesianState::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.

Parameters
stateThe second state
state_variable_typeThe name of the variable from the CartesianStateVariable structure to apply the distance on. Default ALL for full distance across all dimensions
Returns
dist The distance value as a double

Definition at line 472 of file CartesianState.cpp.

◆ get_acceleration()

Eigen::Matrix< double, 6, 1 > state_representation::CartesianState::get_acceleration ( ) const

Getter of the 6d acceleration from linear and angular acceleration attributes.

Definition at line 188 of file CartesianState.cpp.

◆ get_angular_acceleration()

const Eigen::Vector3d & state_representation::CartesianState::get_angular_acceleration ( ) const

Getter of the angular acceleration attribute.

Definition at line 183 of file CartesianState.cpp.

◆ get_angular_velocity()

const Eigen::Vector3d & state_representation::CartesianState::get_angular_velocity ( ) const

Getter of the angular velocity attribute.

Definition at line 169 of file CartesianState.cpp.

◆ get_force()

const Eigen::Vector3d & state_representation::CartesianState::get_force ( ) const

Getter of the force attribute.

Definition at line 192 of file CartesianState.cpp.

◆ get_linear_acceleration()

const Eigen::Vector3d & state_representation::CartesianState::get_linear_acceleration ( ) const

Getter of the linear acceleration attribute.

Definition at line 178 of file CartesianState.cpp.

◆ get_linear_velocity()

const Eigen::Vector3d & state_representation::CartesianState::get_linear_velocity ( ) const

Getter of the linear velocity attribute.

Definition at line 164 of file CartesianState.cpp.

◆ get_orientation()

const Eigen::Quaterniond & state_representation::CartesianState::get_orientation ( ) const

Getter of the orientation attribute.

Definition at line 144 of file CartesianState.cpp.

◆ get_orientation_coefficients()

Eigen::Vector4d state_representation::CartesianState::get_orientation_coefficients ( ) const

Getter of the orientation attribute as Vector4d of coefficients.

Quaternion coefficients are returned using the (w, x, y, z) convention

Definition at line 149 of file CartesianState.cpp.

◆ get_pose()

Eigen::Matrix< double, 7, 1 > state_representation::CartesianState::get_pose ( ) const

Getter of the pose from position and orientation attributes.

Returns
The pose as a 7d vector. Quaternion coefficients are returned using the (w, x, y, z) convention

Definition at line 153 of file CartesianState.cpp.

◆ get_position()

const Eigen::Vector3d & state_representation::CartesianState::get_position ( ) const

Getter of the position attribute.

Definition at line 139 of file CartesianState.cpp.

◆ get_state_variable()

Eigen::VectorXd state_representation::CartesianState::get_state_variable ( const CartesianStateVariable &  state_variable_type) const
protected

Getter of the variable value corresponding to the input.

Parameters
state_variable_typeThe type of variable to get

Definition at line 89 of file CartesianState.cpp.

◆ get_torque()

const Eigen::Vector3d & state_representation::CartesianState::get_torque ( ) const

Getter of the torque attribute.

Definition at line 197 of file CartesianState.cpp.

◆ get_transformation_matrix()

Eigen::Matrix4d state_representation::CartesianState::get_transformation_matrix ( ) const

Getter of a pose from position and orientation attributes.

Returns
The pose as a 4x4 transformation matrix

Definition at line 157 of file CartesianState.cpp.

◆ get_twist()

Eigen::Matrix< double, 6, 1 > state_representation::CartesianState::get_twist ( ) const

Getter of the 6d twist from linear and angular velocity attributes.

Definition at line 174 of file CartesianState.cpp.

◆ get_wrench()

Eigen::Matrix< double, 6, 1 > state_representation::CartesianState::get_wrench ( ) const

Getter of the 6d wrench from force and torque attributes.

Definition at line 202 of file CartesianState.cpp.

◆ Identity()

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

Constructor for the identity Cartesian state (identity pose and 0 for the rest)

Definition at line 68 of file CartesianState.cpp.

◆ inverse()

CartesianState state_representation::CartesianState::inverse ( ) const

Compute the inverse of the current Cartesian state.

The spatial properties of a CartesianState are measured at the frame and expressed in the reference frame coordinate system. The inverse operation yields the spatial properties of the reference frame as measured from the previous frame. For a state A expressed in reference frame B, the result will be frame B expressed in reference frame A.

Warning
The wrench is not supported by this operation will be set to zero
Returns
The inverse state

Definition at line 524 of file CartesianState.cpp.

◆ normalize()

void state_representation::CartesianState::normalize ( const CartesianStateVariable &  state_variable_type = CartesianStateVariable::ALL)

Normalize inplace the state at the state variable given in argument. Default is full state.

Parameters
state_variable_typeThe type of state variable to compute the norms on

Definition at line 558 of file CartesianState.cpp.

◆ normalized()

CartesianState state_representation::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.

Parameters
state_variable_typeThe type of state variable to compute the norms on
Returns
The normalized state

Definition at line 598 of file CartesianState.cpp.

◆ norms()

std::vector< double > state_representation::CartesianState::norms ( const CartesianStateVariable &  state_variable_type = CartesianStateVariable::ALL) const
virtual

Compute the norms of the state variable specified by the input type. Default is full state.

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

Reimplemented in state_representation::CartesianAcceleration, state_representation::CartesianPose, state_representation::CartesianTwist, and state_representation::CartesianWrench.

Definition at line 604 of file CartesianState.cpp.

◆ operator*() [1/3]

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

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

: For a state 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 left operand frame
Returns
The transformed state expressed in the left operand reference frame

Definition at line 694 of file CartesianState.cpp.

◆ operator*() [2/3]

Eigen::Vector3d state_representation::CartesianState::operator* ( const Eigen::Vector3d &  vector) const

Transform a vector into the state reference frame.

Parameters
vectorA position vector
Returns
The transformed vector expressed in the state reference frame

Definition at line 726 of file CartesianState.cpp.

◆ operator*() [3/3]

CartesianState state_representation::CartesianState::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 716 of file CartesianState.cpp.

◆ operator*=() [1/2]

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

Transform inplace a Cartesian state into the current reference frame.

: For a state 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 current state frame
Returns
The transformed state expressed in the original reference frame

Definition at line 644 of file CartesianState.cpp.

◆ operator*=() [2/2]

CartesianState & state_representation::CartesianState::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

Definition at line 700 of file CartesianState.cpp.

◆ operator+()

CartesianState state_representation::CartesianState::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 765 of file CartesianState.cpp.

◆ operator+=()

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

Add inplace another Cartesian state.

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

Definition at line 744 of file CartesianState.cpp.

◆ operator-() [1/2]

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

Negate a Cartesian state.

Returns
The negative value of the Cartesian state

Definition at line 771 of file CartesianState.cpp.

◆ operator-() [2/2]

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

Compute the difference with another Cartesian state.

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

Definition at line 791 of file CartesianState.cpp.

◆ operator-=()

CartesianState & state_representation::CartesianState::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 all the state variables

Definition at line 786 of file CartesianState.cpp.

◆ operator/()

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

Scale a Cartesian state 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 state

Definition at line 738 of file CartesianState.cpp.

◆ operator/=()

CartesianState & state_representation::CartesianState::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 state

Definition at line 730 of file CartesianState.cpp.

◆ operator=()

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

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

Parameters
stateThe state with value to assign
Returns
Reference to the current state with new values

Definition at line 83 of file CartesianState.cpp.

◆ Random()

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

Constructor for a random Cartesian state.

Definition at line 75 of file CartesianState.cpp.

◆ reset()

void state_representation::CartesianState::reset ( )
overridevirtual

Reset the object to a post-construction state.

Reimplemented from state_representation::State.

Definition at line 519 of file CartesianState.cpp.

◆ set_acceleration() [1/2]

void state_representation::CartesianState::set_acceleration ( const Eigen::Matrix< double, 6, 1 > &  acceleration)

Setter of the linear and angular acceleration from a 6d acceleration vector.

Definition at line 389 of file CartesianState.cpp.

◆ set_acceleration() [2/2]

void state_representation::CartesianState::set_acceleration ( const std::vector< double > &  acceleration)

Setter of the linear and angular acceleration from a std vector.

Definition at line 393 of file CartesianState.cpp.

◆ set_angular_acceleration() [1/3]

void state_representation::CartesianState::set_angular_acceleration ( const double &  x,
const double &  y,
const double &  z 
)

Setter of the angular acceleration from three scalar coordinates.

Definition at line 385 of file CartesianState.cpp.

◆ set_angular_acceleration() [2/3]

void state_representation::CartesianState::set_angular_acceleration ( const Eigen::Vector3d &  angular_acceleration)

Setter of the angular velocity attribute.

Definition at line 377 of file CartesianState.cpp.

◆ set_angular_acceleration() [3/3]

void state_representation::CartesianState::set_angular_acceleration ( const std::vector< double > &  angular_acceleration)

Setter of the angular acceleration from a std vector.

Definition at line 381 of file CartesianState.cpp.

◆ set_angular_velocity() [1/3]

void state_representation::CartesianState::set_angular_velocity ( const double &  x,
const double &  y,
const double &  z 
)

Setter of the angular velocity from three scalar coordinates.

Definition at line 353 of file CartesianState.cpp.

◆ set_angular_velocity() [2/3]

void state_representation::CartesianState::set_angular_velocity ( const Eigen::Vector3d &  angular_velocity)

Setter of the angular velocity attribute.

Definition at line 345 of file CartesianState.cpp.

◆ set_angular_velocity() [3/3]

void state_representation::CartesianState::set_angular_velocity ( const std::vector< double > &  angular_velocity)

Setter of the angular velocity from a std vector.

Definition at line 349 of file CartesianState.cpp.

◆ set_data() [1/2]

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

Set the data of the state from all the state variables in a single Eigen vector.

Reimplemented from state_representation::State.

Reimplemented in state_representation::CartesianAcceleration, state_representation::CartesianPose, state_representation::CartesianTwist, and state_representation::CartesianWrench.

Definition at line 429 of file CartesianState.cpp.

◆ set_data() [2/2]

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

Set the data of the state from all the state variables in a single std vector.

Reimplemented from state_representation::State.

Reimplemented in state_representation::CartesianAcceleration, state_representation::CartesianPose, state_representation::CartesianTwist, and state_representation::CartesianWrench.

Definition at line 433 of file CartesianState.cpp.

◆ set_force() [1/3]

void state_representation::CartesianState::set_force ( const double &  x,
const double &  y,
const double &  z 
)

Setter of the force from three scalar coordinates.

Definition at line 405 of file CartesianState.cpp.

◆ set_force() [2/3]

void state_representation::CartesianState::set_force ( const Eigen::Vector3d &  force)

Setter of the force attribute.

Definition at line 397 of file CartesianState.cpp.

◆ set_force() [3/3]

void state_representation::CartesianState::set_force ( const std::vector< double > &  force)

Setter of the force from a std vector.

Definition at line 401 of file CartesianState.cpp.

◆ set_linear_acceleration() [1/3]

void state_representation::CartesianState::set_linear_acceleration ( const double &  x,
const double &  y,
const double &  z 
)

Setter of the linear acceleration from three scalar coordinates.

Definition at line 373 of file CartesianState.cpp.

◆ set_linear_acceleration() [2/3]

void state_representation::CartesianState::set_linear_acceleration ( const Eigen::Vector3d &  linear_acceleration)

Setter of the linear acceleration attribute.

Definition at line 365 of file CartesianState.cpp.

◆ set_linear_acceleration() [3/3]

void state_representation::CartesianState::set_linear_acceleration ( const std::vector< double > &  linear_acceleration)

Setter of the linear acceleration from a std vector.

Definition at line 369 of file CartesianState.cpp.

◆ set_linear_velocity() [1/3]

void state_representation::CartesianState::set_linear_velocity ( const double &  x,
const double &  y,
const double &  z 
)

Setter of the linear velocity from three scalar coordinates.

Definition at line 341 of file CartesianState.cpp.

◆ set_linear_velocity() [2/3]

void state_representation::CartesianState::set_linear_velocity ( const Eigen::Vector3d &  linear_velocity)

Setter of the linear velocity attribute.

Definition at line 333 of file CartesianState.cpp.

◆ set_linear_velocity() [3/3]

void state_representation::CartesianState::set_linear_velocity ( const std::vector< double > &  linear_velocity)

Setter of the linear velocity from a std vector.

Definition at line 337 of file CartesianState.cpp.

◆ set_orientation() [1/4]

void state_representation::CartesianState::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)

Definition at line 316 of file CartesianState.cpp.

◆ set_orientation() [2/4]

void state_representation::CartesianState::set_orientation ( const Eigen::Quaterniond &  orientation)

Setter of the orientation.

Definition at line 301 of file CartesianState.cpp.

◆ set_orientation() [3/4]

void state_representation::CartesianState::set_orientation ( const Eigen::Vector4d &  orientation)

Setter of the orientation from a 4d vector.

Parameters
orientationThe orientation coefficients as a 4d vector. Quaternion coefficients use the (w, x, y, z) convention

Definition at line 308 of file CartesianState.cpp.

◆ set_orientation() [4/4]

void state_representation::CartesianState::set_orientation ( const std::vector< double > &  orientation)

Setter of the orientation from a std vector.

Parameters
orientationThe orientation coefficients as a 4d std vector. Quaternion coefficients use the (w, x, y, z) convention

Definition at line 312 of file CartesianState.cpp.

◆ set_pose() [1/3]

void state_representation::CartesianState::set_pose ( const Eigen::Matrix< double, 7, 1 > &  pose)

Setter of the pose from both position and orientation as Eigen 7d vector.

Parameters
poseThe pose as a 7d vector. Quaternion coefficients use the (w, x, y, z) convention

Definition at line 325 of file CartesianState.cpp.

◆ set_pose() [2/3]

void state_representation::CartesianState::set_pose ( const Eigen::Vector3d &  position,
const Eigen::Quaterniond &  orientation 
)

Setter of the pose from both position and orientation.

Definition at line 320 of file CartesianState.cpp.

◆ set_pose() [3/3]

void state_representation::CartesianState::set_pose ( const std::vector< double > &  pose)

Setter of the pose from both position and orientation as std vector.

Parameters
poseThe pose as a 7d vector. Quaternion coefficients use the (w, x, y, z) convention

Definition at line 329 of file CartesianState.cpp.

◆ set_position() [1/3]

void state_representation::CartesianState::set_position ( const double &  x,
const double &  y,
const double &  z 
)

Setter of the position from three scalar coordinates.

Definition at line 297 of file CartesianState.cpp.

◆ set_position() [2/3]

void state_representation::CartesianState::set_position ( const Eigen::Vector3d &  position)

Setter of the position.

Definition at line 289 of file CartesianState.cpp.

◆ set_position() [3/3]

void state_representation::CartesianState::set_position ( const std::vector< double > &  position)

Setter of the position from a std vector.

Definition at line 293 of file CartesianState.cpp.

◆ set_state_variable() [1/2]

void state_representation::CartesianState::set_state_variable ( const Eigen::VectorXd &  new_value,
const CartesianStateVariable &  state_variable_type 
)
protected

Setter of the variable value corresponding to the input.

Parameters
new_valueThe new value of the variable as Eigen vector
state_variable_typeThe type of variable to set

Definition at line 225 of file CartesianState.cpp.

◆ set_state_variable() [2/2]

void state_representation::CartesianState::set_state_variable ( const std::vector< double > &  new_value,
const CartesianStateVariable &  state_variable_type 
)
protected

Setter of the variable value corresponding to the input.

Parameters
new_valueThe new value of the variable as std vector
state_variable_typeThe type of variable to set

Definition at line 219 of file CartesianState.cpp.

◆ set_torque() [1/3]

void state_representation::CartesianState::set_torque ( const double &  x,
const double &  y,
const double &  z 
)

Setter of the torque from three scalar coordinates.

Definition at line 417 of file CartesianState.cpp.

◆ set_torque() [2/3]

void state_representation::CartesianState::set_torque ( const Eigen::Vector3d &  torque)

Setter of the torque attribute.

Definition at line 409 of file CartesianState.cpp.

◆ set_torque() [3/3]

void state_representation::CartesianState::set_torque ( const std::vector< double > &  torque)

Setter of the torque from a std vector.

Definition at line 413 of file CartesianState.cpp.

◆ set_twist() [1/2]

void state_representation::CartesianState::set_twist ( const Eigen::Matrix< double, 6, 1 > &  twist)

Setter of the linear and angular velocities from a 6d twist vector.

Definition at line 357 of file CartesianState.cpp.

◆ set_twist() [2/2]

void state_representation::CartesianState::set_twist ( const std::vector< double > &  twist)

Setter of the linear and angular velocities from a std vector.

Definition at line 361 of file CartesianState.cpp.

◆ set_wrench() [1/2]

void state_representation::CartesianState::set_wrench ( const Eigen::Matrix< double, 6, 1 > &  wrench)

Setter of the force and torque from a 6d wrench vector.

Definition at line 421 of file CartesianState.cpp.

◆ set_wrench() [2/2]

void state_representation::CartesianState::set_wrench ( const std::vector< double > &  wrench)

Setter of the force and torque from a std vector.

Definition at line 425 of file CartesianState.cpp.

◆ set_zero()

void state_representation::CartesianState::set_zero ( )

Set the State to a zero value.

Definition at line 437 of file CartesianState.cpp.

◆ to_std_vector()

std::vector< double > state_representation::CartesianState::to_std_vector ( ) const

Return the state as a std vector.

Definition at line 214 of file CartesianState.cpp.

◆ to_string()

std::string state_representation::CartesianState::to_string ( ) const
overrideprotectedvirtual

Convert the state to its string representation.

Reimplemented from state_representation::State.

Definition at line 802 of file CartesianState.cpp.

Friends And Related Symbol Documentation

◆ dist

double dist ( const CartesianState s1,
const CartesianState s2,
const CartesianStateVariable &  state_variable_type = CartesianStateVariable::ALL 
)
friend

Compute the distance between two Cartesian states.

Parameters
s1The first Cartesian state
s2The second Cartesian state
state_variable_typeType of the distance between position, orientation, linear_velocity, etc. Default ALL for full distance across all dimensions
Returns
The distance between the two states
Parameters
s1The first Cartesian state
s2The second Cartesian state
state_variable_typeName of the state variable from the CartesianStateVariable enum to apply the distance on. Default ALL for full distance across all dimensions
Returns
The distance between the two states

Definition at line 515 of file CartesianState.cpp.

◆ operator*

CartesianState operator* ( double  lambda,
const CartesianState state 
)
friend

Scale a Cartesian state 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
stateThe Cartesian state to be scaled
Returns
The scaled Cartesian state

Definition at line 722 of file CartesianState.cpp.

◆ operator<<

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

Overload the ostream operator for printing.

Parameters
osThe ostream to append the string representing the state to
stateThe state to print
Returns
The appended ostream

Definition at line 833 of file CartesianState.cpp.

◆ swap

void swap ( CartesianState state1,
CartesianState state2 
)
friend

Swap the values of two Cartesian states.

Parameters
state1Cartesian state to be swapped with 2
state2Cartesian state to be swapped with 1

Definition at line 590 of file CartesianState.hpp.


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