mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-09 10:41:15 +00:00
Added non-final versions of iris and tower firmware.
This commit is contained in:
92
software/firmware/libraries/SBUS/README.md
Normal file
92
software/firmware/libraries/SBUS/README.md
Normal file
@@ -0,0 +1,92 @@
|
||||
# SBUS
|
||||
Library for communicating with SBUS receivers and servos using Teensy 3.x and Teensy LC devices.
|
||||
|
||||
# Description
|
||||
SBUS is a protocol for RC receivers to send commands to servos. Unlike PWM, SBUS uses a bus architecture where a single signal line can be connected up to 16 servos with each receiving a unique command. SBUS capable servos are required; each can be programmed with a unique address (Channel 0 - 15) using an SBUS servo programmer. Advantages of SBUS include the reduction of wiring clutter and ease of parsing commands from RC receivers.
|
||||
|
||||
Much of the information gathered on the SBUS protocol comes from [Uwe Gartmann](https://developer.mbed.org/users/Digixx/notebook/futaba-s-bus-controlled-by-mbed/). Implementation of sending SBUS packet data to servos on Teensy devices was greatly aided by this discussion and feedback from [Paul Stroffregen](https://forum.pjrc.com/archive/index.php/t-23956.html).
|
||||
|
||||
The SBUS protocol uses inverted serial logic with a baud rate of 100000, 8 data bits, even parity bit, and 2 stop bits. The SBUS packet is 25 bytes long consisting of:
|
||||
* Byte[0]: SBUS Header, 0x0F
|
||||
* Byte[1-22]: 16 servo channels, 11 bits per servo channel
|
||||
* Byte[23]:
|
||||
* Bit 7: digital channel 17 (0x80)
|
||||
* Bit 6: digital channel 18 (0x40)
|
||||
* Bit 5: frame lost (0x20)
|
||||
* Bit 4: failsafe activated (0x10)
|
||||
* Bit 0 - 3: n/a
|
||||
* Byte[24]: SBUS End Byte, 0x00
|
||||
|
||||
A table mapping bytes[1-22] to servo channels is [included](https://github.com/bolderflight/SBUS/blob/master/docs/bit-mapping.pdf).
|
||||
|
||||
This library has two basic modes of functionality:
|
||||
|
||||
1. Reading and parsing SBUS packets. This is useful for using an SBUS capable receiver to receive commands from a RC transmitter and parse the SBUS packet for vehicle control (closed loop control laws, servo mapping, mode change commands) and logging. SBUS packet reading and parsing is available with raw count data and calibrated to a +/- 1.0 float. Additionally, lost frame and failsafe data is made available.
|
||||
2. Writing SBUS packets. This is useful for commanding up to 16 SBUS capable servos from the Teensy device.
|
||||
|
||||
This library has been tested using FrSky SBUS capable receivers (X8R and X4R) and FrSky SBUS capable servos (D25MA). Feedback from users, especially with other brand receivers and servos (i.e. Futaba), would be greatly appreciated.
|
||||
|
||||
# Usage
|
||||
This library uses the [hardware serial](https://www.pjrc.com/teensy/td_uart.html) for Teensy devices. Additionally, this library [**requires Teensyduino 1.30 or above**](https://www.pjrc.com/teensy/td_download.html).
|
||||
|
||||
Simply clone or download and extract the zipped library into your Arduino/libraries folder.
|
||||
|
||||
Bind your SBUS capable receiver to your transmitter. Setup your SBUS capable servos by programming each with a unique channel number.
|
||||
|
||||
**SBUS(HardwareSerial& bus)**
|
||||
A SBUS object should be declared, specifying the hardware serial port the SBUS receiver and servos are connected to. For example, the following code declares a SBUS object called *x8r* located on the Teensy hardware serial port 1:
|
||||
|
||||
```C++
|
||||
SBUS x8r(Serial1);
|
||||
```
|
||||
|
||||
**void begin()**
|
||||
This should be called in your setup function. It initializes the serial communication between the Teensy and SBUS receiver and servos.
|
||||
|
||||
```C++
|
||||
x8r.begin();
|
||||
```
|
||||
|
||||
**bool read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames)**
|
||||
*read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames)* reads data from the SBUS receiver and parses the SBUS packet. When a complete packet is received, *read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames)* returns *true* and the *channels[0-15]*, *failsafe*, and *lost frames* data is available. Note that *lost frames* is a counter that increments once each time a lost frame flag is read in the SBUS packet. For example, placing the following code in the loop function will print the value of *channel 0* every time a valid SBUS packet is received.
|
||||
|
||||
```C++
|
||||
uint16_t channels[16];
|
||||
uint8_t failSafe;
|
||||
uint16_t lostFrames = 0;
|
||||
|
||||
if(x8r.read(&channels[0], &failSafe, &lostFrames)){
|
||||
Serial.println(channels[0]);
|
||||
}
|
||||
```
|
||||
|
||||
**bool readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames)**
|
||||
*readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames)* reads data from the SBUS receiver and parses the SBUS packet. The data from *channels[0-15]* is calibrated to a +/- 1.0 float value assuming a linear relationship based on the minimum and maximum value (172 and 1811 using FrSky set to 0-100%). When a complete packet is received, *readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames)* returns *true* and the *calChannels[0-15]*, *failsafe*, and *lost frames* data is available. Note that *lost frames* is a counter that increments once each time a lost frame flag is read in the SBUS packet. For example, placing the following code in the loop function will print the calibrated value of *channel 0* every time a valid SBUS packet is received.
|
||||
|
||||
```C++
|
||||
float channels[16];
|
||||
uint8_t failSafe;
|
||||
uint16_t lostFrames = 0;
|
||||
|
||||
if(x8r.readCal(&channels[0], &failSafe, &lostFrames)){
|
||||
Serial.println(channels[0]);
|
||||
}
|
||||
```
|
||||
|
||||
**void write(uint16_t* channels)**
|
||||
*write(uint16_t* channels)* writes the SBUS packet to SBUS capable servos given position commands from *channels[0-15]*. Note that this function simply creates and sends the SBUS packet, but does not handle timing (i.e. the time between sending subsequent SBUS packets). This timing must be handled by the calling function. For example, placing the following code in the loop function will create and send the SBUS packet to servos every time a valid SBUS packet is received.
|
||||
|
||||
```C++
|
||||
uint16_t channels[16];
|
||||
uint8_t failSafe;
|
||||
uint16_t lostFrames = 0;
|
||||
|
||||
// look for a good SBUS packet from the receiver
|
||||
if(x8r.read(&channels[0], &failSafe, &lostFrames)){
|
||||
// write the SBUS packet to SBUS compatible servos
|
||||
x8r.write(&channels[0]);
|
||||
}
|
||||
```
|
||||
|
||||
# Wiring
|
||||
Please refer to the [Teensy pinout diagrams](https://www.pjrc.com/teensy/pinout.html) for hardware serial port pin information. The SBUS capable receiver ground should be connected to the Teensy ground. The receiver power may be connected to the Teensy Vin or to an external 5V power source. Receiver signal should be connected to the Teensy RX pin on the specified hardware serial port. The SBUS capable servo ground should be connected to the Teensy ground. **Servo power must come from an external power source**; Vin is not likely capable of supplying the necessary current. Servo signal should be connected to the Teensy TX pin on the specified hardware serial port.
|
||||
249
software/firmware/libraries/SBUS/SBUS.cpp
Normal file
249
software/firmware/libraries/SBUS/SBUS.cpp
Normal file
@@ -0,0 +1,249 @@
|
||||
/*
|
||||
SBUS.cpp
|
||||
Brian R Taylor
|
||||
brian.taylor@bolderflight.com
|
||||
2017-01-13
|
||||
|
||||
Copyright (c) 2016 Bolder Flight Systems
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy of this software
|
||||
and associated documentation files (the "Software"), to deal in the Software without restriction,
|
||||
including without limitation the rights to use, copy, modify, merge, publish, distribute,
|
||||
sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all copies or
|
||||
substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
|
||||
BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
||||
NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
|
||||
DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
|
||||
// Teensy 3.0 || Teensy 3.1/3.2 || Teensy 3.5 || Teensy 3.6 || Teensy LC
|
||||
#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MK64FX512__) || \
|
||||
defined(__MK66FX1M0__) || defined(__MKL26Z64__)
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "SBUS.h"
|
||||
|
||||
#if defined(__MK20DX128__) || defined(__MK20DX256__)
|
||||
// globals needed for emulating two stop bytes on Teensy 3.0 and 3.1/3.2
|
||||
IntervalTimer serialTimer;
|
||||
HardwareSerial* SERIALPORT;
|
||||
uint8_t PACKET[25];
|
||||
volatile int SENDINDEX;
|
||||
void sendByte();
|
||||
#endif
|
||||
|
||||
/* SBUS object, input the serial bus */
|
||||
SBUS::SBUS(HardwareSerial& bus){
|
||||
_bus = &bus;
|
||||
}
|
||||
|
||||
/* starts the serial communication */
|
||||
void SBUS::begin(){
|
||||
// initialize parsing state
|
||||
_fpos = 0;
|
||||
#if defined(__MK20DX128__) || defined(__MK20DX256__) // Teensy 3.0 || Teensy 3.1/3.2
|
||||
// begin the serial port for SBUS
|
||||
_bus->begin(100000,SERIAL_8E1_RXINV_TXINV);
|
||||
SERIALPORT = _bus;
|
||||
#endif
|
||||
|
||||
#if defined(__MK64FX512__) || defined(__MK66FX1M0__) || defined(__MKL26Z64__) // Teensy 3.5 || Teensy 3.6 || Teensy LC
|
||||
// begin the serial port for SBUS
|
||||
_bus->begin(100000,SERIAL_8E2_RXINV_TXINV);
|
||||
#endif
|
||||
}
|
||||
|
||||
/* read the SBUS data and calibrate it to +/- 1 */
|
||||
bool SBUS::readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames){
|
||||
uint16_t channels[16];
|
||||
|
||||
// read the SBUS data
|
||||
if(read(&channels[0],failsafe,lostFrames)){
|
||||
|
||||
// linear calibration
|
||||
for(uint8_t i = 0; i < 16; i++){
|
||||
calChannels[i] = channels[i] * _sbusScale + _sbusBias;
|
||||
}
|
||||
|
||||
// return true on receiving a full packet
|
||||
return true;
|
||||
}
|
||||
else{
|
||||
|
||||
// return false if a full packet is not received
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
/* read the SBUS data */
|
||||
bool SBUS::read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames){
|
||||
|
||||
// parse the SBUS packet
|
||||
if(parse()){
|
||||
|
||||
// 16 channels of 11 bit data
|
||||
channels[0] = (int16_t) ((_payload[0] |_payload[1]<<8) & 0x07FF);
|
||||
channels[1] = (int16_t) ((_payload[1]>>3 |_payload[2]<<5) & 0x07FF);
|
||||
channels[2] = (int16_t) ((_payload[2]>>6 |_payload[3]<<2 |_payload[4]<<10) & 0x07FF);
|
||||
channels[3] = (int16_t) ((_payload[4]>>1 |_payload[5]<<7) & 0x07FF);
|
||||
channels[4] = (int16_t) ((_payload[5]>>4 |_payload[6]<<4) & 0x07FF);
|
||||
channels[5] = (int16_t) ((_payload[6]>>7 |_payload[7]<<1 |_payload[8]<<9) & 0x07FF);
|
||||
channels[6] = (int16_t) ((_payload[8]>>2 |_payload[9]<<6) & 0x07FF);
|
||||
channels[7] = (int16_t) ((_payload[9]>>5 |_payload[10]<<3) & 0x07FF);
|
||||
channels[8] = (int16_t) ((_payload[11] |_payload[12]<<8) & 0x07FF);
|
||||
channels[9] = (int16_t) ((_payload[12]>>3|_payload[13]<<5) & 0x07FF);
|
||||
channels[10] = (int16_t) ((_payload[13]>>6|_payload[14]<<2|_payload[15]<<10) & 0x07FF);
|
||||
channels[11] = (int16_t) ((_payload[15]>>1|_payload[16]<<7) & 0x07FF);
|
||||
channels[12] = (int16_t) ((_payload[16]>>4|_payload[17]<<4) & 0x07FF);
|
||||
channels[13] = (int16_t) ((_payload[17]>>7|_payload[18]<<1|_payload[19]<<9) & 0x07FF);
|
||||
channels[14] = (int16_t) ((_payload[19]>>2|_payload[20]<<6) & 0x07FF);
|
||||
channels[15] = (int16_t) ((_payload[20]>>5|_payload[21]<<3) & 0x07FF);
|
||||
|
||||
// count lost frames
|
||||
if (_payload[22] & _sbusLostFrame) {
|
||||
*lostFrames = *lostFrames + 1;
|
||||
}
|
||||
|
||||
// failsafe state
|
||||
if (_payload[22] & _sbusFailSafe) {
|
||||
*failsafe = 1;
|
||||
}
|
||||
else{
|
||||
*failsafe = 0;
|
||||
}
|
||||
|
||||
// return true on receiving a full packet
|
||||
return true;
|
||||
}
|
||||
else{
|
||||
|
||||
// return false if a full packet is not received
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
/* parse the SBUS data */
|
||||
bool SBUS::parse(){
|
||||
static elapsedMicros sbusTime = 0;
|
||||
|
||||
if(sbusTime > SBUS_TIMEOUT){_fpos = 0;}
|
||||
|
||||
// see if serial data is available
|
||||
while(_bus->available() > 0){
|
||||
sbusTime = 0;
|
||||
static uint8_t c;
|
||||
static uint8_t b;
|
||||
c = _bus->read();
|
||||
|
||||
// find the header
|
||||
if(_fpos == 0){
|
||||
if((c == _sbusHeader)&&((b == _sbusFooter)||((b & 0x0F) == _sbus2Footer))){
|
||||
_fpos++;
|
||||
}
|
||||
else{
|
||||
_fpos = 0;
|
||||
}
|
||||
}
|
||||
else{
|
||||
|
||||
// strip off the data
|
||||
if((_fpos-1) < _payloadSize){
|
||||
_payload[_fpos-1] = c;
|
||||
_fpos++;
|
||||
}
|
||||
|
||||
// check the end byte
|
||||
if((_fpos-1) == _payloadSize){
|
||||
if((c == _sbusFooter)||((c & 0x0F) == _sbus2Footer)) {
|
||||
_fpos = 0;
|
||||
return true;
|
||||
}
|
||||
else{
|
||||
_fpos = 0;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
b = c;
|
||||
}
|
||||
// return false if a partial packet
|
||||
return false;
|
||||
}
|
||||
|
||||
/* write SBUS packets */
|
||||
void SBUS::write(uint16_t* channels){
|
||||
uint8_t packet[25];
|
||||
|
||||
/* assemble the SBUS packet */
|
||||
|
||||
// SBUS header
|
||||
packet[0] = _sbusHeader;
|
||||
|
||||
// 16 channels of 11 bit data
|
||||
packet[1] = (uint8_t) ((channels[0] & 0x07FF));
|
||||
packet[2] = (uint8_t) ((channels[0] & 0x07FF)>>8 | (channels[1] & 0x07FF)<<3);
|
||||
packet[3] = (uint8_t) ((channels[1] & 0x07FF)>>5 | (channels[2] & 0x07FF)<<6);
|
||||
packet[4] = (uint8_t) ((channels[2] & 0x07FF)>>2);
|
||||
packet[5] = (uint8_t) ((channels[2] & 0x07FF)>>10 | (channels[3] & 0x07FF)<<1);
|
||||
packet[6] = (uint8_t) ((channels[3] & 0x07FF)>>7 | (channels[4] & 0x07FF)<<4);
|
||||
packet[7] = (uint8_t) ((channels[4] & 0x07FF)>>4 | (channels[5] & 0x07FF)<<7);
|
||||
packet[8] = (uint8_t) ((channels[5] & 0x07FF)>>1);
|
||||
packet[9] = (uint8_t) ((channels[5] & 0x07FF)>>9 | (channels[6] & 0x07FF)<<2);
|
||||
packet[10] = (uint8_t) ((channels[6] & 0x07FF)>>6 | (channels[7] & 0x07FF)<<5);
|
||||
packet[11] = (uint8_t) ((channels[7] & 0x07FF)>>3);
|
||||
packet[12] = (uint8_t) ((channels[8] & 0x07FF));
|
||||
packet[13] = (uint8_t) ((channels[8] & 0x07FF)>>8 | (channels[9] & 0x07FF)<<3);
|
||||
packet[14] = (uint8_t) ((channels[9] & 0x07FF)>>5 | (channels[10] & 0x07FF)<<6);
|
||||
packet[15] = (uint8_t) ((channels[10] & 0x07FF)>>2);
|
||||
packet[16] = (uint8_t) ((channels[10] & 0x07FF)>>10 | (channels[11] & 0x07FF)<<1);
|
||||
packet[17] = (uint8_t) ((channels[11] & 0x07FF)>>7 | (channels[12] & 0x07FF)<<4);
|
||||
packet[18] = (uint8_t) ((channels[12] & 0x07FF)>>4 | (channels[13] & 0x07FF)<<7);
|
||||
packet[19] = (uint8_t) ((channels[13] & 0x07FF)>>1);
|
||||
packet[20] = (uint8_t) ((channels[13] & 0x07FF)>>9 | (channels[14] & 0x07FF)<<2);
|
||||
packet[21] = (uint8_t) ((channels[14] & 0x07FF)>>6 | (channels[15] & 0x07FF)<<5);
|
||||
packet[22] = (uint8_t) ((channels[15] & 0x07FF)>>3);
|
||||
|
||||
// flags
|
||||
packet[23] = 0x00;
|
||||
|
||||
// footer
|
||||
packet[24] = _sbusFooter;
|
||||
|
||||
#if defined(__MK20DX128__) || defined(__MK20DX256__) // Teensy 3.0 || Teensy 3.1/3.2
|
||||
// use ISR to send byte at a time,
|
||||
// 130 us between bytes to emulate 2 stop bits
|
||||
noInterrupts();
|
||||
memcpy(&PACKET,&packet,sizeof(packet));
|
||||
interrupts();
|
||||
serialTimer.priority(255);
|
||||
serialTimer.begin(sendByte,130);
|
||||
#endif
|
||||
|
||||
#if defined(__MK64FX512__) || defined(__MK66FX1M0__) || defined(__MKL26Z64__) // Teensy 3.5 || Teensy 3.6 || Teensy LC
|
||||
// write packet
|
||||
_bus->write(packet,25);
|
||||
#endif
|
||||
}
|
||||
|
||||
// function to send byte at a time with
|
||||
// ISR to emulate 2 stop bits on Teensy 3.0 and 3.1/3.2
|
||||
#if defined(__MK20DX128__) || defined(__MK20DX256__) // Teensy 3.0 || Teensy 3.1/3.2
|
||||
void sendByte(){
|
||||
if(SENDINDEX < 25) {
|
||||
SERIALPORT->write(PACKET[SENDINDEX]);
|
||||
SENDINDEX++;
|
||||
}
|
||||
else{
|
||||
serialTimer.end();
|
||||
SENDINDEX = 0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
54
software/firmware/libraries/SBUS/SBUS.h
Normal file
54
software/firmware/libraries/SBUS/SBUS.h
Normal file
@@ -0,0 +1,54 @@
|
||||
/*
|
||||
SBUS.h
|
||||
Brian R Taylor
|
||||
brian.taylor@bolderflight.com
|
||||
2017-01-13
|
||||
|
||||
Copyright (c) 2016 Bolder Flight Systems
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy of this software
|
||||
and associated documentation files (the "Software"), to deal in the Software without restriction,
|
||||
including without limitation the rights to use, copy, modify, merge, publish, distribute,
|
||||
sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all copies or
|
||||
substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
|
||||
BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
||||
NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
|
||||
DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
|
||||
#ifndef SBUS_h
|
||||
#define SBUS_h
|
||||
|
||||
#include "Arduino.h"
|
||||
|
||||
class SBUS{
|
||||
public:
|
||||
SBUS(HardwareSerial& bus);
|
||||
void begin();
|
||||
bool read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames);
|
||||
bool readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames);
|
||||
void write(uint16_t* channels);
|
||||
private:
|
||||
uint8_t _fpos;
|
||||
const uint16_t SBUS_TIMEOUT = 10000;
|
||||
const float _sbusScale = 0.00122025625f;
|
||||
const float _sbusBias = -1.2098840f;
|
||||
const uint8_t _sbusHeader = 0x0F;
|
||||
const uint8_t _sbusFooter = 0x00;
|
||||
const uint8_t _sbus2Footer = 0x04;
|
||||
const uint8_t _sbusLostFrame = 0x04;
|
||||
const uint8_t _sbusFailSafe = 0x08;
|
||||
static const uint8_t _payloadSize = 24;
|
||||
uint8_t _payload[_payloadSize];
|
||||
HardwareSerial* _bus;
|
||||
|
||||
bool parse();
|
||||
};
|
||||
|
||||
#endif
|
||||
BIN
software/firmware/libraries/SBUS/docs/bit-mapping.ods
Normal file
BIN
software/firmware/libraries/SBUS/docs/bit-mapping.ods
Normal file
Binary file not shown.
BIN
software/firmware/libraries/SBUS/docs/bit-mapping.pdf
Normal file
BIN
software/firmware/libraries/SBUS/docs/bit-mapping.pdf
Normal file
Binary file not shown.
@@ -0,0 +1,82 @@
|
||||
/*
|
||||
SBUS_example.ino
|
||||
Brian R Taylor
|
||||
brian.taylor@bolderflight.com
|
||||
2017-01-13
|
||||
|
||||
Copyright (c) 2016 Bolder Flight Systems
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy of this software
|
||||
and associated documentation files (the "Software"), to deal in the Software without restriction,
|
||||
including without limitation the rights to use, copy, modify, merge, publish, distribute,
|
||||
sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all copies or
|
||||
substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
|
||||
BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
||||
NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
|
||||
DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
|
||||
// This example reads 10 analog inputs, linearly maps them to SBUS
|
||||
// servo commands and sends the command to the servos. In this case
|
||||
// an interrupt is used to control packet timing.
|
||||
|
||||
#include <TimerOne.h>
|
||||
#include "SBUS.h"
|
||||
|
||||
// a SBUS object, which is on Teensy hardware
|
||||
// serial port 1
|
||||
SBUS x8r(Serial1);
|
||||
|
||||
// analog read values, 16 bit counts
|
||||
uint16_t ain[10];
|
||||
|
||||
void setup() {
|
||||
|
||||
// serial to display the channel commands for debugging
|
||||
Serial.begin(115200);
|
||||
|
||||
// begin the SBUS communication
|
||||
x8r.begin();
|
||||
|
||||
// setup the analog read resolution to 16 bits
|
||||
analogReadResolution(16);
|
||||
|
||||
// setup an interrupt to send packets every 9 ms
|
||||
Timer1.initialize(9000);
|
||||
Timer1.attachInterrupt(sendSBUS);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
}
|
||||
|
||||
/* reads analog inputs and sends an SBUS packet */
|
||||
void sendSBUS() {
|
||||
float scaleFactor = 1639.0f / 65535.0f;
|
||||
float bias = 172.0f;
|
||||
uint16_t channels[16];
|
||||
|
||||
// read the analog inputs
|
||||
for(uint8_t i = 14; i < 24; i++) {
|
||||
ain[i-14] = analogRead(i);
|
||||
}
|
||||
|
||||
// linearly map the analog measurements (0-65535)
|
||||
// to the SBUS commands (172-1811)
|
||||
for(uint8_t i = 0; i < 10; i++) {
|
||||
channels[i] = (uint16_t)(((float)ain[i]) * scaleFactor + bias);
|
||||
Serial.print(channels[i]); // print the channel command (172-1811)
|
||||
Serial.print("\t");
|
||||
}
|
||||
Serial.println();
|
||||
|
||||
// write the SBUS packet to an SBUS compatible servo
|
||||
x8r.write(&channels[0]);
|
||||
}
|
||||
|
||||
@@ -0,0 +1,61 @@
|
||||
/*
|
||||
SBUS_example.ino
|
||||
Brian R Taylor
|
||||
brian.taylor@bolderflight.com
|
||||
2016-09-21
|
||||
|
||||
Copyright (c) 2016 Bolder Flight Systems
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy of this software
|
||||
and associated documentation files (the "Software"), to deal in the Software without restriction,
|
||||
including without limitation the rights to use, copy, modify, merge, publish, distribute,
|
||||
sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all copies or
|
||||
substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
|
||||
BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
||||
NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
|
||||
DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
|
||||
// This example reads an SBUS packet from an
|
||||
// SBUS receiver (FrSky X8R) and then takes that
|
||||
// packet and writes it back to an SBUS
|
||||
// compatible servo. The SBUS out capability (i.e.
|
||||
// writing a command to the servo) could be generated
|
||||
// independently; however, the packet timing would need
|
||||
// to be controlled by the programmer, the write function
|
||||
// simply generates an SBUS packet and writes it to the
|
||||
// servos. In this case the packet timing is handled by the
|
||||
// SBUS receiver and waiting for a good packet read.
|
||||
|
||||
#include "SBUS.h"
|
||||
|
||||
// a SBUS object, which is on Teensy hardware
|
||||
// serial port 1
|
||||
SBUS x8r(Serial1);
|
||||
|
||||
// channel, fail safe, and lost frames data
|
||||
uint16_t channels[16];
|
||||
uint8_t failSafe;
|
||||
uint16_t lostFrames = 0;
|
||||
|
||||
void setup() {
|
||||
// begin the SBUS communication
|
||||
x8r.begin();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
// look for a good SBUS packet from the receiver
|
||||
if(x8r.read(&channels[0], &failSafe, &lostFrames)){
|
||||
|
||||
// write the SBUS packet to an SBUS compatible servo
|
||||
x8r.write(&channels[0]);
|
||||
}
|
||||
}
|
||||
|
||||
5
software/firmware/libraries/SBUS/keywords.txt
Normal file
5
software/firmware/libraries/SBUS/keywords.txt
Normal file
@@ -0,0 +1,5 @@
|
||||
SBUS KEYWORD1
|
||||
begin KEYWORD2
|
||||
read KEYWORD2
|
||||
readCal KEYWORD2
|
||||
write KEYWORD2
|
||||
Reference in New Issue
Block a user