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

Class to define twist in cartesian space as 3D linear and angular velocity vectors. More...

#include <CartesianTwist.hpp>

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

Public Member Functions

const Eigen::Vector3d & get_position () const =delete
 
const Eigen::Quaterniond & get_orientation () const =delete
 
Eigen::Vector4d get_orientation_coefficients () const =delete
 
Eigen::Matrix< double, 7, 1 > get_pose () const =delete
 
Eigen::Matrix4d get_transformation_matrix () 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_position (const Eigen::Vector3d &position)=delete
 
void set_position (const std::vector< double > &position)=delete
 
void set_position (const double &x, const double &y, const double &z)=delete
 
void set_orientation (const Eigen::Quaterniond &orientation)=delete
 
void set_orientation (const Eigen::Vector4d &orientation)=delete
 
void set_orientation (const std::vector< double > &orientation)=delete
 
void set_orientation (const double &w, const double &x, const double &y, const double &z)=delete
 
void set_pose (const Eigen::Vector3d &position, const Eigen::Quaterniond &orientation)=delete
 
void set_pose (const Eigen::Matrix< double, 7, 1 > &pose)=delete
 
void set_pose (const std::vector< double > &pose)=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
 
CartesianState operator*= (const CartesianState &state)=delete
 
CartesianState operator* (const CartesianState &state)=delete
 
 CartesianTwist ()
 Empty constructor. More...
 
 CartesianTwist (const std::string &name, const std::string &reference="world")
 Constructor with name and reference frame provided. More...
 
 CartesianTwist (const CartesianTwist &twist)
 Copy constructor. More...
 
 CartesianTwist (const CartesianState &state)
 Copy constructor from a CartesianState. More...
 
 CartesianTwist (const CartesianPose &pose)
 Copy constructor from a CartesianPose by considering that it is equivalent to dividing the pose by 1 second. More...
 
 CartesianTwist (const CartesianAcceleration &acceleration)
 Copy constructor from a CartesianAcceleration by considering that it is a twist over 1 second. More...
 
 CartesianTwist (const std::string &name, const Eigen::Vector3d &linear_velocity, const std::string &reference="world")
 Construct a CartesianTwist from a linear velocity given as a vector. More...
 
 CartesianTwist (const std::string &name, const Eigen::Vector3d &linear_velocity, const Eigen::Vector3d &angular_velocity, const std::string &reference="world")
 Construct a CartesianTwist from a linear velocity and angular velocity given as vectors. More...
 
 CartesianTwist (const std::string &name, const Eigen::Matrix< double, 6, 1 > &twist, const std::string &reference="world")
 Construct a CartesianTwist from a single 6d twist vector. More...
 
CartesianTwistoperator= (const CartesianTwist &twist)=default
 Copy assignment operator that have to be defined to the custom assignment operator. More...
 
CartesianTwistoperator+= (const CartesianTwist &twist)
 Overload the += operator. More...
 
CartesianTwist operator+ (const CartesianTwist &twist) const
 Overload the + operator with a twist. More...
 
CartesianTwistoperator-= (const CartesianTwist &twist)
 Overload the -= operator. More...
 
CartesianTwist operator- (const CartesianTwist &twist) const
 Overload the - operator with a twist. More...
 
CartesianTwistoperator*= (double lambda)
 Overload the *= operator with a scalar. More...
 
CartesianTwist operator* (double lambda) const
 Overload the * operator with a scalar. More...
 
CartesianTwistoperator/= (double lambda)
 Overload the /= operator with a scalar. More...
 
CartesianTwist operator/ (double lambda) const
 Overload the / operator with a scalar. More...
 
CartesianTwistoperator*= (const Eigen::Matrix< double, 6, 6 > &lambda)
 Overload the *= operator with a gain matrix. More...
 
CartesianPose operator* (const std::chrono::nanoseconds &dt) const
 Overload the * operator with a time period. More...
 
CartesianAcceleration operator/ (const std::chrono::nanoseconds &dt) const
 Overload the / operator with a time period. More...
 
void clamp (double max_linear, double max_angular, double linear_noise_ratio=0, double angular_noise_ratio=0)
 Clamp inplace the magnitude of the twist to the values in argument. More...
 
CartesianTwist clamped (double max_linear, double max_angular, double noise_ratio=0, double angular_noise_ratio=0) const
 Return the clamped twist. More...
 
CartesianTwist copy () const
 Return a copy of the CartesianTwist. More...
 
Eigen::VectorXd data () const override
 Returns the twist data as an Eigen vector. More...
 
void set_data (const Eigen::VectorXd &data) override
 Set the twist data from an Eigen vector. More...
 
void set_data (const std::vector< double > &data) override
 Set the twist data from a std vector. More...
 
CartesianTwist inverse () const
 Compute the inverse of the current CartesianTwist. More...
 
std::vector< double > norms (const CartesianStateVariable &state_variable_type=CartesianStateVariable::TWIST) const override
 Compute the norms of the state variable specified by the input type (default is full twist) More...
 
CartesianTwist normalized (const CartesianStateVariable &state_variable_type=CartesianStateVariable::TWIST) const
 Compute the normalized twist at the state variable given in argument (default is full twist) More...
 
- Public Member Functions inherited from state_representation::CartesianState
 CartesianState ()
 Empty constructor. More...
 
 CartesianState (const std::string &name, const std::string &reference="world")
 Constructor with name and reference frame provided. More...
 
 CartesianState (const CartesianState &state)=default
 Copy constructor of a CartesianState.
 
CartesianStateoperator= (const CartesianState &state)
 Copy assignment operator that have to be defined to the custom assignment operator. More...
 
const Eigen::Vector3d & get_position () const
 Getter of the position attribute. More...
 
const Eigen::Quaterniond & get_orientation () const
 Getter of the orientation attribute. More...
 
Eigen::Vector4d get_orientation_coefficients () const
 Getter of the orientation attribute as Vector4d of coefficients Beware, quaternion coefficients are returned using the (w, x, y, z) convention. More...
 
Eigen::Matrix< double, 7, 1 > get_pose () const
 Getter of a pose from position and orientation attributes. More...
 
Eigen::Matrix4d get_transformation_matrix () const
 Getter of a pose from position and orientation attributes. More...
 
const Eigen::Vector3d & get_linear_velocity () const
 Getter of the linear velocity attribute. More...
 
const Eigen::Vector3d & get_angular_velocity () const
 Getter of the angular velocity attribute. More...
 
Eigen::Matrix< double, 6, 1 > get_twist () const
 Getter of the 6d twist from linear and angular velocity attributes. More...
 
const Eigen::Vector3d & get_linear_acceleration () const
 Getter of the linear acceleration attribute. More...
 
const Eigen::Vector3d & get_angular_acceleration () const
 Getter of the angular acceleration attribute. More...
 
Eigen::Matrix< double, 6, 1 > get_acceleration () const
 Getter of the 6d acceleration from linear and angular acceleration attributes. More...
 
const Eigen::Vector3d & get_force () const
 Getter of the force attribute. More...
 
const Eigen::Vector3d & get_torque () const
 Getter of the torque attribute. More...
 
Eigen::Matrix< double, 6, 1 > get_wrench () const
 Getter of the 6d wrench from force and torque attributes. More...
 
void set_position (const Eigen::Vector3d &position)
 Setter of the position. More...
 
void set_position (const std::vector< double > &position)
 Setter of the position from a std vector. More...
 
void set_position (const double &x, const double &y, const double &z)
 Setter of the position from three scalar coordinates. More...
 
void set_orientation (const Eigen::Quaterniond &orientation)
 Setter of the orientation. More...
 
void set_orientation (const Eigen::Vector4d &orientation)
 Setter of the orientation from a 4d vector. More...
 
void set_orientation (const std::vector< double > &orientation)
 Setter of the orientation from a std vector. More...
 
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) More...
 
void set_pose (const Eigen::Vector3d &position, const Eigen::Quaterniond &orientation)
 Setter of the pose from both position and orientation. More...
 
void set_pose (const Eigen::Matrix< double, 7, 1 > &pose)
 Setter of the pose from both position and orientation as Eigen 7d vector. More...
 
void set_pose (const std::vector< double > &pose)
 Setter of the pose from both position and orientation as std vector. More...
 
void set_linear_velocity (const Eigen::Vector3d &linear_velocity)
 Setter of the linear velocity attribute. More...
 
void set_linear_velocity (const std::vector< double > &linear_velocity)
 Setter of the linear velocity from a std vector. More...
 
void set_linear_velocity (const double &x, const double &y, const double &z)
 Setter of the linear velocity from three scalar coordinates. More...
 
void set_angular_velocity (const Eigen::Vector3d &angular_velocity)
 Setter of the angular velocity attribute. More...
 
void set_angular_velocity (const std::vector< double > &angular_velocity)
 Setter of the angular velocity from a std vector. More...
 
void set_angular_velocity (const double &x, const double &y, const double &z)
 Setter of the angular velocity from three scalar coordinates. More...
 
void set_twist (const Eigen::Matrix< double, 6, 1 > &twist)
 Setter of the linear and angular velocities from a 6d twist vector. More...
 
void set_twist (const std::vector< double > &twist)
 Setter of the linear and angular velocities from a std vector. More...
 
void set_linear_acceleration (const Eigen::Vector3d &linear_acceleration)
 Setter of the linear acceleration attribute. More...
 
void set_linear_acceleration (const std::vector< double > &linear_acceleration)
 Setter of the linear acceleration from a std vector. More...
 
void set_linear_acceleration (const double &x, const double &y, const double &z)
 Setter of the linear acceleration from three scalar coordinates. More...
 
void set_angular_acceleration (const Eigen::Vector3d &angular_acceleration)
 Setter of the angular velocity attribute. More...
 
void set_angular_acceleration (const std::vector< double > &angular_acceleration)
 Setter of the angular acceleration from a std vector. More...
 
void set_angular_acceleration (const double &x, const double &y, const double &z)
 Setter of the angular acceleration from three scalar coordinates. More...
 
void set_acceleration (const Eigen::Matrix< double, 6, 1 > &acceleration)
 Setter of the linear and angular acceleration from a 6d acceleration vector. More...
 
void set_acceleration (const std::vector< double > &acceleration)
 Setter of the linear and angular acceleration from a std vector. More...
 
void set_force (const Eigen::Vector3d &force)
 Setter of the force attribute. More...
 
void set_force (const std::vector< double > &force)
 Setter of the force from a std vector. More...
 
void set_force (const double &x, const double &y, const double &z)
 Setter of the force from three scalar coordinates. More...
 
void set_torque (const Eigen::Vector3d &torque)
 Setter of the torque attribute. More...
 
void set_torque (const std::vector< double > &torque)
 Setter of the torque from a std vector. More...
 
void set_torque (const double &x, const double &y, const double &z)
 Setter of the torque from three scalar coordinates. More...
 
void set_wrench (const Eigen::Matrix< double, 6, 1 > &wrench)
 Setter of the force and torque from a 6d wrench vector. More...
 
void set_wrench (const std::vector< double > &wrench)
 Setter of the force and torque from a std vector. More...
 
void initialize () override
 Initialize the CartesianState to a zero value. More...
 
void set_zero ()
 Set the State to a zero value. More...
 
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. More...
 
CartesianState copy () const
 Return a copy of the CartesianState. More...
 
virtual Eigen::VectorXd data () const
 Return the data as the concatenation of all the state variables in a single vector. More...
 
Eigen::ArrayXd array () const
 Return the data vector as an Eigen Array. More...
 
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. More...
 
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. More...
 
CartesianStateoperator*= (const CartesianState &state)
 Overload the *= operator with another state by deriving the equations of motions. More...
 
CartesianState operator* (const CartesianState &state) const
 Overload the * operator with another state by deriving the equations of motions. More...
 
CartesianStateoperator*= (double lambda)
 Overload the *= operator with a scalar. More...
 
CartesianState operator* (double lambda) const
 Overload the * operator with a scalar. More...
 
CartesianStateoperator/= (double lambda)
 Overload the /= operator with a scalar. More...
 
CartesianState operator/ (double lambda) const
 Overload the / operator with a scalar. More...
 
CartesianStateoperator+= (const CartesianState &state)
 Overload the += operator. More...
 
CartesianState operator+ (const CartesianState &state) const
 Overload the + operator. More...
 
CartesianStateoperator-= (const CartesianState &state)
 Overload the -= operator. More...
 
CartesianState operator- (const CartesianState &state) const
 Overload the - operator. More...
 
CartesianState inverse () const
 Compute the inverse of the current CartesianState. More...
 
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. More...
 
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) More...
 
void normalize (const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL)
 Normalize inplace the state at the state variable given in argument (default is full state) More...
 
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) More...
 
std::vector< double > to_std_vector () const
 Return the state as a std vector. 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...
 

Static Public Member Functions

static CartesianTwist Zero (const std::string &name, const std::string &reference="world")
 Constructor for the zero twist. More...
 
static CartesianTwist Random (const std::string &name, const std::string &reference="world")
 Constructor for a random twist. More...
 
- 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 CartesianState (identity pose and 0 for the rest) More...
 
static CartesianState Random (const std::string &name, const std::string &reference="world")
 Constructor for a random state. More...
 

Friends

CartesianState operator*= (const CartesianState &state, const CartesianTwist &twist)=delete
 
std::ostream & operator<< (std::ostream &os, const CartesianTwist &twist)
 Overload the ostream operator for printing. More...
 
CartesianTwist operator* (const CartesianState &state, const CartesianTwist &twist)
 Overload the * operator with a CartesianState. More...
 
CartesianTwist operator* (double lambda, const CartesianTwist &twist)
 Overload the * operator with a scalar. More...
 
CartesianTwist operator* (const Eigen::Matrix< double, 6, 6 > &lambda, const CartesianTwist &twist)
 Overload the * operator with a gain matrix. More...
 
CartesianPose operator* (const std::chrono::nanoseconds &dt, const CartesianTwist &twist)
 Overload the * operator with a time period. More...
 

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. More...
 
void set_state_variable (const Eigen::VectorXd &new_value, const CartesianStateVariable &state_variable_type)
 Setter of the variable value corresponding to the input. More...
 
- Protected Member Functions inherited from state_representation::State
void set_type (const StateType &type)
 Override the state type. More...
 

Detailed Description

Class to define twist in cartesian space as 3D linear and angular velocity vectors.

Definition at line 15 of file CartesianTwist.hpp.

Constructor & Destructor Documentation

◆ CartesianTwist() [1/9]

state_representation::CartesianTwist::CartesianTwist ( )
explicit

Empty constructor.

Definition at line 7 of file CartesianTwist.cpp.

◆ CartesianTwist() [2/9]

state_representation::CartesianTwist::CartesianTwist ( 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

Definition at line 11 of file CartesianTwist.cpp.

◆ CartesianTwist() [3/9]

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

Copy constructor.

Definition at line 47 of file CartesianTwist.cpp.

◆ CartesianTwist() [4/9]

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

Copy constructor from a CartesianState.

Definition at line 39 of file CartesianTwist.cpp.

◆ CartesianTwist() [5/9]

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

Copy constructor from a CartesianPose by considering that it is equivalent to dividing the pose by 1 second.

Definition at line 50 of file CartesianTwist.cpp.

◆ CartesianTwist() [6/9]

state_representation::CartesianTwist::CartesianTwist ( const CartesianAcceleration acceleration)

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

Definition at line 52 of file CartesianTwist.cpp.

◆ CartesianTwist() [7/9]

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

Construct a CartesianTwist from a linear velocity given as a vector.

Definition at line 16 of file CartesianTwist.cpp.

◆ CartesianTwist() [8/9]

state_representation::CartesianTwist::CartesianTwist ( const std::string &  name,
const Eigen::Vector3d &  linear_velocity,
const Eigen::Vector3d &  angular_velocity,
const std::string &  reference = "world" 
)
explicit

Construct a CartesianTwist from a linear velocity and angular velocity given as vectors.

Definition at line 23 of file CartesianTwist.cpp.

◆ CartesianTwist() [9/9]

state_representation::CartesianTwist::CartesianTwist ( const std::string &  name,
const Eigen::Matrix< double, 6, 1 > &  twist,
const std::string &  reference = "world" 
)
explicit

Construct a CartesianTwist from a single 6d twist vector.

Definition at line 32 of file CartesianTwist.cpp.

Member Function Documentation

◆ clamp()

void state_representation::CartesianTwist::clamp ( double  max_linear,
double  max_angular,
double  linear_noise_ratio = 0,
double  angular_noise_ratio = 0 
)

Clamp inplace the magnitude of the twist to the values in argument.

Parameters
max_linearthe maximum magnitude of the linear velocity
max_angularthe maximum magnitude of the angular velocity
linear_noise_ratioif provided, this value will be used to apply a deadzone under which the linear velocity will be set to 0
angular_noise_ratioif provided, this value will be used to apply a deadzone under which the angular velocity will be set to 0

Definition at line 148 of file CartesianTwist.cpp.

◆ clamped()

CartesianTwist state_representation::CartesianTwist::clamped ( double  max_linear,
double  max_angular,
double  noise_ratio = 0,
double  angular_noise_ratio = 0 
) const

Return the clamped twist.

Parameters
max_linearthe maximum magnitude of the linear velocity
max_angularthe maximum magnitude of the angular velocity
noise_ratioif provided, this value will be used to apply a deadzone under which the linear velocity will be set to 0
angular_noise_ratioif provided, this value will be used to apply a deadzone under which the angular velocity will be set to 0
Returns
the clamped twist

Definition at line 157 of file CartesianTwist.cpp.

◆ copy()

CartesianTwist state_representation::CartesianTwist::copy ( ) const

Return a copy of the CartesianTwist.

Returns
the copy

Definition at line 165 of file CartesianTwist.cpp.

◆ data()

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

Returns the twist data as an Eigen vector.

Returns
the twist data vector

Reimplemented from state_representation::CartesianState.

Definition at line 170 of file CartesianTwist.cpp.

◆ inverse()

CartesianTwist state_representation::CartesianTwist::inverse ( ) const

Compute the inverse of the current CartesianTwist.

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

Definition at line 186 of file CartesianTwist.cpp.

◆ normalized()

CartesianTwist state_representation::CartesianTwist::normalized ( const CartesianStateVariable &  state_variable_type = CartesianStateVariable::TWIST) const
inline

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

Parameters
state_variable_typethe type of state variable to compute the norms on
Returns
the normalized twist

Definition at line 327 of file CartesianTwist.hpp.

◆ norms()

std::vector< double > state_representation::CartesianTwist::norms ( const CartesianStateVariable &  state_variable_type = CartesianStateVariable::TWIST) const
inlineoverridevirtual

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

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 323 of file CartesianTwist.hpp.

◆ operator*() [1/2]

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

Overload the * operator with a time period.

Parameters
dtthe time period to multiply with
Returns
the CartesianPose corresponding to the displacement over the time period

Definition at line 112 of file CartesianTwist.cpp.

◆ operator*() [2/2]

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

Overload the * operator with a scalar.

Parameters
lambdathe scalar to multiply with
Returns
the CartesianTwist multiplied by lambda

Definition at line 88 of file CartesianTwist.cpp.

◆ operator*=() [1/2]

CartesianTwist & state_representation::CartesianTwist::operator*= ( const Eigen::Matrix< double, 6, 6 > &  lambda)

Overload the *= operator with a gain matrix.

Parameters
lambdathe matrix to multiply with
Returns
the CartesianTwist multiplied by lambda

Definition at line 101 of file CartesianTwist.cpp.

◆ operator*=() [2/2]

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

Overload the *= operator with a scalar.

Parameters
lambdathe scalar to multiply with
Returns
the CartesianTwist multiplied by lambda

Definition at line 83 of file CartesianTwist.cpp.

◆ operator+()

CartesianTwist state_representation::CartesianTwist::operator+ ( const CartesianTwist twist) const

Overload the + operator with a twist.

Parameters
twistCartesianTwist to add to
Returns
the current CartesianTwist added the CartesianTwist given in argument

Definition at line 70 of file CartesianTwist.cpp.

◆ operator+=()

CartesianTwist & state_representation::CartesianTwist::operator+= ( const CartesianTwist twist)

Overload the += operator.

Parameters
twistCartesianTwist to add to
Returns
the current CartesianTwist added the CartesianTwist given in argument

Definition at line 65 of file CartesianTwist.cpp.

◆ operator-()

CartesianTwist state_representation::CartesianTwist::operator- ( const CartesianTwist twist) const

Overload the - operator with a twist.

Parameters
twistCartesianTwist to subtract
Returns
the current CartesianTwist minus the CartesianTwist given in argument

Definition at line 79 of file CartesianTwist.cpp.

◆ operator-=()

CartesianTwist & state_representation::CartesianTwist::operator-= ( const CartesianTwist twist)

Overload the -= operator.

Parameters
twistCartesianTwist to subtract
Returns
the current CartesianTwist minus the CartesianTwist given in argument

Definition at line 74 of file CartesianTwist.cpp.

◆ operator/() [1/2]

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

Overload the / operator with a time period.

Parameters
dtthe time period to divide by
Returns
the corresponding CartesianAcceleration

Definition at line 135 of file CartesianTwist.cpp.

◆ operator/() [2/2]

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

Overload the / operator with a scalar.

Parameters
lambdathe scalar to divide with
Returns
the CartesianTwist divided by lambda

Definition at line 97 of file CartesianTwist.cpp.

◆ operator/=()

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

Overload the /= operator with a scalar.

Parameters
lambdathe scalar to divide with
Returns
the CartesianTwist divided by lambda

Definition at line 92 of file CartesianTwist.cpp.

◆ operator=()

CartesianTwist & state_representation::CartesianTwist::operator= ( const CartesianTwist twist)
default

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

Parameters
twistthe twist with value to assign
Returns
reference to the current twist with new values

◆ Random()

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

Constructor for a random twist.

Parameters
namethe name of the state
referencethe name of the reference frame
Returns
CartesianTwist random twist

Definition at line 59 of file CartesianTwist.cpp.

◆ set_data() [1/2]

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

Set the twist data from an Eigen vector.

Parameters
thetwist data vector

Reimplemented from state_representation::CartesianState.

Definition at line 174 of file CartesianTwist.cpp.

◆ set_data() [2/2]

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

Set the twist data from a std vector.

Parameters
thetwist data vector

Reimplemented from state_representation::CartesianState.

Definition at line 182 of file CartesianTwist.cpp.

◆ Zero()

CartesianTwist state_representation::CartesianTwist::Zero ( const std::string &  name,
const std::string &  reference = "world" 
)
static

Constructor for the zero twist.

Parameters
namethe name of the state
referencethe name of the reference frame
Returns
CartesianTwist with zero values

Definition at line 55 of file CartesianTwist.cpp.

Friends And Related Function Documentation

◆ operator* [1/4]

CartesianTwist operator* ( const CartesianState state,
const CartesianTwist twist 
)
friend

Overload the * operator with a CartesianState.

Parameters
statethe state to multiply with
Returns
the CartesianTwist provided multiplied by the state

Definition at line 205 of file CartesianTwist.cpp.

◆ operator* [2/4]

CartesianTwist operator* ( const Eigen::Matrix< double, 6, 6 > &  lambda,
const CartesianTwist twist 
)
friend

Overload the * operator with a gain matrix.

Parameters
lambdathe matrix to multiply with
Returns
the CartesianTwist provided multiplied by lambda

Definition at line 213 of file CartesianTwist.cpp.

◆ operator* [3/4]

CartesianPose operator* ( const std::chrono::nanoseconds &  dt,
const CartesianTwist twist 
)
friend

Overload the * operator with a time period.

Parameters
dtthe time period to multiply with
Returns
the CartesianPose corresponding to the displacement over the time period

Definition at line 219 of file CartesianTwist.cpp.

◆ operator* [4/4]

CartesianTwist operator* ( double  lambda,
const CartesianTwist twist 
)
friend

Overload the * operator with a scalar.

Parameters
lambdathe scalar to multiply with
Returns
the CartesianTwist provided multiplied by lambda

Definition at line 209 of file CartesianTwist.cpp.

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const CartesianTwist twist 
)
friend

Overload the ostream operator for printing.

Parameters
osthe ostream to append the string representing the CartesianTwist to
CartesianTwistthe CartesianTwist to print
Returns
the appended ostream

Definition at line 190 of file CartesianTwist.cpp.


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