| ROBOOP, A Robotics Object Oriented Package in C++
    | 
Modified DH notation and minimal inertial parameters robot class. More...
#include <robot.h>
 
  
 | Public Member Functions | |
| mRobot_min_para (const int ndof=1) | |
| Constructor. | |
| mRobot_min_para (const Matrix &dhinit) | |
| Constructor. | |
| mRobot_min_para (const Matrix &initrobot, const Matrix &initmotor) | |
| Constructor. | |
| mRobot_min_para (const mRobot_min_para &x) | |
| Copy constructor. | |
| mRobot_min_para (const std::string &filename, const std::string &robotName) | |
| virtual | ~mRobot_min_para () | 
| Destructor. | |
| virtual void | robotType_inv_kin () | 
| Identify inverse kinematics familly.  More... | |
| ReturnMatrix | inv_kin (const Matrix &Tobj, const int mj=0) | 
| Overload inv_kin function. | |
| virtual ReturnMatrix | inv_kin (const Matrix &Tobj, const int mj, const int endlink, bool &converge) | 
| Inverse kinematics solutions.  More... | |
| virtual ReturnMatrix | inv_kin_rhino (const Matrix &Tobj, bool &converge) | 
| Analytic Rhino inverse kinematics.  More... | |
| virtual ReturnMatrix | inv_kin_puma (const Matrix &Tobj, bool &converge) | 
| Analytic Puma inverse kinematics.  More... | |
| virtual ReturnMatrix | inv_kin_schilling (const Matrix &Tobj, bool &converge) | 
| Analytic Schilling inverse kinematics.  More... | |
| virtual void | kine_pd (Matrix &Rot, ColumnVector &pos, ColumnVector &pos_dot, const int ref=0) const | 
| Direct kinematics with velocity.  More... | |
| 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 | 
| Jacobian of mobile joints up to endlink expressed at frame ref.  More... | |
| virtual ReturnMatrix | jacobian_dot (const int ref=0) const | 
| Jacobian derivative of mobile joints expressed at frame ref.  More... | |
| virtual void | dTdqi (Matrix &dRot, ColumnVector &dp, const int i) | 
| Partial derivative of the robot position (homogeneous transf.)  More... | |
| virtual ReturnMatrix | dTdqi (const int i) | 
| Partial derivative of the robot position (homogeneous transf.)  More... | |
| virtual ReturnMatrix | torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp) | 
| Joint torque without contact force based on Recursive Newton-Euler formulation. | |
| virtual ReturnMatrix | torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp, const ColumnVector &Fext_, const ColumnVector &Next_) | 
| Joint torque based on Recursive Newton-Euler formulation.  More... | |
| virtual ReturnMatrix | torque_novelocity (const ColumnVector &qpp) | 
| Joint torque. when joint velocity is 0, based on Recursive Newton-Euler formulation. | |
| 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) | 
| Delta torque dynamics.  More... | |
| virtual void | dq_torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp, const ColumnVector &dq, ColumnVector &torque, ColumnVector &dtorque) | 
| Delta torque due to delta joint position.  More... | |
| virtual void | dqp_torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &dqp, ColumnVector &torque, ColumnVector &dtorque) | 
| Delta torque due to delta joint velocity.  More... | |
| virtual ReturnMatrix | G () | 
| Joint torque due to gravity based on Recursive Newton-Euler formulation. | |
| virtual ReturnMatrix | C (const ColumnVector &qp) | 
| Joint torque due to centrifugal and Corriolis based on Recursive Newton-Euler formulation. | |
|  Public Member Functions inherited from Robot_basic | |
| 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... | |
| ReturnMatrix | inv_kin (const Matrix &Tobj, const int mj, bool &converge) | 
| 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... | |
| 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. | |
| 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... | |
| void | error (const std::string &msg1) const | 
| Print the message msg1 on the console. | |
| Additional Inherited Members | |
|  Public Attributes inherited from Robot_basic | |
| 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. | |
Modified DH notation and minimal inertial parameters robot class.
| 
 | virtual | 
Delta torque dynamics.
See mRobot::delta_torque for equations.
Implements Robot_basic.
Definition at line 507 of file delta_t.cpp.
| 
 | virtual | 
Delta torque due to delta joint position.
This function computes  . See mRobot::delta_torque for equations.
. See mRobot::delta_torque for equations. 
Implements Robot_basic.
Definition at line 331 of file comp_dq.cpp.
| 
 | virtual | 
Delta torque due to delta joint velocity.
This function computes  . See mRobot::delta_torque for equations.
. See mRobot::delta_torque for equations. 
Implements Robot_basic.
Definition at line 299 of file comp_dqp.cpp.
| 
 | virtual | 
Partial derivative of the robot position (homogeneous transf.)
This function computes the partial derivatives:
![\[ \frac{\partial{}^0 T_n}{\partial q_i} = {}^0 T_{i} Q_i \; {}^{i} T_n \]](form_111.png) 
See mRobot::dTdqi(Matrix & dRot, ColumnVector & dp, const int i) for equations.
Implements Robot_basic.
Definition at line 825 of file kinemat.cpp.
References threebythreeident.
| 
 | virtual | 
Partial derivative of the robot position (homogeneous transf.)
See mRobot::dTdqi(Matrix & dRot, ColumnVector & dp, const int i) for equations.
Implements Robot_basic.
Definition at line 883 of file kinemat.cpp.
| 
 | virtual | 
Inverse kinematics solutions.
The solution is based on the analytic inverse kinematics if robot type (familly) is Rhino or Puma, otherwise used the numerical algoritm defined in Robot_basic class.
Reimplemented from Robot_basic.
Definition at line 1007 of file invkine.cpp.
References Robot_basic::inv_kin().
| 
 | virtual | 
Analytic Puma inverse kinematics.
converge will be false if the desired end effector pose is outside robot range.
Implements Robot_basic.
Definition at line 1126 of file invkine.cpp.
| 
 | virtual | 
Analytic Rhino inverse kinematics.
converge will be false if the desired end effector pose is outside robot range.
Implements Robot_basic.
Definition at line 1029 of file invkine.cpp.
| 
 | virtual | 
Analytic Schilling inverse kinematics.
converge will be false if the desired end effector pose is outside robot range.
Implements Robot_basic.
Definition at line 1287 of file invkine.cpp.
| 
 | virtual | 
Jacobian of mobile joints up to endlink expressed at frame ref.
See Robot::jacobian for equations.
Implements Robot_basic.
Definition at line 901 of file kinemat.cpp.
| 
 | virtual | 
Jacobian derivative of mobile joints expressed at frame ref.
See Robot::jacobian_dot for equations.
Implements Robot_basic.
Definition at line 957 of file kinemat.cpp.
| 
 | virtual | 
Direct kinematics with velocity.
| Rot,: | Frame j rotation matrix w.r.t to the base frame. | 
| pos,: | Frame j position vector wr.r.t to the base frame. | 
| pos_dot,: | Frame j velocity vector w.r.t to the base frame. | 
| j,: | Frame j. Print an error on the console if j is out of range. | 
Implements Robot_basic.
Definition at line 795 of file kinemat.cpp.
| 
 | virtual | 
Identify inverse kinematics familly.
Identify the inverse kinematics analytic solution based on the similarity of the robot DH parameters and the DH parameters of know robots (ex: Puma, Rhino, ...). The inverse kinematics will be based on a numerical alogorithm if there is no match .
Implements Robot_basic.
Definition at line 1419 of file robot.cpp.
References Robot_basic::DEFAULT, Robot_basic::PUMA, Puma_mDH(), Robot_basic::RHINO, Rhino_mDH(), Robot_basic::robotType, Robot_basic::SCHILLING, and Schilling_mDH().
Referenced by mRobot_min_para().
| 
 | virtual | 
Joint torque based on Recursive Newton-Euler formulation.
See ReturnMatrix mRobot::torque(const ColumnVector & q, const ColumnVector & qp, const ColumnVector & qpp, const ColumnVector & Fext, const ColumnVector & Next) for the Recursive Newton-Euler formulation.
Implements Robot_basic.
Definition at line 693 of file dynamics.cpp.
References sign().