AC_PosControl_Sub.h 2.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950
  1. #pragma once
  2. #include "AC_PosControl.h"
  3. class AC_PosControl_Sub : public AC_PosControl {
  4. public:
  5. AC_PosControl_Sub(const AP_AHRS_View & ahrs, const AP_InertialNav& inav,
  6. const AP_Motors& motors, AC_AttitudeControl& attitude_control);
  7. /// set_alt_max - sets maximum altitude above the ekf origin in cm
  8. /// only enforced when set_alt_target_from_climb_rate is used
  9. /// set to zero to disable limit
  10. void set_alt_max(float alt) { _alt_max = alt; }
  11. /// set_alt_min - sets the minimum altitude (maximum depth) in cm
  12. /// only enforced when set_alt_target_from_climb_rate is used
  13. /// set to zero to disable limit
  14. void set_alt_min(float alt) { _alt_min = alt; }
  15. /// set_alt_target_from_climb_rate - adjusts target up or down using a climb rate in cm/s
  16. /// should be called continuously (with dt set to be the expected time between calls)
  17. /// actual position target will be moved no faster than the speed_down and speed_up
  18. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  19. /// set force_descend to true during landing to allow target to move low enough to slow the motors
  20. void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend) override;
  21. /// set_alt_target_from_climb_rate_ff - adjusts target up or down using a climb rate in cm/s using feed-forward
  22. /// should be called continuously (with dt set to be the expected time between calls)
  23. /// actual position target will be moved no faster than the speed_down and speed_up
  24. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  25. /// set force_descend to true during landing to allow target to move low enough to slow the motors
  26. void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend) override;
  27. /// relax_alt_hold_controllers - set all desired and targets to measured
  28. void relax_alt_hold_controllers(float throttle_setting) {
  29. AC_PosControl::relax_alt_hold_controllers(throttle_setting);
  30. }
  31. /// relax_alt_hold_controllers - set all desired and targets to measured
  32. /// integrator is not reset
  33. void relax_alt_hold_controllers();
  34. //void relax_part_hold_controllers();
  35. void reset_I();
  36. float get_alt(){return _inav.get_altitude();};
  37. private:
  38. float _alt_max; // max altitude - should be updated from the main code with altitude limit from fence
  39. float _alt_min; // min altitude - should be updated from the main code with altitude limit from fence
  40. };