Scilab Function
Last update : October 2007

rt_itorque - compute the manipulator inertia torque component[view code]

Calling Sequence

tau_i = rt_itorque(robot, q, qdd)

Parameters

Description

This function returns the joint torque due to inertia at the specified pose q and acceleration qdd which is given by the relation tau_i = M(q) * qdd.

If q and qdd are row vectors (p = 1), tau_i is a row vector of joint torques. Else (p > 1), tau_i is a matrix in which each row is the inertia torque for the corresponding rows of q and qdd.

If robot contains motor inertia parameters then motor inertia, referred to the link reference frame, will be added to the diagonal of inertia matrix (M) and influence the inertia torque result.

Examples

   // The following example shows how to compute the inertial torque
   // contributions for a simple two link RR planar, when joint trajectories
   // in terms of position, velocity and acceleration are given.
   // Trajectories have the same duration and a triangular-velocity profile.
   // Initially the manipulator has a down-elbow configuration such that its
   // end-effector is at point (0.2, 0) metres in the operating space.
   // Both its joints move through an excursion of %pi/2 radians in 0.5 sec.

   // load the joint trajectories
   load("<PATH>/demos/rne/config-tlexamp.dat",..
        "t_tlexamp", "q_tlexamp", "qd_tlexamp", "qdd_tlexamp");

   // load RR parameters
   exec <PATH>/demos/rne/manip-tlexamp.sce;

   // compute inertial torque contribution:
   // B(q) * D^2(q)
   tic();..
   I = rt_inertia(manip_tlexamp, q_tlexamp);..
   I11 = I(1, 1, :); i11 = matrix(I11, length(t_tlexamp), 1);..
   I12 = I(1, 2, :); i12 = matrix(I12, length(t_tlexamp), 1);..
   I21 = I(2, 1, :); i21 = matrix(I21, length(t_tlexamp), 1);..
   I22 = I(2, 2, :); i22 = matrix(I22, length(t_tlexamp), 1);..
   taui_1 = i11 .* qdd_tlexamp(:, 1) + i12 .* qdd_tlexamp(:, 2);..
   taui_2 = i21 .* qdd_tlexamp(:, 1) + i22 .* qdd_tlexamp(:, 2);..
   toc(),

   // rt_itorque(), direct approach!
   tic(); taui = rt_itorque(manip_tlexamp, q_tlexamp, qdd_tlexamp); toc(),

   // worst case error
   max(max(abs(taui - [taui_1, taui_2]), "r")),
   
  

See Also

rt_robot,  rt_frne,  rt_rne,  rt_coriolis,  rt_inertia,  rt_gravload,  

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

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