diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json index 0b17403..cadd43e 100644 --- a/.vscode/c_cpp_properties.json +++ b/.vscode/c_cpp_properties.json @@ -5,18 +5,18 @@ "includePath": [ "${workspaceFolder}/flix", "${workspaceFolder}/gazebo", - "~/.arduino15/packages/esp32/hardware/esp32/3.0.5/cores/esp32", - "~/.arduino15/packages/esp32/hardware/esp32/3.0.5/libraries/**", - "~/.arduino15/packages/esp32/hardware/esp32/3.0.5/variants/d1_mini32", - "~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-33fbade6/esp32/**", - "~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-33fbade6/esp32/dio_qspi/include", + "~/.arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32", + "~/.arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**", + "~/.arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32", + "~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/**", + "~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include", "~/Arduino/libraries/**", "/usr/include/**" ], "forcedInclude": [ "${workspaceFolder}/.vscode/intellisense.h", - "~/.arduino15/packages/esp32/hardware/esp32/3.0.5/cores/esp32/Arduino.h", - "~/.arduino15/packages/esp32/hardware/esp32/3.0.5/variants/d1_mini32/pins_arduino.h", + "~/.arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32/Arduino.h", + "~/.arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h", "${workspaceFolder}/flix/cli.ino", "${workspaceFolder}/flix/control.ino", "${workspaceFolder}/flix/estimate.ino", @@ -52,18 +52,18 @@ "includePath": [ "${workspaceFolder}/flix", "${workspaceFolder}/gazebo", - "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.5/cores/esp32", - "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.5/libraries/**", - "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.5/variants/d1_mini32", - "~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-33fbade6/esp32/include/**", - "~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-33fbade6/esp32/dio_qspi/include", + "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32", + "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**", + "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32", + "~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/include/**", + "~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include", "~/Documents/Arduino/libraries/**", "/opt/homebrew/include/**" ], "forcedInclude": [ "${workspaceFolder}/.vscode/intellisense.h", - "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.5/cores/esp32/Arduino.h", - "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.5/variants/d1_mini32/pins_arduino.h", + "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32/Arduino.h", + "~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h", "${workspaceFolder}/flix/flix.ino", "${workspaceFolder}/flix/cli.ino", "${workspaceFolder}/flix/control.ino", @@ -100,17 +100,17 @@ "includePath": [ "${workspaceFolder}/flix", "${workspaceFolder}/gazebo", - "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.5/cores/esp32", - "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.5/libraries/**", - "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.5/variants/d1_mini32", - "~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-33fbade6/esp32/**", - "~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-33fbade6/esp32/dio_qspi/include", + "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32", + "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**", + "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32", + "~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/**", + "~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include", "~/Documents/Arduino/libraries/**" ], "forcedInclude": [ "${workspaceFolder}/.vscode/intellisense.h", - "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.5/cores/esp32/Arduino.h", - "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.5/variants/d1_mini32/pins_arduino.h", + "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32/Arduino.h", + "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h", "${workspaceFolder}/flix/cli.ino", "${workspaceFolder}/flix/control.ino", "${workspaceFolder}/flix/estimate.ino", diff --git a/Makefile b/Makefile index 5a6fa86..0da2e4f 100644 --- a/Makefile +++ b/Makefile @@ -13,10 +13,10 @@ monitor: dependencies .dependencies: arduino-cli core update-index --config-file arduino-cli.yaml - arduino-cli core install esp32:esp32@3.0.5 --config-file arduino-cli.yaml + arduino-cli core install esp32:esp32@3.0.7 --config-file arduino-cli.yaml arduino-cli lib update-index arduino-cli lib install "FlixPeriph" - arduino-cli lib install "MAVLink"@2.0.11 + arduino-cli lib install "MAVLink"@2.0.12 touch .dependencies gazebo/build cmake: gazebo/CMakeLists.txt diff --git a/README.md b/README.md index 79ad9d0..f30d670 100644 --- a/README.md +++ b/README.md @@ -53,7 +53,7 @@ See [instructions on running the simulation](docs/build.md). |Type|Part|Image|Quantity| |-|-|:-:|:-:| |Microcontroller board|ESP32 Mini||1| -|IMU and barometer² board|GY-91 (or other MPU-9250/MPU-6500 board)||1| +|IMU (and barometer²) board|GY‑91 (or other MPU‑9250/MPU‑6500 board), ICM‑20948³||1| |Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)||4| |Propeller|Hubsan 55 mm||4| |MOSFET (transistor)|100N03A or [analog](https://t.me/opensourcequadcopter/33)||4| @@ -62,16 +62,18 @@ See [instructions on running the simulation](docs/build.md). |Li-Po Battery charger|Any||1| |Screws for IMU board mounting|M3x5||2| |Screws for frame assembly|M1.4x5||4| -|Frame bottom part|3D printed:
[`flix-frame.stl`](docs/assets/flix-frame.stl) [`flix-frame.step`](docs/assets/flix-frame.step)||1| +|Frame bottom part|3D printed⁴:
[`flix-frame.stl`](docs/assets/flix-frame.stl) [`flix-frame.step`](docs/assets/flix-frame.step)||1| |Frame top part|3D printed:
[`esp32-holder.stl`](docs/assets/esp32-holder.stl) [`esp32-holder.step`](docs/assets/esp32-holder.step)||1| |Washer for IMU board mounting|3D printed:
[`washer-m3.stl`](docs/assets/washer-m3.stl) [`washer-m3.step`](docs/assets/washer-m3.step)||1| -|*RC transmitter (optional)*|*KINGKONG TINY X8 or other³*||1| -|*RC receiver (optional)*|*DF500 or other³*||1| +|*RC transmitter (optional)*|*KINGKONG TINY X8 or other⁵*||1| +|*RC receiver (optional)*|*DF500 or other⁵*||1| |Wires|28 AWG recommended||| |Tape, double-sided tape|||| *² — barometer is not used for now.*
-*³ — you may use any transmitter-receiver pair with SBUS interface.* +*³ — change `MPU9250` to `ICM20948` in `imu.ino` file if using ICM-20948 board.*
+*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*
+*⁵ — you may use any transmitter-receiver pair with SBUS interface.* Tools required for assembly: @@ -98,9 +100,9 @@ Complete diagram is Work-in-Progress. ### Notes * Power ESP32 Mini with Li-Po battery using VCC (+) and GND (-) pins. -* Connect the GY-91 board to the ESP32 Mini using VSPI, power it using 3.3V and GND pins: +* Connect the IMU board to the ESP32 Mini using VSPI, power it using 3.3V and GND pins: - |GY-91 pin|ESP32 pin| + |IMU pin|ESP32 pin| |-|-| |GND|GND| |3.3V|3.3V| @@ -127,9 +129,19 @@ Complete diagram is Work-in-Progress. |-|-| |GND|GND| |VIN|VC (or 3.3V depending on the receiver)| - |Signal|GPIO4⁴| + |Signal|GPIO4⁶| -*⁴ — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.* +*⁶ — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.* + +### IMU placement + +Required IMU orientation on the drone is **FLU** (Forward, Left, Up)⁷: + +GY-91 axis + +In case of using **FRD** orientation (Forward, Right, Down), use [the code for rotation](https://gist.github.com/okalachev/713db47e31bce643dbbc9539d166ce98). + +*⁷ — This X/Y/Z IMU axis orientation is used in the Flix IMU library, internal accel/gyro/mag axes differ.* ## Version 0 diff --git a/docs/build.md b/docs/build.md index 924beb2..e3a4f9c 100644 --- a/docs/build.md +++ b/docs/build.md @@ -9,7 +9,9 @@ cd flix ## Simulation -### Ubuntu +### Ubuntu 20.04 + +The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you have a newer version, consider using a virtual machine. 1. Install Arduino CLI: @@ -104,10 +106,10 @@ cd flix ### Arduino IDE (Windows, Linux, macOS) 1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended). -2. Install ESP32 core, version 3.0.5 (version 2.x is not supported). See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE. +2. Install ESP32 core, version 3.0.7 (version 2.x is not supported). See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE. 3. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library): * `FlixPeriph`, the latest version. - * `MAVLink`, version 2.0.11. + * `MAVLink`, version 2.0.12. 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). 5. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE. 6. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE. diff --git a/docs/img/flu.svg b/docs/img/flu.svg new file mode 100644 index 0000000..2ff7d41 --- /dev/null +++ b/docs/img/flu.svg @@ -0,0 +1,81 @@ + + + + + + + + + + + + + + + + + + + + + + + + + X/Forward + Y/Left + Z/Up + + diff --git a/docs/img/icm-20948.jpg b/docs/img/icm-20948.jpg new file mode 100644 index 0000000..5e6af23 Binary files /dev/null and b/docs/img/icm-20948.jpg differ diff --git a/docs/troubleshooting.md b/docs/troubleshooting.md index 25f130c..106bcd5 100644 --- a/docs/troubleshooting.md +++ b/docs/troubleshooting.md @@ -13,7 +13,14 @@ Do the following: * **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V. * **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 output. +* **Make sure correct IMU model is chosen**. If using ICM-20948 board, change `MPU9250` to `ICM20948` everywhere in the `imu.ino` file. * **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. +* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**. +* **Make sure you're not moving the drone several seconds after the power on**. The drone calibrates its gyroscope on the start so it should stay still for a while. +* **Check the IMU sample rate**. Perform `imu` command. The `rate` field should be about 1000 (Hz). +* **Check the IMU data**. Perform `imu` command, check raw accelerometer and gyro output. The output should change as you move the drone. +* **Calibrate the accelerometer.** if is wasn't done before. Perform `ca` command and put the results to `imu.ino` file. +* **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. * **Check the motors**. Perform the following commands using Serial Monitor: * `mfr` — should rotate front right motor (counter-clockwise). * `mfl` — should rotate front left motor (clockwise). @@ -21,11 +28,5 @@ Do the following: * `mrr` — should rotate rear right motor (clockwise). * **Calibrate the RC** if you use it. Perform `rc` command and put the results to `rc.ino` file. * **Check the RC data** if you use it. Use `rc` command, `Control` should show correct values between -1 and 1, and between 0 and 1 for the throttle. -* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**. -* **Make sure you're not moving the drone several seconds after the power on**. The drone calibrates its gyroscope on the start so it should stay still for a while. -* **Check the IMU frequency**. Perform `imu` command. The `frequency` field should be about 1000 (Hz). -* **Check the IMU data**. Perform `imu` command, check raw accelerometer and gyro output. The output should change as you move the drone. -* **Calibrate the accelerometer.** if is wasn't done before. Perform `ca` command and put the results to `imu.ino` file. -* **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. * **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement. * **Check the gyroscope only attitude estimation**. Comment out `applyAcc();` line in `estimate.ino` and check if the attitude estimation in QGroundControl. It should be stable, but only drift very slowly. diff --git a/flix/cli.ino b/flix/cli.ino index f414967..824d8b3 100644 --- a/flix/cli.ino +++ b/flix/cli.ino @@ -30,8 +30,7 @@ const char* motd = "cr - calibrate RC\n" "cg - calibrate gyro\n" "ca - calibrate accel\n" -"mfr, mfl, mrr, mrl - test appropriate motor\n" -"fullmot - full motor test\n" +"mfr, mfl, mrr, mrl - test motor\n" "reset - reset drone's state\n"; const struct Param { @@ -54,7 +53,7 @@ const struct Param { {"lpr", &ratesFilter.alpha, nullptr}, {"lpd", &rollRatePID.lpf.alpha, &pitchRatePID.lpf.alpha}, - {"ss", &loopFreq, nullptr}, + {"ss", &loopRate, nullptr}, {"dt", &dt, nullptr}, {"t", &t, nullptr}, }; @@ -74,7 +73,7 @@ void doCommand(String& command, String& value) { Serial.printf("gyro: %f %f %f\n", rates.x, rates.y, rates.z); Serial.printf("acc: %f %f %f\n", acc.x, acc.y, acc.z); printIMUCal(); - Serial.printf("frequency: %f\n", loopFreq); + Serial.printf("rate: %f\n", loopRate); } else if (command == "rc") { Serial.printf("Raw: throttle %d yaw %d pitch %d roll %d armed %d mode %d\n", channels[RC_CHANNEL_THROTTLE], channels[RC_CHANNEL_YAW], channels[RC_CHANNEL_PITCH], @@ -102,8 +101,6 @@ void doCommand(String& command, String& value) { cliTestMotor(MOTOR_REAR_RIGHT); } else if (command == "mrl") { cliTestMotor(MOTOR_REAR_LEFT); - } else if (command == "fullmot") { - fullMotorTest(value.toInt()); } else if (command == "reset") { attitude = Quaternion(); } else { @@ -135,8 +132,9 @@ void showTable() { void cliTestMotor(uint8_t n) { Serial.printf("Testing motor %d\n", n); motors[n] = 1; + delay(50); // ESP32 may need to wait until the end of the current cycle to change duty https://github.com/espressif/arduino-esp32/issues/5306 sendMotors(); - delay(5000); + delay(3000); motors[n] = 0; sendMotors(); Serial.println("Done"); diff --git a/flix/flix.ino b/flix/flix.ino index 8183e55..dea10d9 100644 --- a/flix/flix.ino +++ b/flix/flix.ino @@ -25,7 +25,7 @@ float t = NAN; // current step time, s float dt; // time delta from previous step, s -float loopFreq; // loop frequency, Hz +float loopRate; // loop rate, Hz int16_t channels[RC_CHANNELS]; // raw rc channels float controls[RC_CHANNELS]; // normalized controls in range [-1..1] ([0..1] for throttle) float controlsTime; // time of the last controls update diff --git a/flix/imu.ino b/flix/imu.ino index 4fb4c34..9f29767 100644 --- a/flix/imu.ino +++ b/flix/imu.ino @@ -27,14 +27,15 @@ void setupIMU() { delay(1000); } } + configureIMU(); calibrateGyro(); } void configureIMU() { IMU.setAccelRange(IMU.ACCEL_RANGE_4G); IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS); - IMU.setDlpfBandwidth(IMU.DLPF_BANDWIDTH_184HZ); - IMU.setSrd(0); // set sample rate to 1000 Hz + IMU.setDLPF(IMU.DLPF_MAX); + IMU.setRate(IMU.RATE_1KHZ_APPROX); } void readIMU() { @@ -66,8 +67,6 @@ void calibrateGyro() { void calibrateAccel() { Serial.println("Calibrating accelerometer"); IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode - IMU.setDlpfBandwidth(IMU.DLPF_BANDWIDTH_20HZ); - IMU.setSrd(19); Serial.setTimeout(60000); Serial.print("Place level [enter] "); Serial.readStringUntil('\n'); @@ -88,7 +87,7 @@ void calibrateAccel() { } void calibrateAccelOnce() { - const int samples = 100; + const int samples = 1000; static Vector accMax(-INFINITY, -INFINITY, -INFINITY); static Vector accMin(INFINITY, INFINITY, INFINITY); @@ -124,6 +123,6 @@ void printIMUCal() { } void printIMUInfo() { - Serial.printf("type: %s\n", IMU.getType()); + Serial.printf("model: %s\n", IMU.getModel()); Serial.printf("who am I: 0x%02X\n", IMU.whoAmI()); } diff --git a/flix/motors.ino b/flix/motors.ino index d2d14bd..0c17cd1 100644 --- a/flix/motors.ino +++ b/flix/motors.ino @@ -37,14 +37,3 @@ void sendMotors() { ledcWrite(MOTOR_2_PIN, signalToDutyCycle(motors[2])); ledcWrite(MOTOR_3_PIN, signalToDutyCycle(motors[3])); } - -void fullMotorTest(int n) { - printf("Full test for motor %d\n", n); - for (float signal = 0; signal <= 1; signal += 0.1) { - printf("Motor %d: %f\n", n, signal); - ledcWrite(n, signalToDutyCycle(signal)); - delay(3000); - } - printf("Motor %d: %f\n", n, 0); - ledcWrite(n, signalToDutyCycle(0)); -} diff --git a/flix/rc.ino b/flix/rc.ino index adc723a..7af6e25 100644 --- a/flix/rc.ino +++ b/flix/rc.ino @@ -9,7 +9,7 @@ int channelNeutral[] = {995, 883, 200, 972, 512, 512, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; int channelMax[] = {1651, 1540, 1713, 1630, 1472, 1472, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; -SBUS RC(Serial2, 16, 17); // NOTE: remove pin numbers (16, 17) if you use the new default pins for Serial2 (4, 25) +SBUS RC(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins void setupRC() { Serial.println("Setup RC"); diff --git a/flix/time.ino b/flix/time.ino index 4632bfb..da9f1c8 100644 --- a/flix/time.ino +++ b/flix/time.ino @@ -12,16 +12,16 @@ void step() { dt = 0; // assume dt to be zero on first step and on reset } - computeLoopFreq(); + computeLoopRate(); } -void computeLoopFreq() { +void computeLoopRate() { static float windowStart = 0; - static uint32_t freq = 0; - freq++; + static uint32_t rate = 0; + rate++; if (t - windowStart >= 1) { // 1 second window - loopFreq = freq; + loopRate = rate; windowStart = t; - freq = 0; + rate = 0; } } diff --git a/flix/util.ino b/flix/util.ino index 3976783..b5373d1 100644 --- a/flix/util.ino +++ b/flix/util.ino @@ -15,14 +15,6 @@ float mapff(float x, float in_min, float in_max, float out_min, float out_max) { return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; } -int8_t sign(float x) { - return (x > 0) - (x < 0); -} - -float randomFloat(float min, float max) { - return min + (max - min) * (float)rand() / RAND_MAX; -} - // Wrap angle to [-PI, PI) float wrapAngle(float angle) { angle = fmodf(angle, 2 * PI); diff --git a/gazebo/flix.h b/gazebo/flix.h index bc15f94..72787f5 100644 --- a/gazebo/flix.h +++ b/gazebo/flix.h @@ -21,7 +21,7 @@ float t = NAN; float dt; -float loopFreq; +float loopRate; float motors[4]; int16_t channels[16]; // raw rc channels float controls[RC_CHANNELS]; @@ -32,7 +32,7 @@ Vector rates; Quaternion attitude; // declarations -void computeLoopFreq(); +void computeLoopRate(); void applyGyro(); void applyAcc(); void control(); @@ -57,7 +57,6 @@ inline Quaternion FLU2FRD(const Quaternion &q); void setLED(bool on) {}; void calibrateGyro() { printf("Skip gyro calibrating\n"); }; void calibrateAccel() { printf("Skip accel calibrating\n"); }; -void fullMotorTest(int n) { printf("Skip full motor test\n"); }; void sendMotors() {}; void printIMUCal() { printf("cal: N/A\n"); }; void printIMUInfo() {};