Scilab Function
Last update : October 2007

rt_fkine - compute the forward kinematics for a serial n-link manipulator[view code]

Calling Sequence

T = rt_fkine(robot, q)

Parameters

Description

This function computes forward kinematics for the joint coordinates q giving a homogeneous tranform for the location of the end-effector. robot is a robot object which contains a kinematic model in either standard or modified Denavit-Hartenberg notation. Note that the robot object can specify an arbitrary homogeneous transform for the base of the robot.

If q is a vector (p = 1) it is interpreted as the generalized joint coordinates, and rt_fkine returns a homogeneous transformation for the final link of the manipulator. If q is a matrix (p > 1) each row is interpreted as a joint state vector and T is a p-dimensional array in which each entry is the resulting homogeneous transform for the corresponding row in q.

Examples

   // To show how the FKP (Forward Kinematic Problem) for a Puma 560 can
   // be solved, the following code could be used.

   // load Puma 560 parameters
   exec <PATH>/models/rt_puma560.sce;

   // forward kinematic computation:
   // q is a joint state vector
   Tz = rt_fkine(p560, qz);     // joint coordinates are zero
   disp(Tz);                    // display the end-effector location

   // q is a trajectory in the joint space
   t = [0:.056:5].';            // time vector
   q = rt_jtraj(qz, qready, t); // create a path
   T = rt_fkine(p560, q);       // trajectory from qz to qready
   disp(T(:,:,1));              // display e.e. location when q is qz
                                // (note that is the same of Tz)
   disp(T(:,:,10));             // display e.e. location for the 10th
                                // point in trajectory
   
  

Cautionary

Note that the dimensional units for the last column of the T matrix will be the same as the dimensional units used in the robot object robot. The units can be whatever you choose (metres, inches, cubits or furlongs) but the choice will affect the numerical value of the elements in the last column of T. The toolbox definitions rt_puma560 and rt_stanford all use SI units with dimensions in metres.

See Also

rt_link,  rt_robot,  

Authors

original Matlab version by

Peter I. Corke CSIRO Manufacturing Science and Technology

Scilab implementation by

Matteo Morelli Interdepartmental Research Center "E. Piaggio", University of Pisa

Bibliography

Corke, P.I. "A Robotics Toolbox for MATLAB", IEEE Robotics and Automation Magazine, Volume 3(1), March 1996, pp. 24-32

R. P. Paul, Robot Manipulators: Mathematics, Programming and Control. Cambridge, Massachusetts: MIT Press, 1981.

J. J. Craig, Introduction to Robotics. Addison Wesley, second ed., 1989.

Get the Robotics Toolbox for Scilab/Scicos at SourceForge.net. Fast, secure and Free Open Source software downloads