123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174 |
- #include "AP_Parachute.h"
- #include <AP_Relay/AP_Relay.h>
- #include <AP_Math/AP_Math.h>
- #include <RC_Channel/RC_Channel.h>
- #include <SRV_Channel/SRV_Channel.h>
- #include <AP_Notify/AP_Notify.h>
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Logger/AP_Logger.h>
- #include <GCS_MAVLink/GCS.h>
- extern const AP_HAL::HAL& hal;
- const AP_Param::GroupInfo AP_Parachute::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO_FLAGS("ENABLED", 0, AP_Parachute, _enabled, 0, AP_PARAM_FLAG_ENABLE),
-
-
-
-
-
- AP_GROUPINFO("TYPE", 1, AP_Parachute, _release_type, AP_PARACHUTE_TRIGGER_TYPE_RELAY_0),
-
-
-
-
-
-
-
- AP_GROUPINFO("SERVO_ON", 2, AP_Parachute, _servo_on_pwm, AP_PARACHUTE_SERVO_ON_PWM_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("SERVO_OFF", 3, AP_Parachute, _servo_off_pwm, AP_PARACHUTE_SERVO_OFF_PWM_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("ALT_MIN", 4, AP_Parachute, _alt_min, AP_PARACHUTE_ALT_MIN_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("DELAY_MS", 5, AP_Parachute, _delay_ms, AP_PARACHUTE_RELEASE_DELAY_MS),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("CRT_SINK", 6, AP_Parachute, _critical_sink, AP_PARACHUTE_CRITICAL_SINK_DEFAULT),
-
-
- AP_GROUPEND
- };
- void AP_Parachute::enabled(bool on_off)
- {
- _enabled = on_off;
-
- _release_time = 0;
- AP::logger().Write_Event(_enabled ? DATA_PARACHUTE_ENABLED : DATA_PARACHUTE_DISABLED);
- }
- void AP_Parachute::release()
- {
-
- if (_enabled <= 0) {
- return;
- }
- gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Released");
- AP::logger().Write_Event(DATA_PARACHUTE_RELEASED);
-
- if (_release_time == 0) {
- _release_time = AP_HAL::millis();
- }
- _release_initiated = true;
-
- AP_Notify::flags.parachute_release = 1;
- }
- void AP_Parachute::update()
- {
-
- if (_enabled <= 0) {
- return;
- }
-
- uint32_t time = AP_HAL::millis();
- if((_critical_sink > 0) && (_sink_rate > _critical_sink) && !_release_initiated && _is_flying) {
- if(_sink_time == 0) {
- _sink_time = AP_HAL::millis();
- }
- if((time - _sink_time) >= 1000) {
- release();
- }
- } else {
- _sink_time = 0;
- }
-
-
- uint32_t time_diff = AP_HAL::millis() - _release_time;
- uint32_t delay_ms = _delay_ms<=0 ? 0: (uint32_t)_delay_ms;
-
-
- if ((_release_time != 0) && !_release_in_progress) {
- if (time_diff >= delay_ms) {
- if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
-
- SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_on_pwm);
- }else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
-
- _relay.on(_release_type);
- }
- _release_in_progress = true;
- _released = true;
- }
- }else if ((_release_time == 0) || time_diff >= delay_ms + AP_PARACHUTE_RELEASE_DURATION_MS) {
- if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
-
- SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_off_pwm);
- }else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
-
- _relay.off(_release_type);
- }
-
- _release_in_progress = false;
- _release_time = 0;
-
- AP_Notify::flags.parachute_release = 0;
- }
- }
- AP_Parachute *AP_Parachute::_singleton;
- namespace AP {
- AP_Parachute *parachute()
- {
- return AP_Parachute::get_singleton();
- }
- }
|