Copter: use hal.util soft_armed state
This commit is contained in:
parent
50466848f7
commit
0cc83b1826
@ -1080,7 +1080,7 @@ static void load_parameters(void)
|
||||
}
|
||||
// disable centrifugal force correction, it will be enabled as part of the arming process
|
||||
ahrs.set_correct_centrifugal(false);
|
||||
ahrs.set_armed(false);
|
||||
hal.util->set_soft_armed(false);
|
||||
|
||||
// setup different AHRS gains for ArduCopter than the default
|
||||
// but allow users to override in their config
|
||||
|
@ -171,7 +171,7 @@ static bool init_arm_motors(bool arming_from_gcs)
|
||||
|
||||
// enable gps velocity based centrefugal force compensation
|
||||
ahrs.set_correct_centrifugal(true);
|
||||
ahrs.set_armed(true);
|
||||
hal.util->set_soft_armed(true);
|
||||
|
||||
// set hover throttle
|
||||
motors.set_mid_throttle(g.throttle_mid);
|
||||
@ -713,7 +713,7 @@ static void init_disarm_motors()
|
||||
|
||||
// disable gps velocity based centrefugal force compensation
|
||||
ahrs.set_correct_centrifugal(false);
|
||||
ahrs.set_armed(false);
|
||||
hal.util->set_soft_armed(false);
|
||||
}
|
||||
|
||||
// motors_output - send output to motors library which will adjust and send to ESCs and servos
|
||||
|
Loading…
Reference in New Issue
Block a user