Tekkotsu Homepage | Demos | Overview | Downloads | Dev. Resources | Reference | Credits |
ROBOOP::Robot Class Reference#include <robot.h>
Inheritance diagram for ROBOOP::Robot:
![]() Detailed DescriptionDH notation robot class.Definition at line 388 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 known 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 1406 of file robot.cpp. Referenced by Robot().
Direct kinematics with velocity.
Implements ROBOOP::Robot_basic. Definition at line 424 of file kinemat.cpp.
Overload inv_kin function.
Reimplemented from ROBOOP::Robot_basic. Definition at line 576 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 584 of file invkine.cpp.
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 611 of file invkine.cpp.
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 638 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 663 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 762 of file invkine.cpp. Referenced by inv_kin().
Definition at line 1000 of file invkine.cpp. Referenced by inv_kin_goose_neck(), and inv_kin_goose_neck_pos().
Jacobian of mobile links up to endlink expressed at frame ref. The Jacobian expressed in based frame is
where
Expressed in a different frame the Jacobian is obtained by
Implements ROBOOP::Robot_basic. Definition at line 557 of file kinemat.cpp.
Jacobian derivative of mobile joints expressed at frame ref. The Jacobian derivative expressed in based frame is
where
Expressed in a different frame the Jacobian derivative is obtained by
Implements ROBOOP::Robot_basic. Definition at line 653 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 419 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:
in standard notation and
in modified notation, with
for a revolute joint and
for a prismatic joint.
Implements ROBOOP::Robot_basic. Definition at line 454 of file kinemat.cpp.
Partial derivative of the robot position (homogeneous transf.). See Robot::dTdqi(Matrix & dRot, ColumnVector & dpos, const int i, const int endlink) for equations. Implements ROBOOP::Robot_basic. Definition at line 539 of file kinemat.cpp.
Joint torque, without contact force, based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 130 of file dynamics.cpp.
Joint torque based on Recursive Newton-Euler formulation.
In order to apply the RNE as presented in Murray 86, let us define the following variables (referenced in the
Forward Iterations for
Backward Iterations for
Implements ROBOOP::Robot_basic. Definition at line 143 of file dynamics.cpp.
Joint torque. when joint velocity is 0, based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 267 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 63 of file delta_t.cpp.
Delta torque due to delta joint position.
This function computes Implements ROBOOP::Robot_basic. Definition at line 65 of file comp_dq.cpp.
Delta torque due to delta joint velocity.
This function computes Implements ROBOOP::Robot_basic. Definition at line 63 of file comp_dqp.cpp.
Joint torque due to gravity based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 316 of file dynamics.cpp.
Joint torque due to centrifugal and Corriolis based on Recursive Newton-Euler formulation.
Implements ROBOOP::Robot_basic. Definition at line 355 of file dynamics.cpp.
Definition at line 1107 of file invkine.cpp. Referenced by computeSecondERSLink(), and inv_kin_ers_pos().
The documentation for this class was generated from the following files: |
ROBOOP v1.21a |
Generated Thu Nov 22 00:51:35 2007 by Doxygen 1.5.4 |