Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

ROBOOP::mRobot_min_para Class Reference

#include <robot.h>

Inheritance diagram for ROBOOP::mRobot_min_para:

List of all members.


Detailed Description

Modified DH notation and minimal inertial parameters robot class.

Definition at line 507 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 std::string &filename, const std::string &robotName)
 Constructor.
 mRobot_min_para (const Config &robData, const std::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
 Direct kinematics with velocity.
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 joints 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 &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)
 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 &torque, 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.

Constructor & Destructor Documentation

ROBOOP::mRobot_min_para::mRobot_min_para ( const int  ndof = 1  )  [explicit]

Constructor.

Definition at line 1526 of file robot.cpp.

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

Constructor.

Definition at line 1535 of file robot.cpp.

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

Constructor.

Definition at line 1545 of file robot.cpp.

ROBOOP::mRobot_min_para::mRobot_min_para ( const mRobot_min_para x  ) 

Copy constructor.

Definition at line 1555 of file robot.cpp.

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

Constructor.

Definition at line 1564 of file robot.cpp.

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

Definition at line 1574 of file robot.cpp.

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

Destructor.

Definition at line 516 of file robot.h.


Member Function Documentation

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

Overload = operator.

Definition at line 1580 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 1587 of file robot.cpp.

Referenced by mRobot_min_para().

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 1559 of file invkine.cpp.

Referenced by inv_kin().

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 520 of file robot.h.

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 1567 of file invkine.cpp.

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 1589 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 1688 of file invkine.cpp.

Referenced by inv_kin().

void ROBOOP::mRobot_min_para::kine_pd ( Matrix Rot,
ColumnVector pos,
ColumnVector pos_dot,
const int  j = 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 1000 of file kinemat.cpp.

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 526 of file robot.h.

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

Jacobian of mobile joints up to endlink expressed at frame ref.

See Robot::jacobian for equations.

Implements ROBOOP::Robot_basic.

Definition at line 1106 of file kinemat.cpp.

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

Jacobian derivative of mobile joints expressed at frame ref.

See Robot::jacobian_dot for equations.

Implements ROBOOP::Robot_basic.

Definition at line 1161 of file kinemat.cpp.

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 529 of file robot.h.

Referenced by dTdqi().

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 530 of file robot.h.

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

\[ \frac{\partial{}^0 T_n}{\partial q_i} = {}^0 T_{i} Q_i \; {}^{i} T_n \]

See mRobot::dTdqi(Matrix & dRot, ColumnVector & dpos, const int i, const int endlink) for equations.

Implements ROBOOP::Robot_basic.

Definition at line 1030 of file kinemat.cpp.

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

Partial derivative of the robot position (homogeneous transf.).

See mRobot::dTdqi(Matrix & dRot, ColumnVector & dpos, const int i, const int endlink) for equations.

Implements ROBOOP::Robot_basic.

Definition at line 1088 of file kinemat.cpp.

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

Joint torque without contact force based on Recursive Newton-Euler formulation.

Implements ROBOOP::Robot_basic.

Definition at line 682 of file dynamics.cpp.

ReturnMatrix ROBOOP::mRobot_min_para::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.

See ReturnMatrix mRobot::torque(const ColumnVector & q, const ColumnVector & qp, const ColumnVector & qpp, const ColumnVector & Fext, const ColumnVector & Next) for the Recursive Newton-Euler formulation.

Implements ROBOOP::Robot_basic.

Definition at line 692 of file dynamics.cpp.

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

Joint torque. when joint velocity is 0, based on Recursive Newton-Euler formulation.

Implements ROBOOP::Robot_basic.

Definition at line 777 of file dynamics.cpp.

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 ltorque,
ColumnVector dtorque 
) [virtual]

Delta torque dynamics.

See mRobot::delta_torque for equations.

Implements ROBOOP::Robot_basic.

Definition at line 509 of file delta_t.cpp.

void ROBOOP::mRobot_min_para::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 $S_2(q, \dot{q}, \ddot{q})\delta q$. See mRobot::delta_torque for equations.

Implements ROBOOP::Robot_basic.

Definition at line 335 of file comp_dq.cpp.

void ROBOOP::mRobot_min_para::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 $S_1(q, \dot{q}, \ddot{q})\delta \dot{q}$. See mRobot::delta_torque for equations.

Implements ROBOOP::Robot_basic.

Definition at line 303 of file comp_dqp.cpp.

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

Joint torque due to gravity based on Recursive Newton-Euler formulation.

Implements ROBOOP::Robot_basic.

Definition at line 827 of file dynamics.cpp.

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

Joint torque due to centrifugal and Corriolis based on Recursive Newton-Euler formulation.

Implements ROBOOP::Robot_basic.

Definition at line 868 of file dynamics.cpp.


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

ROBOOP v1.21a
Generated Thu Nov 22 00:51:36 2007 by Doxygen 1.5.4