Plane: fix for new compass API
This commit is contained in:
parent
56f44266d8
commit
e362b4fc04
@ -1534,7 +1534,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
ins.set_accel(0, accels);
|
ins.set_accel(0, accels);
|
||||||
|
|
||||||
barometer.setHIL(packet.alt*0.001f);
|
barometer.setHIL(packet.alt*0.001f);
|
||||||
compass.setHIL(packet.roll, packet.pitch, packet.yaw);
|
compass.setHIL(0, packet.roll, packet.pitch, packet.yaw);
|
||||||
|
compass.setHIL(1, packet.roll, packet.pitch, packet.yaw);
|
||||||
|
|
||||||
// cope with DCM getting badly off due to HIL lag
|
// cope with DCM getting badly off due to HIL lag
|
||||||
if (g.hil_err_limit > 0 &&
|
if (g.hil_err_limit > 0 &&
|
||||||
|
Loading…
Reference in New Issue
Block a user