Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add: parachute timeout parameter #27500

Draft
wants to merge 5 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 11 additions & 6 deletions ArduCopter/crash_check.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,13 @@
#include "Copter.h"

// Code to detect a crash main ArduCopter code
#define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash
#if PARACHUTE == ENABLED
// CRASH_CHECK_TRIGGER_SEC should be grater than CHUTE_TIMEOUT, to prevent disarming without deploying parachute
#define CRASH_CHECK_TRIGGER_SEC (parachute.get_chute_timeout() + 1.0)
#else
#define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash
#endif

#define CRASH_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees beyond target angle is signal we are out of control
#define CRASH_CHECK_ANGLE_MIN_DEG 15.0f // vehicle must be leaning at least 15deg to trigger crash check
#define CRASH_CHECK_SPEED_MAX 10.0f // vehicle must be moving at less than 10m/s to trigger crash check
Expand Down Expand Up @@ -86,7 +92,7 @@ void Copter::crash_check()
// we may be crashing
crash_counter++;

// check if crashing for 2 seconds
// check if crashing for time defined by CRASH_CHECK_TRIGGER_SEC seconds
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the multiply in this line ends up multiplying by 1.0, not the users value

LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH);
// send message to gcs
Expand Down Expand Up @@ -232,7 +238,6 @@ void Copter::yaw_imbalance_check()
#if PARACHUTE == ENABLED

// Code to detect a crash main ArduCopter code
#define PARACHUTE_CHECK_TRIGGER_SEC 1 // 1 second of loss of control triggers the parachute
#define PARACHUTE_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees off from target indicates a loss of control

// parachute_check - disarms motors and triggers the parachute if serious loss of control has been detected
Expand Down Expand Up @@ -302,7 +307,7 @@ void Copter::parachute_check()
}

// increment counter
if (control_loss_count < (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
if (control_loss_count < (parachute.get_chute_timeout()*scheduler.get_loop_rate_hz())) {
control_loss_count++;
}

Expand All @@ -317,8 +322,8 @@ void Copter::parachute_check()

// To-Do: add check that the vehicle is actually falling

// check if loss of control for at least 1 second
} else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
// check if loss of control for at least time defined in CHUTE_TIMEOUT parameter
} else if (control_loss_count >= (parachute.get_chute_timeout()*scheduler.get_loop_rate_hz())) {
// reset control loss counter
control_loss_count = 0;
LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_LOSS_OF_CONTROL);
Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_Parachute/AP_Parachute.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,14 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = {
// @User: Standard
AP_GROUPINFO("OPTIONS", 7, AP_Parachute, _options, AP_PARACHUTE_OPTIONS_DEFAULT),

// @Param: TIMEOUT
// @DisplayName: Parachute timeout
// @Description: Triggers the parachute if the loss of control lasts for the time specified by this parameter
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Need to mention that it's copter only.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe we should make the parameters only appear for copter..?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@rmackay9 how to achieve it? I've tried with APM_BUILD_COPTER_OR_HELI but automatic checks failed.

// @Units: s
// @Range: 0.5 5.0
// @User: Advanced
AP_GROUPINFO_FRAME("TIMEOUT", 8, AP_Parachute, _timeout, AP_PARACHUTE_TIMEOUT_DEFAULT, AP_PARAM_FRAME_COPTER),

AP_GROUPEND
};

Expand Down
8 changes: 6 additions & 2 deletions libraries/AP_Parachute/AP_Parachute.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#define AP_PARACHUTE_CRITICAL_SINK_DEFAULT 0 // default critical sink speed in m/s to trigger emergency parachute
#define AP_PARACHUTE_OPTIONS_DEFAULT 0 // default parachute options: enabled disarm after parachute release
#define AP_PARACHUTE_TIMEOUT_DEFAULT 1.0f // default parachute control loss timeout

#ifndef HAL_PARACHUTE_ENABLED
// default to parachute enabled to match previous configs
Expand Down Expand Up @@ -90,6 +91,9 @@ class AP_Parachute {
// Return the relay index that would be used for param conversion to relay functions
bool get_legacy_relay_index(int8_t &index) const;

// Return the CHUTE_TIMEOUT parameter value
float get_chute_timeout() const { return _timeout; }

static const struct AP_Param::GroupInfo var_info[];

// get singleton instance
Expand All @@ -105,6 +109,8 @@ class AP_Parachute {
AP_Int16 _alt_min; // min altitude the vehicle should have before parachute is released
AP_Int16 _delay_ms; // delay before chute release for motors to stop
AP_Float _critical_sink; // critical sink rate to trigger emergency parachute
AP_Int32 _options; // optional behaviour for parachute bitmask
AP_Float _timeout; // loss of control timeout value in seconds

// internal variables
uint32_t _release_time; // system time that parachute is ordered to be released (actual release will happen 0.5 seconds later)
Expand All @@ -118,8 +124,6 @@ class AP_Parachute {
HoldOpen = (1U<<0),
SkipDisarmBeforeParachuteRelease = (1U<<1),
};

AP_Int32 _options;
};

namespace AP {
Expand Down
Loading