Control Libraries 7.4.0
|
Class to define a robot Jacobian matrix. More...
#include <Jacobian.hpp>
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. | |
Jacobian & | operator= (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. | |
State & | operator= (const State &state) |
Copy assignment operator that has to be defined to the custom assignment operator. | |
const StateType & | get_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. | |
Class to define a robot Jacobian matrix.
Definition at line 21 of file Jacobian.hpp.
state_representation::Jacobian::Jacobian | ( | ) |
Empty constructor for a Jacobian.
Definition at line 19 of file Jacobian.cpp.
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.
robot_name | The name of the associated robot |
nb_joints | The number of joints of the robot |
frame | The name of the frame at which the Jacobian is computed |
reference_frame | The name of the reference frame in which the Jacobian is expressed (default is "world") |
Definition at line 23 of file Jacobian.cpp.
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.
robot_name | The name of the associated robot |
joint_names | The vector of joint names of the robot |
frame | The name of the frame at which the Jacobian is computed |
reference_frame | The name of the reference frame in which the Jacobian is expressed (default is "world") |
Definition at line 35 of file Jacobian.cpp.
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.
robot_name | The name of the associated robot |
frame | The name of the frame at which the Jacobian is computed |
data | The values of the Jacobian matrix |
reference_frame | The name of the reference frame in which the Jacobian is expressed (default is "world") |
Definition at line 42 of file Jacobian.cpp.
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.
robot_name | The name of the associated robot |
joint_names | The vector of joint names of the robot |
frame | The name of the frame at which the Jacobian is computed |
data | The values of the Jacobian matrix |
reference_frame | The name of the reference frame in which the Jacobian is expressed (default is "world") |
Definition at line 51 of file Jacobian.cpp.
state_representation::Jacobian::Jacobian | ( | const Jacobian & | jacobian | ) |
Copy constructor of a Jacobian.
Definition at line 58 of file Jacobian.cpp.
Eigen::VectorXd state_representation::Jacobian::col | ( | unsigned int | index | ) | const |
Accessor of the column data at given index.
index | The index of the desired column |
Definition at line 97 of file Jacobian.cpp.
unsigned int state_representation::Jacobian::cols | ( | ) | const |
Getter of the number of columns attribute.
Definition at line 93 of file Jacobian.cpp.
Jacobian state_representation::Jacobian::copy | ( | ) | const |
Return a copy of the Jacobian.
Definition at line 162 of file Jacobian.cpp.
const Eigen::MatrixXd & state_representation::Jacobian::data | ( | ) | const |
Getter of the data attribute.
Definition at line 113 of file Jacobian.cpp.
const std::string & state_representation::Jacobian::get_frame | ( | ) | const |
Getter of the frame attribute.
Definition at line 105 of file Jacobian.cpp.
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.
const std::string & state_representation::Jacobian::get_reference_frame | ( | ) | const |
Getter of the reference frame attribute.
Definition at line 109 of file Jacobian.cpp.
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
Definition at line 172 of file Jacobian.cpp.
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.
twist | The Cartesian twist to be transformed to joint space |
Definition at line 185 of file Jacobian.cpp.
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.
matrix | The matrix to solve the system with |
Definition at line 180 of file Jacobian.cpp.
|
overridevirtual |
Check if the Jacobian is incompatible for operations with the state given as argument.
state | The state to check compatibility with |
Reimplemented from state_representation::State.
Definition at line 192 of file Jacobian.cpp.
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)
row | The index of the row |
column | The index of the column |
Definition at line 310 of file Jacobian.cpp.
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)
row | The index of the row |
column | The index of the column |
Definition at line 322 of file Jacobian.cpp.
Eigen::MatrixXd state_representation::Jacobian::operator* | ( | const Eigen::MatrixXd & | matrix | ) | const |
Overload the * operator with an arbitrary matrix.
matrix | The matrix to multiply with |
Definition at line 272 of file Jacobian.cpp.
CartesianTwist state_representation::Jacobian::operator* | ( | const JointVelocities & | dq | ) | const |
Overload the * operator with a JointVelocities.
dq | The joint velocities to multiply with |
Definition at line 283 of file Jacobian.cpp.
Copy assignment operator that has to be defined to the custom assignment operator.
jacobian | The Jacobian with value to assign |
Definition at line 79 of file Jacobian.cpp.
Eigen::MatrixXd state_representation::Jacobian::pseudoinverse | ( | ) | const |
Return the pseudoinverse of the Jacobian matrix.
Definition at line 245 of file Jacobian.cpp.
JointVelocities state_representation::Jacobian::pseudoinverse | ( | const CartesianTwist & | twist | ) | const |
Transform a Cartesian twist to joint space by pre-multiplying the Jacobian pseudoinverse.
twist | The Cartesian twist to be transformed to joint space |
Definition at line 254 of file Jacobian.cpp.
Eigen::MatrixXd state_representation::Jacobian::pseudoinverse | ( | const Eigen::MatrixXd & | matrix | ) | const |
Multiply the given matrix by the pseudoinverse of the Jacobian matrix.
matrix | The matrix to be multiplied with the Jacobian |
Definition at line 249 of file Jacobian.cpp.
|
static |
Constructor for a random Jacobian.
robot_name | The name of the associated robot |
joint_names | The vector of joint names of the robot |
frame | The name of the frame at which the Jacobian is computed |
reference_frame | The name of the reference frame in which the Jacobian is expressed (default is "world") |
Definition at line 72 of file Jacobian.cpp.
|
static |
Constructor for a random Jacobian.
robot_name | The name of the associated robot |
nb_joints | The number of joints of the robot |
frame | The name of the frame at which the Jacobian is computed |
reference_frame | The name of the reference frame in which the Jacobian is expressed (default is "world") |
Definition at line 66 of file Jacobian.cpp.
|
overridevirtual |
Reset the object to a post-construction state.
Reimplemented from state_representation::State.
Definition at line 167 of file Jacobian.cpp.
Eigen::VectorXd state_representation::Jacobian::row | ( | unsigned int | index | ) | const |
Accessor of the row data at given index.
index | The index of the desired row |
Definition at line 89 of file Jacobian.cpp.
unsigned int state_representation::Jacobian::rows | ( | ) | const |
Getter of the number of rows attribute.
Definition at line 85 of file Jacobian.cpp.
|
overridevirtual |
Setter of the data attribute.
Reimplemented from state_representation::State.
Definition at line 150 of file Jacobian.cpp.
void state_representation::Jacobian::set_frame | ( | const std::string & | frame | ) |
Setter of the frame.
Definition at line 140 of file Jacobian.cpp.
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.
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.
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.
void state_representation::Jacobian::set_zero | ( | ) |
Set the Jacobian matrix to a zero value.
Definition at line 156 of file Jacobian.cpp.
Eigen::MatrixXd state_representation::Jacobian::transpose | ( | ) | const |
Return the transpose of the Jacobian matrix.
Definition at line 261 of file Jacobian.cpp.
JointTorques state_representation::Jacobian::transpose | ( | const CartesianWrench & | wrench | ) | const |
Transform a Cartesian wrench to joint space by pre-multiplying the Jacobian transpose.
wrench | The Cartesian wrench to be transformed to joint space |
Definition at line 265 of file Jacobian.cpp.
|
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
pose | The Cartesian pose to multiply with |
jacobian | The Jacobian to be multiplied with the Cartesian pose |
Definition at line 291 of file Jacobian.cpp.
|
friend |
Overload the * operator with a 6x6 matrix on the left side.
matrix | The matrix to multiply with |
jacobian | The Jacobian |
Definition at line 277 of file Jacobian.cpp.
|
friend |
Overload the ostream operator for printing.
os | The ostream to append the string representing the Jacobian to |
jacobian | The Jacobian to print |
Definition at line 333 of file Jacobian.cpp.
Swap the values of the two Jacobians.
Definition at line 333 of file Jacobian.hpp.