開源自制的6通道航模遙控器(二)-Arduino接收機增加SBUS輸出

前言

前幾天開源了自制的6通道航模遙控器(開源自制的6通道航模遙控器,超簡單不超過100行代碼),受到許多粉絲的關注,美中不足的是隻實現了6個通道的PWM輸出,沒有SBUS輸出,接線太複雜。經過一段時間的查閱資料和開發,終於實現了SBUS輸出,這樣就可以用三根線實現16個伺服通道和2個數字通道的輸出了!

1. 新增元件

1k電阻一個,10k電阻一個,SS8050三極管一個(貼片體積更小)

2. 電路連接

原理圖如下,基本和之前的原理圖相同,只是加上了SBUS的取反電路。

元件連接圖如下:

 

3. 軟件部分

SBUS協議使用波特率爲100000、8個數據位,偶數奇偶校驗位和2個停止位的反向串行邏輯。SBUS數據包的長度爲25個字節,包括:
字節[0]:SBUS頭,0x0F
字節[1-22]:16個伺服通道,每個伺服通道採用11位編碼
字節[23]:
          位7:數字通道17(0x80)
          位6:數字通道18(0x40)
          位5:丟幀(0x20)
          位4:用來激活故障安全(0x10)
          位0-3:n/a
字節[24]:SBUS結束字節,0x00

S.Bus協議通過硬件電路取反,如果沒有反相電路,Arduino將無法直接與其他SBUS設備通信。F1和F4飛控根本沒有內置反相器,因此任何UART都可以直接使用;對於F3和F7飛控,INAV / Betaflight固件可以禁用軟件中的反相。
程序中採用“ FASSTest 18CH”協議的Futaba S.Bus 編碼16個RC通道和2個數字通道(ON / OFF)。

SBUS的每個RC通道值映射爲:
-100%= 173(相當於PWM伺服信號中的1000)
0%= 992(相當於PWM伺服信號中的1500)
100%= 1811(相當於PMW伺服信號中的2000)

Arduino的串行端口必須配置爲100000bps, SERIAL_8E2(8個數據位,偶校驗,2個停止位)。

#define RC_CHANNEL_MIN 1000
#define RC_CHANNEL_MAX 2000
#define SBUS_MIN_OFFSET 173
#define SBUS_MID_OFFSET 992
#define SBUS_MAX_OFFSET 1811
#define SBUS_CHANNEL_NUMBER 6
#define SBUS_PACKET_LENGTH 25
#define SBUS_FRAME_HEADER 0x0f
#define SBUS_FRAME_FOOTER 0x00
#define SBUS_FRAME_FOOTER_V2 0x04
#define SBUS_STATE_FAILSAFE 0x08
#define SBUS_STATE_SIGNALLOSS 0x04
#define SBUS_UPDATE_RATE 9 //ms

#include <SPI.h>
#include <nRF24L01.h> // 安裝RF24庫
#include <RF24.h>
#include <Servo.h>
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);     // SPI通信,引腳對應關係:CE ->7,CSN ->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 sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe){
    static int output[SBUS_CHANNEL_NUMBER] = {0};
    /*將chanel值1000-2000映射到SBUS協議的173-1811*/
    for (uint8_t i = 0; i < SBUS_CHANNEL_NUMBER; i++) {
        output[i] = map(channels[i], RC_CHANNEL_MIN, RC_CHANNEL_MAX, SBUS_MIN_OFFSET, SBUS_MAX_OFFSET);
    }
    
    uint8_t stateByte = 0x00;
    if (isSignalLoss) {
        stateByte |= SBUS_STATE_SIGNALLOSS; // 丟失信號標誌
    }
    if (isFailsafe) {
        stateByte |= SBUS_STATE_FAILSAFE;   // 激活故障安全標誌
    }
    packet[0] = SBUS_FRAME_HEADER; //SBUS頭,0x0F
    packet[1] = (uint8_t) (output[0] & 0x07FF);
    packet[2] = (uint8_t) ((output[0] & 0x07FF)>>8 | (output[1] & 0x07FF)<<3);
    packet[3] = (uint8_t) ((output[1] & 0x07FF)>>5 | (output[2] & 0x07FF)<<6);
    packet[4] = (uint8_t) ((output[2] & 0x07FF)>>2);
    packet[5] = (uint8_t) ((output[2] & 0x07FF)>>10 | (output[3] & 0x07FF)<<1);
    packet[6] = (uint8_t) ((output[3] & 0x07FF)>>7 | (output[4] & 0x07FF)<<4);
    packet[7] = (uint8_t) ((output[4] & 0x07FF)>>4 | (output[5] & 0x07FF)<<7);
    packet[8] = (uint8_t) ((output[5] & 0x07FF)>>1);
    packet[9] = (uint8_t) ((output[5] & 0x07FF)>>9 | (output[6] & 0x07FF)<<2);
    packet[10] = (uint8_t) ((output[6] & 0x07FF)>>6 | (output[7] & 0x07FF)<<5);
    packet[11] = (uint8_t) ((output[7] & 0x07FF)>>3);
    packet[12] = (uint8_t) ((output[8] & 0x07FF));
    packet[13] = (uint8_t) ((output[8] & 0x07FF)>>8 | (output[9] & 0x07FF)<<3);
    packet[14] = (uint8_t) ((output[9] & 0x07FF)>>5 | (output[10] & 0x07FF)<<6);  
    packet[15] = (uint8_t) ((output[10] & 0x07FF)>>2);
    packet[16] = (uint8_t) ((output[10] & 0x07FF)>>10 | (output[11] & 0x07FF)<<1);
    packet[17] = (uint8_t) ((output[11] & 0x07FF)>>7 | (output[12] & 0x07FF)<<4);
    packet[18] = (uint8_t) ((output[12] & 0x07FF)>>4 | (output[13] & 0x07FF)<<7);
    packet[19] = (uint8_t) ((output[13] & 0x07FF)>>1);
    packet[20] = (uint8_t) ((output[13] & 0x07FF)>>9 | (output[14] & 0x07FF)<<2);
    packet[21] = (uint8_t) ((output[14] & 0x07FF)>>6 | (output[15] & 0x07FF)<<5);
    packet[22] = (uint8_t) ((output[15] & 0x07FF)>>3);
    packet[23] = stateByte;         // 標誌位
    packet[24] = SBUS_FRAME_FOOTER; // SBUS結束字節
}

uint8_t sbusPacket[SBUS_PACKET_LENGTH];// 25個字節的數據包
int rcChannels[SBUS_CHANNEL_NUMBER];   // 6通道信號,可以增加
uint32_t sbusTime = 0;
bool signalLoss = false;  // true時表示丟失信號

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(10,OUTPUT);     // LED推輓輸出
  digitalWrite(10,HIGH);
  Serial.begin(100000, SERIAL_8E2); // 將串口波特率設爲100000,數據位8,偶校驗,停止位2
}
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值
    signalLoss = true;
//    Serial.print("無信號");
    digitalWrite(10,HIGH);
  }
  else{
    digitalWrite(10,LOW);
    }
  rcChannels[0] = map(data.roll,     0, 255, 1000, 2000);// 將0~255映射到1000~2000,即(1ms~2ms)/20ms的PWM輸出
  rcChannels[1] = map(data.pitch,    0, 255, 1000, 2000);
  rcChannels[2] = map(data.throttle, 0, 255, 1000, 2000);
  rcChannels[3] = map(data.yaw,      0, 255, 1000, 2000);
  rcChannels[4] = map(data.gyr,      0, 255, 1000, 2000);
  rcChannels[5] = map(data.pit,      0, 255, 1000, 2000);
  uint32_t currentMillis = millis();
  if (currentMillis > sbusTime) {
      sbusPreparePacket(sbusPacket, rcChannels, signalLoss, false); // 6通道數值轉換爲SBUS數據包
      Serial.write(sbusPacket, SBUS_PACKET_LENGTH); // 將SBUS數據包通過串口TX0輸出
      sbusTime = currentMillis + SBUS_UPDATE_RATE;
  }
  ch1.writeMicroseconds(rcChannels[0]);//寫入us值,PWM輸出
  ch2.writeMicroseconds(rcChannels[1]);
  ch3.writeMicroseconds(rcChannels[2]);
  ch4.writeMicroseconds(rcChannels[3]);
  ch5.writeMicroseconds(rcChannels[4]);
  ch6.writeMicroseconds(rcChannels[5]);
}

4. 實現效果

筆者將Arduino接收機連接F3飛控,已經可以在betaflight-configurator軟件中看到接收到信號了。

值得一提的是,前6個通道輸出是沒問題的,但是筆者調試時發現,後面的通道值會跟隨前6個通道的變化而變化,嘗試修改代碼也沒有解決。雖然這個問題不影響使用,但這是一個安全隱患,如果有大神解決了,歡迎評論指正哈~

參考鏈接

https://quadmeup.com/generate-s-bus-with-arduino-in-a-simple-way

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章