mirror of https://github.com/ArduPilot/ardupilot
Copter: update brake-timeout to work with master
We added mode-change reasons since PR was submitted
This commit is contained in:
parent
0a2336a5a8
commit
cfb2a6b2f9
|
@ -78,10 +78,9 @@ void Copter::brake_run()
|
|||
pos_control.set_alt_target_from_climb_rate_ff(0.0f, G_Dt, false);
|
||||
pos_control.update_z_controller();
|
||||
|
||||
if (brake_timeout_ms != 0 && millis()-brake_timeout_start >= brake_timeout_ms)
|
||||
{
|
||||
if(!set_mode(LOITER)) {
|
||||
set_mode(ALT_HOLD);
|
||||
if (brake_timeout_ms != 0 && millis()-brake_timeout_start >= brake_timeout_ms) {
|
||||
if (!set_mode(LOITER, MODE_REASON_BRAKE_TIMEOUT)) {
|
||||
set_mode(ALT_HOLD, MODE_REASON_BRAKE_TIMEOUT);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -118,7 +118,8 @@ enum mode_reason_t {
|
|||
MODE_REASON_MISSION_END,
|
||||
MODE_REASON_THROTTLE_LAND_ESCAPE,
|
||||
MODE_REASON_FENCE_BREACH,
|
||||
MODE_REASON_TERRAIN_FAILSAFE
|
||||
MODE_REASON_TERRAIN_FAILSAFE,
|
||||
MODE_REASON_BRAKE_TIMEOUT
|
||||
};
|
||||
|
||||
// Tuning enumeration
|
||||
|
|
Loading…
Reference in New Issue