SIM_Parachute.h 1.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758
  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 simulation class
  15. */
  16. #pragma once
  17. #include "stdint.h"
  18. #include <AP_Param/AP_Param.h>
  19. #include "SITL_Input.h"
  20. #include <AP_Math/AP_Math.h>
  21. namespace SITL {
  22. class Parachute {
  23. public:
  24. Parachute() {
  25. AP_Param::setup_object_defaults(this, var_info);
  26. };
  27. // update parachute state
  28. void update(const struct sitl_input &input);
  29. Vector3f drag() const;
  30. static const struct AP_Param::GroupInfo var_info[];
  31. bool is_enabled() const {return static_cast<bool>(parachute_enable);}
  32. private:
  33. AP_Int8 parachute_enable; // enable parachute sim
  34. AP_Int8 parachute_pin; // pin with pyrotechnics on
  35. const uint32_t report_interval = 1000000; // microseconds
  36. uint64_t last_report_us;
  37. uint32_t deployed_ms; // time parachute was deployed
  38. uint64_t last_update_us;
  39. bool should_report();
  40. bool zero_report_done = false;
  41. };
  42. }