From a873942f737d79745f0c41e052aea37ceb03bf69 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 9 Jun 2014 12:02:28 -0700 Subject: [PATCH] Fix to restore Gimbal control after Mission with ROI --- ArduCopter/flight_mode.pde | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/flight_mode.pde b/ArduCopter/flight_mode.pde index db2fb54830..2ab6b64cef 100644 --- a/ArduCopter/flight_mode.pde +++ b/ArduCopter/flight_mode.pde @@ -213,6 +213,9 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) if (mission.state() == AP_Mission::MISSION_RUNNING) { mission.stop(); } +#if MOUNT == ENABLED + camera_mount.set_mode_to_default(); +#endif // MOUNT == ENABLED } // smooth throttle transition when switching from manual to automatic flight modes