mirror of https://github.com/ArduPilot/ardupilot
Copter: set the ahrs.set_armed() flag
This commit is contained in:
parent
33851030a4
commit
a45d77f893
|
@ -1050,6 +1050,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);
|
||||
|
||||
// setup different AHRS gains for ArduCopter than the default
|
||||
// but allow users to override in their config
|
||||
|
|
|
@ -172,6 +172,7 @@ static void init_arm_motors()
|
|||
|
||||
// enable gps velocity based centrefugal force compensation
|
||||
ahrs.set_correct_centrifugal(true);
|
||||
ahrs.set_armed(true);
|
||||
|
||||
// set hover throttle
|
||||
motors.set_mid_throttle(g.throttle_mid);
|
||||
|
@ -527,6 +528,7 @@ static void init_disarm_motors()
|
|||
|
||||
// disable gps velocity based centrefugal force compensation
|
||||
ahrs.set_correct_centrifugal(false);
|
||||
ahrs.set_armed(false);
|
||||
}
|
||||
|
||||
/*****************************************
|
||||
|
|
Loading…
Reference in New Issue