DH notation robot class. More...
#include <robot.h>

| Public Member Functions | |
| virtual ReturnMatrix | C (const ColumnVector &qp) | 
| Joint torque due to centrifugal and Corriolis 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 <orque, ColumnVector &dtorque) | 
| Delta torque dynamics. | |
| 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. | |
| virtual void | dqp_torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &dqp, ColumnVector &torque, ColumnVector &dtorque) | 
| Delta torque due to delta joint velocity. | |
| virtual void | dTdqi (Matrix &dRot, ColumnVector &dp, const int i) | 
| Partial derivative of the robot position (homogeneous transf.) | |
| virtual ReturnMatrix | dTdqi (const int i) | 
| Partial derivative of the robot position (homogeneous transf.) | |
| virtual ReturnMatrix | G () | 
| Joint torque due to gravity based on Recursive Newton-Euler formulation. | |
| 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. | |
| virtual ReturnMatrix | inv_kin_puma (const Matrix &Tobj, bool &converge) | 
| Analytic Puma inverse kinematics. | |
| virtual ReturnMatrix | inv_kin_rhino (const Matrix &Tobj, bool &converge) | 
| Analytic Rhino inverse kinematics. | |
| virtual ReturnMatrix | inv_kin_schilling (const Matrix &Tobj, bool &converge) | 
| Analytic Schilling inverse kinematics. | |
| 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 links up to endlink expressed at frame ref. | |
| virtual ReturnMatrix | jacobian_dot (const int ref=0) const | 
| Jacobian derivative of mobile joints expressed at frame ref. | |
| virtual void | kine_pd (Matrix &Rot, ColumnVector &pos, ColumnVector &pos_dot, const int ref) const | 
| Direct kinematics with velocity. | |
| Robot (const int ndof=1) | |
| Constructor. | |
| Robot (const Matrix &initrobot) | |
| Constructor. | |
| Robot (const Matrix &initrobot, const Matrix &initmotor) | |
| Constructor. | |
| Robot (const Robot &x) | |
| Copy constructor. | |
| Robot (const std::string &filename, const std::string &robotName) | |
| virtual void | robotType_inv_kin () | 
| Identify inverse kinematics familly. | |
| 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. | |
| virtual ReturnMatrix | torque_novelocity (const ColumnVector &qpp) | 
| Joint torque. when joint velocity is 0, based on Recursive Newton-Euler formulation. | |
| virtual | ~Robot () | 
| Destructor. | |
| Robot::Robot | ( | const int | ndof = 1 | ) | 
| Robot::Robot | ( | const Matrix & | initrobot | ) | 
| Robot::Robot | ( | const Matrix & | initrobot, | 
| const Matrix & | initmotor | ||
| ) | 
| Robot::Robot | ( | const Robot & | x | ) | 
| Robot::Robot | ( | const std::string & | filename, | 
| const std::string & | robotName | ||
| ) | 
| virtual Robot::~Robot | ( | ) |  [inline, virtual] | 
| ReturnMatrix Robot::C | ( | const ColumnVector & | qp | ) |  [virtual] | 
Joint torque due to centrifugal and Corriolis based on Recursive Newton-Euler formulation.
Implements Robot_basic.
Definition at line 360 of file dynamics.cpp.
| void Robot::delta_torque | ( | const ColumnVector & | q, | 
| const ColumnVector & | qp, | ||
| const ColumnVector & | qpp, | ||
| const ColumnVector & | dq, | ||
| const ColumnVector & | dqp, | ||
| const ColumnVector & | dqpp, | ||
| ColumnVector & | ltorque, | ||
| ColumnVector & | dtorque | ||
| ) |  [virtual] | 
Delta torque dynamics.
This function computes
![\[ \delta \tau = D(q) \delta \ddot{q} + S_1(q,\dot{q}) \delta \dot{q} + S_2(q,\dot{q},\ddot{q}) \delta q \]](form_45.png) 
Murray and Neuman Cite_: Murray86 have developed an efficient recursive linearized Newton-Euler formulation. In order to apply the RNE as presented in let us define the following variables
![\[ p_{di} = \frac{\partial p_i}{\partial d_i} = \left [ \begin{array}{ccc} 0 & \sin \alpha_i & \cos \alpha_i \end{array} \right ]^T \]](form_46.png) 
![\[ Q = \left [ \begin{array}{ccc} 0 & -1 & 0 \\ 1 & 0 & 0 \\ 0 & 0 & 0 \end{array} \right ] \]](form_47.png) 
Forward Iterations for  . Initialize:
. Initialize:  .
. 
![\[ \delta \omega_i = R_i^T \{\delta \omega_{i-1} + \sigma_i [ z_0 \delta \dot{\theta}_i - Q(\omega_{i-1} + \dot{\theta}_i ) \delta \theta_i ] \} \]](form_50.png) 
![\[ \delta \dot{\omega}_i = R_i^T \{ \delta \dot{\omega}_{i-1} + \sigma_i [z_0 \delta \ddot{\theta}_i + \delta \omega_{i-1} \times (z_0 \dot{\theta}_i ) + \omega_{i-1} \times (z_0 \delta \dot{\theta}_i )] - \sigma_i Q [ \omega_{i-1} + z_0 \ddot{\theta}_i + \omega_{i-1} \times (z_0 \dot{\theta}_i )] \delta \theta_i \} \]](form_51.png) 
![\[ \delta \dot{v}_i = R_i^T \{ \delta \dot{v}_{i-1} - \sigma_i Q \dot{v}_{i-1} \delta \theta_i + (1 -\sigma_i) [z_0 \delta \ddot{d}_i + 2 \delta \omega_{i-1} \times (z_0 \dot{d}_i ) + 2 \omega_{i-1} \times (z_0 \delta \dot{d}_i )] \} + \delta \dot{\omega}_i \times p_i + \delta \omega_i \times ( \omega_i \times p_i) + \omega_i \times ( \delta \omega_i \times p_i) + (1 - \sigma_i) (\dot{\omega}_i \times p_{di} + \omega_i \times ( \omega_i \times p_{di}) ) \delta d_i \]](form_52.png) 
Backward Iterations for  . Initialize:
. Initialize:  .
.
![\[ \delta \dot{v}_{ci} = \delta v_i + \delta \omega_i \times r_i + \delta \omega_i \times (\omega_i \times r_i) + \omega_i \times (\delta \omega_i \times r_i) \]](form_55.png) 
![\[ \delta F_i = m_i \delta \dot{v}_{ci} \]](form_56.png) 
![\[ \delta N_i = I_{ci} \delta \dot{\omega}_i + \delta \omega_i \times (I_{ci} \omega_i) + \omega_i \times (I_{ci} \delta \omega_i) \]](form_57.png) 
![\[ \delta f_i = R_{i+1} [ \delta f_{i+1} ] + \delta F_{i} + \sigma_{i+1} Q R_{i+1} [ f_{i+1} ] \delta \theta_{i+1} \]](form_58.png) 
![\[ \delta n_i = R_{i+1} [ \delta n_{i+1} ] + \delta N_{i} + p_{i} \times \delta f_{i} + r_{i} \times \delta F_{i} + (1 - \sigma_i) (p_{di} \times f_{i}) \delta d_i + \sigma_{i+1} Q R_{i+1} [ n_{i+1} ] \delta \theta_{i+1} \]](form_59.png) 
![\[ \delta \tau_i = \sigma_i [ \delta n_i^T (R_i^T z_0) - n_i^T (R_i^T Q z_0) \delta \theta_i] + (1 -\sigma_i) [ \delta f_i^T (R_i^T z_0) ] \]](form_60.png) 
Implements Robot_basic.
Definition at line 65 of file delta_t.cpp.
| void Robot::dq_torque | ( | const ColumnVector & | q, | 
| const ColumnVector & | qp, | ||
| const ColumnVector & | qpp, | ||
| const ColumnVector & | dq, | ||
| ColumnVector & | ltorque, | ||
| ColumnVector & | dtorque | ||
| ) |  [virtual] | 
Delta torque due to delta joint position.
This function computes  . See Robot::delta_torque for equations.
. See Robot::delta_torque for equations. 
Implements Robot_basic.
Definition at line 65 of file comp_dq.cpp.
| void Robot::dqp_torque | ( | const ColumnVector & | q, | 
| const ColumnVector & | qp, | ||
| const ColumnVector & | dqp, | ||
| ColumnVector & | ltorque, | ||
| ColumnVector & | dtorque | ||
| ) |  [virtual] | 
Delta torque due to delta joint velocity.
This function computes  . See Robot::delta_torque for equations.
. See Robot::delta_torque for equations. 
Implements Robot_basic.
Definition at line 63 of file comp_dqp.cpp.
| void Robot::dTdqi | ( | Matrix & | dRot, | 
| ColumnVector & | dp, | ||
| const int | i | ||
| ) |  [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-1} Q_i \; {}^{i-1} T_n \]](form_110.png) 
in standard notation and
![\[ \frac{\partial{}^0 T_n}{\partial q_i} = {}^0 T_{i} Q_i \; {}^{i} T_n \]](form_111.png) 
in modified notation,
with
![\[ Q_i = \left [ \begin{array}{cccc} 0 & -1 & 0 & 0 \\ 1 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 \end{array} \right ] \]](form_112.png) 
for a revolute joint and
![\[ Q_i = \left [ \begin{array}{cccc} 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 0 \\ 0 & 0 & 0 & 1 \\ 0 & 0 & 0 & 0 \end{array} \right ] \]](form_113.png) 
for a prismatic joint.
 and
 and  are modified on output.
 are modified on output. 
Implements Robot_basic.
Definition at line 249 of file kinemat.cpp.
| ReturnMatrix Robot::dTdqi | ( | const int | i | ) |  [virtual] | 
Partial derivative of the robot position (homogeneous transf.)
See Robot::dTdqi(Matrix & dRot, ColumnVector & dp, const int i) for equations.
Implements Robot_basic.
Definition at line 334 of file kinemat.cpp.
| ReturnMatrix Robot::G | ( | ) |  [virtual] | 
Joint torque due to gravity based on Recursive Newton-Euler formulation.
Implements Robot_basic.
Definition at line 321 of file dynamics.cpp.
| ReturnMatrix Robot::inv_kin | ( | const Matrix & | Tobj, | 
| const int | mj = 0 | ||
| ) |  [virtual] | 
Overload inv_kin function.
Reimplemented from Robot_basic.
Definition at line 218 of file invkine.cpp.
| ReturnMatrix Robot::inv_kin | ( | const Matrix & | Tobj, | 
| const int | mj, | ||
| const int | endlink, | ||
| bool & | converge | ||
| ) |  [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 226 of file invkine.cpp.
| ReturnMatrix Robot::inv_kin_puma | ( | const Matrix & | Tobj, | 
| bool & | converge | ||
| ) |  [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 348 of file invkine.cpp.
| ReturnMatrix Robot::inv_kin_rhino | ( | const Matrix & | Tobj, | 
| bool & | converge | ||
| ) |  [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 251 of file invkine.cpp.
| ReturnMatrix Robot::inv_kin_schilling | ( | const Matrix & | Tobj, | 
| bool & | converge | ||
| ) |  [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 508 of file invkine.cpp.
| virtual ReturnMatrix Robot::jacobian | ( | const int | ref = 0 | ) | const  [inline, virtual] | 
Jacobian of mobile links expressed at frame ref.
Reimplemented from Robot_basic.
| ReturnMatrix Robot::jacobian | ( | const int | endlink, | 
| const int | ref | ||
| ) | const  [virtual] | 
Jacobian of mobile links up to endlink expressed at frame ref.
The Jacobian expressed in based frame is
![\[ ^{0}J(q) = \left[ \begin{array}{cccc} ^{0}J_1(q) & ^{0}J_2(q) & \cdots & ^{0}J_n(q) \\ \end{array} \right] \]](form_116.png) 
 where  is defined by
 is defined by 
![\[ ^{0}J_i(q) = \begin{array}{cc} \left[ \begin{array}{c} z_i \times ^{i}p_n \\ z_i \\ \end{array} \right] & \textrm{rotoid joint} \end{array} \]](form_118.png) 
![\[ ^{0}J_i(q) = \begin{array}{cc} \left[ \begin{array}{c} z_i \\ 0 \\ \end{array} \right] & \textrm{prismatic joint} \\ \end{array} \]](form_119.png) 
Expressed in a different frame the Jacobian is obtained by
![\[ ^{i}J(q) = \left[ \begin{array}{cc} ^{0}_iR^T & 0 \\ 0 & ^{0}_iR^T \end{array} \right] {^{0}}J(q) \]](form_120.png) 
Implements Robot_basic.
Definition at line 352 of file kinemat.cpp.
| ReturnMatrix Robot::jacobian_dot | ( | const int | ref = 0 | ) | const  [virtual] | 
Jacobian derivative of mobile joints expressed at frame ref.
The Jacobian derivative expressed in based frame is
![\[ ^{0}\dot{J}(q,\dot{q}) = \left[ \begin{array}{cccc} ^{0}\dot{J}_1(q,\dot{q}) & ^{0}\dot{J}_2(q,\dot{q}) & \cdots & ^{0}\dot{J}_n(q,\dot{q}) \\ \end{array} \right] \]](form_121.png) 
 where  is defined by
 is defined by 
![\[ ^{0}\dot{J}_i(q,\dot{q}) = \begin{array}{cc} \left[ \begin{array}{c} \omega_{i-1} \times z_i \\ \omega_{i-1} \times ^{i-1}p_n + z_i \times ^{i-1}\dot{p}_n \end{array} \right] & \textrm{rotoid joint} \end{array} \]](form_123.png) 
![\[ ^{0}\dot{J}_i(q,\dot{q}) = \begin{array}{cc} \left[ \begin{array}{c} 0 \\ 0 \\ \end{array} \right] & \textrm{prismatic joint} \\ \end{array} \]](form_124.png) 
Expressed in a different frame the Jacobian derivative is obtained by
![\[ ^{i}J(q) = \left[ \begin{array}{cc} ^{0}_iR^T & 0 \\ 0 & ^{0}_iR^T \end{array} \right] {^{0}}J(q) \]](form_120.png) 
Implements Robot_basic.
Definition at line 449 of file kinemat.cpp.
| void Robot::kine_pd | ( | Matrix & | Rot, | 
| ColumnVector & | pos, | ||
| ColumnVector & | pos_dot, | ||
| const int | j | ||
| ) | const  [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 219 of file kinemat.cpp.
| void Robot::robotType_inv_kin | ( | ) |  [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.
| ReturnMatrix Robot::torque | ( | const ColumnVector & | q, | 
| const ColumnVector & | qp, | ||
| const ColumnVector & | qpp | ||
| ) |  [virtual] | 
Joint torque, without contact force, based on Recursive Newton-Euler formulation.
Implements Robot_basic.
Definition at line 135 of file dynamics.cpp.
| ReturnMatrix Robot::torque | ( | const ColumnVector & | q, | 
| const ColumnVector & | qp, | ||
| const ColumnVector & | qpp, | ||
| const ColumnVector & | Fext, | ||
| const ColumnVector & | Next | ||
| ) |  [virtual] | 
Joint torque based on Recursive Newton-Euler formulation.
In order to apply the RNE as presented in Murray 86, let us define the following variables (referenced in the  coordinate frame if applicable):
 coordinate frame if applicable):
 is the joint type;
 is the joint type;  for a revolute joint and
 for a revolute joint and  for a prismatic joint.
 for a prismatic joint.
![$ z_0 = \left [ \begin{array}{ccc} 0 & 0 & 1 \end{array} \right ]^T$](form_74.png)
![$p_i = \left [ \begin{array}{ccc} a_i & d_i \sin \alpha_i & d_i \cos \alpha_i \end{array} \right ]^T$](form_75.png) is the position of the
 is the position of the  with respect to the
 with respect to the  frame.
 frame.
Forward Iterations for  . Initialize:
. Initialize:  and
 and  .
. 
![\[ \omega_i = R_i^T [\omega_{i-1} + \sigma_i z_0 \dot{\theta}_i ] \]](form_79.png) 
![\[ \dot{\omega}_i = R_i^T \{ \dot{\omega}_{i-1} + \sigma_i [z_0 \ddot{\theta}_i + \omega_{i-1} \times (z_0 \dot{\theta}_i )] \} \]](form_80.png) 
![\[ \dot{v}_i = R_i^T \{ \dot{v}_{i-1} + (1 -\sigma_i) [z_0 \ddot{d}_i + 2 \omega_{i-1} \times (z_0 \dot{d}_i )] \} + \dot{\omega}_i \times p_i + \omega_i \times ( \omega_i \times p_i) \]](form_81.png) 
Backward Iterations for  . Initialize: $f_{n+1} = n_{n+1} = 0$.
. Initialize: $f_{n+1} = n_{n+1} = 0$. 
![\[ \dot{v}_{ci} = v_i + \omega_i \times r_i + \omega_i \times (\omega_i \times r_i) \]](form_82.png) 
![\[ F_i = m_i \dot{v}_{ci} \]](form_83.png) 
![\[ N_i = I_{ci} \dot{\omega}_i + \omega_i \times (I_{ci} \omega_i) \]](form_84.png) 
![\[ f_i = R_{i+1} [ f_{i+1} ] + F_{i} \]](form_85.png) 
![\[ n_i = R_{i+1} [ n_{i+1} ] + p_{i} \times f_{i} + N_{i} + r_{i} \times F_{i} \]](form_86.png) 
![\[ \tau_i = \sigma_i n_i^T (R_i^T z_0) + (1 - \sigma_i) f_i^T (R_i^T z_0) \]](form_87.png) 
Implements Robot_basic.
Definition at line 148 of file dynamics.cpp.
| ReturnMatrix Robot::torque_novelocity | ( | const ColumnVector & | qpp | ) |  [virtual] | 
Joint torque. when joint velocity is 0, based on Recursive Newton-Euler formulation.
Implements Robot_basic.
Definition at line 272 of file dynamics.cpp.