使用MATLAB基于Puma560机械臂模型实现六自由度搬运机器人搬运小球动画

mdl_puma560

p = [0.8 0 -0.2];

T = transl(p) * troty(pi/2);

q1= [0.2,0.6,-2.6,0.47,0.46,1.2];

qqr = p560.ikine6s(T, 'ru');
qqr(6)=1.2;

qrt = jtraj(q1, qqr,20);  

ae = [-132 24];

p(1) = 1;

clf

plot_sphere(p, 0.045, 'b');

p560.plot3d(qrt, 'view', ae, 'nowrist');  

qr =[1.6,0.48,-2.4,0.5,0.4,1.2];

qrt = jtraj(qqr, qr, 20);  

clf

for i=1:length(qrt)

    T = p560.fkine(qrt(i,:)); 

    Tball = T * SE3(0,0,0.2);

    P = Tball.t;

     clf

    plot_sphere(P, 0.045, 'b');

    p560.plot3d(qrt(i,:), 'view', ae, 'nowrist');

    pause(0.01)

end

qrr=[1.6,0.8,-2.2,0.5,-0.6,1.2];

qrt1 = jtraj(qr, qrr, 15);  

pause(0.5)

for i=1:length(qrt1)

    T = p560.fkine(qrt1(i,:)); 

    clf

    plot_sphere(P, 0.045, 'b');

    p560.plot3d(qrt1(i,:), 'view', ae, 'nowrist');

    pause(0.01)

end


1. mdl_puma560`:加载Puma 560机械臂模型。

2. p = [0.8 0 -0.2];`:定义球的位置。

3. T = transl(p) * troty(pi/2);`:计算抓取姿态。通过平移和旋转矩阵构建变换矩阵T,用于描述机械臂的末端执行器在空间中的位置和姿态。

4. q1 = [0.2,0.6,-2.6,0.47,0.46,1.2];`:定义机械臂的起始关节角度。

5. qqr = p560.ikine6s(T, 'ru');`:使用逆解算法计算出抓取姿态下的关节角度。

6. qqr(6) = 1.2;`:将第六个关节角度设置为1.2。

7. qrt = jtraj(q1, qqr, 20);`:计算从起始关节角度q1到抓取姿态下的关节角度qqr之间的路径,共计20个点。

8. ae = [-132 24];`:定义视图的旋转角度。

9. p(1) = 1;`:将球的x坐标位置改为1。

10. plot_sphere(p, 0.045, 'b');`:绘制球的位置。

11. p560.plot3d(qrt, 'view', ae, 'nowrist');`:将机械臂从起始位置运动到球的位置,并绘制运动轨迹,其中'view'参数指定视图的旋转角度,'nowrist'参数表示不显示手腕坐标系的箭头。

12. qr = [1.6,0.48,-2.4,0.5,0.4,1.2];`:定义机械臂的新关节角度。

13. qrt = jtraj(qqr, qr, 20);`:计算从抓取姿态下的关节角度qqr到新关节角度qr之间的路径,共计20个点。

14. 在一个循环中,根据每个关节角度计算末端执行器的姿态,绘制球的位置并实时显示机械臂的运动轨迹。

15. qrr = [1.6,0.8,-2.2,0.5,-0.6,1.2];`:定义机械臂的目标关节角度。

16. qrt1 = jtraj(qr, qrr, 15);`:计算从新关节角度qr到目标关节角度qrr之间的路径,共计15个点。

17. 在另一个循环中,根据每个关节角度计算末端执行器的姿态,绘制球的位置并实时显示机械臂的运动轨迹。

  • 4
    点赞
  • 29
    收藏
    觉得还不错? 一键收藏
  • 2
    评论
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值