Browse Source

Plane: fixed mavlink levelling

this was broken by a recent commit (after 2.72 was released)
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
5ba171af9a
  1. 2
      ArduPlane/GCS_Mavlink.pde
  2. 2
      ArduPlane/setup.pde
  3. 8
      ArduPlane/system.pde

2
ArduPlane/GCS_Mavlink.pde

@ -1136,7 +1136,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1136,7 +1136,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1 ||
packet.param2 == 1) {
startup_INS_ground();
startup_INS_ground(true);
} else if (packet.param3 == 1) {
init_barometer();
if (airspeed.enabled()) {

2
ArduPlane/setup.pde

@ -376,7 +376,7 @@ setup_erase(uint8_t argc, const Menu::arg *argv) @@ -376,7 +376,7 @@ setup_erase(uint8_t argc, const Menu::arg *argv)
static int8_t
setup_level(uint8_t argc, const Menu::arg *argv)
{
startup_INS_ground();
startup_INS_ground(true);
return 0;
}

8
ArduPlane/system.pde

@ -281,7 +281,7 @@ static void startup_ground(void) @@ -281,7 +281,7 @@ static void startup_ground(void)
//INS ground start
//------------------------
//
startup_INS_ground();
startup_INS_ground(false);
// read the radio to set trims
// ---------------------------
@ -427,7 +427,7 @@ static void check_short_failsafe() @@ -427,7 +427,7 @@ static void check_short_failsafe()
}
static void startup_INS_ground(void)
static void startup_INS_ground(bool do_accel_init)
{
#if HIL_MODE != HIL_MODE_DISABLED
while (!barometer.healthy) {
@ -453,6 +453,10 @@ static void startup_INS_ground(void) @@ -453,6 +453,10 @@ static void startup_INS_ground(void)
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
flash_leds);
if (do_accel_init) {
ins.init_accel(flash_leds);
ahrs.set_trim(Vector3f(0, 0, 0));
}
ahrs.reset();
// read Baro pressure at ground

Loading…
Cancel
Save