1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071 |
- #include "SIM_Parachute.h"
- #include "AP_HAL/AP_HAL.h"
- #include <AP_Math/AP_Math.h>
- #include <GCS_MAVLink/GCS.h>
- using namespace SITL;
- const AP_Param::GroupInfo Parachute::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO("ENABLE", 0, Parachute, parachute_enable, 0),
-
-
-
-
-
- AP_GROUPINFO("PIN", 1, Parachute, parachute_pin, -1),
- AP_GROUPEND
- };
- void Parachute::update(const struct sitl_input &input)
- {
- const int16_t pwm = parachute_pin >= 1 ? input.servos[parachute_pin-1] : -1;
- const uint64_t now = AP_HAL::micros64();
-
- if (pwm >= 1250) {
- if (!deployed_ms) {
- deployed_ms = AP_HAL::millis();
- gcs().send_text(MAV_SEVERITY_WARNING, "BANG! Parachute deployed");
- }
- }
- last_update_us = now;
- }
- bool Parachute::should_report()
- {
- if (AP_HAL::micros64() - last_report_us < report_interval) {
- return false;
- }
- return false;
- }
|