Browse Source

ArduCopter: bug fix to ROI when no camera mount is specific

mission-4.1.18
rmackay9 13 years ago
parent
commit
3c9ba94f42
  1. 2
      ArduCopter/commands_logic.pde

2
ArduCopter/commands_logic.pde

@ -867,7 +867,7 @@ static void do_nav_roi() @@ -867,7 +867,7 @@ static void do_nav_roi()
#if MOUNT == ENABLED
// check if mount type requires us to rotate the quad
if( camera_mount.get_mount_type() == AP_Mount::k_tilt_roll ) {
if( camera_mount.get_mount_type() != AP_Mount::k_pan_tilt && camera_mount.get_mount_type() != AP_Mount::k_pan_tilt_roll ) {
yaw_tracking = MAV_ROI_LOCATION;
target_WP = command_nav_queue;
auto_yaw = get_bearing_cd(&current_loc, &target_WP);

Loading…
Cancel
Save