ROBOOP, A Robotics Object Oriented Package in C++
|
Virtual base robot class. More...
#include <robot.h>
Public Member Functions | |
Robot_basic (const int ndof=1, const bool dh_parameter=false, const bool min_inertial_para=false) | |
Constructor. More... | |
Robot_basic (const Matrix &initrobot_motor, const bool dh_parameter=false, const bool min_inertial_para=false) | |
Constructor. More... | |
Robot_basic (const Matrix &initrobot, const Matrix &initmotor, const bool dh_parameter=false, const bool min_inertial_para=false) | |
Constructor. More... | |
Robot_basic (const std::string &filename, const std::string &robotName, const bool dh_parameter=false, const bool min_inertial_para=false) | |
Robot_basic (const Robot_basic &x) | |
Copy constructor. | |
virtual | ~Robot_basic () |
Destructor. More... | |
Robot_basic & | operator= (const Robot_basic &x) |
Overload = operator. | |
Real | get_q (const int i) const |
bool | get_DH () const |
Return true if in DH notation, false otherwise. | |
int | get_dof () const |
Return dof. | |
int | get_available_dof () const |
Counts number of currently non-immobile links. | |
int | get_available_dof (const int endlink) const |
Counts number of currently non-immobile links up to and including endlink. | |
int | get_fix () const |
Return fix. | |
ReturnMatrix | get_q (void) const |
Return the joint position vector. | |
ReturnMatrix | get_qp (void) const |
Return the joint velocity vector. | |
ReturnMatrix | get_qpp (void) const |
Return the joint acceleration vector. | |
ReturnMatrix | get_available_q (void) const |
Return the joint position vector of available (non-immobile) joints. | |
ReturnMatrix | get_available_qp (void) const |
Return the joint velocity vector of available (non-immobile) joints. | |
ReturnMatrix | get_available_qpp (void) const |
Return the joint acceleration vector of available (non-immobile) joints. | |
ReturnMatrix | get_available_q (const int endlink) const |
Return the joint position vector of available (non-immobile) joints up to and including endlink. | |
ReturnMatrix | get_available_qp (const int endlink) const |
Return the joint velocity vector of available (non-immobile) joints up to and including endlink. | |
ReturnMatrix | get_available_qpp (const int endlink) const |
Return the joint acceleration vector of available (non-immobile) joints up to and including endlink. | |
void | set_q (const ColumnVector &q) |
Set the joint position vector. More... | |
void | set_q (const Matrix &q) |
Set the joint position vector. More... | |
void | set_q (const Real q, const int i) |
void | set_qp (const ColumnVector &qp) |
Set the joint velocity vector. | |
void | set_qpp (const ColumnVector &qpp) |
Set the joint acceleration vector. | |
void | kine (Matrix &Rot, ColumnVector &pos) const |
Direct kinematics at end effector. More... | |
void | kine (Matrix &Rot, ColumnVector &pos, const int j) const |
Direct kinematics at end effector. More... | |
ReturnMatrix | kine (void) const |
Return the end effector direct kinematics transform matrix. | |
ReturnMatrix | kine (const int j) const |
Return the frame j direct kinematics transform matrix. | |
ReturnMatrix | kine_pd (const int ref=0) const |
Direct kinematics with velocity. More... | |
virtual void | kine_pd (Matrix &Rot, ColumnVector &pos, ColumnVector &pos_dot, const int ref) const =0 |
virtual void | robotType_inv_kin ()=0 |
virtual ReturnMatrix | inv_kin (const Matrix &Tobj, const int mj=0) |
Numerical inverse kinematics. See inv_kin(const Matrix & Tobj, const int mj, const int endlink, bool & converge) More... | |
ReturnMatrix | inv_kin (const Matrix &Tobj, const int mj, bool &converge) |
virtual ReturnMatrix | inv_kin (const Matrix &Tobj, const int mj, const int endlink, bool &converge) |
Numerical inverse kinematics. More... | |
virtual ReturnMatrix | inv_kin_rhino (const Matrix &Tobj, bool &converge)=0 |
virtual ReturnMatrix | inv_kin_puma (const Matrix &Tobj, bool &converge)=0 |
virtual ReturnMatrix | inv_kin_schilling (const Matrix &Tobj, bool &converge)=0 |
virtual ReturnMatrix | jacobian (const int ref=0) const |
Jacobian of mobile links expressed at frame ref. | |
virtual ReturnMatrix | jacobian (const int endlink, const int ref) const =0 |
virtual ReturnMatrix | jacobian_dot (const int ref=0) const =0 |
ReturnMatrix | jacobian_DLS_inv (const double eps, const double lambda_max, const int ref=0) const |
Inverse Jacobian based on damped least squares inverse. More... | |
virtual void | dTdqi (Matrix &dRot, ColumnVector &dp, const int i)=0 |
virtual ReturnMatrix | dTdqi (const int i)=0 |
ReturnMatrix | acceleration (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &tau) |
Joints acceleration without contact force. | |
ReturnMatrix | acceleration (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &tau, const ColumnVector &Fext, const ColumnVector &Next) |
Joints acceleration. More... | |
ReturnMatrix | inertia (const ColumnVector &q) |
Inertia of the manipulator. | |
virtual ReturnMatrix | torque_novelocity (const ColumnVector &qpp)=0 |
virtual ReturnMatrix | torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp)=0 |
virtual ReturnMatrix | torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp, const ColumnVector &Fext_, const ColumnVector &Next_)=0 |
virtual void | delta_torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp, const ColumnVector &dq, const ColumnVector &dqp, const ColumnVector &dqpp, ColumnVector &torque, ColumnVector &dtorque)=0 |
virtual void | dq_torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp, const ColumnVector &dq, ColumnVector &torque, ColumnVector &dtorque)=0 |
virtual void | dqp_torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &dqp, ColumnVector &torque, ColumnVector &dtorque)=0 |
ReturnMatrix | dtau_dq (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp) |
Sensitivity of the dynamics with respect to . More... | |
ReturnMatrix | dtau_dqp (const ColumnVector &q, const ColumnVector &qp) |
Sensitivity of the dynamics with respect to . More... | |
virtual ReturnMatrix | G ()=0 |
virtual ReturnMatrix | C (const ColumnVector &qp)=0 |
void | error (const std::string &msg1) const |
Print the message msg1 on the console. | |
Public Attributes | |
ColumnVector * | w |
ColumnVector * | wp |
ColumnVector * | vp |
ColumnVector * | a |
ColumnVector * | f |
ColumnVector * | f_nv |
ColumnVector * | n |
ColumnVector * | n_nv |
ColumnVector * | F |
ColumnVector * | N |
ColumnVector * | p |
ColumnVector * | pp |
ColumnVector * | dw |
ColumnVector * | dwp |
ColumnVector * | dvp |
ColumnVector * | da |
ColumnVector * | df |
ColumnVector * | dn |
ColumnVector * | dF |
ColumnVector * | dN |
ColumnVector * | dp |
ColumnVector | z0 |
Axis vector at each joint. | |
ColumnVector | gravity |
Gravity vector. | |
Matrix * | R |
Temprary rotation matrix. | |
Link * | links |
Pointer on Link cclass. | |
Private Types | |
enum | EnumRobotType { DEFAULT = 0, RHINO = 1, PUMA = 2, SCHILLING = 3 } |
enum EnumRobotType More... | |
Private Member Functions | |
void | cleanUpPointers () |
Free all vectors and matrix memory. | |
Private Attributes | |
EnumRobotType | robotType |
Robot type. | |
int | dof |
Degree of freedom. | |
int | fix |
Virtual link, used with modified DH notation. | |
Friends | |
class | Robot |
class | mRobot |
class | mRobot_min_para |
class | Robotgl |
class | mRobotgl |
|
private |
Robot_basic::Robot_basic | ( | const int | ndof = 1 , |
const bool | dh_parameter = false , |
||
const bool | min_inertial_para = false |
||
) |
Constructor.
ndof,: | Robot degree of freedom. |
dh_parameter,: | true if DH notation, false if modified DH notation. |
min_inertial_para,: | true inertial parameter are in minimal form. |
Allocate memory for vectors and matrix pointers. Initialize all the Links instance.
Definition at line 569 of file robot.cpp.
References cleanUpPointers(), dof, fix, gravity, links, R, threebythreeident, and z0.
Robot_basic::Robot_basic | ( | const Matrix & | dhinit, |
const bool | dh_parameter = false , |
||
const bool | min_inertial_para = false |
||
) |
Constructor.
dhinit,: | Robot initialization matrix. |
dh_parameter,: | true if DH notation, false if modified DH notation. |
min_inertial_para,: | true inertial parameter are in minimal form. |
Allocate memory for vectors and matrix pointers. Initialize all the Links instance.
Definition at line 339 of file robot.cpp.
References cleanUpPointers(), dof, error(), fix, gravity, links, R, threebythreeident, and z0.
Robot_basic::Robot_basic | ( | const Matrix & | initrobot, |
const Matrix & | initmotor, | ||
const bool | dh_parameter = false , |
||
const bool | min_inertial_para = false |
||
) |
Constructor.
initrobot,: | Robot initialization matrix. |
initmotor,: | Motor initialization matrix. |
dh_parameter,: | true if DH notation, false if modified DH notation. |
min_inertial_para,: | true inertial parameter are in minimal form. |
Allocate memory for vectors and matrix pointers. Initialize all the Links instance.
Definition at line 447 of file robot.cpp.
References cleanUpPointers(), dof, error(), fix, gravity, links, R, threebythreeident, and z0.
|
virtual |
Destructor.
Free all vectors and matrix memory.
Definition at line 875 of file robot.cpp.
References cleanUpPointers().
ReturnMatrix Robot_basic::acceleration | ( | const ColumnVector & | q, |
const ColumnVector & | qp, | ||
const ColumnVector & | tau_cmd, | ||
const ColumnVector & | Fext, | ||
const ColumnVector & | Next | ||
) |
Joints acceleration.
The robot dynamics is
then the joint acceleration is
Definition at line 108 of file dynamics.cpp.
ReturnMatrix Robot_basic::dtau_dq | ( | const ColumnVector & | q, |
const ColumnVector & | qp, | ||
const ColumnVector & | qpp | ||
) |
Sensitivity of the dynamics with respect to .
This function computes .
Definition at line 54 of file sensitiv.cpp.
ReturnMatrix Robot_basic::dtau_dqp | ( | const ColumnVector & | q, |
const ColumnVector & | qp | ||
) |
Sensitivity of the dynamics with respect to .
This function computes .
Definition at line 80 of file sensitiv.cpp.
|
inline |
< Return joint i position.
Definition at line 231 of file robot.h.
Referenced by Clik::Clik(), Dynamics::set_robot_on_first_point_of_splines(), Resolved_acc::torque_cmd(), Computed_torque_method::torque_cmd(), and Proportional_Derivative::torque_cmd().
|
virtual |
Numerical inverse kinematics. See inv_kin(const Matrix & Tobj, const int mj, const int endlink, bool & converge)
Overload inv_kin function.
Reimplemented in mRobot_min_para, mRobot, and Robot.
Definition at line 79 of file invkine.cpp.
Referenced by Robot::inv_kin(), mRobot::inv_kin(), mRobot_min_para::inv_kin(), and Dynamics::set_robot_on_first_point_of_splines().
|
virtual |
Numerical inverse kinematics.
Tobj,: | Transformation matrix expressing the desired end effector pose. |
mj,: | Select algorithm type, 0: based on Jacobian, 1: based on derivative of T. |
converge,: | Indicate if the algorithm converge. |
endlink,: | the link to pretend is the end effector |
The joint position vector before the inverse kinematics is returned if the algorithm does not converge.
Reimplemented in mRobot_min_para, mRobot, and Robot.
Definition at line 87 of file invkine.cpp.
ReturnMatrix Robot_basic::jacobian_DLS_inv | ( | const double | eps, |
const double | lambda_max, | ||
const int | ref = 0 |
||
) | const |
Inverse Jacobian based on damped least squares inverse.
eps,: | Range of singular region. |
lambda_max,: | Value to obtain a good solution in singular region. |
ref,: | Selected frame (ex: joint 4). |
The Jacobian inverse, based on damped least squares, is
where and is a damping factor and the identity matrix respectively. Based on SVD (Singular Value Decomposition) the Jacobian is , where , and are respectively the input vector, the ouput vector and the singular values ( , is the rank of J). Using the previous equations we obtain
A singular region, based on the smallest singular value, can be defined by
Definition at line 165 of file kinemat.cpp.
Referenced by Clik::q_qdot(), and Resolved_acc::torque_cmd().
void Robot_basic::kine | ( | Matrix & | Rot, |
ColumnVector & | pos | ||
) | const |
Direct kinematics at end effector.
Rot,: | End effector orientation. |
pos,: | Enf effector position. |
Definition at line 88 of file kinemat.cpp.
Referenced by Clik::endeff_pos_ori_err(), and Impedance::Impedance().
void Robot_basic::kine | ( | Matrix & | Rot, |
ColumnVector & | pos, | ||
const int | j | ||
) | const |
Direct kinematics at end effector.
Rot,: | Frame j orientation. |
pos,: | Frame j position. |
j,: | Selected frame. |
Definition at line 98 of file kinemat.cpp.
ReturnMatrix Robot_basic::kine_pd | ( | const int | j = 0 | ) | const |
Direct kinematics with velocity.
Return a matrix. The first three columns are the frame j to the base rotation, the fourth column is the frame j w.r.t to the base postion vector and the last column is the frame j w.r.t to the base translational velocity vector. Print an error on the console if j is out of range.
Definition at line 138 of file kinemat.cpp.
Referenced by Resolved_acc::torque_cmd().
void Robot_basic::set_q | ( | const ColumnVector & | q | ) |
Set the joint position vector.
Set the joint position vector and recalculate the orientation matrix R and the position vector p (see Link class). Print an error if the size of q is incorrect.
Definition at line 1133 of file robot.cpp.
References dof, error(), get_available_dof(), links, Link::p, Link::R, and Link::transform().
Referenced by Clik::endeff_pos_ori_err(), Clik::q_qdot(), Dynamics::set_robot_on_first_point_of_splines(), and Dynamics::xdot().
void Robot_basic::set_q | ( | const Matrix & | q | ) |
Set the joint position vector.
Set the joint position vector and recalculate the orientation matrix R and the position vector p (see Link class). Print an error if the size of q is incorrect.
Definition at line 1066 of file robot.cpp.
References dof, error(), get_available_dof(), links, Link::p, Link::R, and Link::transform().