mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
AP_Mount: Solo provides calc_angle_to_xxx relative_pan argument
This commit is contained in:
parent
3c501bb408
commit
57a508b037
@ -69,7 +69,7 @@ void AP_Mount_SoloGimbal::update()
|
|||||||
// point mount to a GPS point given by the mission planner
|
// point mount to a GPS point given by the mission planner
|
||||||
case MAV_MOUNT_MODE_GPS_POINT:
|
case MAV_MOUNT_MODE_GPS_POINT:
|
||||||
_gimbal.set_lockedToBody(false);
|
_gimbal.set_lockedToBody(false);
|
||||||
UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true));
|
UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true, true));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_MOUNT_MODE_HOME_LOCATION:
|
case MAV_MOUNT_MODE_HOME_LOCATION:
|
||||||
@ -80,11 +80,11 @@ void AP_Mount_SoloGimbal::update()
|
|||||||
_state._roi_target = AP::ahrs().get_home();
|
_state._roi_target = AP::ahrs().get_home();
|
||||||
_state._roi_target_set = true;
|
_state._roi_target_set = true;
|
||||||
_gimbal.set_lockedToBody(false);
|
_gimbal.set_lockedToBody(false);
|
||||||
UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true));
|
UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true, true));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_MOUNT_MODE_SYSID_TARGET:
|
case MAV_MOUNT_MODE_SYSID_TARGET:
|
||||||
UNUSED_RESULT(calc_angle_to_sysid_target(_angle_ef_target_rad, true, true));
|
UNUSED_RESULT(calc_angle_to_sysid_target(_angle_ef_target_rad, true, true, true));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
|
Loading…
Reference in New Issue
Block a user