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

Class to define CartesianPose 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
 
CartesianState operator*= (const CartesianState &state)=delete
 
 CartesianPose ()
 Empty constructor. More...
 
 CartesianPose (const std::string &name, const std::string &reference="world")
 Constructor with name and reference frame provided. More...
 
 CartesianPose (const CartesianPose &pose)
 Copy constructor. More...
 
 CartesianPose (const CartesianState &state)
 Copy constructor from a CartesianState. More...
 
 CartesianPose (const CartesianTwist &twist)
 Copy constructor from a CartesianTwist by considering that it is a displacement over 1 second. More...
 
 CartesianPose (const std::string &name, const Eigen::Vector3d &position, const std::string &reference="world")
 Constructor of a CartesianPose from a position given as a vector of coordinates. More...
 
 CartesianPose (const std::string &name, double x, double y, double z, const std::string &reference="world")
 Constructor of a CartesianPose from a position given as three scalar coordinates. More...
 
 CartesianPose (const std::string &name, const Eigen::Quaterniond &orientation, const std::string &reference="world")
 Constructor of a CartesianPose from a quaternion. More...
 
 CartesianPose (const std::string &name, const Eigen::Vector3d &position, const Eigen::Quaterniond &orientation, const std::string &reference="world")
 Constructor of a CartesianPose from a position given as a vector of coordinates and a quaternion. More...
 
CartesianPoseoperator= (const CartesianPose &pose)=default
 Copy assignment operator that have to be defined to the custom assignment operator. More...
 
Eigen::Vector3d operator* (const Eigen::Vector3d &vector) const
 Overload the * operator for a vector input. More...
 
CartesianPoseoperator*= (const CartesianPose &pose)
 Overload the *= operator. More...
 
CartesianPose operator* (const CartesianPose &pose) const
 Overload the * operator. More...
 
CartesianState operator* (const CartesianState &state) const
 Overload the * operator. More...
 
CartesianTwist operator* (const CartesianTwist &twist) const
 Overload the * operator. More...
 
CartesianAcceleration operator* (const CartesianAcceleration &acceleration) const
 Overload the * operator. More...
 
CartesianWrench operator* (const CartesianWrench &wrench) const
 Overload the * operator. More...
 
CartesianPoseoperator*= (double lambda)
 Overload the *= operator with a scalar. More...
 
CartesianPose operator* (double lambda) const
 Overload the * operator with a scalar. More...
 
CartesianPoseoperator/= (double lambda)
 Overload the /= operator with a scalar. More...
 
CartesianPose operator/ (double lambda) const
 Overload the / operator with a scalar. More...
 
CartesianPoseoperator+= (const CartesianPose &pose)
 Overload the += operator. More...
 
CartesianPose operator+ (const CartesianPose &pose) const
 Overload the + operator with a pose. More...
 
CartesianPoseoperator-= (const CartesianPose &pose)
 Overload the -= operator. More...
 
CartesianPose operator- (const CartesianPose &pose) const
 Overload the - operator with a pose. More...
 
CartesianTwist operator/ (const std::chrono::nanoseconds &dt) const
 Overload the / operator with a time period. More...
 
CartesianPose copy () const
 Return a copy of the CartesianPose. More...
 
Eigen::VectorXd data () const override
 Returns the pose data as an Eigen vector. More...
 
void set_data (const Eigen::VectorXd &data) override
 Set the pose data from an Eigen vector. More...
 
void set_data (const std::vector< double > &data) override
 Set the pose data from a std vector. More...
 
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) More...
 
CartesianPose inverse () const
 Compute the inverse of the current CartesianPose. More...
 
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) 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 CartesianPose Identity (const std::string &name, const std::string &reference="world")
 Constructor for the identity pose. More...
 
static CartesianPose Random (const std::string &name, const std::string &reference="world")
 Constructor for a random pose. 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 CartesianPose &pose)=delete
 
std::ostream & operator<< (std::ostream &os, const CartesianPose &pose)
 Overload the ostream operator for printing. More...
 
CartesianPose operator* (const CartesianState &state, const CartesianPose &pose)
 Overload the * operator with a CartesianState. More...
 
CartesianPose operator* (double lambda, const CartesianPose &pose)
 Overload the * operator with a scalar. 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 CartesianPose in cartesian space as 3D position and quaternion based orientation.

Definition at line 17 of file CartesianPose.hpp.

Constructor & Destructor Documentation

◆ CartesianPose() [1/9]

state_representation::CartesianPose::CartesianPose ( )
explicit

Empty constructor.

Definition at line 8 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 12 of file CartesianPose.cpp.

◆ CartesianPose() [3/9]

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

Copy constructor.

Definition at line 53 of file CartesianPose.cpp.

◆ CartesianPose() [4/9]

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

Copy constructor from a CartesianState.

Definition at line 45 of file CartesianPose.cpp.

◆ CartesianPose() [5/9]

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

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

Definition at line 55 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 CartesianPose 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 16 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 CartesianPose 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 22 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 CartesianPose 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 29 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 CartesianPose 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 36 of file CartesianPose.cpp.

Member Function Documentation

◆ copy()

CartesianPose state_representation::CartesianPose::copy ( ) const

Return a copy of the CartesianPose.

Returns
the copy

Definition at line 151 of file CartesianPose.cpp.

◆ data()

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

Returns the pose data as an Eigen vector.

Returns
the pose data vector

Reimplemented from state_representation::CartesianState.

Definition at line 156 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
CartesianPose identity pose

Definition at line 57 of file CartesianPose.cpp.

◆ inverse()

CartesianPose state_representation::CartesianPose::inverse ( ) const

Compute the inverse of the current CartesianPose.

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

Definition at line 172 of file CartesianPose.cpp.

◆ normalized()

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

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

Definition at line 337 of file CartesianPose.hpp.

◆ norms()

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

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 333 of file CartesianPose.hpp.

◆ operator*() [1/7]

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

Overload the * operator.

Parameters
accelerationCartesianAcceleration to multiply with
Returns
the current CartesianPose multiplied by the CartesianAcceleration given in argument

Definition at line 86 of file CartesianPose.cpp.

◆ operator*() [2/7]

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

Overload the * operator.

Parameters
poseCartesianPose to multiply with
Returns
the current CartesianPose multiplied by the CartesianPose given in argument

Definition at line 74 of file CartesianPose.cpp.

◆ operator*() [3/7]

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

Overload the * operator.

Parameters
stateCartesianState to multiply with
Returns
the current CartesianPose multiplied by the CartesianState given in argument

Definition at line 78 of file CartesianPose.cpp.

◆ operator*() [4/7]

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

Overload the * operator.

Parameters
twistCartesianTwist to multiply with
Returns
the current CartesianPose multiplied by the CartesianTwist given in argument

Definition at line 82 of file CartesianPose.cpp.

◆ operator*() [5/7]

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

Overload the * operator.

Parameters
wrenchCartesianWrench to multiply with
Returns
the current CartesianPose multiplied by the CartesianWrench given in argument

Definition at line 90 of file CartesianPose.cpp.

◆ operator*() [6/7]

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

Overload the * operator for a vector input.

Parameters
vectorvector to multiply with, representing either a position, velocity or acceleration
Returns
the vector multiplied by the current CartesianPose

Definition at line 65 of file CartesianPose.cpp.

◆ operator*() [7/7]

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

Overload the * operator with a scalar.

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

Definition at line 99 of file CartesianPose.cpp.

◆ operator*=() [1/2]

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

Overload the *= operator.

Parameters
poseCartesianPose to multiply with
Returns
the current CartesianPose multiplied by the CartesianPose given in argument

Definition at line 69 of file CartesianPose.cpp.

◆ operator*=() [2/2]

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

Overload the *= operator with a scalar.

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

Definition at line 94 of file CartesianPose.cpp.

◆ operator+()

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

Overload the + operator with a pose.

Parameters
poseCartesianPose to add to
Returns
the current CartesianPose added the CartesianPose given in argument

Definition at line 117 of file CartesianPose.cpp.

◆ operator+=()

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

Overload the += operator.

Parameters
poseCartesianPose to add to
Returns
the current CartesianPose added the CartesianPose given in argument

Definition at line 112 of file CartesianPose.cpp.

◆ operator-()

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

Overload the - operator with a pose.

Parameters
poseCartesianPose to subtract
Returns
the current CartesianPose minus the CartesianPose given in argument

Definition at line 126 of file CartesianPose.cpp.

◆ operator-=()

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

Overload the -= operator.

Parameters
poseCartesianPose to subtract
Returns
the current CartesianPose minus the CartesianPose given in argument

Definition at line 121 of file CartesianPose.cpp.

◆ operator/() [1/2]

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

Overload the / operator with a time period.

Parameters
dtthe time period to divide by
Returns
the corresponding CartesianTwist

Definition at line 130 of file CartesianPose.cpp.

◆ operator/() [2/2]

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

Overload the / operator with a scalar.

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

Definition at line 108 of file CartesianPose.cpp.

◆ operator/=()

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

Overload the /= operator with a scalar.

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

Definition at line 103 of file CartesianPose.cpp.

◆ operator=()

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

Copy assignment operator that have 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
CartesianPose random pose

Definition at line 61 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.

Parameters
thepose data vector

Reimplemented from state_representation::CartesianState.

Definition at line 160 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.

Parameters
thepose data vector

Reimplemented from state_representation::CartesianState.

Definition at line 168 of file CartesianPose.cpp.

Friends And Related Function Documentation

◆ operator* [1/2]

CartesianPose operator* ( const CartesianState state,
const CartesianPose pose 
)
friend

Overload the * operator with a CartesianState.

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

Definition at line 197 of file CartesianPose.cpp.

◆ operator* [2/2]

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

Overload the * operator with a scalar.

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

Definition at line 201 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 CartesianPose to
CartesianPosethe CartesianPose to print
Returns
the appended ostream

Definition at line 176 of file CartesianPose.cpp.


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