2013-10-29 10:11:48 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-05-29 23:12:49 -03:00
# include "Copter.h"
2013-10-29 10:11:48 -03:00
// Code to detect a crash main ArduCopter code
2015-06-17 08:37:15 -03:00
# define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash
2015-06-17 22:48:54 -03:00
# define CRASH_CHECK_ANGLE_DEVIATION_CD 3000.0f // 30 degrees beyond angle max is signal we are inverted
2015-06-17 08:37:15 -03:00
# define CRASH_CHECK_ACCEL_MAX 3.0f // vehicle must be accelerating less than 3m/s/s to be considered crashed
2013-10-29 10:11:48 -03:00
// crash_check - disarms motors if a crash has been detected
// crashes are detected by the vehicle being more than 20 degrees beyond it's angle limits continuously for more than 1 second
2015-06-17 08:37:15 -03:00
// called at MAIN_LOOP_RATE
2015-05-29 23:12:49 -03:00
void Copter : : crash_check ( )
2013-10-29 10:11:48 -03:00
{
2015-06-17 08:37:15 -03:00
static uint16_t crash_counter ; // number of iterations vehicle may have been crashed
2013-10-29 10:11:48 -03:00
2015-08-30 23:15:46 -03:00
// return immediately if disarmed, or crash checking disabled
if ( ! motors . armed ( ) | | ap . land_complete | | g . fs_crash_check = = 0 ) {
2015-06-17 08:37:15 -03:00
crash_counter = 0 ;
2013-10-29 10:11:48 -03:00
return ;
}
// return immediately if we are not in an angle stabilize flight mode or we are flipping
2014-02-03 03:25:11 -04:00
if ( control_mode = = ACRO | | control_mode = = FLIP ) {
2015-06-17 08:37:15 -03:00
crash_counter = 0 ;
2013-10-29 10:11:48 -03:00
return ;
}
2015-06-17 08:37:15 -03:00
// vehicle not crashed if 1hz filtered acceleration is more than 3m/s (1G on Z-axis has been subtracted)
if ( land_accel_ef_filter . get ( ) . length ( ) > = CRASH_CHECK_ACCEL_MAX ) {
crash_counter = 0 ;
return ;
}
2013-10-30 01:27:06 -03:00
2015-06-17 10:08:48 -03:00
// check for angle error over 30 degrees
const Vector3f angle_error = attitude_control . angle_bf_error ( ) ;
2015-06-17 22:48:54 -03:00
if ( pythagorous2 ( angle_error . x , angle_error . y ) < = CRASH_CHECK_ANGLE_DEVIATION_CD ) {
2015-06-17 08:37:15 -03:00
crash_counter = 0 ;
2015-06-17 10:08:48 -03:00
return ;
}
// we may be crashing
crash_counter + + ;
// check if crashing for 2 seconds
if ( crash_counter > = ( CRASH_CHECK_TRIGGER_SEC * MAIN_LOOP_RATE ) ) {
// log an error in the dataflash
Log_Write_Error ( ERROR_SUBSYSTEM_CRASH_CHECK , ERROR_CODE_CRASH_CHECK_CRASH ) ;
// send message to gcs
2015-08-11 20:50:34 -03:00
gcs_send_text_P ( MAV_SEVERITY_CRITICAL , PSTR ( " Crash: Disarming " ) ) ;
2015-06-17 10:08:48 -03:00
// disarm motors
init_disarm_motors ( ) ;
2013-10-29 10:11:48 -03:00
}
}
2014-04-02 12:20:20 -03:00
# if PARACHUTE == ENABLED
// Code to detect a crash main ArduCopter code
2015-06-17 08:37:15 -03:00
# 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
2014-04-02 12:20:20 -03:00
// 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
2015-06-17 08:37:15 -03:00
// called at MAIN_LOOP_RATE
2015-05-29 23:12:49 -03:00
void Copter : : parachute_check ( )
2014-04-02 12:20:20 -03:00
{
2015-06-17 08:37:15 -03:00
static uint16_t control_loss_count ; // number of iterations we have been out of control
2014-04-02 12:20:20 -03:00
static int32_t baro_alt_start ;
// exit immediately if parachute is not enabled
if ( ! parachute . enabled ( ) ) {
return ;
}
2014-04-02 21:56:30 -03:00
// call update to give parachute a chance to move servo or relay back to off position
parachute . update ( ) ;
2014-04-02 12:20:20 -03:00
// return immediately if motors are not armed or pilot's throttle is above zero
if ( ! motors . armed ( ) ) {
control_loss_count = 0 ;
return ;
}
// return immediately if we are not in an angle stabilize flight mode or we are flipping
if ( control_mode = = ACRO | | control_mode = = FLIP ) {
control_loss_count = 0 ;
return ;
}
2014-04-03 05:55:34 -03:00
// ensure we are flying
if ( ap . land_complete ) {
2014-04-02 21:56:30 -03:00
control_loss_count = 0 ;
return ;
}
2014-04-03 05:55:34 -03:00
// ensure the first control_loss event is from above the min altitude
2015-05-12 09:49:44 -03:00
if ( control_loss_count = = 0 & & parachute . alt_min ( ) ! = 0 & & ( current_loc . alt < ( int32_t ) parachute . alt_min ( ) * 100 ) ) {
2014-04-03 05:55:34 -03:00
return ;
}
2015-06-17 22:48:54 -03:00
// check for angle error over 30 degrees
const Vector3f angle_error = attitude_control . angle_bf_error ( ) ;
if ( pythagorous2 ( angle_error . x , angle_error . y ) < = CRASH_CHECK_ANGLE_DEVIATION_CD ) {
control_loss_count = 0 ;
return ;
}
2014-04-02 12:20:20 -03:00
2015-06-17 22:48:54 -03:00
// increment counter
if ( control_loss_count < ( PARACHUTE_CHECK_TRIGGER_SEC * MAIN_LOOP_RATE ) ) {
2014-04-02 12:20:20 -03:00
control_loss_count + + ;
2015-06-17 22:48:54 -03:00
}
2014-04-02 12:20:20 -03:00
2015-06-17 22:48:54 -03:00
// record baro alt if we have just started losing control
if ( control_loss_count = = 1 ) {
baro_alt_start = baro_alt ;
// exit if baro altitude change indicates we are not falling
} else if ( baro_alt > = baro_alt_start ) {
control_loss_count = 0 ;
return ;
// 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 * MAIN_LOOP_RATE ) ) {
// reset control loss counter
2014-04-02 12:20:20 -03:00
control_loss_count = 0 ;
2015-06-17 22:48:54 -03:00
// log an error in the dataflash
Log_Write_Error ( ERROR_SUBSYSTEM_CRASH_CHECK , ERROR_CODE_CRASH_CHECK_LOSS_OF_CONTROL ) ;
// release parachute
parachute_release ( ) ;
2014-04-02 12:20:20 -03:00
}
}
// parachute_release - trigger the release of the parachute, disarm the motors and notify the user
2015-05-29 23:12:49 -03:00
void Copter : : parachute_release ( )
2014-04-02 12:20:20 -03:00
{
2014-04-03 05:55:34 -03:00
// send message to gcs and dataflash
2015-08-11 20:50:34 -03:00
gcs_send_text_P ( MAV_SEVERITY_CRITICAL , PSTR ( " Parachute: Released! " ) ) ;
2014-04-03 05:55:34 -03:00
Log_Write_Event ( DATA_PARACHUTE_RELEASED ) ;
2014-04-02 12:20:20 -03:00
// disarm motors
init_disarm_motors ( ) ;
// release parachute
parachute . release ( ) ;
}
2014-04-02 21:56:30 -03:00
// parachute_manual_release - trigger the release of the parachute, after performing some checks for pilot error
// checks if the vehicle is landed
2015-05-29 23:12:49 -03:00
void Copter : : parachute_manual_release ( )
2014-04-02 21:56:30 -03:00
{
2014-04-07 00:16:57 -03:00
// exit immediately if parachute is not enabled
if ( ! parachute . enabled ( ) ) {
return ;
}
2015-05-12 09:54:07 -03:00
// do not release if vehicle is landed
2014-04-02 21:56:30 -03:00
// do not release if we are landed or below the minimum altitude above home
2015-05-12 09:54:07 -03:00
if ( ap . land_complete ) {
// warn user of reason for failure
2015-08-11 20:50:34 -03:00
gcs_send_text_P ( MAV_SEVERITY_CRITICAL , PSTR ( " Parachute: Landed " ) ) ;
2015-05-12 09:54:07 -03:00
// log an error in the dataflash
Log_Write_Error ( ERROR_SUBSYSTEM_PARACHUTE , ERROR_CODE_PARACHUTE_LANDED ) ;
return ;
}
// do not release if we are landed or below the minimum altitude above home
if ( ( parachute . alt_min ( ) ! = 0 & & ( current_loc . alt < ( int32_t ) parachute . alt_min ( ) * 100 ) ) ) {
2014-04-02 21:56:30 -03:00
// warn user of reason for failure
2015-08-11 20:50:34 -03:00
gcs_send_text_P ( MAV_SEVERITY_CRITICAL , PSTR ( " Parachute: Too Low " ) ) ;
2014-04-03 05:55:34 -03:00
// log an error in the dataflash
Log_Write_Error ( ERROR_SUBSYSTEM_PARACHUTE , ERROR_CODE_PARACHUTE_TOO_LOW ) ;
2014-04-02 21:56:30 -03:00
return ;
}
// if we get this far release parachute
parachute_release ( ) ;
}
2014-04-03 05:55:34 -03:00
2014-04-06 23:18:54 -03:00
# endif // PARACHUTE == ENABLED