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:
![]() Detailed DescriptionModified DH notation and minimal inertial parameters robot class.Definition at line 507 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 1587 of file robot.cpp. Referenced by mRobot_min_para().
Overload inv_kin function.
Reimplemented from ROBOOP::Robot_basic. Definition at line 1559 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 1567 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 1589 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 1688 of file invkine.cpp. Referenced by inv_kin().
Direct kinematics with velocity.
Implements ROBOOP::Robot_basic. Definition at line 1000 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 1106 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 1161 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 529 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:
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.
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.
Joint torque without contact force based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 682 of file dynamics.cpp.
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.
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.
Delta torque dynamics. See mRobot::delta_torque for equations. Implements ROBOOP::Robot_basic. Definition at line 509 of file delta_t.cpp.
Delta torque due to delta joint position.
This function computes Implements ROBOOP::Robot_basic. Definition at line 335 of file comp_dq.cpp.
Delta torque due to delta joint velocity.
This function computes Implements ROBOOP::Robot_basic. Definition at line 303 of file comp_dqp.cpp.
Joint torque due to gravity based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 827 of file dynamics.cpp.
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 |