mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: bug fix to ROI when no camera mount is specific
This commit is contained in:
parent
f88ca4b7e4
commit
9d5d9ce3fc
|
@ -867,7 +867,7 @@ static void do_nav_roi()
|
||||||
#if MOUNT == ENABLED
|
#if 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.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;
|
yaw_tracking = MAV_ROI_LOCATION;
|
||||||
target_WP = command_nav_queue;
|
target_WP = command_nav_queue;
|
||||||
auto_yaw = get_bearing_cd(¤t_loc, &target_WP);
|
auto_yaw = get_bearing_cd(¤t_loc, &target_WP);
|
||||||
|
|
Loading…
Reference in New Issue