JACOBN Compute manipulator Jacobian in end-effector frame JN = JACOBN(ROBOT, Q) Returns a Jacobian matrix for the robot ROBOT in pose Q. The manipulator Jacobian matrix maps differential changes in joint space to differential Cartesian motion of the end-effector (end-effector coords). dX = J dQ This function uses the technique of Paul, Shimano, Mayer Differential Kinematic Control Equations for Simple Manipulators IEEE SMC 11(6) 1981 pp. 456-460 For an n-axis manipulator the Jacobian is a 6 x n matrix. See also: JACOB0, DIFF2TR, TR2DIFF
0001 %JACOBN Compute manipulator Jacobian in end-effector frame 0002 % 0003 % JN = JACOBN(ROBOT, Q) 0004 % 0005 % Returns a Jacobian matrix for the robot ROBOT in pose Q. 0006 % 0007 % The manipulator Jacobian matrix maps differential changes in joint space 0008 % to differential Cartesian motion of the end-effector (end-effector coords). 0009 % dX = J dQ 0010 % 0011 % This function uses the technique of 0012 % Paul, Shimano, Mayer 0013 % Differential Kinematic Control Equations for Simple Manipulators 0014 % IEEE SMC 11(6) 1981 0015 % pp. 456-460 0016 % 0017 % For an n-axis manipulator the Jacobian is a 6 x n matrix. 0018 % 0019 % See also: JACOB0, DIFF2TR, TR2DIFF 0020 0021 % Copyright (C) 1999-2008, by Peter I. Corke 0022 % 0023 % This file is part of The Robotics Toolbox for Matlab (RTB). 0024 % 0025 % RTB is free software: you can redistribute it and/or modify 0026 % it under the terms of the GNU Lesser General Public License as published by 0027 % the Free Software Foundation, either version 3 of the License, or 0028 % (at your option) any later version. 0029 % 0030 % RTB is distributed in the hope that it will be useful, 0031 % but WITHOUT ANY WARRANTY; without even the implied warranty of 0032 % MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 0033 % GNU Lesser General Public License for more details. 0034 % 0035 % You should have received a copy of the GNU Leser General Public License 0036 % along with RTB. If not, see <http://www.gnu.org/licenses/>. 0037 0038 function J = jacobn(robot, q) 0039 0040 n = robot.n; 0041 L = robot.link; % get the links 0042 0043 J = []; 0044 U = robot.tool; 0045 for j=n:-1:1, 0046 if robot.mdh == 0, 0047 % standard DH convention 0048 U = L{j}( q(j) ) * U; 0049 end 0050 if L{j}.RP == 'R', 0051 % revolute axis 0052 d = [ -U(1,1)*U(2,4)+U(2,1)*U(1,4) 0053 -U(1,2)*U(2,4)+U(2,2)*U(1,4) 0054 -U(1,3)*U(2,4)+U(2,3)*U(1,4)]; 0055 delta = U(3,1:3)'; % nz oz az 0056 else 0057 % prismatic axis 0058 d = U(3,1:3)'; % nz oz az 0059 delta = zeros(3,1); % 0 0 0 0060 end 0061 J = [[d; delta] J]; 0062 0063 if robot.mdh ~= 0, 0064 % modified DH convention 0065 U = L{j}( q(j) ) * U; 0066 end 0067 end