mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
Copter: fix the defined value for parachute check
This commit is contained in:
parent
f4e71b40d1
commit
a40e020813
@ -233,7 +233,7 @@ void Copter::yaw_imbalance_check()
|
||||
|
||||
// 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_CD 3000 // 30 degrees off from target indicates a loss of control
|
||||
#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
|
||||
// vehicle is considered to have a "serious loss of control" by the vehicle being more than 30 degrees off from the target roll and pitch angles continuously for 1 second
|
||||
@ -295,7 +295,7 @@ void Copter::parachute_check()
|
||||
|
||||
// check for angle error over 30 degrees
|
||||
const float angle_error = attitude_control->get_att_error_angle_deg();
|
||||
if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
|
||||
if (angle_error <= PARACHUTE_CHECK_ANGLE_DEVIATION_DEG) {
|
||||
if (control_loss_count > 0) {
|
||||
control_loss_count--;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user