Browse Source

Copter: send extended status to GCS only after initialisation

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
bf18fb896a
  1. 1
      ArduCopter/ArduCopter.pde
  2. 12
      ArduCopter/GCS_Mavlink.pde
  3. 3
      ArduCopter/system.pde

1
ArduCopter/ArduCopter.pde

@ -388,6 +388,7 @@ static union { @@ -388,6 +388,7 @@ static union {
uint8_t rc_receiver_present : 1; // 14 // true if we have an rc receiver present (i.e. if we've ever received an update
uint8_t compass_mot : 1; // 15 // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // 16 // true if we are currently performing the motors test
uint8_t initialised : 1; // 17 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
};
uint32_t value;
} ap;

12
ArduCopter/GCS_Mavlink.pde

@ -481,10 +481,14 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) @@ -481,10 +481,14 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
break;
case MSG_EXTENDED_STATUS1:
CHECK_PAYLOAD_SIZE(SYS_STATUS);
send_extended_status1(chan);
CHECK_PAYLOAD_SIZE(POWER_STATUS);
gcs[chan-MAVLINK_COMM_0].send_power_status();
// send extended status only once vehicle has been initialised
// to avoid unnecessary errors being reported to user
if (ap.initialised) {
CHECK_PAYLOAD_SIZE(SYS_STATUS);
send_extended_status1(chan);
CHECK_PAYLOAD_SIZE(POWER_STATUS);
gcs[chan-MAVLINK_COMM_0].send_power_status();
}
break;
case MSG_EXTENDED_STATUS2:

3
ArduCopter/system.pde

@ -295,6 +295,9 @@ static void init_ardupilot() @@ -295,6 +295,9 @@ static void init_ardupilot()
}
cliSerial->print_P(PSTR("\nReady to FLY "));
// flag that initialisation has completed
ap.initialised = true;
}

Loading…
Cancel
Save