AP_LandingGear.cpp 8.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267
  1. #include "AP_LandingGear.h"
  2. #include <AP_Relay/AP_Relay.h>
  3. #include <AP_Math/AP_Math.h>
  4. #include <SRV_Channel/SRV_Channel.h>
  5. #include <AP_HAL/AP_HAL.h>
  6. #include <AP_Logger/AP_Logger.h>
  7. #include <GCS_MAVLink/GCS.h>
  8. extern const AP_HAL::HAL& hal;
  9. const AP_Param::GroupInfo AP_LandingGear::var_info[] = {
  10. // 0 and 1 used by previous retract and deploy pwm, now replaced with SERVOn_MIN/MAX/REVERSED
  11. // @Param: STARTUP
  12. // @DisplayName: Landing Gear Startup position
  13. // @Description: Landing Gear Startup behaviour control
  14. // @Values: 0:WaitForPilotInput, 1:Retract, 2:Deploy
  15. // @User: Standard
  16. AP_GROUPINFO("STARTUP", 2, AP_LandingGear, _startup_behaviour, (uint8_t)AP_LandingGear::LandingGear_Startup_WaitForPilotInput),
  17. // @Param: DEPLOY_PIN
  18. // @DisplayName: Chassis deployment feedback pin
  19. // @Description: Pin number to use for detection of gear deployment. If set to -1 feedback is disabled.
  20. // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6
  21. // @User: Standard
  22. // @RebootRequired: True
  23. AP_GROUPINFO("DEPLOY_PIN", 3, AP_LandingGear, _pin_deployed, -1),
  24. // @Param: DEPLOY_POL
  25. // @DisplayName: Chassis deployment feedback pin polarity
  26. // @Description: Polarity for feedback pin. If this is 1 then the pin should be high when gear are deployed. If set to 0 then then deployed gear level is low.
  27. // @Values: 0:Low,1:High
  28. // @User: Standard
  29. AP_GROUPINFO("DEPLOY_POL", 4, AP_LandingGear, _pin_deployed_polarity, 0),
  30. // @Param: WOW_PIN
  31. // @DisplayName: Weight on wheels feedback pin
  32. // @Description: Pin number to use for feedback of weight on wheels condition. If set to -1 feedback is disabled.
  33. // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6
  34. // @User: Standard
  35. // @RebootRequired: True
  36. AP_GROUPINFO("WOW_PIN", 5, AP_LandingGear, _pin_weight_on_wheels, DEFAULT_PIN_WOW),
  37. // @Param: WOW_POL
  38. // @DisplayName: Weight on wheels feedback pin polarity
  39. // @Description: Polarity for feedback pin. If this is 1 then the pin should be high when there is weight on wheels. If set to 0 then then weight on wheels level is low.
  40. // @Values: 0:Low,1:High
  41. // @User: Standard
  42. AP_GROUPINFO("WOW_POL", 6, AP_LandingGear, _pin_weight_on_wheels_polarity, DEFAULT_PIN_WOW_POL),
  43. // @Param: DEPLOY_ALT
  44. // @DisplayName: Landing gear deployment altitude
  45. // @Description: Altitude where the landing gear will be deployed. This should be lower than the RETRACT_ALT. If zero then altitude is not used for deploying landing gear. Only applies when vehicle is armed.
  46. // @Units: m
  47. // @Range: 0 1000
  48. // @Increment: 1
  49. // @User: Standard
  50. AP_GROUPINFO("DEPLOY_ALT", 7, AP_LandingGear, _deploy_alt, 0),
  51. // @Param: RETRACT_ALT
  52. // @DisplayName: Landing gear retract altitude
  53. // @Description: Altitude where the landing gear will be retracted. This should be higher than the DEPLOY_ALT. If zero then altitude is not used for retracting landing gear. Only applies when vehicle is armed.
  54. // @Units: m
  55. // @Range: 0 1000
  56. // @Increment: 1
  57. // @User: Standard
  58. AP_GROUPINFO("RETRACT_ALT", 8, AP_LandingGear, _retract_alt, 0),
  59. AP_GROUPEND
  60. };
  61. AP_LandingGear *AP_LandingGear::_singleton;
  62. /// initialise state of landing gear
  63. void AP_LandingGear::init()
  64. {
  65. if (_pin_deployed != -1) {
  66. hal.gpio->pinMode(_pin_deployed, HAL_GPIO_INPUT);
  67. // set pullup/pulldown to default to non-deployed state
  68. hal.gpio->write(_pin_deployed, !_pin_deployed_polarity);
  69. log_wow_state(wow_state_current);
  70. }
  71. if (_pin_weight_on_wheels != -1) {
  72. hal.gpio->pinMode(_pin_weight_on_wheels, HAL_GPIO_INPUT);
  73. // set pullup/pulldown to default to flying state
  74. hal.gpio->write(_pin_weight_on_wheels, !_pin_weight_on_wheels_polarity);
  75. log_wow_state(wow_state_current);
  76. }
  77. switch ((enum LandingGearStartupBehaviour)_startup_behaviour.get()) {
  78. default:
  79. case LandingGear_Startup_WaitForPilotInput:
  80. // do nothing
  81. break;
  82. case LandingGear_Startup_Retract:
  83. retract();
  84. break;
  85. case LandingGear_Startup_Deploy:
  86. deploy();
  87. break;
  88. }
  89. }
  90. /// set landing gear position to retract, deploy or deploy-and-keep-deployed
  91. void AP_LandingGear::set_position(LandingGearCommand cmd)
  92. {
  93. switch (cmd) {
  94. case LandingGear_Retract:
  95. retract();
  96. break;
  97. case LandingGear_Deploy:
  98. deploy();
  99. break;
  100. }
  101. }
  102. /// deploy - deploy landing gear
  103. void AP_LandingGear::deploy()
  104. {
  105. // set servo PWM to deployed position
  106. SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::SRV_CHANNEL_LIMIT_MAX);
  107. // set deployed flag
  108. _deployed = true;
  109. _have_changed = true;
  110. gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: DEPLOY");
  111. }
  112. /// retract - retract landing gear
  113. void AP_LandingGear::retract()
  114. {
  115. // set servo PWM to retracted position
  116. SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
  117. // reset deployed flag
  118. _deployed = false;
  119. _have_changed = true;
  120. gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: RETRACT");
  121. }
  122. bool AP_LandingGear::deployed()
  123. {
  124. if (_pin_deployed == -1) {
  125. return _deployed;
  126. } else {
  127. return hal.gpio->read(_pin_deployed) == _pin_deployed_polarity ? true : false;
  128. }
  129. }
  130. AP_LandingGear::LG_WOW_State AP_LandingGear::get_wow_state()
  131. {
  132. return wow_state_current;
  133. }
  134. AP_LandingGear::LG_LandingGear_State AP_LandingGear::get_state()
  135. {
  136. return gear_state_current;
  137. }
  138. uint32_t AP_LandingGear::get_gear_state_duration_ms()
  139. {
  140. if (last_gear_event_ms == 0) {
  141. return 0;
  142. }
  143. return AP_HAL::millis() - last_gear_event_ms;
  144. }
  145. uint32_t AP_LandingGear::get_wow_state_duration_ms()
  146. {
  147. if (last_wow_event_ms == 0) {
  148. return 0;
  149. }
  150. return AP_HAL::millis() - last_wow_event_ms;
  151. }
  152. void AP_LandingGear::update(float height_above_ground_m)
  153. {
  154. if (_pin_weight_on_wheels == -1) {
  155. last_wow_event_ms = 0;
  156. wow_state_current = LG_WOW_UNKNOWN;
  157. } else {
  158. LG_WOW_State wow_state_new = hal.gpio->read(_pin_weight_on_wheels) == _pin_weight_on_wheels_polarity ? LG_WOW : LG_NO_WOW;
  159. if (wow_state_new != wow_state_current) {
  160. // we changed states, lets note the time.
  161. last_wow_event_ms = AP_HAL::millis();
  162. log_wow_state(wow_state_new);
  163. }
  164. wow_state_current = wow_state_new;
  165. }
  166. if (_pin_deployed == -1) {
  167. last_gear_event_ms = 0;
  168. // If there was no pilot input and state is still unknown - leave it as it is
  169. if (gear_state_current != LG_UNKNOWN) {
  170. gear_state_current = (_deployed == true ? LG_DEPLOYED : LG_RETRACTED);
  171. }
  172. } else {
  173. LG_LandingGear_State gear_state_new;
  174. if (_deployed) {
  175. gear_state_new = (deployed() == true ? LG_DEPLOYED : LG_DEPLOYING);
  176. } else {
  177. gear_state_new = (deployed() == false ? LG_RETRACTED : LG_RETRACTING);
  178. }
  179. if (gear_state_new != gear_state_current) {
  180. // we changed states, lets note the time.
  181. last_gear_event_ms = AP_HAL::millis();
  182. log_wow_state(wow_state_current);
  183. }
  184. gear_state_current = gear_state_new;
  185. }
  186. /*
  187. check for height based triggering
  188. */
  189. int16_t alt_m = constrain_int16(height_above_ground_m, 0, INT16_MAX);
  190. if (hal.util->get_soft_armed()) {
  191. // only do height based triggering when armed
  192. if ((!_deployed || !_have_changed) &&
  193. _deploy_alt > 0 &&
  194. alt_m <= _deploy_alt &&
  195. _last_height_above_ground > _deploy_alt) {
  196. deploy();
  197. }
  198. if ((_deployed || !_have_changed) &&
  199. _retract_alt > 0 &&
  200. _retract_alt >= _deploy_alt &&
  201. alt_m >= _retract_alt &&
  202. _last_height_above_ground < _retract_alt) {
  203. retract();
  204. }
  205. }
  206. _last_height_above_ground = alt_m;
  207. }
  208. // log weight on wheels state
  209. void AP_LandingGear::log_wow_state(LG_WOW_State state)
  210. {
  211. AP::logger().Write("LGR", "TimeUS,LandingGear,WeightOnWheels", "Qbb",
  212. AP_HAL::micros64(),
  213. (int8_t)gear_state_current, (int8_t)state);
  214. }
  215. bool AP_LandingGear::check_before_land(void)
  216. {
  217. // If the landing gear state is not known (most probably as it is not used)
  218. if (get_state() == LG_UNKNOWN) {
  219. return true;
  220. }
  221. // If the landing gear was not used - return true, otherwise - check for deployed
  222. return (get_state() == LG_DEPLOYED);
  223. }