diff --git a/.markdownlint.json b/.markdownlint.json
index 753942e..f98602c 100644
--- a/.markdownlint.json
+++ b/.markdownlint.json
@@ -65,5 +65,6 @@
"PX4"
]
},
- "MD045": false
+ "MD045": false,
+ "MD060": false
}
diff --git a/docs/img/imu-axes.png b/docs/img/imu-axes.png
new file mode 100644
index 0000000..003f03a
Binary files /dev/null and b/docs/img/imu-axes.png differ
diff --git a/docs/img/imu-rot-1.png b/docs/img/imu-rot-1.png
new file mode 100644
index 0000000..55981b3
Binary files /dev/null and b/docs/img/imu-rot-1.png differ
diff --git a/docs/img/imu-rot-2.png b/docs/img/imu-rot-2.png
new file mode 100644
index 0000000..91f2978
Binary files /dev/null and b/docs/img/imu-rot-2.png differ
diff --git a/docs/img/imu-rot-3.png b/docs/img/imu-rot-3.png
new file mode 100644
index 0000000..80165bf
Binary files /dev/null and b/docs/img/imu-rot-3.png differ
diff --git a/docs/img/imu-rot-4.png b/docs/img/imu-rot-4.png
new file mode 100644
index 0000000..f9c4d09
Binary files /dev/null and b/docs/img/imu-rot-4.png differ
diff --git a/docs/img/imu-rot-5.png b/docs/img/imu-rot-5.png
new file mode 100644
index 0000000..76e71e3
Binary files /dev/null and b/docs/img/imu-rot-5.png differ
diff --git a/docs/img/imu-rot-6.png b/docs/img/imu-rot-6.png
new file mode 100644
index 0000000..22b4399
Binary files /dev/null and b/docs/img/imu-rot-6.png differ
diff --git a/docs/img/imu-rot-7.png b/docs/img/imu-rot-7.png
new file mode 100644
index 0000000..df80a7e
Binary files /dev/null and b/docs/img/imu-rot-7.png differ
diff --git a/docs/img/imu-rot-8.png b/docs/img/imu-rot-8.png
new file mode 100644
index 0000000..f8a44ce
Binary files /dev/null and b/docs/img/imu-rot-8.png differ
diff --git a/docs/usage.md b/docs/usage.md
index 327bbbe..17fbe2b 100644
--- a/docs/usage.md
+++ b/docs/usage.md
@@ -73,14 +73,6 @@ ICM20948 imu(SPI); // For ICM-20948
MPU6050 imu(Wire); // For MPU-6050
```
-### Setup the IMU orientation
-
-The IMU orientation is defined in `rotateIMU` function in the `imu.ino` file. Change it so it converts the IMU axes to the drone's axes correctly. **Drone axes are X forward, Y left, Z up**:
-
-
-
-See various [IMU boards axes orientations table](https://github.com/okalachev/flixperiph/?tab=readme-ov-file#imu-axes-orientation) to help you set up the correct orientation.
-
### Connect using QGroundControl
QGroundControl is a ground control station software that can be used to monitor and control the drone.
@@ -88,7 +80,7 @@ QGroundControl is a ground control station software that can be used to monitor
1. Install mobile or desktop version of [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html).
2. Power up the drone.
3. Connect your computer or smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
-4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically
+4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
### Access console
@@ -104,11 +96,35 @@ To access the console using QGroundControl:
1. Connect to the drone using QGroundControl app.
2. Go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*.
-
+
+
> [!TIP]
> Use `help` command to see the list of available commands.
+### Access parameters
+
+The drone is configured using parameters. To access and modify them, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*:
+
+
+
+### Define IMU orientation
+
+Use parameters, to define the IMU board axes orientation relative to the drone's axes: `IMU_ROT_ROLL`, `IMU_ROT_PITCH`, and `IMU_ROT_YAW`.
+
+The drone has *X* axis pointing forward, *Y* axis pointing left, and *Z* axis pointing up, and the supported IMU boards have *X* axis pointing to the pins side and *Z* axis pointing up from the component side:
+
+
+
+Use the following table to set the parameters for common IMU orientations:
+
+|Orientation|Parameters|Orientation|Parameters|
+|:-:|-|-|-|
+|
|`IMU_ROT_ROLL` = 0
`IMU_ROT_PITCH` = 0
`IMU_ROT_YAW` = 0 |
|`IMU_ROT_ROLL` = 3.142
`IMU_ROT_PITCH` = 0
`IMU_ROT_YAW` = 0|
+|
|`IMU_ROT_ROLL` = 0
`IMU_ROT_PITCH` = 0
`IMU_ROT_YAW` = 1.571|
|`IMU_ROT_ROLL` = 3.142
`IMU_ROT_PITCH` = 0
`IMU_ROT_YAW` = -1.571|
+|
|`IMU_ROT_ROLL` = 0
`IMU_ROT_PITCH` = 0
`IMU_ROT_YAW` = 3.142|
|`IMU_ROT_ROLL` = 3.142
`IMU_ROT_PITCH` = 0
`IMU_ROT_YAW` = 3.142|
+|
☑️ **Default**|
`IMU_ROT_ROLL` = 0
`IMU_ROT_PITCH` = 0
`IMU_ROT_YAW` = -1.571|
|`IMU_ROT_ROLL` = 3.142
`IMU_ROT_PITCH` = 0
`IMU_ROT_YAW` = 1.571|
+
### Calibrate accelerometer
Before flight you need to calibrate the accelerometer:
@@ -225,12 +241,6 @@ In this mode, the pilot inputs are ignored (except the mode switch, if configure
If the pilot moves the control sticks, the drone will switch back to *STAB* mode.
-## Adjusting parameters
-
-You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*.
-
-
-
## Flight log
After the flight, you can download the flight log for analysis wirelessly. Use the following for that:
diff --git a/flix/imu.ino b/flix/imu.ino
index 67b26eb..7c482f1 100644
--- a/flix/imu.ino
+++ b/flix/imu.ino
@@ -10,6 +10,7 @@
#include "util.h"
MPU9250 imu(SPI);
+Vector imuRotation(0, 0, -PI / 2); // imu orientation as Euler angles
Vector accBias;
Vector accScale(1, 1, 1);
@@ -37,16 +38,10 @@ void readIMU() {
// apply scale and bias
acc = (acc - accBias) / accScale;
gyro = gyro - gyroBias;
- // rotate
- rotateIMU(acc);
- rotateIMU(gyro);
-}
-
-void rotateIMU(Vector& data) {
- // Rotate from LFD to FLU
- // NOTE: In case of using other IMU orientation, change this line:
- data = Vector(data.y, data.x, -data.z);
- // Axes orientation for various boards: https://github.com/okalachev/flixperiph#imu-axes-orientation
+ // rotate to body frame
+ Quaternion rotation = Quaternion::fromEuler(imuRotation);
+ acc = Quaternion::rotateVector(acc, rotation.inversed());
+ gyro = Quaternion::rotateVector(gyro, rotation.inversed());
}
void calibrateGyroOnce() {
diff --git a/flix/parameters.ino b/flix/parameters.ino
index 0738f12..3d7bfdd 100644
--- a/flix/parameters.ino
+++ b/flix/parameters.ino
@@ -43,6 +43,9 @@ Parameter parameters[] = {
{"CTL_Y_RATE_MAX", &maxRate.z},
{"CTL_TILT_MAX", &tiltMax},
// imu
+ {"IMU_ROT_ROLL", &imuRotation.x},
+ {"IMU_ROT_PITCH", &imuRotation.y},
+ {"IMU_ROT_YAW", &imuRotation.z},
{"IMU_ACC_BIAS_X", &accBias.x},
{"IMU_ACC_BIAS_Y", &accBias.y},
{"IMU_ACC_BIAS_Z", &accBias.z},
diff --git a/gazebo/flix.h b/gazebo/flix.h
index be6c750..e7d3a2c 100644
--- a/gazebo/flix.h
+++ b/gazebo/flix.h
@@ -22,6 +22,7 @@ Vector gyro;
Vector rates;
Quaternion attitude;
bool landed;
+Vector imuRotation;
// declarations
void step();