mirror of https://github.com/ArduPilot/ardupilot
Sub: Disable input hold on disarm
This commit is contained in:
parent
15658f1526
commit
69be1725b6
|
@ -643,6 +643,7 @@ private:
|
|||
void handle_jsbutton_press(uint8_t button,bool shift=false,bool held=false);
|
||||
JSButton* get_button(uint8_t index);
|
||||
void default_js_buttons(void);
|
||||
void clear_input_hold();
|
||||
void init_barometer(bool save);
|
||||
void read_barometer(void);
|
||||
void init_rangefinder(void);
|
||||
|
|
|
@ -550,3 +550,11 @@ void Sub::set_neutral_controls()
|
|||
|
||||
hal.rcin->set_overrides(channels, 10);
|
||||
}
|
||||
|
||||
void Sub::clear_input_hold()
|
||||
{
|
||||
xTrim = 0;
|
||||
yTrim = 0;
|
||||
zTrim = 0;
|
||||
input_hold_engaged = false;
|
||||
}
|
||||
|
|
|
@ -120,6 +120,9 @@ void Sub::init_disarm_motors()
|
|||
// disable gps velocity based centrefugal force compensation
|
||||
ahrs.set_correct_centrifugal(false);
|
||||
hal.util->set_soft_armed(false);
|
||||
|
||||
// clear input holds
|
||||
clear_input_hold();
|
||||
}
|
||||
|
||||
// motors_output - send output to motors library which will adjust and send to ESCs and servos
|
||||
|
|
Loading…
Reference in New Issue