前言
前段時間跟着LOLI大神的教程製作了LOLI三代控,效果很好。但是,由於LOLI三代控的接收機帶有數據回傳功能,也就是接收機的無線模塊也承擔了發射數據功能,所以接收機也要使用帶有功率放大芯片的NRF24L01模塊才能實現遠距離通信,這不僅擡高了成本還帶來了體積的增加。於是筆者打算自制一個較簡單的6通道航模遙控器,正好手上有一個沒有接收機的天地飛-06X,決定對其進行改造,一番查閱資料後用Arduino Pro Mini開發板實現了基礎的功能,效果還不錯。
1. 材料清單
USB轉TTL模塊*1
Arduino Pro Mini開發板*2
NRF24L01無線通信模塊*2
ams1117-3.3電壓轉換芯片1個
100uF電解電容*2
104電容*2
三腳開關*4
10k電阻*1,20k電阻*1
導線及插針若干
2. 硬件部分
按照原理圖焊接電路,盡情飛線叭,有條件的話可以設計PCB做的好看一些。
a)遙控器端
遙控器端負責發送數據,所以使用可以無線透傳2000m的NRF24L01無線通信模塊;
筆者的飛線不忍直視 ,100m的NRF24L01模塊不夠用,果斷換了2000m的。
b)接收機端
接收機端負責接收數據,使用100m的NRF24L01無線通信模塊足夠了。
3. 軟件部分
a)遙控器端
將USB轉TTL模塊連接電腦,引腳接線如下:
TX0--RXD
RX1--TXD
VCC--3V3
GND--GND
打開Arduino IDE,選擇遙控器端的程序打開,這裏要下載RF24封裝庫,下載方法如下:
項目》加載庫》管理庫,打開庫管理器
輸入RF24搜索,選擇圖中的庫進行安裝,安裝完畢後點擊關閉;
燒寫程序之前,要先選擇自己的開發板型號,如下圖,處理器選擇自己的開發板類型,端口選擇USB轉TTL所在的端口號
點擊上傳,燒寫程序;
等待上傳完成後,打開串口監視器查看4個ADC的數值;
通信地址可以改爲自己喜歡的地址,每個位是十六進制(0~9、A~F) ;
向各個方向撥動搖桿,通過串口監視器查看輸出值,然後把每個通道的最小值、 中值、最大值填入程序中,最後再上傳一次代碼。
完整的Arduino代碼如下:
/* ArduinoProMini-6通道發射器
* by Bilibili 蔡子CaiZi
*
* A0~5 -> 模擬輸入,2~5 -> 通道正反開關
* A6 -> 電壓檢測
* 6 -> 蜂鳴器
*
* NRF24L01 | Arduino
* CE -> 7
* CSN -> 8
* MOSI -> 11
* MISO -> 12
* SCK -> 13
* IRQ -> 無連接
* VCC -> 小於3.6V
* GND -> GND
*/
#include <SPI.h>
#include <nRF24L01.h>
#include <RF24.h>
const uint64_t pipeOut = 0xBBBBBBBBB; //爲何這麼多B幣?與接收器中相同的地址進行通信
RF24 radio(7, 8); // SPI通信,引腳對應關係:CE ->7,CSN ->8
struct Signal {
byte roll;
byte pitch;
byte throttle;
byte yaw;
byte gyr;
byte pit;
};
Signal data;
void ResetData()
{
data.roll = 127; // 橫滾通道AIL(中心點127)
data.pitch = 127; // 俯仰通道ELE
data.throttle = 0; // 信號丟失時,關閉油門THR
data.yaw = 127; // 航向通道RUD
data.gyr = 0; //第五通道
data.pit = 0; //第六通道
}
void setup()
{
radio.begin();
radio.openWritingPipe(pipeOut);//pipeOut通信地址
radio.stopListening(); //發射模式
ResetData();//初始化6個通道值
Serial.begin(115200);
pinMode(2,INPUT);//正反通道開關爲數字輸入
pinMode(3,INPUT);
pinMode(4,INPUT);
pinMode(5,INPUT);
pinMode(6,OUTPUT);//蜂鳴器推輓輸出
if (analogRead(A6)*3.28*3/1023<5){//調整3校準電壓檢測,5爲報警電壓
for(int i=0;i<3;i++){
digitalWrite(6,HIGH);//蜂鳴器響
delay(100);
digitalWrite(6,LOW);
delay(100);
}
}
else{
digitalWrite(6,HIGH);//蜂鳴器響
delay(100);
digitalWrite(6,LOW);
}
}
// 將ADC獲取的0~1023轉換到0~255
int chValue(int val, int lower, int middle, int upper, bool reverse)
{
val = constrain(val, lower, upper);//將val限制在lower~upper範圍內
if ( val < middle )
val = map(val, lower, middle, 0, 128);
else
val = map(val, middle, upper, 128, 255);
return ( reverse ? 255 - val : val );
}
void loop()
{
Serial.print("\t");Serial.print(analogRead(A0));//將數據通過串口輸出
Serial.print("\t");Serial.print(analogRead(A1));
Serial.print("\t");Serial.print(analogRead(A2));
Serial.print("\t");Serial.println(analogRead(A3));
// 需要對搖桿的最值、中值進行設置
data.roll = chValue( analogRead(A0), 59, 517, 882, digitalRead(2));
data.pitch = chValue( analogRead(A1), 115, 525, 896, digitalRead(3));
data.throttle = chValue( analogRead(A2), 145, 522, 920, digitalRead(4));
data.yaw = chValue( analogRead(A3), 70, 530, 925, digitalRead(5));
data.gyr = chValue( analogRead(A4), 0, 510, 1020, false );
data.pit = chValue( analogRead(A5), 0, 510, 1020, false );
radio.write(&data, sizeof(Signal));//將數據發送出去
// Serial.print("\t");Serial.print(data.roll);
// Serial.print("\t");Serial.print(data.pitch);
// Serial.print("\t");Serial.print(data.throttle);
// Serial.print("\t");Serial.print(data.yaw);
// Serial.print("\t");Serial.print(data.gyr);
// Serial.print("\t");Serial.println(data.pit);
}
b)接收機端
接收機端的下載操作與遙控器端的操作基本相同,這裏不再贅述了,完整代碼如下:
/* ArduinoProMini-6通道接收機
* by Bilibili 蔡子CaiZi
*
* PWM輸出 -> 引腳2~6、9
*
* NRF24L01 | Arduino
* CE -> 7
* CSN -> 8
* MOSI -> 11
* MISO -> 12
* SCK -> 13
* IRQ -> 無連接
* VCC -> 小於3.6V
* GND -> GND
*/
#include <SPI.h>
#include <nRF24L01.h>
#include <RF24.h>
#include <Servo.h>
int ch_width_1 = 0, ch_width_2 = 0, ch_width_3 = 0, ch_width_4 = 0, ch_width_5 = 0, ch_width_6 = 0;
Servo ch1; Servo ch2; Servo ch3; Servo ch4; Servo ch5; Servo ch6;
struct Signal {
byte roll;
byte pitch;
byte throttle;
byte yaw;
byte gyr;
byte pit;
};
Signal data;
const uint64_t pipeIn = 0xBBBBBBBBB;//與發射端地址相同
RF24 radio(7, 8);
void ResetData()
{
data.roll = 127; // 橫滾通道中心點(254/2 = 127)
data.pitch = 127; // 俯仰通道
data.throttle = 0; // 信號丟失時,關閉油門
data.yaw = 127; // 航向通道
data.gyr = 0; //第五通道
data.pit = 0; //第六通道
}
void setup()
{
//設置PWM信號輸出引腳
ch1.attach(2);
ch2.attach(3);
ch3.attach(4);
ch4.attach(5);
ch5.attach(6);
ch6.attach(9);
//配置NRF24L01模塊
ResetData();
radio.begin();
radio.openReadingPipe(1,pipeIn);//與發射端地址相同
radio.startListening(); //接收模式
pinMode(LED_BUILTIN,OUTPUT);//LED推輓輸出
digitalWrite(LED_BUILTIN,HIGH);
Serial.begin(115200);
}
unsigned long lastRecvTime = 0;
void recvData()
{
while ( radio.available() ) {
radio.read(&data, sizeof(Signal));//接收數據
lastRecvTime = millis(); //當前時間ms
}
}
void loop()
{
recvData();
unsigned long now = millis();
if ( now - lastRecvTime > 1000 ) {
ResetData(); //兩次接收超過1s表示失去信號,輸出reset值
// Serial.print("無信號");
digitalWrite(LED_BUILTIN,HIGH);
}
else{
digitalWrite(LED_BUILTIN,LOW);
}
ch_width_1 = map(data.roll, 0, 255, 1000, 2000);// 將0~255映射到1000~2000,即1ms~2ms/20ms的PWM輸出
ch_width_2 = map(data.pitch, 0, 255, 1000, 2000);
ch_width_3 = map(data.throttle, 0, 255, 1000, 2000);
ch_width_4 = map(data.yaw, 0, 255, 1000, 2000);
ch_width_5 = map(data.gyr, 0, 255, 1000, 2000);
ch_width_6 = map(data.pit, 0, 255, 1000, 2000);
Serial.print("\t");Serial.print(ch_width_1);
Serial.print("\t");Serial.print(ch_width_2);
Serial.print("\t");Serial.print(ch_width_3);
Serial.print("\t");Serial.print(ch_width_4);
Serial.print("\t");Serial.print(ch_width_5);
Serial.print("\t");Serial.println(ch_width_6);
// 將PWM信號輸出至引腳
ch1.writeMicroseconds(ch_width_1);//寫入us值
ch2.writeMicroseconds(ch_width_2);
ch3.writeMicroseconds(ch_width_3);
ch4.writeMicroseconds(ch_width_4);
ch5.writeMicroseconds(ch_width_5);
ch6.writeMicroseconds(ch_width_6);
}
4. 實現效果
視頻已上傳B站:https://www.bilibili.com/video/BV1Wk4y1R7N3/
實際拉距測試中,無線傳輸500m沒有壓力。現在只是實現了基礎的6通道遙控功能,後期再不斷優化改進,計劃改進方向:
- 遙控器端,加入OLED顯示屏+按鍵檢測,方便人機交互操作;
- 接收機端,加入SBUS輸出、PPM輸出。
參考鏈接
http://www.rcpano.net/2020/04/09/how-to-make-6-channel-radio-control-for-models-diy-proportional-rc/