mirror of https://github.com/ArduPilot/ardupilot
Copter: Use AP_Mount::clear_roi_target() to remove ROI
This commit is contained in:
parent
2c6798a540
commit
98dfaba23d
|
@ -154,9 +154,7 @@ void Mode::AutoYaw::set_roi(const Location &roi_location)
|
|||
auto_yaw.set_mode_to_default(false);
|
||||
#if HAL_MOUNT_ENABLED
|
||||
// switch off the camera tracking if enabled
|
||||
if (copter.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
|
||||
copter.camera_mount.set_mode_to_default();
|
||||
}
|
||||
copter.camera_mount.clear_roi_target();
|
||||
#endif // HAL_MOUNT_ENABLED
|
||||
} else {
|
||||
#if HAL_MOUNT_ENABLED
|
||||
|
|
Loading…
Reference in New Issue