ROBOOP::mRobot Class Reference#include <robot.h>
Inheritance diagram for ROBOOP::mRobot:
[legend]List of all members.
Detailed Description
Modified DH notation robot class.
Definition at line 448 of file robot.h.
|
Public Member Functions |
| mRobot (const int ndof=1) |
| Constructor.
|
| mRobot (const Matrix &initrobot_motor) |
| Constructor.
|
| mRobot (const Matrix &initrobot, const Matrix &initmotor) |
| Constructor.
|
| mRobot (const mRobot &x) |
| Copy constructor.
|
| mRobot (const string &filename, const string &robotName) |
| Constructor.
|
| mRobot (const Config &robData, const string &robotName) |
| ~mRobot () |
| Destructor.
|
mRobot & | operator= (const mRobot &x) |
| Overload = operator.
|
virtual void | robotType_inv_kin () |
| Identify inverse kinematics familly.
|
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_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 void | kine_pd (Matrix &Rot, ColumnVector &pos, ColumnVector &pos_dot, const int ref) const |
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 |
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) |
virtual ReturnMatrix | dTdqi (const int i, const int endlink) |
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 &torque, 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) |
Constructor & Destructor Documentation
ROBOOP::mRobot::mRobot |
( |
const int |
ndof = 1 |
) |
[explicit] |
|
ROBOOP::mRobot::mRobot |
( |
const Matrix & |
initrobot_motor |
) |
[explicit] |
|
ROBOOP::mRobot::mRobot |
( |
const Matrix & |
initrobot, |
|
|
const Matrix & |
initmotor |
|
) |
[explicit] |
|
ROBOOP::mRobot::mRobot |
( |
const mRobot & |
x |
) |
|
|
ROBOOP::mRobot::mRobot |
( |
const string & |
filename, |
|
|
const string & |
robotName |
|
) |
[explicit] |
|
ROBOOP::mRobot::mRobot |
( |
const Config & |
robData, |
|
|
const string & |
robotName |
|
) |
[explicit] |
|
ROBOOP::mRobot::~mRobot |
( |
|
) |
[inline] |
|
|
Destructor.
Definition at line 456 of file robot.h. |
Member Function Documentation
virtual ReturnMatrix ROBOOP::mRobot::dTdqi |
( |
const int |
i, |
|
|
const int |
endlink |
|
) |
[virtual] |
|
virtual void ROBOOP::mRobot::dTdqi |
( |
Matrix & |
dRot, |
|
|
ColumnVector & |
dpos, |
|
|
const int |
i, |
|
|
const int |
endlink |
|
) |
[virtual] |
|
virtual ReturnMatrix ROBOOP::mRobot::dTdqi |
( |
const int |
i |
) |
[inline, virtual] |
|
virtual void ROBOOP::mRobot::dTdqi |
( |
Matrix & |
dRot, |
|
|
ColumnVector & |
dpos, |
|
|
const int |
i |
|
) |
[inline, virtual] |
|
ReturnMatrix ROBOOP::mRobot::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 1107 of file invkine.cpp. |
virtual ReturnMatrix ROBOOP::mRobot::inv_kin |
( |
const Matrix & |
Tobj, |
|
|
const int |
mj, |
|
|
bool & |
converge |
|
) |
[inline, virtual] |
|
ReturnMatrix ROBOOP::mRobot::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 1236 of file invkine.cpp.
Referenced by inv_kin(). |
ReturnMatrix ROBOOP::mRobot::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 1129 of file invkine.cpp.
Referenced by inv_kin(). |
virtual ReturnMatrix ROBOOP::mRobot::jacobian |
( |
const int |
endlink, |
|
|
const int |
ref |
|
) |
const [virtual] |
|
virtual ReturnMatrix ROBOOP::mRobot::jacobian |
( |
const int |
ref = 0 |
) |
const [inline, virtual] |
|
virtual ReturnMatrix ROBOOP::mRobot::jacobian_dot |
( |
const int |
ref = 0 |
) |
const [virtual] |
|
void ROBOOP::mRobot::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 1496 of file robot.cpp.
Referenced by mRobot(). |
The documentation for this class was generated from the following files:
|