@ -536,14 +536,14 @@ void Sub::set_auto_yaw_roi(const Location &roi_location)
if ( roi_location . alt = = 0 & & roi_location . lat = = 0 & & roi_location . lng = = 0 ) {
if ( roi_location . alt = = 0 & & roi_location . lat = = 0 & & roi_location . lng = = 0 ) {
// set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
// set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
# if MOUNT == ENABLED
# if HAL_MOUNT_ ENABLED
// switch off the camera tracking if enabled
// switch off the camera tracking if enabled
if ( camera_mount . get_mode ( ) = = MAV_MOUNT_MODE_GPS_POINT ) {
if ( camera_mount . get_mode ( ) = = MAV_MOUNT_MODE_GPS_POINT ) {
camera_mount . set_mode_to_default ( ) ;
camera_mount . set_mode_to_default ( ) ;
}
}
# endif // MOUNT == ENABLED
# endif // HAL_MOUNT_ ENABLED
} else {
} else {
# if MOUNT == ENABLED
# if HAL_MOUNT_ ENABLED
// check if mount type requires us to rotate the quad
// check if mount type requires us to rotate the quad
if ( ! camera_mount . has_pan_control ( ) ) {
if ( ! camera_mount . has_pan_control ( ) ) {
roi_WP = pv_location_to_vector ( roi_location ) ;
roi_WP = pv_location_to_vector ( roi_location ) ;
@ -562,7 +562,7 @@ void Sub::set_auto_yaw_roi(const Location &roi_location)
// if we have no camera mount aim the quad at the location
// if we have no camera mount aim the quad at the location
roi_WP = pv_location_to_vector ( roi_location ) ;
roi_WP = pv_location_to_vector ( roi_location ) ;
set_auto_yaw_mode ( AUTO_YAW_ROI ) ;
set_auto_yaw_mode ( AUTO_YAW_ROI ) ;
# endif // MOUNT == ENABLED
# endif // HAL_MOUNT_ ENABLED
}
}
}
}