From cfb2a6b2f9e4f84b01ce5ec55b21984e2387bba2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 13 May 2016 11:39:37 +0900 Subject: [PATCH] Copter: update brake-timeout to work with master We added mode-change reasons since PR was submitted --- ArduCopter/control_brake.cpp | 7 +++---- ArduCopter/defines.h | 3 ++- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduCopter/control_brake.cpp b/ArduCopter/control_brake.cpp index 02ef385049..01d01c65a6 100644 --- a/ArduCopter/control_brake.cpp +++ b/ArduCopter/control_brake.cpp @@ -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); } } } diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 6354205f11..2d460b0a2a 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -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