mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
ACM : removed 2-level DCM gain change - .1 will still be the default.
This commit is contained in:
parent
575a9c4fd1
commit
c81064279a
@ -158,10 +158,6 @@ static void init_arm_motors()
|
|||||||
// temp hack
|
// temp hack
|
||||||
motor_light = true;
|
motor_light = true;
|
||||||
digitalWrite(A_LED_PIN, LED_ON);
|
digitalWrite(A_LED_PIN, LED_ON);
|
||||||
|
|
||||||
// revert back to user default
|
|
||||||
ahrs._kp.load();
|
|
||||||
ahrs._kp_yaw.load();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -177,9 +173,6 @@ static void init_disarm_motors()
|
|||||||
|
|
||||||
g.throttle_cruise.save();
|
g.throttle_cruise.save();
|
||||||
|
|
||||||
ahrs._kp.set(0.8);
|
|
||||||
ahrs._kp_yaw.set(0.8);
|
|
||||||
|
|
||||||
// we are not in the air
|
// we are not in the air
|
||||||
takeoff_complete = false;
|
takeoff_complete = false;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user