Browse Source

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
master
Andrew Tridgell 13 years ago
parent
commit
8d1729b3ba
  1. 2
      ArduPlane/GCS_Mavlink.pde

2
ArduPlane/GCS_Mavlink.pde

@ -113,7 +113,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan) @@ -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…
Cancel
Save