mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Mount: backend calc_angle_to_xxx requires relative_pan argument
This commit is contained in:
parent
3711c362ce
commit
f426711177
@ -166,10 +166,7 @@ float AP_Mount_Backend::angle_input_rad(const RC_Channel* rc, int16_t angle_min,
|
|||||||
return radians(((rc->norm_input_ignore_trim() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min)*0.01f);
|
return radians(((rc->norm_input_ignore_trim() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min)*0.01f);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Mount_Backend::calc_angle_to_roi_target(Vector3f& angles_to_target_rad,
|
bool AP_Mount_Backend::calc_angle_to_roi_target(Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan) const
|
||||||
bool calc_tilt,
|
|
||||||
bool calc_pan,
|
|
||||||
bool relative_pan) const
|
|
||||||
{
|
{
|
||||||
if (!_state._roi_target_set) {
|
if (!_state._roi_target_set) {
|
||||||
return false;
|
return false;
|
||||||
@ -177,10 +174,7 @@ bool AP_Mount_Backend::calc_angle_to_roi_target(Vector3f& angles_to_target_rad,
|
|||||||
return calc_angle_to_location(_state._roi_target, angles_to_target_rad, calc_tilt, calc_pan, relative_pan);
|
return calc_angle_to_location(_state._roi_target, angles_to_target_rad, calc_tilt, calc_pan, relative_pan);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Mount_Backend::calc_angle_to_sysid_target(Vector3f& angles_to_target_rad,
|
bool AP_Mount_Backend::calc_angle_to_sysid_target(Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan) const
|
||||||
bool calc_tilt,
|
|
||||||
bool calc_pan,
|
|
||||||
bool relative_pan) const
|
|
||||||
{
|
{
|
||||||
if (!_state._target_sysid_location_set) {
|
if (!_state._target_sysid_location_set) {
|
||||||
return false;
|
return false;
|
||||||
@ -188,11 +182,7 @@ bool AP_Mount_Backend::calc_angle_to_sysid_target(Vector3f& angles_to_target_rad
|
|||||||
if (!_state._target_sysid) {
|
if (!_state._target_sysid) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return calc_angle_to_location(_state._target_sysid_location,
|
return calc_angle_to_location(_state._target_sysid_location, angles_to_target_rad, calc_tilt, calc_pan, relative_pan);
|
||||||
angles_to_target_rad,
|
|
||||||
calc_tilt,
|
|
||||||
calc_pan,
|
|
||||||
relative_pan);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (in radians) to point at the given target
|
// calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (in radians) to point at the given target
|
||||||
|
@ -98,27 +98,17 @@ protected:
|
|||||||
|
|
||||||
// calc_angle_to_location - calculates the earth-frame roll, tilt
|
// calc_angle_to_location - calculates the earth-frame roll, tilt
|
||||||
// and pan angles (in radians) to point at the given target
|
// and pan angles (in radians) to point at the given target
|
||||||
bool calc_angle_to_location(const struct Location &target,
|
bool calc_angle_to_location(const struct Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan) const WARN_IF_UNUSED;
|
||||||
Vector3f& angles_to_target_rad,
|
|
||||||
bool calc_tilt,
|
|
||||||
bool calc_pan,
|
|
||||||
bool relative_pan = true) const WARN_IF_UNUSED;
|
|
||||||
|
|
||||||
// calc_angle_to_roi_target - calculates the earth-frame roll, tilt
|
// calc_angle_to_roi_target - calculates the earth-frame roll, tilt
|
||||||
// and pan angles (in radians) to point at the ROI-target (as set
|
// and pan angles (in radians) to point at the ROI-target (as set
|
||||||
// by various mavlink messages)
|
// by various mavlink messages)
|
||||||
bool calc_angle_to_roi_target(Vector3f& angles_to_target_rad,
|
bool calc_angle_to_roi_target(Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan) const WARN_IF_UNUSED;
|
||||||
bool calc_tilt,
|
|
||||||
bool calc_pan,
|
|
||||||
bool relative_pan = true) const WARN_IF_UNUSED;
|
|
||||||
|
|
||||||
// calc_angle_to_sysid_target - calculates the earth-frame roll, tilt
|
// calc_angle_to_sysid_target - calculates the earth-frame roll, tilt
|
||||||
// and pan angles (in radians) to point at the sysid-target (as set
|
// and pan angles (in radians) to point at the sysid-target (as set
|
||||||
// by various mavlink messages)
|
// by various mavlink messages)
|
||||||
bool calc_angle_to_sysid_target(Vector3f& angles_to_target_rad,
|
bool calc_angle_to_sysid_target(Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan) const WARN_IF_UNUSED;
|
||||||
bool calc_tilt,
|
|
||||||
bool calc_pan,
|
|
||||||
bool relative_pan = true) const WARN_IF_UNUSED;
|
|
||||||
|
|
||||||
// get the mount mode from frontend
|
// get the mount mode from frontend
|
||||||
MAV_MOUNT_MODE get_mode(void) const { return _frontend.get_mode(_instance); }
|
MAV_MOUNT_MODE get_mode(void) const { return _frontend.get_mode(_instance); }
|
||||||
|
Loading…
Reference in New Issue
Block a user