mirror of https://github.com/ArduPilot/ardupilot
Hack to prevent fly aways
Cleanup to remove SIMPLE mode switch note
This commit is contained in:
parent
c01361a79d
commit
4efbae4a1c
|
@ -121,8 +121,8 @@ get_nav_throttle(int32_t z_error)
|
|||
{
|
||||
int16_t rate_error;
|
||||
|
||||
float dt = (abs(z_error) < 400) ? .1 : 0.0;
|
||||
//float dt = .1;
|
||||
// XXX HACK, need a better way not to ramp this i term in large altitude changes.
|
||||
float dt = (abs(z_error) < 400) ? .1 : 0.01;
|
||||
|
||||
// limit error to prevent I term run up
|
||||
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
|
||||
|
|
|
@ -51,9 +51,6 @@ static void read_trim_switch()
|
|||
do_flip = true;
|
||||
}
|
||||
|
||||
#elif CH7_OPTION == CH7_SIMPLE_MODE
|
||||
//Serial.println(g.rc_7.control_in, DEC);
|
||||
|
||||
#elif CH7_OPTION == CH7_SET_HOVER
|
||||
// switch is engaged
|
||||
if (g.rc_7.control_in > 800){
|
||||
|
|
Loading…
Reference in New Issue