Skip to content

Commit

Permalink
SITL: Added comment to clarify IMU acceleration value
Browse files Browse the repository at this point in the history
  • Loading branch information
Tuxliri committed Jan 15, 2025
1 parent 4088ab9 commit f313d44
Showing 1 changed file with 6 additions and 0 deletions.
6 changes: 6 additions & 0 deletions libraries/SITL/examples/JSON/C++/minimal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit f313d44

Please sign in to comment.