12345678910111213141516171819202122232425262728293031323334353637383940414243444546 |
- #pragma once
- #include "AC_PosControl.h"
- class AC_PosControl_Sub : public AC_PosControl {
- public:
- AC_PosControl_Sub(const AP_AHRS_View & ahrs, const AP_InertialNav& inav,
- const AP_Motors& motors, AC_AttitudeControl& attitude_control);
-
-
-
- void set_alt_max(float alt) { _alt_max = alt; }
-
-
-
- void set_alt_min(float alt) { _alt_min = alt; }
-
-
-
-
-
- void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend) override;
-
-
-
-
-
- void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend) override;
-
- void relax_alt_hold_controllers(float throttle_setting) {
- AC_PosControl::relax_alt_hold_controllers(throttle_setting);
- }
-
-
- void relax_alt_hold_controllers();
- private:
- float _alt_max;
- float _alt_min;
- };
|