Gift|孩子的礼物:麦轮遥控小车

Posted by Chao Zhang on July 24, 2023

抽空为孩子做了一个麦克纳姆轮遥控小车,记录一下做法:

1. Mechanics

麦克纳姆轮小车运动原理

安装有麦克纳姆轮的小车具有全向移动能力(前后移动、左右横移,左右自旋),运动十分灵活。

做麦轮小车,首先需了解其运动原理。这部分主要参考了程欢欢智能小车,其原理讲解形象清晰,易于理解;且给出了核心代码,对编写自己的程序帮助很大。

图1-1 运动原理和核心代码

机械结构设计

在SolidWorks中设计好整车CAD模型。

为缓解运动中车轮悬空的问题,前桥设计为了一个带限位的整体悬挂。

为提升整体“气质”,上下安装版采用了茶色亚克力板。

图1-2 CAD模型和实物

2. Electronics

选型及连接

硬件选型主要考虑是易用性,没太考虑价格因素。硬件主要包括RC遥控单元电机及驱动单元主控单元供电单元

Fig. 3 Electronics Conections

RC遥控数据解析

电机及驱动PWM调速

3. Software

代码结构

代码实现

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
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
/************************
  @ Tittle: RC car for Qiyu
  @ run in Arduino Mega 2560
  @ by Zhang Chao
  @ 2023/7/1
*************************/
#include "sbus.h"  // RC Receiver的SBUS解析库

/* SBUS object, reading SBUS */
bfs::SbusRx sbus_rx(&Serial2);
/* SBUS data */
bfs::SbusData data;

/* GPIO definition */
const int FL_PWM = 11;  // 特别注意,UNO和MEGA板的Timer和PWM Pin的对应关系不同
const int FL_INA = 22;
const int FL_INB = 23;

const int FR_PWM = 12;
const int FR_INA = 24;
const int FR_INB = 25;

const int BL_PWM = 2;
const int BL_INA = 26;
const int BL_INB = 27;

const int BR_PWM = 5;
const int BR_INA = 28;
const int BR_INB = 29;

int FB = 0;   // 通道2舵量 - 前进/后退
int LR = 0;   // 通道1舵量 - 左移/右移
int TU = 0;   // 通道4舵量 - 左旋/右旋
int SPD = 0;  // 通道5舵量 - 高/中/低档位
int LOCK = 0; // 通道8舵量 - 档位加密(高速挡调了SPD后,还需通道8舵量匹配方才激活)

bool connected = false; //指示遥控器是否连接

void chassis_ctl(int FB, int LR, int TU, int SPD, int LOCK);


void setup() {
  /* Serial to display data */
  Serial.begin(115200);
  while (!Serial) {}
  /* Begin the SBUS communication */
  sbus_rx.Begin();

  /* GPIO Setup */
  pinMode(FL_INA, OUTPUT);
  pinMode(FL_INB, OUTPUT);

  pinMode(FR_INA, OUTPUT);
  pinMode(FR_INB, OUTPUT);

  pinMode(BL_INA, OUTPUT);
  pinMode(BL_INB, OUTPUT);

  pinMode(BR_INA, OUTPUT);
  pinMode(BR_INB, OUTPUT);

}

void loop() {
  if (sbus_rx.Read()) 
  {
    connected = true;
    /* Grab the received data */
    data = sbus_rx.data();
    /* Display the received data */
    for (int8_t i = 0; i < data.NUM_CH; i++) {
      //Serial.print(data.ch[i]);
      //Serial.print("\t");
    }
  }

  FB = data.ch[1];
  LR = data.ch[0];
  TU = data.ch[3];
  SPD = data.ch[4];
  LOCK = data.ch[7];

  // 未连接遥控器时,机器人不运动
  if (connected)
  {
    chassis_ctl(FB,LR,TU,SPD,LOCK);
  }
  
}


/************************
  @ 麦轮底盘运控控制
  @ 输入:为各通道舵量
      FB: 通道2舵量 - 前进/后退
      LR: 通道1舵量 - 左移/右移
      TU: 通道4舵量 - 左旋/右旋
      SPD: 通道5舵量 - 高/中/低档位
*************************/
void chassis_ctl(int FB, int LR, int TU, int SPD, int LOCK)   
{
  FB = FB - 1000; //把舵量转换到-800~800
  LR = LR - 1000;
  TU = TU - 1000;
  double SPD_val = 0;
  if (SPD == 1800 && LOCK > 1500 && LOCK <1700)           // 高速挡
  {SPD_val = 1;}
  else if (SPD == 1000 && LOCK > 1500 && LOCK <1700)         // 中速挡
  {SPD_val = 0.5;}
  else                      // 低速挡
  {SPD_val = 0.25;}

  //总舵量限幅,即轮子转速限幅
  int move_sum = abs(FB) + abs(LR) + abs(TU);
  if (move_sum > 800)
  {
    double k = 800.0/move_sum;
    FB = FB*k;
    LR = LR*k;
    TU = TU*k;
  }

  int FL_CH_val = FB + LR + TU;  // 左前轮
  int FR_CH_val = FB - LR - TU;  // 右前轮
  int BL_CH_val = FB - LR + TU;  // 左后轮
  int BR_CH_val = FB + LR - TU;  // 右后轮

  // 左前轮运动
  double FL_PWM_val = 0;
  if (FL_CH_val >= 0)
  {
    FL_PWM_val = SPD_val* 255 * FL_CH_val / 800;   // 舵量转换为analogWrite函数的输入
    digitalWrite(FL_INA,HIGH);
    digitalWrite(FL_INB,LOW);
    analogWrite(FL_PWM, FL_PWM_val);
    
  }
  else
  {
    FL_PWM_val = -SPD_val * 255 * FL_CH_val / 800;   // 舵量转换为analogWrite函数的输入
    digitalWrite(FL_INA,LOW);
    digitalWrite(FL_INB,HIGH);
    analogWrite(FL_PWM, FL_PWM_val);
  }
  Serial.print(FL_PWM_val);
  Serial.print("\t");
  

  // 右前轮运动
  double FR_PWM_val = 0;
  if (FR_CH_val >= 0)
  {
    FR_PWM_val = SPD_val * 255 * FR_CH_val / 800;   // 舵量转换为analogWrite函数的输入
    digitalWrite(FR_INA,LOW);
    digitalWrite(FR_INB,HIGH);
    analogWrite(FR_PWM, FR_PWM_val);
  }
  else
  {
    FR_PWM_val = -SPD_val * 255 * FR_CH_val / 800;   // 舵量转换为analogWrite函数的输入
    digitalWrite(FR_INA,HIGH);
    digitalWrite(FR_INB,LOW);
    analogWrite(FR_PWM, FR_PWM_val);
  }
  Serial.print(FR_PWM_val);
  Serial.print("\t");
  

  // 左后轮运动
  double BL_PWM_val = 0;
  if (BL_CH_val >= 0)
  {
    BL_PWM_val = SPD_val * 255 * BL_CH_val / 800;   // 舵量转换为analogWrite函数的输入
    digitalWrite(BL_INA,LOW);
    digitalWrite(BL_INB,HIGH);
    analogWrite(BL_PWM, BL_PWM_val);
  }
  else
  {
    BL_PWM_val = -SPD_val * 255 * BL_CH_val / 800;   // 舵量转换为analogWrite函数的输入
    digitalWrite(BL_INA,HIGH);
    digitalWrite(BL_INB,LOW);
    analogWrite(BL_PWM, BL_PWM_val);
  }
  Serial.print(BL_PWM_val);
  Serial.print("\t");
  

  // 右后轮运动
  double BR_PWM_val = 0;
  if (BR_CH_val >= 0)
  {
    BR_PWM_val = SPD_val * 255 * BR_CH_val / 800;   // 舵量转换为analogWrite函数的输入
    digitalWrite(BR_INA,HIGH);
    digitalWrite(BR_INB,LOW);
    analogWrite(BR_PWM, BR_PWM_val);
  }
  else
  {
    BR_PWM_val = -SPD_val * 255 * BR_CH_val / 800;   // 舵量转换为analogWrite函数的输入
    digitalWrite(BR_INA,LOW);
    digitalWrite(BR_INB,HIGH);
    analogWrite(BR_PWM, BR_PWM_val);
  }
  Serial.print(BR_PWM_val);
  Serial.print("\t");
  
  Serial.println(data.failsafe);
}