开源自制的6通道航模遥控器(一) 超简单不超过100行代码

前言

前段时间跟着LOLI大神的教程制作了LOLI三代控,效果很好。但是,由于LOLI三代控的接收机带有数据回传功能,也就是接收机的无线模块也承担了发射数据功能,所以接收机也要使用带有功率放大芯片的NRF24L01模块才能实现远距离通信,这不仅抬高了成本还带来了体积的增加。于是笔者打算自制一个较简单的6通道航模遥控器,正好手上有一个没有接收机的天地飞-06X,决定对其进行改造,一番查阅资料后用Arduino Pro Mini开发板实现了基础的功能,效果还不错。

1. 材料清单

USB转TTL模块*1

Arduino Pro Mini开发板*2

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第1张图片

NRF24L01无线通信模块*2

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第2张图片

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第3张图片

ams1117-3.3电压转换芯片1个

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第4张图片

 

100uF电解电容*2

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第5张图片

104电容*2

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第6张图片

三脚开关*4

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第7张图片

10k电阻*1,20k电阻*1

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第8张图片

导线及插针若干

2. 硬件部分

按照原理图焊接电路,尽情飞线叭,有条件的话可以设计PCB做的好看一些。

a)遥控器端

遥控器端负责发送数据,所以使用可以无线透传2000m的NRF24L01无线通信模块;

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第9张图片

 

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第10张图片

笔者的飞线不忍直视 ,100m的NRF24L01模块不够用,果断换了2000m的。

 

b)接收机端

接收机端负责接收数据,使用100m的NRF24L01无线通信模块足够了。

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第11张图片

 

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第12张图片

3. 软件部分

a)遥控器端

将USB转TTL模块连接电脑,引脚接线如下:

TX0--RXD
RX1--TXD
VCC--3V3
GND--GND

打开Arduino IDE,选择遥控器端的程序打开,这里要下载RF24封装库,下载方法如下:

项目》加载库》管理库,打开库管理器

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第13张图片

输入RF24搜索,选择图中的库进行安装,安装完毕后点击关闭; 

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第14张图片

烧写程序之前,要先选择自己的开发板型号,如下图,处理器选择自己的开发板类型,端口选择USB转TTL所在的端口号 

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第15张图片

点击上传,烧写程序;

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第16张图片

等待上传完成后,打开串口监视器查看4个ADC的数值;

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第17张图片

通信地址可以改为自己喜欢的地址,每个位是十六进制(0~9、A~F) ;

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第18张图片

向各个方向拨动摇杆,通过串口监视器查看输出值,然后把每个通道的最小值、 中值、最大值填入程序中,最后再上传一次代码。

开源自制的6通道航模遥控器(一) 超简单不超过100行代码_第19张图片 完整的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 
#include 
#include 
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 
#include 
#include 
#include 
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站

[DIY] 开源自制的6通道航模遥控器,超简单不超过100行代码 (基于Arduino Pro Mini开发板+NRF24L01无线通信模块)

实际拉距测试中,无线传输500m没有压力。现在只是实现了基础的6通道遥控功能,后期再不断优化改进,计划改进方向:

  1. 遥控器端,加入OLED显示屏+按键检测,方便人机交互操作;
  2. 接收机端,加入SBUS输出、PPM输出。

参考链接

http://www.rcpano.net/2020/04/09/how-to-make-6-channel-radio-control-for-models-diy-proportional-rc/

你可能感兴趣的:(Arduino)