mirror of https://github.com/ArduPilot/ardupilot
Copter: when arming set home to current loc only if not locked
This commit is contained in:
parent
9e156d2f81
commit
e7579198c9
|
@ -140,12 +140,11 @@ static bool init_arm_motors(bool arming_from_gcs)
|
|||
|
||||
initial_armed_bearing = ahrs.yaw_sensor;
|
||||
|
||||
// Reset home position
|
||||
// -------------------
|
||||
if (ap.home_is_set) {
|
||||
init_home();
|
||||
calc_distance_and_bearing();
|
||||
// Reset home position if it has already been set before (but not locked)
|
||||
if (ap.home_state == HOME_SET_NOT_LOCKED) {
|
||||
set_home_to_current_location();
|
||||
}
|
||||
calc_distance_and_bearing();
|
||||
|
||||
if(did_ground_start == false) {
|
||||
startup_ground(true);
|
||||
|
|
Loading…
Reference in New Issue