12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758 |
- #pragma once
- #include "stdint.h"
- #include <AP_Param/AP_Param.h>
- #include "SITL_Input.h"
- #include <AP_Math/AP_Math.h>
- namespace SITL {
- class Parachute {
- public:
- Parachute() {
- AP_Param::setup_object_defaults(this, var_info);
- };
-
- void update(const struct sitl_input &input);
- Vector3f drag() const;
- static const struct AP_Param::GroupInfo var_info[];
- bool is_enabled() const {return static_cast<bool>(parachute_enable);}
- private:
- AP_Int8 parachute_enable;
- AP_Int8 parachute_pin;
- const uint32_t report_interval = 1000000;
- uint64_t last_report_us;
- uint32_t deployed_ms;
- uint64_t last_update_us;
- bool should_report();
- bool zero_report_done = false;
- };
- }
|