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:
Andrew Tridgell 2012-02-14 08:52:35 +11:00
parent 6a42598ade
commit 8d1729b3ba

View File

@ -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,