From 2257009ebaa6300ef082e9616d7fd5c59c846019 Mon Sep 17 00:00:00 2001 From: Davide Iafrate Date: Wed, 15 Jan 2025 11:29:39 +0100 Subject: [PATCH] SITL: Added comment to clarify IMU acceleration value --- libraries/SITL/examples/JSON/C++/minimal.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/SITL/examples/JSON/C++/minimal.cpp b/libraries/SITL/examples/JSON/C++/minimal.cpp index a97f1ab76e9cb9..fb6ff421ae581f 100644 --- a/libraries/SITL/examples/JSON/C++/minimal.cpp +++ b/libraries/SITL/examples/JSON/C++/minimal.cpp @@ -67,6 +67,12 @@ int main() { ap.setWindvane(1 , 1); ap.setRangefinder(rangefinder_example, 6); + /* + When the drone is on a surface the accelerometer of the imu senses the counteracting + force of the flat surface pushing up against gravity, thus an upward acceleration + of 9.81 m/s^2. In the FRD body reference frame (z-axis pointing down) this is an + acceleration of -9.81 m/s^2. + */ // send with the required ap.SendState(timestamp, 0, 0, 0, // gyro