mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Mavlink: report the corrected pitch via MAVLink
this subtracts the TRIM_PITCH_CD from the pitch reported via MAVLink. That gives a better indication of the true pitch in the tlog
This commit is contained in:
parent
a1c041b597
commit
3907cf81f8
@ -113,7 +113,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
|
||||
chan,
|
||||
micros(),
|
||||
dcm.roll,
|
||||
dcm.pitch,
|
||||
dcm.pitch - radians(g.pitch_trim*0.01),
|
||||
dcm.yaw,
|
||||
omega.x,
|
||||
omega.y,
|
||||
|
Loading…
Reference in New Issue
Block a user