AP_Mount: set_roi_target and set_target_sysid lose struct and const before args

This commit is contained in:
Randy Mackay 2022-06-20 19:59:02 +09:00
parent 898bdb864c
commit ec07c15e1e
4 changed files with 9 additions and 9 deletions

View File

@ -772,7 +772,7 @@ void AP_Mount::set_target_sysid(uint8_t instance, uint8_t sysid)
}
// set_roi_target - sets target location that mount should attempt to point towards
void AP_Mount::set_roi_target(uint8_t instance, const struct Location &target_loc)
void AP_Mount::set_roi_target(uint8_t instance, const Location &target_loc)
{
// call instance's set_roi_cmd
if (check_instance(instance)) {

View File

@ -128,12 +128,12 @@ public:
void set_angle_targets(uint8_t instance, float roll, float tilt, float pan);
// set_roi_target - sets target location that mount should attempt to point towards
void set_roi_target(const struct Location &target_loc) { set_roi_target(_primary,target_loc); }
void set_roi_target(uint8_t instance, const struct Location &target_loc);
void set_roi_target(const Location &target_loc) { set_roi_target(_primary,target_loc); }
void set_roi_target(uint8_t instance, const Location &target_loc);
// point at system ID sysid
void set_target_sysid(uint8_t instance, const uint8_t sysid);
void set_target_sysid(const uint8_t sysid) { set_target_sysid(_primary, sysid); }
void set_target_sysid(uint8_t sysid) { set_target_sysid(_primary, sysid); }
void set_target_sysid(uint8_t instance, uint8_t sysid);
// mavlink message handling:
MAV_RESULT handle_command_long(const mavlink_command_long_t &packet);

View File

@ -19,7 +19,7 @@ void AP_Mount_Backend::set_angle_targets(float roll, float tilt, float pan)
}
// set_roi_target - sets target location that mount should attempt to point towards
void AP_Mount_Backend::set_roi_target(const struct Location &target_loc)
void AP_Mount_Backend::set_roi_target(const Location &target_loc)
{
// set the target gps location
_state._roi_target = target_loc;
@ -186,7 +186,7 @@ bool AP_Mount_Backend::calc_angle_to_sysid_target(Vector3f& angles_to_target_rad
}
// calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (in radians) to point at the given target
bool AP_Mount_Backend::calc_angle_to_location(const struct Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan) const
bool AP_Mount_Backend::calc_angle_to_location(const Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan) const
{
Location current_loc;
if (!AP::ahrs().get_location(current_loc)) {

View File

@ -56,7 +56,7 @@ public:
void set_angle_targets(float roll, float tilt, float pan);
// set_roi_target - sets target location that mount should attempt to point towards
void set_roi_target(const struct Location &target_loc);
void set_roi_target(const Location &target_loc);
// set_sys_target - sets system that mount should attempt to point towards
void set_target_sysid(uint8_t sysid);
@ -98,7 +98,7 @@ protected:
// calc_angle_to_location - calculates the earth-frame roll, tilt
// and pan angles (in radians) to point at the given 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;
bool calc_angle_to_location(const Location &target, Vector3f& angles_to_target_rad, bool yaw_is_earth_frame) const WARN_IF_UNUSED;
// calc_angle_to_roi_target - calculates the earth-frame roll, tilt
// and pan angles (in radians) to point at the ROI-target (as set