4自由度直角坐标、6自由度串联机器人MATLAB建模分析

对最近的课程报告做个总结,写点记录,用的是MATLAB的工具箱robotic_toolbox(10.4)

      需要自己安装。

1. 直角坐标机器人

画的不太专业的简图。

 

有个大概的指标

 用改进型DH坐标法建模非常便捷(后置法)

clc;
clear;
% qlim---Z方向
%滑块是 MDH先绕X轴转,再绕Z转
%空间坐标机器人建模
L(1) = Link('theta',pi/2,'a',0,'alpha',-pi/2,'qlim',[0,500],'modified');%X轴
L(2) = Link('theta',pi/2,'a',0,'alpha',pi/2,'qlim',[0,400],'modified');%Y轴
L(3) = Link('theta',-pi/2,'a',0,'alpha',-pi/2,'qlim',[0,300],'modified');%Z轴
L(4) = Link('revolute','a',300,'qlim',[-100*pi/180,100*pi/180],'modified');%U轴,300偏置
a = SerialLink(L,'name','robot\_arm');%取名robot_arm
a.base = transl(0,0,0);
a.teach;

计算工作空间

clc;
clear;
% qlim---Z方向
%滑块是 MDH先绕X轴转,再绕Z转 
%空间坐标机器人建模
L(1) = Link('theta',pi/2,'a',0,'alpha',-pi/2,'qlim',[0,500],'modified');%X轴
L(2) = Link('theta',pi/2,'a',0,'alpha',pi/2,'qlim',[0,400],'modified');%Y轴
L(3) = Link('theta',-pi/2  ,'a',0,'alpha',-pi/2,'qlim',[0,300],'modified');%Z轴
L(4) = Link('revolute','a',300,'qlim',[-100*pi/180,100*pi/180],'modified');%U轴
a = SerialLink(L,'name','robot\_arm');
a.base = transl(0,0,0);
a.teach;

%%计算工作空间
num = 30000;
P = zeros(num,3);
for i= 1:num
    q1 = L(1).qlim(1) + rand *(L(1).qlim(2)-L(1).qlim(1));
    q2 = L(2).qlim(1) + rand *(L(2).qlim(2)-L(2).qlim(1));
    q3 = L(3).qlim(1) + rand *(L(3).qlim(2)-L(3).qlim(1));
    q4 = L(4).qlim(1) + rand *(L(4).qlim(2)-L(4).qlim(1));
    q = [q1,q2,q3,q4];
    T = a.fkine(q);%求正解
    P(i,:) = transl(T);
end
plot3(P(:,1),P(:,2),P(:,3),'b.','MarkerSize',1);
hold on
grid on 
daspect([1 1 1])
view([45 45])
a.plot([0 0 0 0])

2. 六自由度串联机械臂

有个大概的指标

 画个简图

试试标准DH法(standard),个人感觉不如改进型DH简单。

问就是用的Notability

写个表,更推荐配合程序一步一步确定,对新手不太友好。

 为方便分析,我们使

d_1=1,d_2=d_3=d_4=\sqrt{2}

出来了

clc;
clear;
L(1) = Link('revolute','offset',0,'d',1,'a',0,'alpha',-pi/2);
L(2) = Link('revolute','offset',-pi/4,'d',0,'a',sqrt(2),'alpha',0);
L(3) = Link('revolute','offset',pi/2,'d',0,'a',0,'alpha',pi/2);
L(4) = Link('revolute','offset',pi,'d',sqrt(2),'a',0,'alpha',pi/2);
L(5) = Link('revolute','offset',0,'d',0,'a',0,'alpha',-pi/2);
L(6) = Link('revolute','offset',-pi/2,'d',sqrt(2),'a',0,'alpha',0);

a = SerialLink(L,'name','robot_arm');
a.base = transl(0,0,0);

L(1).qlim = [-150,150]/180*pi;
L(2).qlim = [-135,-45]/180*pi;
L(3).qlim = [-70,50]/180*pi;
L(4).qlim = [-90,90]/180*pi;
L(5).qlim = [-90,90]/180*pi;
L(6).qlim = [-180,180]/180*pi;
a.teach;

num = 30000;
P = zeros(num,3);

for i= 1:num
    q1 = L(1).qlim(1) + rand *(L(1).qlim(2)-L(1).qlim(1));
    q2 = L(2).qlim(1) + rand *(L(2).qlim(2)-L(2).qlim(1));
    q3 = L(3).qlim(1) + rand *(L(3).qlim(2)-L(3).qlim(1));
    q4 = L(4).qlim(1) + rand *(L(4).qlim(2)-L(4).qlim(1));
    q5 = L(5).qlim(1) + rand *(L(5).qlim(2)-L(5).qlim(1));
    q6 = L(6).qlim(1) + rand *(L(6).qlim(2)-L(6).qlim(1));
    q = [q1,q2,q3,q4,q5,q6];
    T = a.fkine(q);
    P(i,:) = transl(T);
end

plot3(P(:,1),P(:,2),P(:,3),'b.','MarkerSize',1);
hold on
grid on 
daspect([1 1 1])
view([45 45])
a.plot([0 0 0 0 0 0])

有的同学要求手推带参数的姿态矩阵,封装个函数交给MATLAB就行

function [T06]=mystafkine(theta1,theta2,theta3,theta4,theta5,theta6,d1,d2,d3,d4)
SDH=[theta1   d1      0       -pi/2;
      theta2   0       d2      0;
      theta3   0       0       pi/2;
      theta4   d3      0       pi/2;
      theta5   0       0       -pi/2;
      theta6   d4      0        0];
T01=[cos(SDH(1,1))  -sin(SDH(1,1))*cos(SDH(1,4))   sin(SDH(1,1))*sin(SDH(1,4))    SDH(1,3)*cos(SDH(1,1));
      sin(SDH(1,1))   cos(SDH(1,1))*cos(SDH(1,4))  -cos(SDH(1,1))*sin(SDH(1,4))    SDH(1,3)*sin(SDH(1,1));
      0               sin(SDH(1,4))                 cos(SDH(1,4))                  SDH(1,2);
      0               0                             0                              1];
T12=[cos(SDH(2,1))  -sin(SDH(2,1))*cos(SDH(2,4))   sin(SDH(2,1))*sin(SDH(2,4))    SDH(2,3)*cos(SDH(2,1));
     sin(SDH(2,1))   cos(SDH(2,1))*cos(SDH(2,4))  -cos(SDH(2,1))*sin(SDH(2,4))    SDH(2,3)*sin(SDH(2,1));
      0               sin(SDH(2,4))                 cos(SDH(2,4))                  SDH(2,2);
      0               0                             0                              1];
T23=[cos(SDH(3,1))  -sin(SDH(3,1))*cos(SDH(3,4))   sin(SDH(3,1))*sin(SDH(3,4))    SDH(3,3)*cos(SDH(3,1));
     sin(SDH(3,1))   cos(SDH(3,1))*cos(SDH(3,4))  -cos(SDH(3,1))*sin(SDH(3,4))    SDH(3,3)*sin(SDH(3,1));
      0               sin(SDH(3,4))                 cos(SDH(3,4))                  SDH(3,2);
      0               0                             0                              1];
T34=[cos(SDH(4,1))  -sin(SDH(4,1))*cos(SDH(4,4))   sin(SDH(4,1))*sin(SDH(4,4))    SDH(4,3)*cos(SDH(4,1));
     sin(SDH(4,1))   cos(SDH(4,1))*cos(SDH(4,4))  -cos(SDH(4,1))*sin(SDH(4,4))    SDH(4,3)*sin(SDH(4,1));
      0               sin(SDH(4,4))                 cos(SDH(4,4))                  SDH(4,2);
      0               0                             0                              1];
T45=[cos(SDH(5,1))  -sin(SDH(5,1))*cos(SDH(5,4))   sin(SDH(5,1))*sin(SDH(5,4))    SDH(5,3)*cos(SDH(5,1));
     sin(SDH(5,1))   cos(SDH(5,1))*cos(SDH(5,4))  -cos(SDH(5,1))*sin(SDH(5,4))    SDH(5,3)*sin(SDH(5,1));
      0               sin(SDH(5,4))                 cos(SDH(5,4))                  SDH(5,2);
      0               0                             0                              1];
T56=[cos(SDH(6,1))  -sin(SDH(6,1))*cos(SDH(6,4))   sin(SDH(6,1))*sin(SDH(6,4))    SDH(6,3)*cos(SDH(6,1));
     sin(SDH(6,1))   cos(SDH(6,1))*cos(SDH(6,4))  -cos(SDH(6,1))*sin(SDH(6,4))    SDH(6,3)*sin(SDH(6,1));
      0               sin(SDH(6,4))                 cos(SDH(6,4))                  SDH(6,2);
      0               0                             0                              1];
T06=T01*T12*T23*T34*T45*T56;

%调用用这个
syms theta1 theta2 theta3 theta4 theta5 theta6 d1 d2 d3 d4
T = mystafkine(theta1,theta2,theta3,theta4,theta5,theta6,d1,d2,d3,d4)

然后叫机器人帮你干活

 再来一波轨迹规划

clc;
clear;
L(1) = Link('revolute','offset',0,'d',1,'a',0,'alpha',-pi/2);
L(2) = Link('revolute','offset',-pi/4,'d',0,'a',sqrt(2),'alpha',0);
L(3) = Link('revolute','offset',pi/2,'d',0,'a',0,'alpha',pi/2);
L(4) = Link('revolute','offset',pi,'d',sqrt(2),'a',0,'alpha',pi/2);
L(5) = Link('revolute','offset',0,'d',0,'a',0,'alpha',-pi/2);
L(6) = Link('revolute','offset',-pi/2,'d',sqrt(2),'a',0,'alpha',0);
a = SerialLink(L,'name','robot_arm');
a.base = transl(0,0,0);
L(1).qlim = [-150,150]/180*pi;
L(2).qlim = [-135,-45]/180*pi;
L(3).qlim = [-70,50]/180*pi;
L(4).qlim = [-90,90]/180*pi;
L(5).qlim = [-90,90]/180*pi;
L(6).qlim = [-180,180]/180*pi;
% a.teach;
P1 = [-3.303,0.053,-0.258];
P2 = [-3.147,-2.649,3.324];
t = linspace(0,2,51);
Traj = mtraj(@tpoly,P1,P2,t);
n = size(Traj,1);
T = zeros(4,4,n);

for i = 1:n
    T(:,:,i)=transl(Traj(i,:))*trotx(180);
end
Qtraj = a.ikunc(T);
a.plot(Qtraj,'trail','r');

评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值