ROBOOP::Robot Class Reference#include <robot.h>
Inheritance diagram for ROBOOP::Robot:
[legend]List of all members.
Detailed Description
DH notation robot class.
Definition at line 385 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 string &filename, const string &robotName) |
| Constructor.
|
| Robot (const Config &robData, const string &robotName) |
| ~Robot () |
| Destructor.
|
Robot & | operator= (const Robot &x) |
| Overload = operator.
|
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.
|
virtual ReturnMatrix | inv_kin (const Matrix &Tobj, const int mj=0) |
| Overload inv_kin function.
|
virtual ReturnMatrix | inv_kin (const Matrix &Tobj, const int mj, bool &converge) |
| Numerical inverse kinematics. See inv_kin(const Matrix & Tobj, const int mj, const int endlink, bool & converge).
|
virtual ReturnMatrix | inv_kin (const Matrix &Tobj, const int mj, const int endlink, bool &converge) |
| Inverse kinematics solutions.
|
virtual ReturnMatrix | inv_kin_pos (const ColumnVector &Pobj, const int mj, const int endlink, const ColumnVector &Plink, bool &converge) |
| Inverse kinematics solutions.
|
virtual ReturnMatrix | inv_kin_orientation (const Matrix &Robj, 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_ers_pos (const ColumnVector &Pobj, const int endlink, const ColumnVector &Plink, bool &converge) |
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 |
virtual void | dTdqi (Matrix &dRot, ColumnVector &dpos, const int i) |
| Partial derivative of the robot position (homogeneous transf.) See dTdqi(Matrix & dRot, ColumnVector & dpos, const int i, const int endlink).
|
virtual ReturnMatrix | dTdqi (const int i) |
| Partial derivative of the robot position (homogeneous transf.) See dTdqi(Matrix & dRot, ColumnVector & dpos, const int i, const int endlink).
|
virtual void | dTdqi (Matrix &dRot, ColumnVector &dpos, const int i, const int endlink) |
| Partial derivative of the robot position (homogeneous transf.).
|
virtual ReturnMatrix | dTdqi (const int i, const int endlink) |
| Partial derivative of the robot position (homogeneous transf.).
|
virtual ReturnMatrix | torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp) |
virtual ReturnMatrix | torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp, const ColumnVector &Fext_, const ColumnVector &Next_) |
virtual ReturnMatrix | torque_novelocity (const ColumnVector &qpp) |
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) |
virtual void | dq_torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp, const ColumnVector &dq, ColumnVector &torque, ColumnVector &dtorque) |
virtual void | dqp_torque (const ColumnVector &q, const ColumnVector &qp, const ColumnVector &dqp, ColumnVector &torque, ColumnVector &dtorque) |
virtual ReturnMatrix | G () |
virtual ReturnMatrix | C (const ColumnVector &qp) |
Protected Member Functions |
Real | computeFirstERSLink (int curlink, const ColumnVector &Pobj, const int endlink, const ColumnVector &Plink, Real min, Real max, bool &converge) |
Real | computeSecondERSLink (int curlink, const ColumnVector &Pobj, const int endlink, const ColumnVector &Plink, bool invert, Real min, Real max, bool &converge) |
Real | computeThirdERSLink (int curlink, const ColumnVector &Pobj, const int endlink, const ColumnVector &Plink, bool invert, Real min, Real max, bool &converge) |
Constructor & Destructor Documentation
ROBOOP::Robot::Robot |
( |
const int |
ndof = 1 |
) |
[explicit] |
|
ROBOOP::Robot::Robot |
( |
const Matrix & |
initrobot |
) |
[explicit] |
|
ROBOOP::Robot::Robot |
( |
const Matrix & |
initrobot, |
|
|
const Matrix & |
initmotor |
|
) |
[explicit] |
|
ROBOOP::Robot::Robot |
( |
const Robot & |
x |
) |
|
|
ROBOOP::Robot::Robot |
( |
const string & |
filename, |
|
|
const string & |
robotName |
|
) |
[explicit] |
|
ROBOOP::Robot::Robot |
( |
const Config & |
robData, |
|
|
const string & |
robotName |
|
) |
[explicit] |
|
ROBOOP::Robot::~Robot |
( |
|
) |
[inline] |
|
|
Destructor.
Definition at line 394 of file robot.h. |
Member Function Documentation
Real ROBOOP::Robot::computeSecondERSLink |
( |
int |
curlink, |
|
|
const ColumnVector & |
Pobj, |
|
|
const int |
endlink, |
|
|
const ColumnVector & |
Plink, |
|
|
bool |
invert, |
|
|
Real |
min, |
|
|
Real |
max, |
|
|
bool & |
converge |
|
) |
[protected] |
|
Real ROBOOP::Robot::computeThirdERSLink |
( |
int |
curlink, |
|
|
const ColumnVector & |
Pobj, |
|
|
const int |
endlink, |
|
|
const ColumnVector & |
Plink, |
|
|
bool |
invert, |
|
|
Real |
min, |
|
|
Real |
max, |
|
|
bool & |
converge |
|
) |
[protected] |
|
ReturnMatrix ROBOOP::Robot::dTdqi |
( |
const int |
i, |
|
|
const int |
endlink |
|
) |
[virtual] |
|
void ROBOOP::Robot::dTdqi |
( |
Matrix & |
dRot, |
|
|
ColumnVector & |
dpos, |
|
|
const int |
i, |
|
|
const int |
endlink |
|
) |
[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 ROBOOP::Robot_basic.
Definition at line 454 of file kinemat.cpp. |
virtual ReturnMatrix ROBOOP::Robot::dTdqi |
( |
const int |
i |
) |
[inline, virtual] |
|
virtual void ROBOOP::Robot::dTdqi |
( |
Matrix & |
dRot, |
|
|
ColumnVector & |
dpos, |
|
|
const int |
i |
|
) |
[inline, virtual] |
|
ReturnMatrix ROBOOP::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 ROBOOP::Robot_basic.
Definition at line 583 of file invkine.cpp. |
virtual ReturnMatrix ROBOOP::Robot::inv_kin |
( |
const Matrix & |
Tobj, |
|
|
const int |
mj, |
|
|
bool & |
converge |
|
) |
[inline, virtual] |
|
ReturnMatrix ROBOOP::Robot::inv_kin_orientation |
( |
const Matrix & |
Robj, |
|
|
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 ROBOOP::Robot_basic.
Definition at line 628 of file invkine.cpp. |
|
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 ROBOOP::Robot_basic.
Definition at line 606 of file invkine.cpp. |
ReturnMatrix ROBOOP::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 ROBOOP::Robot_basic.
Definition at line 750 of file invkine.cpp.
Referenced by inv_kin(). |
ReturnMatrix ROBOOP::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 ROBOOP::Robot_basic.
Definition at line 651 of file invkine.cpp.
Referenced by inv_kin(). |
ReturnMatrix ROBOOP::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 ROBOOP::Robot_basic.
Definition at line 557 of file kinemat.cpp. |
virtual ReturnMatrix ROBOOP::Robot::jacobian |
( |
const int |
ref = 0 |
) |
const [inline, virtual] |
|
virtual ReturnMatrix ROBOOP::Robot::jacobian_dot |
( |
const int |
ref = 0 |
) |
const [virtual] |
|
|
Direct kinematics with velocity.
- Parameters:
-
| 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 ROBOOP::Robot_basic.
Definition at line 424 of file kinemat.cpp. |
Robot & ROBOOP::Robot::operator= |
( |
const Robot & |
x |
) |
|
|
void ROBOOP::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 ROBOOP::Robot_basic.
Definition at line 1405 of file robot.cpp.
Referenced by Robot(). |
The documentation for this class was generated from the following files:
|