AP_LandingGear.h 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122
  1. /// @file AP_LandingGear.h
  2. /// @brief Landing gear control library
  3. #pragma once
  4. #include <AP_Param/AP_Param.h>
  5. #include <AP_Common/AP_Common.h>
  6. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  7. #define DEFAULT_PIN_WOW 8
  8. #define DEFAULT_PIN_WOW_POL 1
  9. #else
  10. #define DEFAULT_PIN_WOW -1
  11. #define DEFAULT_PIN_WOW_POL 0
  12. #endif
  13. /// @class AP_LandingGear
  14. /// @brief Class managing the control of landing gear
  15. class AP_LandingGear {
  16. public:
  17. AP_LandingGear() {
  18. // setup parameter defaults
  19. AP_Param::setup_object_defaults(this, var_info);
  20. if (_singleton != nullptr) {
  21. AP_HAL::panic("AP_LandingGear must be singleton");
  22. }
  23. _singleton = this;
  24. }
  25. /* Do not allow copies */
  26. AP_LandingGear(const AP_LandingGear &other) = delete;
  27. AP_LandingGear &operator=(const AP_LandingGear&) = delete;
  28. // get singleton instance
  29. static AP_LandingGear *get_singleton(void) {
  30. return _singleton;
  31. }
  32. // Gear command modes
  33. enum LandingGearCommand {
  34. LandingGear_Retract,
  35. LandingGear_Deploy,
  36. };
  37. // Gear command modes
  38. enum LandingGearStartupBehaviour {
  39. LandingGear_Startup_WaitForPilotInput = 0,
  40. LandingGear_Startup_Retract = 1,
  41. LandingGear_Startup_Deploy = 2,
  42. };
  43. /// initialise state of landing gear
  44. void init();
  45. /// returns true if the landing gear is deployed
  46. bool deployed();
  47. enum LG_LandingGear_State {
  48. LG_UNKNOWN = -1,
  49. LG_RETRACTED = 0,
  50. LG_DEPLOYED = 1,
  51. LG_RETRACTING = 2,
  52. LG_DEPLOYING = 3,
  53. };
  54. /// returns detailed state of gear
  55. LG_LandingGear_State get_state();
  56. enum LG_WOW_State {
  57. LG_WOW_UNKNOWN = -1,
  58. LG_NO_WOW = 0,
  59. LG_WOW = 1,
  60. };
  61. LG_WOW_State get_wow_state();
  62. /// set landing gear position to retract, deploy or deploy-and-keep-deployed
  63. void set_position(LandingGearCommand cmd);
  64. uint32_t get_gear_state_duration_ms();
  65. uint32_t get_wow_state_duration_ms();
  66. static const struct AP_Param::GroupInfo var_info[];
  67. void update(float height_above_ground_m);
  68. bool check_before_land(void);
  69. private:
  70. // Parameters
  71. AP_Int8 _startup_behaviour; // start-up behaviour (see LandingGearStartupBehaviour)
  72. AP_Int8 _pin_deployed;
  73. AP_Int8 _pin_deployed_polarity;
  74. AP_Int8 _pin_weight_on_wheels;
  75. AP_Int8 _pin_weight_on_wheels_polarity;
  76. AP_Int16 _deploy_alt;
  77. AP_Int16 _retract_alt;
  78. // internal variables
  79. bool _deployed; // true if the landing gear has been deployed, initialized false
  80. bool _have_changed; // have we changed the servo state?
  81. int16_t _last_height_above_ground;
  82. // debounce
  83. LG_WOW_State wow_state_current = LG_WOW_UNKNOWN;
  84. uint32_t last_wow_event_ms;
  85. LG_LandingGear_State gear_state_current = LG_UNKNOWN;
  86. uint32_t last_gear_event_ms;
  87. /// retract - retract landing gear
  88. void retract();
  89. /// deploy - deploy the landing gear
  90. void deploy();
  91. // log weight on wheels state
  92. void log_wow_state(LG_WOW_State state);
  93. static AP_LandingGear *_singleton;
  94. };