Copter: int gyros on arm, not on first boot
this makes first boot much faster
This commit is contained in:
parent
d06d999903
commit
4194b2fdd7
@ -162,7 +162,7 @@ static void init_arm_motors()
|
||||
|
||||
if(did_ground_start == false) {
|
||||
did_ground_start = true;
|
||||
startup_ground();
|
||||
startup_ground(true);
|
||||
}
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
|
@ -253,7 +253,7 @@ static void init_ardupilot()
|
||||
reset_control_switch();
|
||||
init_aux_switches();
|
||||
|
||||
startup_ground();
|
||||
startup_ground(false);
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
Log_Write_Startup();
|
||||
@ -266,7 +266,7 @@ static void init_ardupilot()
|
||||
//******************************************************************************
|
||||
//This function does all the calibrations, etc. that we need during a ground start
|
||||
//******************************************************************************
|
||||
static void startup_ground(void)
|
||||
static void startup_ground(bool force_gyro_cal)
|
||||
{
|
||||
gcs_send_text_P(SEVERITY_LOW,PSTR("GROUND START"));
|
||||
|
||||
@ -275,7 +275,7 @@ static void startup_ground(void)
|
||||
|
||||
// Warm up and read Gyro offsets
|
||||
// -----------------------------
|
||||
ins.init(AP_InertialSensor::COLD_START,
|
||||
ins.init(force_gyro_cal?AP_InertialSensor::COLD_START:AP_InertialSensor::WARM_START,
|
||||
ins_sample_rate);
|
||||
#if CLI_ENABLED == ENABLED
|
||||
report_ins();
|
||||
|
Loading…
Reference in New Issue
Block a user