Skip to content

Commit 1c070c2

Browse files
committed
Fix to restore Gimbal control after Mission with ROI
1 parent 2ba1a1a commit 1c070c2

File tree

1 file changed

+4
-0
lines changed

1 file changed

+4
-0
lines changed

ArduCopter/flight_mode.pde

+4
Original file line numberDiff line numberDiff line change
@@ -213,6 +213,10 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
213213
if (mission.state() == AP_Mission::MISSION_RUNNING) {
214214
mission.stop();
215215
}
216+
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
217+
#if MOUNT == ENABLED
218+
camera_mount.set_mode_to_default();
219+
#endif // MOUNT == ENABLED
216220
}
217221

218222
// smooth throttle transition when switching from manual to automatic flight modes

0 commit comments

Comments
 (0)