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

Class to define a robot Jacobian matrix. More...

#include <Jacobian.hpp>

Inheritance diagram for state_representation::Jacobian:
state_representation::State

Public Member Functions

 Jacobian ()
 Empty constructor for a Jacobian.
 
 Jacobian (const std::string &robot_name, unsigned int nb_joints, const std::string &frame, const std::string &reference_frame="world")
 Constructor with name, number of joints, frame and reference frame provided.
 
 Jacobian (const std::string &robot_name, const std::vector< std::string > &joint_names, const std::string &frame, const std::string &reference_frame="world")
 Constructor with name, joint names, frame and reference frame provided.
 
 Jacobian (const std::string &robot_name, const std::string &frame, const Eigen::MatrixXd &data, const std::string &reference_frame="world")
 Constructor with name, frame, Jacobian matrix and reference frame provided.
 
 Jacobian (const std::string &robot_name, const std::vector< std::string > &joint_names, const std::string &frame, const Eigen::MatrixXd &data, const std::string &reference_frame="world")
 Constructor with name, joint names, frame, Jacobian matrix and reference frame provided.
 
 Jacobian (const Jacobian &jacobian)
 Copy constructor of a Jacobian.
 
Jacobianoperator= (const Jacobian &jacobian)
 Copy assignment operator that has to be defined to the custom assignment operator.
 
unsigned int rows () const
 Getter of the number of rows attribute.
 
Eigen::VectorXd row (unsigned int index) const
 Accessor of the row data at given index.
 
unsigned int cols () const
 Getter of the number of columns attribute.
 
Eigen::VectorXd col (unsigned int index) const
 Accessor of the column data at given index.
 
const std::vector< std::string > & get_joint_names () const
 Getter of the joint names attribute.
 
const std::string & get_frame () const
 Getter of the frame attribute.
 
const std::string & get_reference_frame () const
 Getter of the reference frame attribute.
 
const Eigen::MatrixXd & data () const
 Getter of the data attribute.
 
void set_joint_names (unsigned int nb_joints)
 Setter of the joint names attribute from the number of joints.
 
void set_joint_names (const std::vector< std::string > &joint_names)
 Setter of the joint names attribute from a vector of joint names.
 
void set_frame (const std::string &frame)
 Setter of the frame.
 
void set_reference_frame (const std::string &reference_frame)
 Setter of the reference frame.
 
void set_data (const Eigen::MatrixXd &data) override
 Setter of the data attribute.
 
void set_zero ()
 Set the Jacobian matrix to a zero value.
 
Jacobian copy () const
 Return a copy of the Jacobian.
 
void reset () override
 Reset the object to a post-construction state.
 
Eigen::MatrixXd inverse () const
 Return the inverse of the Jacobian matrix.
 
Eigen::MatrixXd inverse (const Eigen::MatrixXd &matrix) const
 Solve the system X = inv(J) * M to obtain X.
 
JointVelocities inverse (const CartesianTwist &twist) const
 Transform the given Cartesian twist to joint space.
 
bool is_incompatible (const State &state) const override
 Check if the Jacobian is incompatible for operations with the state given as argument.
 
Eigen::MatrixXd pseudoinverse () const
 Return the pseudoinverse of the Jacobian matrix.
 
Eigen::MatrixXd pseudoinverse (const Eigen::MatrixXd &matrix) const
 Multiply the given matrix by the pseudoinverse of the Jacobian matrix.
 
JointVelocities pseudoinverse (const CartesianTwist &twist) const
 Transform a Cartesian twist to joint space by pre-multiplying the Jacobian pseudoinverse.
 
Eigen::MatrixXd transpose () const
 Return the transpose of the Jacobian matrix.
 
JointTorques transpose (const CartesianWrench &wrench) const
 Transform a Cartesian wrench to joint space by pre-multiplying the Jacobian transpose.
 
Eigen::MatrixXd operator* (const Eigen::MatrixXd &matrix) const
 Overload the * operator with an arbitrary matrix.
 
CartesianTwist operator* (const JointVelocities &dq) const
 Overload the * operator with a JointVelocities.
 
double & operator() (unsigned int row, unsigned int col)
 Overload the () operator in a non const fashion to modify the value at given (row, col)
 
const double & operator() (unsigned int row, unsigned int col) const
 Overload the () operator in const fashion to access the value at given (row, col)
 
- Public Member Functions inherited from state_representation::State
 State ()
 Empty constructor.
 
 State (const std::string &name)
 Constructor with name specification.
 
 State (const State &state)
 Copy constructor from another state.
 
virtual ~State ()=default
 Virtual destructor.
 
Stateoperator= (const State &state)
 Copy assignment operator that has to be defined to the custom assignment operator.
 
const StateTypeget_type () const
 Getter of the type attribute.
 
const std::string & get_name () const
 Getter of the name attribute.
 
bool is_empty () const
 Getter of the empty attribute.
 
const std::chrono::time_point< std::chrono::steady_clock > & get_timestamp () const
 Getter of the timestamp attribute.
 
virtual void set_name (const std::string &name)
 Setter of the name attribute.
 
void reset_timestamp ()
 Reset the timestamp attribute to now.
 
virtual void set_data (const Eigen::VectorXd &data)
 Set the data of the state from an Eigen vector.
 
virtual void set_data (const std::vector< double > &data)
 Set the data of the state from a std vector.
 
double get_age () const
 Get the age of the state, i.e. the time since the last modification.
 
bool is_deprecated (double time_delay) const
 Check if the state is deprecated given a certain time delay.
 
template<typename DurationT >
bool is_deprecated (const std::chrono::duration< int64_t, DurationT > &time_delay) const
 Check if the state is deprecated given a certain time delay.
 
 operator bool () const noexcept
 Boolean operator for the truthiness of a state.
 

Static Public Member Functions

static Jacobian Random (const std::string &robot_name, unsigned int nb_joints, const std::string &frame, const std::string &reference_frame="world")
 Constructor for a random Jacobian.
 
static Jacobian Random (const std::string &robot_name, const std::vector< std::string > &joint_names, const std::string &frame, const std::string &reference_frame="world")
 Constructor for a random Jacobian.
 

Friends

void swap (Jacobian &jacobian1, Jacobian &jacobian2)
 Swap the values of the two Jacobians.
 
Jacobian operator* (const Eigen::Matrix< double, 6, 6 > &matrix, const Jacobian &jacobian)
 Overload the * operator with a 6x6 matrix on the left side.
 
Jacobian operator* (const CartesianPose &pose, const Jacobian &jacobian)
 Overload the * operator with a Cartesian pose on the left side.
 
std::ostream & operator<< (std::ostream &os, const Jacobian &jacobian)
 Overload the ostream operator for printing.
 

Additional Inherited Members

- Protected Member Functions inherited from state_representation::State
void set_type (const StateType &type)
 Setter of the state type attribute.
 
void set_empty (bool empty=true)
 Setter of the empty attribute.
 
void assert_not_empty () const
 Throw an exception if the state is empty.
 
virtual std::string to_string () const
 Convert the state to its string representation.
 

Detailed Description

Class to define a robot Jacobian matrix.

Definition at line 21 of file Jacobian.hpp.

Constructor & Destructor Documentation

◆ Jacobian() [1/6]

state_representation::Jacobian::Jacobian ( )

Empty constructor for a Jacobian.

Definition at line 19 of file Jacobian.cpp.

◆ Jacobian() [2/6]

state_representation::Jacobian::Jacobian ( const std::string &  robot_name,
unsigned int  nb_joints,
const std::string &  frame,
const std::string &  reference_frame = "world" 
)

Constructor with name, number of joints, frame and reference frame provided.

Parameters
robot_nameThe name of the associated robot
nb_jointsThe number of joints of the robot
frameThe name of the frame at which the Jacobian is computed
reference_frameThe name of the reference frame in which the Jacobian is expressed (default is "world")

Definition at line 23 of file Jacobian.cpp.

◆ Jacobian() [3/6]

state_representation::Jacobian::Jacobian ( const std::string &  robot_name,
const std::vector< std::string > &  joint_names,
const std::string &  frame,
const std::string &  reference_frame = "world" 
)

Constructor with name, joint names, frame and reference frame provided.

Parameters
robot_nameThe name of the associated robot
joint_namesThe vector of joint names of the robot
frameThe name of the frame at which the Jacobian is computed
reference_frameThe name of the reference frame in which the Jacobian is expressed (default is "world")

Definition at line 35 of file Jacobian.cpp.

◆ Jacobian() [4/6]

state_representation::Jacobian::Jacobian ( const std::string &  robot_name,
const std::string &  frame,
const Eigen::MatrixXd &  data,
const std::string &  reference_frame = "world" 
)

Constructor with name, frame, Jacobian matrix and reference frame provided.

Parameters
robot_nameThe name of the associated robot
frameThe name of the frame at which the Jacobian is computed
dataThe values of the Jacobian matrix
reference_frameThe name of the reference frame in which the Jacobian is expressed (default is "world")

Definition at line 42 of file Jacobian.cpp.

◆ Jacobian() [5/6]

state_representation::Jacobian::Jacobian ( const std::string &  robot_name,
const std::vector< std::string > &  joint_names,
const std::string &  frame,
const Eigen::MatrixXd &  data,
const std::string &  reference_frame = "world" 
)

Constructor with name, joint names, frame, Jacobian matrix and reference frame provided.

Parameters
robot_nameThe name of the associated robot
joint_namesThe vector of joint names of the robot
frameThe name of the frame at which the Jacobian is computed
dataThe values of the Jacobian matrix
reference_frameThe name of the reference frame in which the Jacobian is expressed (default is "world")

Definition at line 51 of file Jacobian.cpp.

◆ Jacobian() [6/6]

state_representation::Jacobian::Jacobian ( const Jacobian jacobian)

Copy constructor of a Jacobian.

Definition at line 58 of file Jacobian.cpp.

Member Function Documentation

◆ col()

Eigen::VectorXd state_representation::Jacobian::col ( unsigned int  index) const

Accessor of the column data at given index.

Parameters
indexThe index of the desired column
Returns
The column vector at index

Definition at line 97 of file Jacobian.cpp.

◆ cols()

unsigned int state_representation::Jacobian::cols ( ) const

Getter of the number of columns attribute.

Definition at line 93 of file Jacobian.cpp.

◆ copy()

Jacobian state_representation::Jacobian::copy ( ) const

Return a copy of the Jacobian.

Definition at line 162 of file Jacobian.cpp.

◆ data()

const Eigen::MatrixXd & state_representation::Jacobian::data ( ) const

Getter of the data attribute.

Definition at line 113 of file Jacobian.cpp.

◆ get_frame()

const std::string & state_representation::Jacobian::get_frame ( ) const

Getter of the frame attribute.

Definition at line 105 of file Jacobian.cpp.

◆ get_joint_names()

const std::vector< std::string > & state_representation::Jacobian::get_joint_names ( ) const

Getter of the joint names attribute.

Definition at line 101 of file Jacobian.cpp.

◆ get_reference_frame()

const std::string & state_representation::Jacobian::get_reference_frame ( ) const

Getter of the reference frame attribute.

Definition at line 109 of file Jacobian.cpp.

◆ inverse() [1/3]

Eigen::MatrixXd state_representation::Jacobian::inverse ( ) const

Return the inverse of the Jacobian matrix.

If the matrix is not invertible, an error is thrown advising to use the pseudoinverse function instead

Returns
The inverse of the Jacobian

Definition at line 172 of file Jacobian.cpp.

◆ inverse() [2/3]

JointVelocities state_representation::Jacobian::inverse ( const CartesianTwist twist) const

Transform the given Cartesian twist to joint space.

This uses QR decomposition to solve for the joint velocities, which is more efficient than calculating and multiplying by the Jacobian inverse independently.

Parameters
twistThe Cartesian twist to be transformed to joint space
Returns
The resulting joint velocities from the product inv(J) * twist

Definition at line 185 of file Jacobian.cpp.

◆ inverse() [3/3]

Eigen::MatrixXd state_representation::Jacobian::inverse ( const Eigen::MatrixXd &  matrix) const

Solve the system X = inv(J) * M to obtain X.

This uses QR decomposition to solve for X, which is more efficient than calculating and multiplying by the Jacobian inverse independently.

Parameters
matrixThe matrix to solve the system with
Returns
The result of the product inv(J) * M

Definition at line 180 of file Jacobian.cpp.

◆ is_incompatible()

bool state_representation::Jacobian::is_incompatible ( const State state) const
overridevirtual

Check if the Jacobian is incompatible for operations with the state given as argument.

Parameters
stateThe state to check compatibility with

Reimplemented from state_representation::State.

Definition at line 192 of file Jacobian.cpp.

◆ operator()() [1/2]

double & state_representation::Jacobian::operator() ( unsigned int  row,
unsigned int  col 
)

Overload the () operator in a non const fashion to modify the value at given (row, col)

Parameters
rowThe index of the row
columnThe index of the column
Returns
The reference to the value at the given row and column

Definition at line 310 of file Jacobian.cpp.

◆ operator()() [2/2]

const double & state_representation::Jacobian::operator() ( unsigned int  row,
unsigned int  col 
) const

Overload the () operator in const fashion to access the value at given (row, col)

Parameters
rowThe index of the row
columnThe index of the column
Returns
The const reference to the value at the given row and column

Definition at line 322 of file Jacobian.cpp.

◆ operator*() [1/2]

Eigen::MatrixXd state_representation::Jacobian::operator* ( const Eigen::MatrixXd &  matrix) const

Overload the * operator with an arbitrary matrix.

Parameters
matrixThe matrix to multiply with
Returns
The Jacobian matrix multiplied by the matrix in parameter

Definition at line 272 of file Jacobian.cpp.

◆ operator*() [2/2]

CartesianTwist state_representation::Jacobian::operator* ( const JointVelocities dq) const

Overload the * operator with a JointVelocities.

Parameters
dqThe joint velocities to multiply with
Returns
The corresponding Cartesian twist of the Jacobian frame

Definition at line 283 of file Jacobian.cpp.

◆ operator=()

Jacobian & state_representation::Jacobian::operator= ( const Jacobian jacobian)

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

Parameters
jacobianThe Jacobian with value to assign
Returns
Reference to the current Jacobian with new values

Definition at line 79 of file Jacobian.cpp.

◆ pseudoinverse() [1/3]

Eigen::MatrixXd state_representation::Jacobian::pseudoinverse ( ) const

Return the pseudoinverse of the Jacobian matrix.

Returns
The pseudoinverse of the Jacobian

Definition at line 245 of file Jacobian.cpp.

◆ pseudoinverse() [2/3]

JointVelocities state_representation::Jacobian::pseudoinverse ( const CartesianTwist twist) const

Transform a Cartesian twist to joint space by pre-multiplying the Jacobian pseudoinverse.

Parameters
twistThe Cartesian twist to be transformed to joint space
Returns
The corresponding joint velocities

Definition at line 254 of file Jacobian.cpp.

◆ pseudoinverse() [3/3]

Eigen::MatrixXd state_representation::Jacobian::pseudoinverse ( const Eigen::MatrixXd &  matrix) const

Multiply the given matrix by the pseudoinverse of the Jacobian matrix.

Parameters
matrixThe matrix to be multiplied with the Jacobian
Returns
The result of the matrix multiplication

Definition at line 249 of file Jacobian.cpp.

◆ Random() [1/2]

Jacobian state_representation::Jacobian::Random ( const std::string &  robot_name,
const std::vector< std::string > &  joint_names,
const std::string &  frame,
const std::string &  reference_frame = "world" 
)
static

Constructor for a random Jacobian.

Parameters
robot_nameThe name of the associated robot
joint_namesThe vector of joint names of the robot
frameThe name of the frame at which the Jacobian is computed
reference_frameThe name of the reference frame in which the Jacobian is expressed (default is "world")
Returns
Jacobian with random data values

Definition at line 72 of file Jacobian.cpp.

◆ Random() [2/2]

Jacobian state_representation::Jacobian::Random ( const std::string &  robot_name,
unsigned int  nb_joints,
const std::string &  frame,
const std::string &  reference_frame = "world" 
)
static

Constructor for a random Jacobian.

Parameters
robot_nameThe name of the associated robot
nb_jointsThe number of joints of the robot
frameThe name of the frame at which the Jacobian is computed
reference_frameThe name of the reference frame in which the Jacobian is expressed (default is "world")
Returns
Jacobian with random data values

Definition at line 66 of file Jacobian.cpp.

◆ reset()

void state_representation::Jacobian::reset ( )
overridevirtual

Reset the object to a post-construction state.

Reimplemented from state_representation::State.

Definition at line 167 of file Jacobian.cpp.

◆ row()

Eigen::VectorXd state_representation::Jacobian::row ( unsigned int  index) const

Accessor of the row data at given index.

Parameters
indexThe index of the desired row
Returns
The row vector at index

Definition at line 89 of file Jacobian.cpp.

◆ rows()

unsigned int state_representation::Jacobian::rows ( ) const

Getter of the number of rows attribute.

Definition at line 85 of file Jacobian.cpp.

◆ set_data()

void state_representation::Jacobian::set_data ( const Eigen::MatrixXd &  data)
overridevirtual

Setter of the data attribute.

Reimplemented from state_representation::State.

Definition at line 150 of file Jacobian.cpp.

◆ set_frame()

void state_representation::Jacobian::set_frame ( const std::string &  frame)

Setter of the frame.

Definition at line 140 of file Jacobian.cpp.

◆ set_joint_names() [1/2]

void state_representation::Jacobian::set_joint_names ( const std::vector< std::string > &  joint_names)

Setter of the joint names attribute from a vector of joint names.

Definition at line 130 of file Jacobian.cpp.

◆ set_joint_names() [2/2]

void state_representation::Jacobian::set_joint_names ( unsigned int  nb_joints)

Setter of the joint names attribute from the number of joints.

Definition at line 118 of file Jacobian.cpp.

◆ set_reference_frame()

void state_representation::Jacobian::set_reference_frame ( const std::string &  reference_frame)

Setter of the reference frame.

Definition at line 145 of file Jacobian.cpp.

◆ set_zero()

void state_representation::Jacobian::set_zero ( )

Set the Jacobian matrix to a zero value.

Definition at line 156 of file Jacobian.cpp.

◆ transpose() [1/2]

Eigen::MatrixXd state_representation::Jacobian::transpose ( ) const

Return the transpose of the Jacobian matrix.

Returns
The transposed Jacobian matrix

Definition at line 261 of file Jacobian.cpp.

◆ transpose() [2/2]

JointTorques state_representation::Jacobian::transpose ( const CartesianWrench wrench) const

Transform a Cartesian wrench to joint space by pre-multiplying the Jacobian transpose.

Parameters
wrenchThe Cartesian wrench to be transformed to joint space
Returns
The corresponding joint torques

Definition at line 265 of file Jacobian.cpp.

Friends And Related Symbol Documentation

◆ operator* [1/2]

Jacobian operator* ( const CartesianPose pose,
const Jacobian jacobian 
)
friend

Overload the * operator with a Cartesian pose on the left side.

This operation is equivalent to a change of reference frame of the Jacobian

Parameters
poseThe Cartesian pose to multiply with
jacobianThe Jacobian to be multiplied with the Cartesian pose
Returns
The Jacobian expressed in the new reference frame

Definition at line 291 of file Jacobian.cpp.

◆ operator* [2/2]

Jacobian operator* ( const Eigen::Matrix< double, 6, 6 > &  matrix,
const Jacobian jacobian 
)
friend

Overload the * operator with a 6x6 matrix on the left side.

Parameters
matrixThe matrix to multiply with
jacobianThe Jacobian
Returns
The Jacobian transformed by the matrix

Definition at line 277 of file Jacobian.cpp.

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const Jacobian jacobian 
)
friend

Overload the ostream operator for printing.

Parameters
osThe ostream to append the string representing the Jacobian to
jacobianThe Jacobian to print
Returns
The appended ostream

Definition at line 333 of file Jacobian.cpp.

◆ swap

void swap ( Jacobian jacobian1,
Jacobian jacobian2 
)
friend

Swap the values of the two Jacobians.

Parameters
jacobian1Jacobian to be swapped with 2
jacobian2Jacobian to be swapped with 1

Definition at line 333 of file Jacobian.hpp.


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