mirror of https://github.com/ArduPilot/ardupilot
zero airspeed on ground start when initiated by MAVLink
If the users asks for a new calibration, that should include the airspeed sensor
This commit is contained in:
parent
2137e91ede
commit
2cc0cd65b4
|
@ -286,20 +286,6 @@ static void startup_ground(void)
|
|||
// ---------------------------
|
||||
trim_radio(); // This was commented out as a HACK. Why? I don't find a problem.
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
if (g.airspeed_enabled == true)
|
||||
{
|
||||
// initialize airspeed sensor
|
||||
// --------------------------
|
||||
zero_airspeed();
|
||||
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> zero airspeed calibrated"));
|
||||
}
|
||||
else
|
||||
{
|
||||
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> NO airspeed"));
|
||||
}
|
||||
#endif
|
||||
|
||||
// Save the settings for in-air restart
|
||||
// ------------------------------------
|
||||
//save_EEPROM_groundstart();
|
||||
|
@ -439,6 +425,15 @@ static void startup_IMU_ground(void)
|
|||
//-----------------------------
|
||||
init_barometer();
|
||||
|
||||
if (g.airspeed_enabled == true) {
|
||||
// initialize airspeed sensor
|
||||
// --------------------------
|
||||
zero_airspeed();
|
||||
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> zero airspeed calibrated"));
|
||||
} else {
|
||||
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> NO airspeed"));
|
||||
}
|
||||
|
||||
#endif // HIL_MODE_ATTITUDE
|
||||
|
||||
digitalWrite(B_LED_PIN, HIGH); // Set LED B high to indicate IMU ready
|
||||
|
|
Loading…
Reference in New Issue