% Get robot description run('main_ur.m') % ----------------------------------------------------------------------- % % Getting base parameters of the UR10 manipulator based on the % % Gautier, M., & Khalil, W. (1990). Direct calculation of minimum set % of inertial parameters of serial robots. IEEE Transactions on Robotics % and Automation, 6(3), 368–373. https://doi.org/10.1109/70.56655 % % Here we tried to generilize what was given there to more general % parametrization compared to their modified DH parameters. % ------------------------------------------------------------------------ % ----------------------------------------------------------------------- % Create symbolic parameters % ----------------------------------------------------------------------- m = sym('m%d',[6,1],'real'); hx = sym('h%d_x',[6,1],'real'); hy = sym('h%d_y',[6,1],'real'); hz = sym('h%d_z',[6,1],'real'); ixx = sym('i%d_xx',[6,1],'real'); ixy = sym('i%d_xy',[6,1],'real'); ixz = sym('i%d_xz',[6,1],'real'); iyy = sym('i%d_yy',[6,1],'real'); iyz = sym('i%d_yz',[6,1],'real'); izz = sym('i%d_zz',[6,1],'real'); im = sym('im%d',[6,1],'real'); % Load parameters attached to the end-effector syms ml hl_x hl_y hl_z il_xx il_xy il_xz il_yy il_yz il_zz real % Vector of symbolic parameters for i = 1:6 pi_ur10(:,i) = [ixx(i),ixy(i),ixz(i),iyy(i),iyz(i),izz(i),... hx(i),hy(i),hz(i),m(i)]'; end % ------------------------------------------------------------------------ % Symbolic generilized coordiates, their first and second deriatives % ----------------------------------------------------------------------- q_sym = sym('q%d',[6,1],'real'); qd_sym = sym('qd%d',[6,1],'real'); q2d_sym = sym('q2d%d',[6,1],'real'); % ------------------------------------------------------------------------ % Getting energy functions, to derive dynamics % ------------------------------------------------------------------------ T_pk = sym(zeros(4,4,6)); % transformation between links w_kk(:,1) = sym(zeros(3,1)); % angular velocity k in frame k v_kk(:,1) = sym(zeros(3,1)); % linear velocity of the origin of frame k in frame k g_kk(:,1) = sym([0,0,9.81])'; % vector of graviatational accelerations in frame k p_kk(:,1) = sym(zeros(3,1)); % origin of frame k in frame k DK(:,1) = sym(zeros(10,1)); % gradient of kinetic energy DP(:,1) = sym([zeros(1,6),[0,0,9.81],0]'); % gradient of gravitational energy for i = 1:6 jnt_axs_k = str2num(ur10.robot.joint{i}.axis.Attributes.xyz)'; % Transformation from parent link frame p to current joint frame rpy_k = sym(str2num(ur10.robot.joint{i}.origin.Attributes.rpy)); R_pj = RPY(rpy_k); R_pj(abs(R_pj)