SIM_Parachute.cpp 2.1 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. simple parachute simulator class
  15. */
  16. #include "SIM_Parachute.h"
  17. #include "AP_HAL/AP_HAL.h"
  18. #include <AP_Math/AP_Math.h>
  19. #include <GCS_MAVLink/GCS.h>
  20. using namespace SITL;
  21. // table of user settable parameters
  22. const AP_Param::GroupInfo Parachute::var_info[] = {
  23. // @Param: ENABLE
  24. // @DisplayName: Gripper servo Sim enable/disable
  25. // @Description: Allows you to enable (1) or disable (0) the gripper servo simulation
  26. // @Values: 0:Disabled,1:Enabled
  27. // @User: Advanced
  28. AP_GROUPINFO("ENABLE", 0, Parachute, parachute_enable, 0),
  29. // @Param: PIN
  30. // @DisplayName: Parachute pin
  31. // @Description: The pin number that the Parachute pyrotechnics are connected to. (start at 1)
  32. // @Range: 0 15
  33. // @User: Advanced
  34. AP_GROUPINFO("PIN", 1, Parachute, parachute_pin, -1),
  35. AP_GROUPEND
  36. };
  37. /*
  38. update parachute state
  39. */
  40. void Parachute::update(const struct sitl_input &input)
  41. {
  42. const int16_t pwm = parachute_pin >= 1 ? input.servos[parachute_pin-1] : -1;
  43. const uint64_t now = AP_HAL::micros64();
  44. // const float dt = (now - last_update_us) * 1.0e-6f;
  45. if (pwm >= 1250) {
  46. if (!deployed_ms) {
  47. deployed_ms = AP_HAL::millis();
  48. gcs().send_text(MAV_SEVERITY_WARNING, "BANG! Parachute deployed");
  49. }
  50. }
  51. last_update_us = now;
  52. }
  53. bool Parachute::should_report()
  54. {
  55. if (AP_HAL::micros64() - last_report_us < report_interval) {
  56. return false;
  57. }
  58. return false;
  59. }