Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Mount: privatise various fields and methods #28755

Merged
merged 2 commits into from
Dec 16, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
37 changes: 20 additions & 17 deletions libraries/AP_Mount/AP_Mount_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -271,26 +271,10 @@ class AP_Mount_Backend
// returns true if mavlink heartbeat should be suppressed for this gimbal (only used by Solo gimbal)
virtual bool suppress_heartbeat() const { return false; }

#if AP_MOUNT_POI_TO_LATLONALT_ENABLED
// calculate the Location that the gimbal is pointing at
void calculate_poi();
#endif

// change to RC_TARGETTING mode if rc inputs have changed by more than the dead zone
// should be called on every update
void set_rctargeting_on_rcinput_change();

// get pilot input (in the range -1 to +1) received through RC
void get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const;

// get angle or rate targets from pilot RC
// target_type will be either ANGLE or RATE, rpy will be the target angle in deg or rate in deg/s
void get_rc_target(MountTargetType& target_type, MountTarget& rpy) const;

// get angle targets (in radians) to a Location
// returns true on success, false on failure
bool get_angle_target_to_location(const Location &loc, MountTarget& angle_rad) const WARN_IF_UNUSED;

// get angle targets (in radians) to ROI location
// returns true on success, false on failure
bool get_angle_target_to_roi(MountTarget& angle_rad) const WARN_IF_UNUSED;
Expand Down Expand Up @@ -319,7 +303,6 @@ class AP_Mount_Backend
uint8_t _instance; // this instance's number

MAV_MOUNT_MODE _mode; // current mode (see MAV_MOUNT_MODE enum)
bool _yaw_lock; // yaw_lock used in RC_TARGETING mode. True if the gimbal's yaw target is maintained in earth-frame, if false (aka "follow") it is maintained in body-frame

// structure for MAVLink Targeting angle and rate targets
struct {
Expand All @@ -328,6 +311,26 @@ class AP_Mount_Backend
MountTarget rate_rads; // rate target in rad/s
} mnt_target;

private:

// get pilot input (in the range -1 to +1) received through RC
void get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const;

// get angle or rate targets from pilot RC
// target_type will be either ANGLE or RATE, rpy will be the target angle in deg or rate in deg/s
void get_rc_target(MountTargetType& target_type, MountTarget& rpy) const;

// get angle targets (in radians) to a Location
// returns true on success, false on failure
bool get_angle_target_to_location(const Location &loc, MountTarget& angle_rad) const WARN_IF_UNUSED;

#if AP_MOUNT_POI_TO_LATLONALT_ENABLED
// calculate the Location that the gimbal is pointing at
void calculate_poi();
#endif

bool _yaw_lock; // yaw_lock used in RC_TARGETING mode. True if the gimbal's yaw target is maintained in earth-frame, if false (aka "follow") it is maintained in body-frame

#if AP_MOUNT_POI_TO_LATLONALT_ENABLED
struct {
HAL_Semaphore sem; // semaphore protecting this structure
Expand Down
Loading