Homepage Demos Overview Downloads Tutorials Reference
Credits

ROBOOP::mRobot_min_para Class Reference

#include <robot.h>

Inheritance diagram for ROBOOP::mRobot_min_para:

Inheritance graph
[legend]
List of all members.

Detailed Description

Modified DH notation and minimal inertial parameters robot class.

Definition at line 500 of file 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 string &filename, const string &robotName)
 Constructor.
 mRobot_min_para (const Config &robData, const string &robotName)
 ~mRobot_min_para ()
 Destructor.
mRobot_min_paraoperator= (const mRobot_min_para &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=0) 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_min_para::mRobot_min_para const int  ndof = 1  )  [explicit]
 

Constructor.

Definition at line 1519 of file robot.cpp.

ROBOOP::mRobot_min_para::mRobot_min_para const Matrix dhinit  )  [explicit]
 

Constructor.

Definition at line 1528 of file robot.cpp.

ROBOOP::mRobot_min_para::mRobot_min_para const Matrix initrobot,
const Matrix initmotor
[explicit]
 

Constructor.

Definition at line 1538 of file robot.cpp.

ROBOOP::mRobot_min_para::mRobot_min_para const mRobot_min_para x  ) 
 

Copy constructor.

Definition at line 1548 of file robot.cpp.

ROBOOP::mRobot_min_para::mRobot_min_para const string &  filename,
const string &  robotName
[explicit]
 

Constructor.

Definition at line 1557 of file robot.cpp.

ROBOOP::mRobot_min_para::mRobot_min_para const Config robData,
const string &  robotName
[explicit]
 

Definition at line 1567 of file robot.cpp.

ROBOOP::mRobot_min_para::~mRobot_min_para  )  [inline]
 

Destructor.

Definition at line 509 of file robot.h.


Member Function Documentation

virtual ReturnMatrix ROBOOP::mRobot_min_para::C const ColumnVector qp  )  [virtual]
 

Implements ROBOOP::Robot_basic.

virtual void ROBOOP::mRobot_min_para::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]
 

Implements ROBOOP::Robot_basic.

virtual void ROBOOP::mRobot_min_para::dq_torque const ColumnVector q,
const ColumnVector qp,
const ColumnVector qpp,
const ColumnVector dq,
ColumnVector torque,
ColumnVector dtorque
[virtual]
 

Implements ROBOOP::Robot_basic.

virtual void ROBOOP::mRobot_min_para::dqp_torque const ColumnVector q,
const ColumnVector qp,
const ColumnVector dqp,
ColumnVector torque,
ColumnVector dtorque
[virtual]
 

Implements ROBOOP::Robot_basic.

virtual ReturnMatrix ROBOOP::mRobot_min_para::dTdqi const int  i,
const int  endlink
[virtual]
 

Implements ROBOOP::Robot_basic.

virtual void ROBOOP::mRobot_min_para::dTdqi Matrix dRot,
ColumnVector dpos,
const int  i,
const int  endlink
[virtual]
 

Implements ROBOOP::Robot_basic.

virtual ReturnMatrix ROBOOP::mRobot_min_para::dTdqi const int  i  )  [inline, virtual]
 

Partial derivative of the robot position (homogeneous transf.) See dTdqi(Matrix & dRot, ColumnVector & dpos, const int i, const int endlink).

Reimplemented from ROBOOP::Robot_basic.

Definition at line 523 of file robot.h.

virtual void ROBOOP::mRobot_min_para::dTdqi Matrix dRot,
ColumnVector dpos,
const int  i
[inline, virtual]
 

Partial derivative of the robot position (homogeneous transf.) See dTdqi(Matrix & dRot, ColumnVector & dpos, const int i, const int endlink).

Reimplemented from ROBOOP::Robot_basic.

Definition at line 522 of file robot.h.

Referenced by dTdqi().

virtual ReturnMatrix ROBOOP::mRobot_min_para::G  )  [virtual]
 

Implements ROBOOP::Robot_basic.

ReturnMatrix ROBOOP::mRobot_min_para::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 1407 of file invkine.cpp.

virtual ReturnMatrix ROBOOP::mRobot_min_para::inv_kin const Matrix Tobj,
const int  mj,
bool &  converge
[inline, virtual]
 

Numerical inverse kinematics. See inv_kin(const Matrix & Tobj, const int mj, const int endlink, bool & converge).

Reimplemented from ROBOOP::Robot_basic.

Definition at line 513 of file robot.h.

ReturnMatrix ROBOOP::mRobot_min_para::inv_kin const Matrix Tobj,
const int  mj = 0
[virtual]
 

Overload inv_kin function.

Reimplemented from ROBOOP::Robot_basic.

Definition at line 1399 of file invkine.cpp.

Referenced by inv_kin().

ReturnMatrix ROBOOP::mRobot_min_para::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 1528 of file invkine.cpp.

Referenced by inv_kin().

ReturnMatrix ROBOOP::mRobot_min_para::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 1429 of file invkine.cpp.

Referenced by inv_kin().

virtual ReturnMatrix ROBOOP::mRobot_min_para::jacobian const int  endlink,
const int  ref
const [virtual]
 

Implements ROBOOP::Robot_basic.

virtual ReturnMatrix ROBOOP::mRobot_min_para::jacobian const int  ref = 0  )  const [inline, virtual]
 

Jacobian of mobile links expressed at frame ref.

Reimplemented from ROBOOP::Robot_basic.

Definition at line 519 of file robot.h.

virtual ReturnMatrix ROBOOP::mRobot_min_para::jacobian_dot const int  ref = 0  )  const [virtual]
 

Implements ROBOOP::Robot_basic.

virtual void ROBOOP::mRobot_min_para::kine_pd Matrix Rot,
ColumnVector pos,
ColumnVector pos_dot,
const int  ref = 0
const [virtual]
 

Implements ROBOOP::Robot_basic.

mRobot_min_para & ROBOOP::mRobot_min_para::operator= const mRobot_min_para x  ) 
 

Overload = operator.

Definition at line 1573 of file robot.cpp.

void ROBOOP::mRobot_min_para::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 1580 of file robot.cpp.

Referenced by mRobot_min_para().

virtual ReturnMatrix ROBOOP::mRobot_min_para::torque const ColumnVector q,
const ColumnVector qp,
const ColumnVector qpp,
const ColumnVector Fext_,
const ColumnVector Next_
[virtual]
 

Implements ROBOOP::Robot_basic.

virtual ReturnMatrix ROBOOP::mRobot_min_para::torque const ColumnVector q,
const ColumnVector qp,
const ColumnVector qpp
[virtual]
 

Implements ROBOOP::Robot_basic.

virtual ReturnMatrix ROBOOP::mRobot_min_para::torque_novelocity const ColumnVector qpp  )  [virtual]
 

Implements ROBOOP::Robot_basic.


The documentation for this class was generated from the following files:

ROBOOP v1.21a
Generated Tue Aug 16 16:32:19 2005 by Doxygen 1.4.4