Control Libraries 6.3.4
|
Class to represent a state in Cartesian space. More...
#include <CartesianState.hpp>
Public Member Functions | |
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. | |
CartesianState & | operator= (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... | |
CartesianState & | operator*= (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... | |
CartesianState & | operator*= (double lambda) |
Overload the *= operator with a scalar. More... | |
CartesianState | operator* (double lambda) const |
Overload the * operator with a scalar. More... | |
CartesianState & | operator/= (double lambda) |
Overload the /= operator with a scalar. More... | |
CartesianState | operator/ (double lambda) const |
Overload the / operator with a scalar. More... | |
CartesianState & | operator+= (const CartesianState &state) |
Overload the += operator. More... | |
CartesianState | operator+ (const CartesianState &state) const |
Overload the + operator. More... | |
CartesianState & | operator-= (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. | |
SpatialState & | operator= (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. | |
State & | operator= (const State &state) |
Copy assignment operator that have to be defined to the custom assignment operator. More... | |
const StateType & | get_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 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... | |
Protected Member Functions | |
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... | |
Friends | |
void | swap (CartesianState &state1, CartesianState &state2) |
Swap the values of the two CartesianState. More... | |
std::ostream & | operator<< (std::ostream &os, const CartesianState &state) |
Overload the ostream operator for printing. More... | |
CartesianState | operator* (double lambda, const CartesianState &state) |
Overload the * operator with a scalar. More... | |
double | dist (const CartesianState &s1, const CartesianState &s2, const CartesianStateVariable &state_variable_type) |
compute the distance between two CartesianStates More... | |
Class to represent a state in Cartesian space.
Definition at line 47 of file CartesianState.hpp.
|
explicit |
Empty constructor.
Definition at line 9 of file CartesianState.cpp.
|
explicit |
Constructor with name and reference frame provided.
name | the name of the state |
reference | the name of the reference frame |
Definition at line 13 of file CartesianState.cpp.
Eigen::ArrayXd state_representation::CartesianState::array | ( | ) | const |
Return the data vector as an Eigen Array.
Definition at line 329 of file CartesianState.cpp.
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.
max_norm | the maximum norm of the state variable |
state_variable_type | name of the variable from the CartesianStateVariable structure to clamp |
noise_ratio | if 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 481 of file CartesianState.cpp.
CartesianState state_representation::CartesianState::copy | ( | ) | const |
Return a copy of the CartesianState.
Definition at line 312 of file CartesianState.cpp.
|
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 317 of file CartesianState.cpp.
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.
state | the second state |
state_variable_type | name of the variable from the CartesianStateVariable structure to apply the distance on. Default ALL for full distance across all dimensions |
Definition at line 499 of file CartesianState.cpp.
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 96 of file CartesianState.cpp.
const Eigen::Vector3d & state_representation::CartesianState::get_angular_acceleration | ( | ) | const |
Getter of the angular acceleration attribute.
Definition at line 92 of file CartesianState.cpp.
const Eigen::Vector3d & state_representation::CartesianState::get_angular_velocity | ( | ) | const |
Getter of the angular velocity attribute.
Definition at line 78 of file CartesianState.cpp.
const Eigen::Vector3d & state_representation::CartesianState::get_force | ( | ) | const |
Getter of the force attribute.
Definition at line 102 of file CartesianState.cpp.
const Eigen::Vector3d & state_representation::CartesianState::get_linear_acceleration | ( | ) | const |
Getter of the linear acceleration attribute.
Definition at line 88 of file CartesianState.cpp.
const Eigen::Vector3d & state_representation::CartesianState::get_linear_velocity | ( | ) | const |
Getter of the linear velocity attribute.
Definition at line 74 of file CartesianState.cpp.
const Eigen::Quaterniond & state_representation::CartesianState::get_orientation | ( | ) | const |
Getter of the orientation attribute.
Definition at line 52 of file CartesianState.cpp.
Eigen::Vector4d state_representation::CartesianState::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.
Definition at line 56 of file CartesianState.cpp.
Eigen::Matrix< double, 7, 1 > state_representation::CartesianState::get_pose | ( | ) | const |
Getter of a pose from position and orientation attributes.
Definition at line 62 of file CartesianState.cpp.
const Eigen::Vector3d & state_representation::CartesianState::get_position | ( | ) | const |
Getter of the position attribute.
Definition at line 48 of file CartesianState.cpp.
|
inlineprotected |
Getter of the variable value corresponding to the input.
state_variable_type | the type of variable to get |
Definition at line 618 of file CartesianState.hpp.
const Eigen::Vector3d & state_representation::CartesianState::get_torque | ( | ) | const |
Getter of the torque attribute.
Definition at line 106 of file CartesianState.cpp.
Eigen::Matrix4d state_representation::CartesianState::get_transformation_matrix | ( | ) | const |
Getter of a pose from position and orientation attributes.
Definition at line 68 of file CartesianState.cpp.
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 82 of file CartesianState.cpp.
Eigen::Matrix< double, 6, 1 > state_representation::CartesianState::get_wrench | ( | ) | const |
Getter of the 6d wrench from force and torque attributes.
Definition at line 110 of file CartesianState.cpp.
|
static |
Constructor for the identity CartesianState (identity pose and 0 for the rest)
name | the name of the state |
reference | the name of the reference frame |
Definition at line 34 of file CartesianState.cpp.
|
overridevirtual |
Initialize the CartesianState to a zero value.
Reimplemented from state_representation::State.
Definition at line 18 of file CartesianState.cpp.
CartesianState state_representation::CartesianState::inverse | ( | ) | const |
Compute the inverse of the current CartesianState.
Definition at line 449 of file CartesianState.cpp.
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)
state_variable_type | the type of state variable to compute the norms on |
Definition at line 592 of file CartesianState.cpp.
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)
state_variable_type | the type of state variable to compute the norms on |
Definition at line 630 of file CartesianState.cpp.
|
virtual |
Compute the norms of the state variable specified by the input type (default is full state)
state_variable_type | the type of state variable to compute the norms on |
Reimplemented in state_representation::CartesianAcceleration, state_representation::CartesianPose, state_representation::CartesianTwist, and state_representation::CartesianWrench.
Definition at line 552 of file CartesianState.cpp.
CartesianState state_representation::CartesianState::operator* | ( | const CartesianState & | state | ) | const |
Overload the * operator with another state by deriving the equations of motions.
state | the state to compose with corresponding to b_S_c |
Definition at line 377 of file CartesianState.cpp.
CartesianState state_representation::CartesianState::operator* | ( | double | lambda | ) | const |
Overload the * operator with a scalar.
lambda | the scalar to multiply with |
Definition at line 292 of file CartesianState.cpp.
CartesianState & state_representation::CartesianState::operator*= | ( | const CartesianState & | state | ) |
Overload the *= operator with another state by deriving the equations of motions.
state | the state to compose with corresponding to b_S_c |
Definition at line 333 of file CartesianState.cpp.
CartesianState & state_representation::CartesianState::operator*= | ( | double | lambda | ) |
Overload the *= operator with a scalar.
lambda | the scalar to multiply with |
Definition at line 274 of file CartesianState.cpp.
CartesianState state_representation::CartesianState::operator+ | ( | const CartesianState & | state | ) | const |
Overload the + operator.
state | CartesianState to add |
Definition at line 410 of file CartesianState.cpp.
CartesianState & state_representation::CartesianState::operator+= | ( | const CartesianState & | state | ) |
Overload the += operator.
state | CartesianState to add |
Definition at line 383 of file CartesianState.cpp.
CartesianState state_representation::CartesianState::operator- | ( | const CartesianState & | state | ) | const |
Overload the - operator.
state | CartesianState to subtract |
Definition at line 443 of file CartesianState.cpp.
CartesianState & state_representation::CartesianState::operator-= | ( | const CartesianState & | state | ) |
Overload the -= operator.
state | CartesianState to subtract |
Definition at line 416 of file CartesianState.cpp.
CartesianState state_representation::CartesianState::operator/ | ( | double | lambda | ) | const |
Overload the / operator with a scalar.
lambda | the scalar to divide with |
Definition at line 306 of file CartesianState.cpp.
CartesianState & state_representation::CartesianState::operator/= | ( | double | lambda | ) |
Overload the /= operator with a scalar.
lambda | the scalar to divide with |
Definition at line 298 of file CartesianState.cpp.
|
inline |
Copy assignment operator that have to be defined to the custom assignment operator.
state | the state with value to assign |
Definition at line 612 of file CartesianState.hpp.
|
static |
Constructor for a random state.
name | the name of the state |
reference | the name of the reference frame |
Definition at line 41 of file CartesianState.cpp.
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 226 of file CartesianState.cpp.
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 230 of file CartesianState.cpp.
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 222 of file CartesianState.cpp.
void state_representation::CartesianState::set_angular_acceleration | ( | const Eigen::Vector3d & | angular_acceleration | ) |
Setter of the angular velocity attribute.
Definition at line 214 of file CartesianState.cpp.
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 218 of file CartesianState.cpp.
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 186 of file CartesianState.cpp.
void state_representation::CartesianState::set_angular_velocity | ( | const Eigen::Vector3d & | angular_velocity | ) |
Setter of the angular velocity attribute.
Definition at line 178 of file CartesianState.cpp.
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 182 of file CartesianState.cpp.
|
overridevirtual |
Set the data of the state from all the state variables in a single Eigen vector.
the | concatenated data vector |
Reimplemented from state_representation::State.
Reimplemented in state_representation::CartesianAcceleration, state_representation::CartesianPose, state_representation::CartesianTwist, and state_representation::CartesianWrench.
Definition at line 321 of file CartesianState.cpp.
|
overridevirtual |
Set the data of the state from all the state variables in a single std vector.
the | concatenated data vector |
Reimplemented from state_representation::State.
Reimplemented in state_representation::CartesianAcceleration, state_representation::CartesianPose, state_representation::CartesianTwist, and state_representation::CartesianWrench.
Definition at line 325 of file CartesianState.cpp.
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 246 of file CartesianState.cpp.
void state_representation::CartesianState::set_force | ( | const Eigen::Vector3d & | force | ) |
Setter of the force attribute.
Definition at line 238 of file CartesianState.cpp.
void state_representation::CartesianState::set_force | ( | const std::vector< double > & | force | ) |
Setter of the force from a std vector.
Definition at line 242 of file CartesianState.cpp.
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 210 of file CartesianState.cpp.
void state_representation::CartesianState::set_linear_acceleration | ( | const Eigen::Vector3d & | linear_acceleration | ) |
Setter of the linear acceleration attribute.
Definition at line 202 of file CartesianState.cpp.
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 206 of file CartesianState.cpp.
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 174 of file CartesianState.cpp.
void state_representation::CartesianState::set_linear_velocity | ( | const Eigen::Vector3d & | linear_velocity | ) |
Setter of the linear velocity attribute.
Definition at line 166 of file CartesianState.cpp.
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 170 of file CartesianState.cpp.
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 144 of file CartesianState.cpp.
void state_representation::CartesianState::set_orientation | ( | const Eigen::Quaterniond & | orientation | ) |
Setter of the orientation.
Definition at line 128 of file CartesianState.cpp.
void state_representation::CartesianState::set_orientation | ( | const Eigen::Vector4d & | orientation | ) |
Setter of the orientation from a 4d vector.
the | orientation coefficients as a 4d vector. Beware, quaternion coefficients uses the (w, x, y, z) convention |
Definition at line 133 of file CartesianState.cpp.
void state_representation::CartesianState::set_orientation | ( | const std::vector< double > & | orientation | ) |
Setter of the orientation from a std vector.
the | orientation coefficients as a 4d vector. Beware, quaternion coefficients uses the (w, x, y, z) convention |
Definition at line 137 of file CartesianState.cpp.
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.
pose | the pose as a 7d vector. Beware, quaternion coefficients uses the (w, x, y, z) convention |
Definition at line 153 of file CartesianState.cpp.
void state_representation::CartesianState::set_pose | ( | const Eigen::Vector3d & | position, |
const Eigen::Quaterniond & | orientation | ||
) |
Setter of the pose from both position and orientation.
position | the position |
orientation | the orientation |
Definition at line 148 of file CartesianState.cpp.
void state_representation::CartesianState::set_pose | ( | const std::vector< double > & | pose | ) |
Setter of the pose from both position and orientation as std vector.
pose | the pose as a 7d vector. Beware, quaternion coefficients uses the (w, x, y, z) convention |
Definition at line 158 of file CartesianState.cpp.
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 124 of file CartesianState.cpp.
void state_representation::CartesianState::set_position | ( | const Eigen::Vector3d & | position | ) |
Setter of the position.
Definition at line 116 of file CartesianState.cpp.
void state_representation::CartesianState::set_position | ( | const std::vector< double > & | position | ) |
Setter of the position from a std vector.
Definition at line 120 of file CartesianState.cpp.
|
inlineprotected |
Setter of the variable value corresponding to the input.
new_value | the new value of the variable |
state_variable_type | the type of variable to get |
Definition at line 697 of file CartesianState.hpp.
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 258 of file CartesianState.cpp.
void state_representation::CartesianState::set_torque | ( | const Eigen::Vector3d & | torque | ) |
Setter of the torque attribute.
Definition at line 250 of file CartesianState.cpp.
void state_representation::CartesianState::set_torque | ( | const std::vector< double > & | torque | ) |
Setter of the torque from a std vector.
Definition at line 254 of file CartesianState.cpp.
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 190 of file CartesianState.cpp.
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 194 of file CartesianState.cpp.
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 262 of file CartesianState.cpp.
void state_representation::CartesianState::set_wrench | ( | const std::vector< double > & | wrench | ) |
Setter of the force and torque from a std vector.
Definition at line 266 of file CartesianState.cpp.
void state_representation::CartesianState::set_zero | ( | ) |
Set the State to a zero value.
Definition at line 23 of file CartesianState.cpp.
|
inline |
Return the state as a std vector.
Definition at line 758 of file CartesianState.hpp.
|
friend |
compute the distance between two CartesianStates
s1 | the first CartesianState |
s2 | the second CartesianState |
type | of the distance between position, orientation, linear_velocity, etc... default all for full distance across all dimensions |
s1 | the first CartesianState |
s2 | the second CartesianState |
state_variable_type | name of the state variable from the CartesianStateVariable structure to apply the distance on. Default ALL for full distance across all dimensions |
Definition at line 679 of file CartesianState.cpp.
|
friend |
Overload the * operator with a scalar.
lambda | the scalar to multiply with |
Definition at line 675 of file CartesianState.cpp.
|
friend |
Overload the ostream operator for printing.
os | the ostream to append the string representing the state to |
state | the state to print |
Definition at line 636 of file CartesianState.cpp.
|
friend |
Swap the values of the two CartesianState.
state1 | CartesianState to be swapped with 2 |
state2 | CartesianState to be swapped with 1 |
Definition at line 600 of file CartesianState.hpp.