Skip to content

Commit

Permalink
v9.9.1: SBUS & battery protection bugfixes
Browse files Browse the repository at this point in the history
  • Loading branch information
TheDIYGuy999 committed Jun 30, 2022
1 parent 9fe4d74 commit 3157d09
Show file tree
Hide file tree
Showing 8 changed files with 70 additions and 51 deletions.
4 changes: 4 additions & 0 deletions README.md
Expand Up @@ -515,6 +515,10 @@ const uint8_t shakerStop = 60; // Shaker power while engine stop (max. 255, abou

## Changelog (newest on top):

### New in V 9.9.1:
- Flysky SBUS should now be stable with #define EMBEDDED_SBUS. Please let me know, if not.
- BATTERY_PROTECTION: scaling bug with higher resistor values fixed.

### New in V 9.9.0:
- New NEOPIXEL_UNION_JACK animation for Land Rover ;-)
- New MAX_POWER_MILLIAMPS setting for Neopixels. This and other optimizations is eliminating the flickering Neopixels issue
Expand Down
2 changes: 1 addition & 1 deletion src/2_adjustmentsRemote.h
Expand Up @@ -28,7 +28,7 @@
// NOTE: "boolean sbusInverted = true / false" was moved to the remote configuration profiles, so you don't have to change it
uint32_t sbusBaud = 100000; // Standard is 100000. Try to lower it, if your channels are coming in unstable. Working range is about 96000 - 104000.
#define EMBEDDED_SBUS // SBUS library not used, if defined (It is working fine with MICRO_RC, but still unstable with Flysky remotes, use IBUS for them)
uint16_t sbusFailsafeTimeout = 100; // Failsafe is triggered after this timeout in milliseconds (about 100, was 50)
uint16_t sbusFailsafeTimeout = 100; // Failsafe is triggered after this timeout in milliseconds (about 100)

// IBUS communication (RX header, 13 channels not recommended, NO FAILSAFE, if bad contact in iBUS wiring!) --------
//#define IBUS_COMMUNICATION // control signals are coming in via the IBUS interface (comment it out for classic PWM RC signals)
Expand Down
6 changes: 3 additions & 3 deletions src/3_adjustmentsESC.h
Expand Up @@ -130,9 +130,9 @@ const float RECOVERY_HYSTERESIS = 0.2; // around 0.2 V
* When selecting resistors, always use two of the same magnitude: Like, for example, 10k/2k, 20k/4k or 100k/20k. NEVER exceed a ratio LOWER than (4:1 = 4)!
* WARNING: If the ratio is too LOW, like 10k/5k (2:1 = 2), the battery voltage will most likely DAMAGE the controller permanently!
* Example calculation: 2000 / (2000 + 10000) = 0.166 666 666 7; 7.4 V * 0.167 = 1.2358 V (of 3.3 V maximum on GPIO Pin). */
uint16_t RESISTOR_TO_BATTTERY_PLUS = 10000; // Value in Ohms (Ω), for example 10000
uint16_t RESISTOR_TO_GND = 2000; // Value in Ohms (Ω), for example 2000. Measuring exact resistor values before soldering, if possible is recommended!
float DIODE_DROP = 0.34; // Fine adjust measured value and/or consider diode voltage drop (about 0.34V for SS34 diode)
uint32_t RESISTOR_TO_BATTTERY_PLUS = 10000; // Value in Ohms (Ω), for example 10000
uint32_t RESISTOR_TO_GND = 2000; // Value in Ohms (Ω), for example 2000. Measuring exact resistor values before soldering, if possible is recommended!
float DIODE_DROP = 0.0; // Fine adjust measured value and/or consider diode voltage drop (about 0.34V for SS34 diode)
/* It is recommended to add a sticker to your ESP32, which includes the 3 calibration values above */
volatile int outOfFuelVolumePercentage = 80; // Adjust the message volume in %
// Select the out of fuel message you want:
Expand Down
20 changes: 20 additions & 0 deletions src/7_adjustmentsServos.h
Expand Up @@ -22,6 +22,7 @@
// Select the vehicle configuration you have:
#define SERVOS_DEFAULT // <------- Select (remove //) one of the remote configurations below
//#define SERVOS_LANDY
//#define SERVOS_URAL
//#define SERVOS_RGT_EX86100
//#define SERVOS_ACTROS
//#define SERVOS_KING_HAULER
Expand Down Expand Up @@ -66,6 +67,25 @@ const uint16_t STEERING_RAMP_TIME = 0; // 0 = fastest speed, enlarge it to aroun

#endif

// WPL Ural servo configuration profile -------------------------------------------------------------------------------------------
#ifdef SERVOS_URAL

// Servo frequency
const uint8_t SERVO_FREQUENCY = 50; // usually 50Hz, some servos may run smoother @ 100Hz

// WARNING: never connect receiver PWM signals to the "CH" pins in BUS communication mode!

// Servo limits
const uint16_t CH1L = 1990, CH1C = 1640, CH1R = 1090; // CH1 steering left 1990, center 1640, right 1090
const uint16_t CH2L = 670, CH2C = 1800, CH2R = 1800; // CH2 transmission gear 1 978, 2 1800, 3 1800
const uint16_t CH3L = 1300, CH3C = 1450, CH3R = 1600; // CH3 winch pull, off, release
const uint16_t CH4L = 1300, CH4R = 1700; // CH4 trailer coupler (5th. wheel) locked, unlocked

// Servo ramp time
const uint16_t STEERING_RAMP_TIME = 0; // 0 = fastest speed, enlarge it to around 3000 for "scale" servo movements

#endif

// RGT EX86100 servo configuration profile -------------------------------------------------------------------------------------------
#ifdef SERVOS_RGT_EX86100

Expand Down
10 changes: 5 additions & 5 deletions src/9_adjustmentsDashboard.h
Expand Up @@ -12,11 +12,11 @@
*/

//#define SPI_DASHBOARD // A 0.96" SPI LCD is used as dashboard: https://www.ebay.ch/itm/174458054566?hash=item289e82a7a6:g:LpAAAOSwtL1fdDtI

// WARNING:
// Pins 18 (SCL), 19 (DC), 21 (RES) & 23 (SDA) are used for the dashboard in this case!
// The dispay CS pin needs to be connected to GND.
// Shaker, sidelights and both beacon flashers will not work!
/* WARNING:
* Pins 18 (SCL), 19 (DC), 21 (RES) & 23 (SDA) are used for the dashboard in this case!
* The dispay CS pin needs to be connected to GND.
* Shaker, sidelights and both beacon flashers will not work!
*/

uint8_t dashRotation = 3; // 3 = normal, 1 = upside down

Expand Down
16 changes: 6 additions & 10 deletions src/src.ino
Expand Up @@ -18,7 +18,7 @@
Arduino IDE is supported as before, but stuff was renamed and moved to different folders!
*/

char codeVersion[] = "9.9.0"; // Software revision.
char codeVersion[] = "9.9.1"; // Software revision.

// This stuff is required for Visual Studio Code IDE, if .ino is renamed into .cpp!
#include <Arduino.h>
Expand Down Expand Up @@ -1822,19 +1822,15 @@ void readSbusCommands() {
// Signals are coming in via SBUS protocol

static unsigned long lastSbusFailsafe;
static unsigned long lastSbusRead;

if (millis() - lastSbusRead > 20) { // TODO, test for Flysky SBUS bugfix. 20 is not bad, but still a bit unstable! USE IBUS for Flysky!
// look for a good SBUS packet from the receiver
// look for a good SBUS packet from the receiver
#if not defined EMBEDDED_SBUS // ------------------------
if (sBus.read(&SBUSchannels[0], &SBUSfailSafe, &SBUSlostFrame)) {
if (sBus.read(&SBUSchannels[0], &SBUSfailSafe, &SBUSlostFrame)) {
#else // ------------------------------------------------
if (sBus.read() && !sBus.failsafe() && !sBus.lost_frame()) {
if (sBus.read() && !sBus.failsafe() && !sBus.lost_frame()) {
#endif // -----------------------------------------------
sbusInit = true;
lastSbusFailsafe = millis();
lastSbusRead = millis();
}
sbusInit = true;
lastSbusFailsafe = millis();
}

// Failsafe triggering (works, if SBUS wire is unplugged, but SBUSfailSafe signal from the receiver is untested!)
Expand Down
61 changes: 29 additions & 32 deletions src/src/sbus.cpp
Expand Up @@ -55,26 +55,22 @@ bool SbusRx::read() {
/* Parse new data, if available */
if (new_data_) {
/* Grab the channel data */
ch_[0] = static_cast<int16_t>(buf_[1] | buf_[2] << 8 & 0x07FF);
ch_[1] = static_cast<int16_t>(buf_[2] >> 3 | buf_[3] << 5 & 0x07FF);
ch_[2] = static_cast<int16_t>(buf_[3] >> 6 | buf_[4] << 2 |
buf_[5] << 10 & 0x07FF);
ch_[3] = static_cast<int16_t>(buf_[5] >> 1 | buf_[6] << 7 & 0x07FF);
ch_[4] = static_cast<int16_t>(buf_[6] >> 4 | buf_[7] << 4 & 0x07FF);
ch_[5] = static_cast<int16_t>(buf_[7] >> 7 | buf_[8] << 1 |
buf_[9] << 9 & 0x07FF);
ch_[6] = static_cast<int16_t>(buf_[9] >> 2 | buf_[10] << 6 & 0x07FF);
ch_[7] = static_cast<int16_t>(buf_[10] >> 5 | buf_[11] << 3 & 0x07FF);
ch_[8] = static_cast<int16_t>(buf_[12] | buf_[13] << 8 & 0x07FF);
ch_[9] = static_cast<int16_t>(buf_[13] >> 3 | buf_[14] << 5 & 0x07FF);
ch_[10] = static_cast<int16_t>(buf_[14] >> 6 | buf_[15] << 2 |
buf_[16] << 10 & 0x07FF);
ch_[11] = static_cast<int16_t>(buf_[16] >> 1 | buf_[17] << 7 & 0x07FF);
ch_[12] = static_cast<int16_t>(buf_[17] >> 4 | buf_[18] << 4 & 0x07FF);
ch_[13] = static_cast<int16_t>(buf_[18] >> 7 | buf_[19] << 1 |
buf_[20] << 9 & 0x07FF);
ch_[14] = static_cast<int16_t>(buf_[20] >> 2 | buf_[21] << 6 & 0x07FF);
ch_[15] = static_cast<int16_t>(buf_[21] >> 5 | buf_[22] << 3 & 0x07FF);
ch_[0] = static_cast<uint16_t>(buf_[1] | buf_[2] << 8 & 0x07FF);
ch_[1] = static_cast<uint16_t>(buf_[2] >> 3 | buf_[3] << 5 & 0x07FF);
ch_[2] = static_cast<uint16_t>(buf_[3] >> 6 | buf_[4] << 2 |buf_[5] << 10 & 0x07FF);
ch_[3] = static_cast<uint16_t>(buf_[5] >> 1 | buf_[6] << 7 & 0x07FF);
ch_[4] = static_cast<uint16_t>(buf_[6] >> 4 | buf_[7] << 4 & 0x07FF);
ch_[5] = static_cast<uint16_t>(buf_[7] >> 7 | buf_[8] << 1 |buf_[9] << 9 & 0x07FF);
ch_[6] = static_cast<uint16_t>(buf_[9] >> 2 | buf_[10] << 6 & 0x07FF);
ch_[7] = static_cast<uint16_t>(buf_[10] >> 5 | buf_[11] << 3 & 0x07FF);
ch_[8] = static_cast<uint16_t>(buf_[12] | buf_[13] << 8 & 0x07FF);
ch_[9] = static_cast<uint16_t>(buf_[13] >> 3 | buf_[14] << 5 & 0x07FF);
ch_[10] = static_cast<uint16_t>(buf_[14] >> 6 | buf_[15] << 2 |buf_[16] << 10 & 0x07FF);
ch_[11] = static_cast<uint16_t>(buf_[16] >> 1 | buf_[17] << 7 & 0x07FF);
ch_[12] = static_cast<uint16_t>(buf_[17] >> 4 | buf_[18] << 4 & 0x07FF);
ch_[13] = static_cast<uint16_t>(buf_[18] >> 7 | buf_[19] << 1 |buf_[20] << 9 & 0x07FF);
ch_[14] = static_cast<uint16_t>(buf_[20] >> 2 | buf_[21] << 6 & 0x07FF);
ch_[15] = static_cast<uint16_t>(buf_[21] >> 5 | buf_[22] << 3 & 0x07FF);
/* CH 17 */
ch17_ = buf_[23] & CH17_MASK_;
/* CH 18 */
Expand All @@ -89,23 +85,24 @@ bool SbusRx::read() {

// -----------------------------------------------------------------------------------
bool SbusRx::parse() {
/* Parse messages */
while (uart_->available()) {
/* Parse (analyze) messages */
while (uart_->available() > 0) {
cur_byte_ = uart_->read();
if (state_ == 0) {
if ((cur_byte_ == HEADER_) && ((prev_byte_ == FOOTER_) ||
((prev_byte_ & 0x0F) == FOOTER2_))) {
buf_[state_++] = cur_byte_;
if (state_ == 0) { // First byte -----
if ((cur_byte_ == HEADER_) && ((prev_byte_ == FOOTER_) || ((prev_byte_ & 0x0F) == FOOTER2_))) {
state_++;
_sbusMicros = micros();
} else {
state_ = 0;
state_ = 0; // Go back, if header incorrect
}
} else {
if (state_ < BUF_LEN_) {
} else { // Following bytes (read data) -----
if (state_ < BUF_LEN_ - 1) {
buf_[state_++] = cur_byte_;
} else {
}
// End byte & no timeout -----
if (state_ == BUF_LEN_ - 1) {
state_ = 0;
if ((buf_[BUF_LEN_ - 1] == FOOTER_) ||
((buf_[BUF_LEN_ - 1] & 0x0F) == FOOTER2_)) {
if (((cur_byte_ == FOOTER_) || ((cur_byte_ & 0x0F) == FOOTER2_)) && (micros() - _sbusMicros < SBUS_PACKET_TIMEOUT_US)) {
return true;
} else {
return false;
Expand Down
2 changes: 2 additions & 0 deletions src/src/sbus.h
Expand Up @@ -45,6 +45,7 @@ class SbusRx {
uint32_t BAUD_ = 100000;
/* Message len */
static constexpr int8_t BUF_LEN_ = 25;
static constexpr uint32_t SBUS_PACKET_TIMEOUT_US = 7000; // 3000 is the minimum working, but causing failsafe in noisy vehicles, so 7000 is recommended
/* SBUS message defs */
static constexpr int8_t NUM_SBUS_CH_ = 16;
static constexpr uint8_t HEADER_ = 0x0F;
Expand All @@ -55,6 +56,7 @@ class SbusRx {
static constexpr uint8_t LOST_FRAME_MASK_ = 0x04;
static constexpr uint8_t FAILSAFE_MASK_ = 0x08;
/* Parsing state tracking */
uint32_t _sbusMicros = micros();
int8_t state_ = 0;
uint8_t prev_byte_ = FOOTER_;
uint8_t cur_byte_;
Expand Down

0 comments on commit 3157d09

Please sign in to comment.