Scilab Function
Last update : October 2007

rt_rne - compute inverse dynamics via recursive Newton-Euler formulation[view code]

Calling Sequence

tau = rt_rne(robot, q, qd, qdd [, grav [, fext]])
tau = rt_rne(robot, Q [, grav [, fext]])

Parameters

Description

This function computes the equation of motion in an efficent manner, giving joint torques as a function of joint position, velocity and acceleration.

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

Gravity direction is defined by the robot object but may be overridden by providing the gravity acceleration vector grav.

An external generalized force acting on the end of the manipulator may also be specified by the 6-element vector fext in the end-effector coordinate frame.

The torque computed may contain contributions due to armature inertia and joint friction if these are specified in the parameter matrix dyn.

Examples

   // The following example shows how rt_rne() can be used to compute the
   // joint torque 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.
   //
   // References: Chapter 4, Example 4.2, of
   // L. Sciavicco, B. Siciliano, "Modelling and Control of Robot
   // Manipulators", 2nd Edition, Springer-Verlag Advanced Textbooks in
   // Control and Signal Processing Series, London, UK, 2000

   // 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;

   // joint trajectories plotting
   cfh = scf(); drawlater();
   subplot(3,2,1); plot(t_tlexamp, q_tlexamp(:,1));             // POS.
   xgrid(); xtitle("Position Joint 1", "[s]", "[rad]");
   a1 = cfh.children(1); a1.data_bounds = [0 -2; 0.6 5];
   a1.tight_limits = "on"; a1.auto_ticks = ["off" "off" "off"];
   a1.x_ticks = tlist(["ticks", "locations", "labels"],..
        [0 0.1 0.2 0.3 0.4 0.5], ["0" "0.1" "0.2" "0.3" "0.4" "0.5"]);
   a1.y_ticks = tlist(["ticks", "locations", "labels"],..
        [-2 -1 0 1 2 3 4 5], ["-2" "-1" "0" "1" "2" "3" "4" "5"]);
   subplot(3,2,2); plot(t_tlexamp, q_tlexamp(:,2));
   xgrid(); xtitle("Position Joint 2", "[s]", "[rad]");
   a2 = cfh.children(1); a2.data_bounds = [0 -2; 0.6 5];
   a2.tight_limits = "on"; a2.auto_ticks = ["off" "off" "off"];
   a2.x_ticks = tlist(["ticks", "locations", "labels"],..
        [0 0.1 0.2 0.3 0.4 0.5], ["0" "0.1" "0.2" "0.3" "0.4" "0.5"]);
   a2.y_ticks = tlist(["ticks", "locations", "labels"],..
        [-2 -1 0 1 2 3 4], ["-2" "-1" "0" "1" "2" "3" "4" "5"]);

   subplot(3,2,3); plot(t_tlexamp, qd_tlexamp(:,1));            // VEL.
   xgrid(); xtitle("Velocity Joint 1", "[s]", "[rad/s]");
   a3 = cfh.children(1); a3.data_bounds = [0 -1; 0.6 7];
   a3.tight_limits = "on"; a3.auto_ticks = ["off" "off" "off"];
   a3.x_ticks = tlist(["ticks", "locations", "labels"],..
        [0 0.1 0.2 0.3 0.4 0.5 0.6],..
        ["0" "0.1" "0.2" "0.3" "0.4" "0.5" "0.6"]);
   a3.y_ticks = tlist(["ticks", "locations", "labels"],..
        [0 2 4 6], ["0" "2" "4" "6"]);
   subplot(3,2,4); plot(t_tlexamp, qd_tlexamp(:,2));
   xgrid(); xtitle("Velocity Joint 2", "[s]", "[rad/s]");
   a4 = cfh.children(1); a4.data_bounds = [0 -1; 0.6 7];
   a4.tight_limits = "on"; a4.auto_ticks = ["off" "off" "off"];
   a4.x_ticks = tlist(["ticks", "locations", "labels"],..
        [0 0.1 0.2 0.3 0.4 0.5 0.6],..
        ["0" "0.1" "0.2" "0.3" "0.4" "0.5" "0.6"]);
   a4.y_ticks = tlist(["ticks", "locations", "labels"],..
        [0 2 4 6], ["0" "2" "4" "6"]);

   subplot(3,2,5); plot(t_tlexamp, qdd_tlexamp(:,1));           // ACCEL.
   xgrid(); xtitle("Accel. Joint 1", "[s]", "[rad/s^2]");
   a5 = cfh.children(1); a5.data_bounds = [0 -30; 0.6 30];
   a5.tight_limits = "on"; a5.auto_ticks = ["off" "off" "off"];
   a5.x_ticks = tlist(["ticks", "locations", "labels"],..
        [0 0.1 0.2 0.3 0.4 0.5 0.6],..
        ["0" "0.1" "0.2" "0.3" "0.4" "0.5" "0.6"]);
   a5.y_ticks = tlist(["ticks", "locations", "labels"],..
        [-30 -20 -10 0 10 20 30],..
        ["-30" "-20" "-10" "0" "10" "20" "30"]);
   subplot(3,2,6); plot(t_tlexamp, qdd_tlexamp(:,2));
   xgrid(); xtitle("Accel. Joint 2", "[s]", "[rad/s^2]");
   a6 = cfh.children(1); a6.data_bounds = [0 -30; 0.6 30];
   a6.tight_limits = "on"; a6.auto_ticks = ["off" "off" "off"];
   a6.x_ticks = tlist(["ticks", "locations", "labels"],..
        [0 0.1 0.2 0.3 0.4 0.5], ["0" "0.1" "0.2" "0.3" "0.4" "0.5"]);
   a6.y_ticks = tlist(["ticks", "locations", "labels"],..
        [-30 -20 -10 0 10 20 30],..
        ["-30" "-20" "-10" "0" "10" "20" "30"]);
   drawnow();

   // rt_rne() execution
   tic();..                                         // start timer
   tau_rne = rt_rne(manip_tlexamp, q_tlexamp, qd_tlexamp, qdd_tlexamp);..
   toc(),                                           // stop timer

   // results plotting
   cfh = scf();
   drawlater();
   subplot(2,1,1); plot(t_tlexamp, tau_rne(:,1));               // JOINT 1
   xgrid(); xtitle("Joint 1 Torque", "[s]", "[N*m]");
   a7 = cfh.children(1); a7.data_bounds = [0 -6000; 0.6 7000];
   a7.tight_limits = "on"; a7.auto_ticks = ["off" "off" "off"];
   a7.x_ticks = tlist(["ticks", "locations", "labels"],..
        [0 0.1 0.2 0.3 0.4 0.5], ["0" "0.1" "0.2" "0.3" "0.4" "0.5"]);
   a7.y_ticks = tlist(["ticks", "locations", "labels"],..
        [-6000 -4000 -2000 0 2000 4000 6000],..
        ["-6000" "-4000" "-2000" "0" "2000" "4000" "6000"]);

   subplot(2,1,2); plot(t_tlexamp, tau_rne(:,2));               // JOINT 2
   xgrid(); xtitle("Joint 2 Torque", "[s]", "[N*m]");
   a8 = cfh.children(1); a8.data_bounds = [0 -6000; 0.6 7000];
   a8.tight_limits = "on"; a8.auto_ticks = ["off" "off" "off"];
   a8.x_ticks = tlist(["ticks", "locations", "labels"],..
        [0 0.1 0.2 0.3 0.4 0.5], ["0" "0.1" "0.2" "0.3" "0.4" "0.5"]);
   a8.y_ticks = tlist(["ticks", "locations", "labels"],..
        [-6000 -4000 -2000 0 2000 4000 6000],..
        ["-6000" "-4000" "-2000" "0" "2000" "4000" "6000"]);
   drawnow();

   // To observe that better performances in terms of execution time are
   // offered by fast RNE, you can run the following code. 
   tic();..                                         // start timer
   tau_frne = rt_frne(manip_tlexamp, q_tlexamp, qd_tlexamp, qdd_tlexamp);..
   toc(),                                           // stop timer
   
  

Cautionary

This function is a Scilab-code implementation of recursive Newton-Euler (RNE) algorithm for robot inverse dynamics computation. Because of its recursive nature, the algorithm offers best performance (in terms of execution time) when is codified in a compiled programming language. For this reason, a C version of the RNE formulation called " fast RNE " has been implemented (function rt_frne).

In this toolbox, all RNE-based functions like rt_itorque, rt_coriolis, rt_gravload but also rt_inertia and rt_accel make use of function rt_frne.

When fast computation is needed, i.e. when you have to process an entire trajectory instead of a single point on a trajectory, the use of rt_frne function is highly recommended.

See Also

rt_robot,  rt_frne,  rt_itorque,  rt_coriolis,  rt_gravload,  rt_inertia,  rt_cinertia,  rt_accel,  rt_fdyn,  

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

M.W. Walker and D.E. Orin. Efficient dynamic computer simulation of robotic mechanisms. ASME Journal of Dynamic Systems, Measurement and Control, 104:205-211, 1982

L. Sciavicco, B. Siciliano, Modelling and Control of Robot Manipulators. 2nd Edition, Springer-Verlag Advanced Textbooks in Control and Signal Processing Series, London, UK, 2000.

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