#include <robot.h>
Inheritance diagram for Robot:

Definition at line 340 of file robot.h.
Public Member Functions | |
| 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 | ~Robot () |
| Destructor. | |
| virtual void | robotType_inv_kin () |
| Identify inverse kinematics familly. | |
| virtual void | kine_pd (Matrix &Rot, ColumnVector &pos, ColumnVector &pos_dot, const int ref) const |
| Direct kinematics with velocity. | |
| 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_rhino (const Matrix &Tobj, bool &converge) |
| Analytic Rhino inverse kinematics. | |
| virtual ReturnMatrix | inv_kin_puma (const Matrix &Tobj, bool &converge) |
| Analytic Puma 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 | 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 | 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 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 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. | |
| 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.
Definition at line 1284 of file robot.cpp.
References Robot_basic::DEFAULT, Robot_basic::PUMA, Puma_DH(), Robot_basic::RHINO, Rhino_DH(), Robot_basic::robotType, Robot_basic::SCHILLING, and Schilling_DH().
Referenced by Robot().
| 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.
Referenced by Resolved_acc::torque_cmd().
| 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 204 of file invkine.cpp.
References Robot_basic::inv_kin(), inv_kin_puma(), inv_kin_rhino(), inv_kin_schilling(), Robot_basic::PUMA, Robot_basic::RHINO, Robot_basic::robotType, and Robot_basic::SCHILLING.
| 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 229 of file invkine.cpp.
References Robot_basic::a, Link::a, Link::d, G(), Robot_basic::get_q(), K, Robot_basic::links, and M_PI.
Referenced by inv_kin().
| 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 326 of file invkine.cpp.
References Robot_basic::a, Link::a, C(), Link::d, Robot_basic::get_q(), Robot_basic::links, and M_PI.
Referenced by inv_kin().
| 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 486 of file invkine.cpp.
References Robot_basic::a, Link::a, C(), Link::d, Robot_basic::get_q(), K, Robot_basic::links, and M_PI.
Referenced by inv_kin().
| 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
where
is defined by
Expressed in a different frame the Jacobian is obtained by
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
where
is defined by
Expressed in a different frame the Jacobian derivative is obtained by
Implements Robot_basic.
Definition at line 449 of file kinemat.cpp.
Referenced by Resolved_acc::torque_cmd().
| 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:
in standard notation and
in modified notation,
with
for a revolute joint and
for a prismatic joint.
and
are modified on output.
Implements Robot_basic.
Definition at line 249 of file kinemat.cpp.
References Robot_basic::dof, Robot_basic::dp, Robot_basic::links, Robot_basic::p, Link::p, Robot_basic::R, Link::R, and threebythreeident.
Referenced by dTdqi(), and kinematics_demo().
| 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.
References dTdqi().
| 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):
is the joint type;
for a revolute joint and
for a prismatic joint.
![$ z_0 = \left [ \begin{array}{ccc} 0 & 0 & 1 \end{array} \right ]^T$](form_74.png)
is the position of the
with respect to the
frame.
Forward Iterations for
. Initialize:
and
.
Backward Iterations for
. Initialize: $f_{n+1} = n_{n+1} = 0$.
Implements Robot_basic.
Definition at line 148 of file dynamics.cpp.
References Robot_basic::a, Link::B, Link::Cf, Robot_basic::dof, Robot_basic::f, Robot_basic::F, Link::Gr, Robot_basic::gravity, Link::I, Link::Im, Robot_basic::links, Robot_basic::n, Robot_basic::N, Robot_basic::p, Link::R, Robot_basic::R, Robot_basic::set_q(), Robot_basic::set_qp(), sign(), Robot_basic::vp, Robot_basic::w, Robot_basic::wp, and Robot_basic::z0.
| 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
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
Forward Iterations for
. Initialize:
.
Backward Iterations for
. Initialize:
.
Implements Robot_basic.
Definition at line 65 of file delta_t.cpp.
References Robot_basic::a, Robot_basic::da, Robot_basic::df, Robot_basic::dF, Robot_basic::dn, Robot_basic::dN, Robot_basic::dof, Robot_basic::dp, Robot_basic::dvp, Robot_basic::dw, Robot_basic::dwp, Robot_basic::f, Robot_basic::F, Robot_basic::gravity, Link::I, Robot_basic::links, Link::m, Robot_basic::n, Robot_basic::N, Robot_basic::p, Link::R, Robot_basic::R, Robot_basic::set_q(), Robot_basic::vp, Robot_basic::w, Robot_basic::wp, and Robot_basic::z0.
| 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.
Implements Robot_basic.
Definition at line 65 of file comp_dq.cpp.
References Robot_basic::a, Robot_basic::da, Robot_basic::df, Robot_basic::dF, Robot_basic::dn, Robot_basic::dN, Robot_basic::dof, Robot_basic::dp, Robot_basic::dvp, Robot_basic::dw, Robot_basic::dwp, Robot_basic::f, Robot_basic::F, Robot_basic::gravity, Link::I, Robot_basic::links, Link::m, Robot_basic::n, Robot_basic::N, Robot_basic::p, Link::R, Robot_basic::R, Robot_basic::set_q(), Robot_basic::vp, Robot_basic::w, Robot_basic::wp, and Robot_basic::z0.
| 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.
Implements Robot_basic.
Definition at line 63 of file comp_dqp.cpp.
References Robot_basic::a, Robot_basic::da, Robot_basic::df, Robot_basic::dF, Robot_basic::dn, Robot_basic::dN, Robot_basic::dof, Robot_basic::dp, Robot_basic::dvp, Robot_basic::dw, Robot_basic::dwp, Robot_basic::f, Robot_basic::F, Robot_basic::gravity, Link::I, Robot_basic::links, Link::m, Robot_basic::n, Robot_basic::N, Robot_basic::p, Link::R, Robot_basic::R, Robot_basic::set_q(), Robot_basic::vp, Robot_basic::w, Robot_basic::wp, and Robot_basic::z0.
1.5.1