mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: SToRM32 provides calc_angle_to_xxx relative_pan argument
This commit is contained in:
parent
57a508b037
commit
5958bced0c
@ -63,7 +63,7 @@ void AP_Mount_SToRM32::update()
|
||||
|
||||
// point mount to a GPS point given by the mission planner
|
||||
case MAV_MOUNT_MODE_GPS_POINT:
|
||||
if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) {
|
||||
if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true, true)) {
|
||||
resend_now = true;
|
||||
}
|
||||
break;
|
||||
@ -75,13 +75,13 @@ void AP_Mount_SToRM32::update()
|
||||
}
|
||||
_state._roi_target = AP::ahrs().get_home();
|
||||
_state._roi_target_set = true;
|
||||
if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) {
|
||||
if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true, true)) {
|
||||
resend_now = true;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_MOUNT_MODE_SYSID_TARGET:
|
||||
if (calc_angle_to_sysid_target(_angle_ef_target_rad, true, true)) {
|
||||
if (calc_angle_to_sysid_target(_angle_ef_target_rad, true, true, true)) {
|
||||
resend_now = true;
|
||||
}
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user