Home > . > trinterp.m

trinterp

PURPOSE ^

TRINTERP Interpolate homogeneous transformations

SYNOPSIS ^

function t = trinterp(T0, T1, r)

DESCRIPTION ^

TRINTERP Interpolate homogeneous transformations

    TR = TRINTERP(T0, T1, R)

 Returns a homogeneous transform interpolation between T0 and T1 as
 R varies from 0 to 1.  Rotation is interpolated using quaternion
 spherical linear interpolation.

 See also: CTRAJ, QUATERNION

CROSS-REFERENCE INFORMATION ^

This function calls: This function is called by:

SOURCE CODE ^

0001 %TRINTERP Interpolate homogeneous transformations
0002 %
0003 %    TR = TRINTERP(T0, T1, R)
0004 %
0005 % Returns a homogeneous transform interpolation between T0 and T1 as
0006 % R varies from 0 to 1.  Rotation is interpolated using quaternion
0007 % spherical linear interpolation.
0008 %
0009 % See also: CTRAJ, QUATERNION
0010 
0011 % Copyright (C) 1993-2008, by Peter I. Corke
0012 %
0013 % This file is part of The Robotics Toolbox for Matlab (RTB).
0014 %
0015 % RTB is free software: you can redistribute it and/or modify
0016 % it under the terms of the GNU Lesser General Public License as published by
0017 % the Free Software Foundation, either version 3 of the License, or
0018 % (at your option) any later version.
0019 %
0020 % RTB is distributed in the hope that it will be useful,
0021 % but WITHOUT ANY WARRANTY; without even the implied warranty of
0022 % MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
0023 % GNU Lesser General Public License for more details.
0024 %
0025 % You should have received a copy of the GNU Leser General Public License
0026 % along with RTB.  If not, see <http://www.gnu.org/licenses/>.
0027 
0028 function t = trinterp(T0, T1, r)
0029 
0030     q0 = quaternion(T0);
0031     q1 = quaternion(T1);
0032 
0033     p0 = transl(T0);
0034     p1 = transl(T1);
0035 
0036     qr = qinterp(q0, q1, r);
0037     pr = p0*(1-r) + r*p1;
0038 
0039     t = [qr.r pr; 0 0 0 1];

Generated on Sun 15-Feb-2009 18:09:29 by m2html © 2003