Browse Source

APM: fixed HIL build

mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
3c2fc72654
  1. 7
      ArduPlane/GCS_Mavlink.pde
  2. 2
      ArduPlane/Parameters.pde

7
ArduPlane/GCS_Mavlink.pde

@ -1675,9 +1675,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -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;

2
ArduPlane/Parameters.pde

@ -513,9 +513,11 @@ static const AP_Param::Info var_info[] PROGMEM = { @@ -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

Loading…
Cancel
Save