AP_Parachute.cpp 5.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174
  1. #include "AP_Parachute.h"
  2. #include <AP_Relay/AP_Relay.h>
  3. #include <AP_Math/AP_Math.h>
  4. #include <RC_Channel/RC_Channel.h>
  5. #include <SRV_Channel/SRV_Channel.h>
  6. #include <AP_Notify/AP_Notify.h>
  7. #include <AP_HAL/AP_HAL.h>
  8. #include <AP_Logger/AP_Logger.h>
  9. #include <GCS_MAVLink/GCS.h>
  10. extern const AP_HAL::HAL& hal;
  11. const AP_Param::GroupInfo AP_Parachute::var_info[] = {
  12. // @Param: ENABLED
  13. // @DisplayName: Parachute release enabled or disabled
  14. // @Description: Parachute release enabled or disabled
  15. // @Values: 0:Disabled,1:Enabled
  16. // @User: Standard
  17. AP_GROUPINFO_FLAGS("ENABLED", 0, AP_Parachute, _enabled, 0, AP_PARAM_FLAG_ENABLE),
  18. // @Param: TYPE
  19. // @DisplayName: Parachute release mechanism type (relay or servo)
  20. // @Description: Parachute release mechanism type (relay or servo)
  21. // @Values: 0:First Relay,1:Second Relay,2:Third Relay,3:Fourth Relay,10:Servo
  22. // @User: Standard
  23. AP_GROUPINFO("TYPE", 1, AP_Parachute, _release_type, AP_PARACHUTE_TRIGGER_TYPE_RELAY_0),
  24. // @Param: SERVO_ON
  25. // @DisplayName: Parachute Servo ON PWM value
  26. // @Description: Parachute Servo PWM value in microseconds when parachute is released
  27. // @Range: 1000 2000
  28. // @Units: PWM
  29. // @Increment: 1
  30. // @User: Standard
  31. AP_GROUPINFO("SERVO_ON", 2, AP_Parachute, _servo_on_pwm, AP_PARACHUTE_SERVO_ON_PWM_DEFAULT),
  32. // @Param: SERVO_OFF
  33. // @DisplayName: Servo OFF PWM value
  34. // @Description: Parachute Servo PWM value in microseconds when parachute is not released
  35. // @Range: 1000 2000
  36. // @Units: PWM
  37. // @Increment: 1
  38. // @User: Standard
  39. AP_GROUPINFO("SERVO_OFF", 3, AP_Parachute, _servo_off_pwm, AP_PARACHUTE_SERVO_OFF_PWM_DEFAULT),
  40. // @Param: ALT_MIN
  41. // @DisplayName: Parachute min altitude in meters above home
  42. // @Description: Parachute min altitude above home. Parachute will not be released below this altitude. 0 to disable alt check.
  43. // @Range: 0 32000
  44. // @Units: m
  45. // @Increment: 1
  46. // @User: Standard
  47. AP_GROUPINFO("ALT_MIN", 4, AP_Parachute, _alt_min, AP_PARACHUTE_ALT_MIN_DEFAULT),
  48. // @Param: DELAY_MS
  49. // @DisplayName: Parachute release delay
  50. // @Description: Delay in millseconds between motor stop and chute release
  51. // @Range: 0 5000
  52. // @Units: ms
  53. // @Increment: 1
  54. // @User: Standard
  55. AP_GROUPINFO("DELAY_MS", 5, AP_Parachute, _delay_ms, AP_PARACHUTE_RELEASE_DELAY_MS),
  56. // @Param: CRT_SINK
  57. // @DisplayName: Critical sink speed rate in m/s to trigger emergency parachute
  58. // @Description: Release parachute when critical sink rate is reached
  59. // @Range: 0 15
  60. // @Units: m/s
  61. // @Increment: 1
  62. // @User: Standard
  63. AP_GROUPINFO("CRT_SINK", 6, AP_Parachute, _critical_sink, AP_PARACHUTE_CRITICAL_SINK_DEFAULT),
  64. AP_GROUPEND
  65. };
  66. /// enabled - enable or disable parachute release
  67. void AP_Parachute::enabled(bool on_off)
  68. {
  69. _enabled = on_off;
  70. // clear release_time
  71. _release_time = 0;
  72. AP::logger().Write_Event(_enabled ? DATA_PARACHUTE_ENABLED : DATA_PARACHUTE_DISABLED);
  73. }
  74. /// release - release parachute
  75. void AP_Parachute::release()
  76. {
  77. // exit immediately if not enabled
  78. if (_enabled <= 0) {
  79. return;
  80. }
  81. gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Released");
  82. AP::logger().Write_Event(DATA_PARACHUTE_RELEASED);
  83. // set release time to current system time
  84. if (_release_time == 0) {
  85. _release_time = AP_HAL::millis();
  86. }
  87. _release_initiated = true;
  88. // update AP_Notify
  89. AP_Notify::flags.parachute_release = 1;
  90. }
  91. /// update - shuts off the trigger should be called at about 10hz
  92. void AP_Parachute::update()
  93. {
  94. // exit immediately if not enabled or parachute not to be released
  95. if (_enabled <= 0) {
  96. return;
  97. }
  98. // check if the plane is sinking too fast for more than a second and release parachute
  99. uint32_t time = AP_HAL::millis();
  100. if((_critical_sink > 0) && (_sink_rate > _critical_sink) && !_release_initiated && _is_flying) {
  101. if(_sink_time == 0) {
  102. _sink_time = AP_HAL::millis();
  103. }
  104. if((time - _sink_time) >= 1000) {
  105. release();
  106. }
  107. } else {
  108. _sink_time = 0;
  109. }
  110. // calc time since release
  111. uint32_t time_diff = AP_HAL::millis() - _release_time;
  112. uint32_t delay_ms = _delay_ms<=0 ? 0: (uint32_t)_delay_ms;
  113. // check if we should release parachute
  114. if ((_release_time != 0) && !_release_in_progress) {
  115. if (time_diff >= delay_ms) {
  116. if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
  117. // move servo
  118. SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_on_pwm);
  119. }else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
  120. // set relay
  121. _relay.on(_release_type);
  122. }
  123. _release_in_progress = true;
  124. _released = true;
  125. }
  126. }else if ((_release_time == 0) || time_diff >= delay_ms + AP_PARACHUTE_RELEASE_DURATION_MS) {
  127. if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
  128. // move servo back to off position
  129. SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_off_pwm);
  130. }else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
  131. // set relay back to zero volts
  132. _relay.off(_release_type);
  133. }
  134. // reset released flag and release_time
  135. _release_in_progress = false;
  136. _release_time = 0;
  137. // update AP_Notify
  138. AP_Notify::flags.parachute_release = 0;
  139. }
  140. }
  141. // singleton instance
  142. AP_Parachute *AP_Parachute::_singleton;
  143. namespace AP {
  144. AP_Parachute *parachute()
  145. {
  146. return AP_Parachute::get_singleton();
  147. }
  148. }