Skip to content

Commit

Permalink
Update SBUS library version to 8.1.4
Browse files Browse the repository at this point in the history
  • Loading branch information
okalachev committed Mar 6, 2024
1 parent aeec8e3 commit 9c53e24
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 11 deletions.
2 changes: 1 addition & 1 deletion Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ dependencies .dependencies:
arduino-cli core update-index --config-file arduino-cli.yaml
arduino-cli core install esp32:[email protected] --config-file arduino-cli.yaml
arduino-cli lib update-index
arduino-cli lib install "Bolder Flight Systems SBUS"@1.0.1
arduino-cli lib install "Bolder Flight Systems SBUS"@8.1.4
arduino-cli lib install "Bolder Flight Systems MPU9250"@1.0.2
arduino-cli lib install "MAVLink"@2.0.1
touch .dependencies
Expand Down
2 changes: 1 addition & 1 deletion docs/build.md
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ Use USB remote control or QGroundControl mobile app (with *Virtual Joystick* set
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
2. Install ESP32 core using [Boards Manager](https://docs.arduino.cc/learn/starting-guide/cores).
3. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library) (**versions are significant**):
* `Bolder Flight Systems SBUS`, version 1.0.1.
* `Bolder Flight Systems SBUS`, version 8.1.4.
* `Bolder Flight Systems MPU9250`, version 1.0.2.
* `MAVLink`, version 2.0.1.
4. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
Expand Down
2 changes: 1 addition & 1 deletion flix/flix.ino
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
float t = NAN; // current step time, s
float dt; // time delta from previous step, s
float loopFreq; // loop frequency, Hz
uint16_t channels[16]; // raw rc channels
int16_t channels[16]; // raw rc channels
float controls[RC_CHANNELS]; // normalized controls in range [-1..1] ([0..1] for throttle)
Vector rates; // angular rates, rad/s
Vector acc; // accelerometer data, m/s/s
Expand Down
16 changes: 8 additions & 8 deletions flix/rc.ino
Original file line number Diff line number Diff line change
Expand Up @@ -3,25 +3,25 @@

// Work with the RC receiver

#include <SBUS.h>
#include <sbus.h>

// NOTE: use `cr` command and replace with the actual values
int channelNeutral[] = {995, 883, 200, 972, 512, 512};
int channelMax[] = {1651, 1540, 1713, 1630, 1472, 1472};

SBUS RC(Serial2);
bfs::SbusRx RC(&Serial2, 16, 17, true);

void setupRC() {
Serial.println("Setup RC");
RC.begin();
Serial2.setRxInvert(true); // SBUS uses inverted signal
RC.Begin();
}

void readRC() {
bool failsafe, lostFrame;
if (RC.read(channels, &failsafe, &lostFrame)) {
if (failsafe) { return; } // TODO:
if (lostFrame) { return; }
if (RC.Read()) {
bfs::SbusData data = RC.data();
for (int i = 0; i < RC_CHANNELS; i++) {
channels[i] = data.ch[i];
}
normalizeRC();
}
}
Expand Down

0 comments on commit 9c53e24

Please sign in to comment.