AP_Mount: In Servo backend, add overrides for has_roll_control() and has_tilt_control()

This commit is contained in:
Nick Exton 2024-05-16 12:09:37 +10:00 committed by Randy Mackay
parent 0e090faf05
commit e17439287b
2 changed files with 18 additions and 0 deletions

View File

@ -119,6 +119,18 @@ void AP_Mount_Servo::update()
move_servo(_pan_idx, degrees(_angle_bf_output_rad.z)*10, _params.yaw_angle_min*10, _params.yaw_angle_max*10);
}
// returns true if this mount can control its roll
bool AP_Mount_Servo::has_roll_control() const
{
return SRV_Channels::function_assigned(_roll_idx) && roll_range_valid();
}
// returns true if this mount can control its tilt
bool AP_Mount_Servo::has_pitch_control() const
{
return SRV_Channels::function_assigned(_tilt_idx) && pitch_range_valid();
}
// returns true if this mount can control its pan (required for multicopters)
bool AP_Mount_Servo::has_pan_control() const
{

View File

@ -31,6 +31,12 @@ public:
// update mount position - should be called periodically
void update() override;
// returns true if this mount can control its roll
bool has_roll_control() const override;
// returns true if this mount can control its tilt
bool has_pitch_control() const override;
// returns true if this mount can control its pan (required for multicopters)
bool has_pan_control() const override;