Tekkotsu Homepage | Demos | Overview | Downloads | Dev. Resources | Reference | Credits |
ROBOOP::mRobot Class Reference#include <robot.h>
Inheritance diagram for ROBOOP::mRobot:
![]() Detailed DescriptionModified DH notation robot class.Definition at line 455 of file robot.h.
Constructor & Destructor Documentation
Member Function Documentation
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 1503 of file robot.cpp. Referenced by mRobot().
Overload inv_kin function.
Reimplemented from ROBOOP::Robot_basic. Definition at line 1259 of file invkine.cpp. Referenced by inv_kin().
Numerical inverse kinematics. See inv_kin(const Matrix & Tobj, const int mj, const int endlink, bool & converge).
Reimplemented from ROBOOP::Robot_basic.
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 1267 of file invkine.cpp.
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 1289 of file invkine.cpp. Referenced by inv_kin().
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 1396 of file invkine.cpp. Referenced by inv_kin().
Direct kinematics with velocity.
Implements ROBOOP::Robot_basic. Definition at line 755 of file kinemat.cpp.
Jacobian of mobile joints up to endlink expressed at frame ref. See Robot::jacobian for equations. Implements ROBOOP::Robot_basic. Definition at line 885 of file kinemat.cpp.
Jacobian derivative of mobile joints expressed at frame ref. See Robot::jacobian_dot for equations. Implements ROBOOP::Robot_basic. Definition at line 938 of file kinemat.cpp.
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 476 of file robot.h. Referenced by dTdqi().
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.
Partial derivative of the robot position (homogeneous transf.). This function computes the partial derivatives:
with
for a revolute joint and
for a prismatic joint.
Implements ROBOOP::Robot_basic. Definition at line 785 of file kinemat.cpp.
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 867 of file kinemat.cpp.
Joint torque, without contact force, based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 407 of file dynamics.cpp.
Joint torque based on Recursive Newton-Euler formulation.
In order to apply the RNE, let us define the following variables (referenced in the
Forward Iterations for
Backward Iterations for
Implements ROBOOP::Robot_basic. Definition at line 417 of file dynamics.cpp.
Joint torque. when joint velocity is 0, based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 550 of file dynamics.cpp.
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
Backward Iterations for
Implements ROBOOP::Robot_basic. Definition at line 289 of file delta_t.cpp.
Delta torque due to delta joint position.
This function computes Implements ROBOOP::Robot_basic. Definition at line 205 of file comp_dq.cpp.
Delta torque due to delta joint velocity.
This function computes Implements ROBOOP::Robot_basic. Definition at line 188 of file comp_dqp.cpp.
Joint torque due to gravity based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 594 of file dynamics.cpp.
Joint torque due to centrifugal and Corriolis based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 631 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 |