From caa16cbb544686172e87294bb518892c6aeae807 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Jul 2012 10:09:07 +1000 Subject: [PATCH] APM: fixed HIL build --- ArduPlane/GCS_Mavlink.pde | 7 ++++--- ArduPlane/Parameters.pde | 2 ++ 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 3122876f60..fc09eb67d1 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1675,9 +1675,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // rad/sec Vector3f gyros; - gyros.x = (float)packet.xgyro / 1000.0; - gyros.y = (float)packet.ygyro / 1000.0; - gyros.z = (float)packet.zgyro / 1000.0; + gyros.x = packet.rollspeed; + gyros.y = packet.pitchspeed; + gyros.z = packet.yawspeed; + // m/s/s Vector3f accels; accels.x = (float)packet.xacc / 1000.0; diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 7215df53a2..9c43b277cc 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -513,9 +513,11 @@ static const AP_Param::Info var_info[] PROGMEM = { GOBJECT(gcs0, "SR0_", GCS_MAVLINK), GOBJECT(gcs3, "SR3_", GCS_MAVLINK), +#if HIL_MODE == HIL_MODE_DISABLED // @Group: INS_ // @Path: ../libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp GOBJECT(ins, "INS_", AP_InertialSensor_Oilpan), +#endif // @Group: IMU_ // @Path: ../libraries/AP_IMU/IMU.cpp