麦轮底盘教程
首先可以大部分参考这个官方教程:
https://gm0.org/zh-cn/latest/docs/software/tutorials/mecanum-drive.html
下面我对官方教程做一些补充说明
1. 如何推导出⻨克纳姆轮的不同移动⽅式
简而言之,每个麦轮会有一个斜向的实际作用力,我们可以把它分解成竖直和水平方向的两个分力,并且通过力的合成实现不同移动。


下图是电机全部为正值时(向前转)的⻨轮的⼒和向量。当电机为负值时(向后转),⻨轮的⼒和向量都与左图中的呈中⼼对称。
2. 底盘 demo ⽰例
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55
| package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx;
@TeleOp(name="Chasis")
public class Chasis extends LinearOpMode { @Override public void runOpMode() {
DcMotorEx frontLeftMotor = hardwareMap.get(DcMotorEx.class,"leftFrontMotor"); DcMotorEx backLeftMotor = hardwareMap.get(DcMotorEx.class,"leftBackMotor"); DcMotorEx frontRightMotor = hardwareMap.get(DcMotorEx.class,"rightFrontMotor"); DcMotorEx backRightMotor = hardwareMap.get(DcMotorEx.class,"rightBackMotor"); frontRightMotor.setDirection(DcMotor.Direction.REVERSE); backRightMotor.setDirection(DcMotor.Direction.REVERSE); waitForStart();
while (opModeIsActive()){ double x = gamepad1.left_stick_x; double y = -gamepad1.left_stick_y; double rx = -gamepad1.right_stick_x; double a = Math.max(Math.abs(x)+ Math.abs(y)+ Math.abs(rx), 1); frontLeftMotor.setPower((y + x + rx) / a); backLeftMotor.setPower((y-x+rx)/a); frontRightMotor.setPower((y-x-rx)/a); backRightMotor.setPower((y+x-rx)/a); } } }
|
3. 测试
在driver hub的手机上测试,手机要链接车的WiFi。
在dirver hub里写好config,麦轮底盘用到了control hub 和expansion hub,在确定接口的时候可以顺着每个电机的线找到相应的hub和接口,编辑好config后点击 activate。
Tip
多人协作时要统一硬件映射名称,共同使用一个config
用CtoA数据线连接电脑和control hub,注意电脑不要连车的WiFi,AS的顶栏会有一个刷新的图标,点击之后传输程序,传程序之前要写程序的name。
传输好之后在driver hub右侧的倒三角(右侧是TeleOp手动程序)选你自己的程序,把手柄连接到手机上。
第一次启动手柄时按start和x键,手柄震动表示链接成功。