mirror of https://github.com/ArduPilot/ardupilot
ACM: Altitude Adjust
This commit is contained in:
parent
98cc65862d
commit
9d64bea2ef
|
@ -1834,6 +1834,7 @@ void update_throttle_mode(void)
|
||||||
|
|
||||||
case THROTTLE_HOLD:
|
case THROTTLE_HOLD:
|
||||||
// allow interactive changing of atitude
|
// allow interactive changing of atitude
|
||||||
|
/*
|
||||||
if(g.rc_3.control_in < 200) {
|
if(g.rc_3.control_in < 200) {
|
||||||
reset_throttle_counter = 150;
|
reset_throttle_counter = 150;
|
||||||
nav_throttle = get_throttle_rate(-120);
|
nav_throttle = get_throttle_rate(-120);
|
||||||
|
@ -1845,6 +1846,22 @@ void update_throttle_mode(void)
|
||||||
g.rc_3.servo_out = g.throttle_cruise + nav_throttle + angle_boost;
|
g.rc_3.servo_out = g.throttle_cruise + nav_throttle + angle_boost;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
|
if(g.rc_3.radio_in < (g.rc_3.radio_min + 200)){
|
||||||
|
int16_t _rate = 120 - (((g.rc_3.radio_in - g.rc_3.radio_min) * 12) / 20);
|
||||||
|
reset_throttle_counter = 150;
|
||||||
|
nav_throttle = get_throttle_rate(-_rate);
|
||||||
|
g.rc_3.servo_out = g.throttle_cruise + nav_throttle + angle_boost;
|
||||||
|
break;
|
||||||
|
}else if(g.rc_3.radio_in > (g.rc_3.radio_max - 200)){
|
||||||
|
int16_t _rate = 180 - ((g.rc_3.radio_max - g.rc_3.radio_in) * 18) / 20;
|
||||||
|
reset_throttle_counter = 150;
|
||||||
|
nav_throttle = get_throttle_rate(_rate);
|
||||||
|
g.rc_3.servo_out = g.throttle_cruise + nav_throttle + angle_boost;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// allow 1 second of slow down after pilot moves throttle back into deadzone
|
// allow 1 second of slow down after pilot moves throttle back into deadzone
|
||||||
if(reset_throttle_counter > 0) {
|
if(reset_throttle_counter > 0) {
|
||||||
|
|
Loading…
Reference in New Issue