mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: add pre-arm check of radio and accel
Only checks throttle channel and accelerometer scaling
This commit is contained in:
parent
42bca90676
commit
63a48f76e2
@ -359,12 +359,13 @@ static AP_RangeFinder_MaxsonarXL *sonar;
|
||||
//Documentation of GLobals:
|
||||
static union {
|
||||
struct {
|
||||
uint8_t home_is_set : 1; // 1
|
||||
uint8_t simple_mode : 1; // 2 // This is the state of simple mode
|
||||
uint8_t manual_attitude : 1; // 3
|
||||
uint8_t manual_throttle : 1; // 4
|
||||
uint8_t home_is_set : 1; // 0
|
||||
uint8_t simple_mode : 1; // 1 // This is the state of simple mode
|
||||
uint8_t manual_attitude : 1; // 2
|
||||
uint8_t manual_throttle : 1; // 3
|
||||
|
||||
uint8_t low_battery : 1; // 5 // Used to track if the battery is low - LED output flashes when the batt is low
|
||||
uint8_t low_battery : 1; // 4 // Used to track if the battery is low - LED output flashes when the batt is low
|
||||
uint8_t pre_arm_check : 1; // 5 // true if the radio and accel calibration have been performed
|
||||
uint8_t armed : 1; // 6
|
||||
uint8_t auto_armed : 1; // 7 // stops auto missions from beginning until throttle is raised
|
||||
|
||||
@ -1295,6 +1296,9 @@ static void super_slow_loop()
|
||||
if ((g.log_bitmask & MASK_LOG_CURRENT) && motors.armed())
|
||||
Log_Write_Current();
|
||||
|
||||
// perform pre-arm checks
|
||||
pre_arm_checks();
|
||||
|
||||
// this function disarms the copter if it has been sitting on the ground for any moment of time greater than 25 seconds
|
||||
// but only of the control mode is manual
|
||||
if((control_mode <= ACRO) && (g.rc_3.control_in == 0) && motors.armed()) {
|
||||
|
@ -17,6 +17,12 @@ static void arm_motors()
|
||||
return;
|
||||
}
|
||||
|
||||
// ensure pre-arm checks have been successful
|
||||
if(!ap.pre_arm_check) {
|
||||
return;
|
||||
}
|
||||
|
||||
// ensure we are in Stabilize, Acro or TOY mode
|
||||
if ((control_mode > ACRO) && ((control_mode != TOY_A) && (control_mode != TOY_M))) {
|
||||
arming_counter = 0;
|
||||
return;
|
||||
@ -166,6 +172,27 @@ static void init_arm_motors()
|
||||
failsafe_enable();
|
||||
}
|
||||
|
||||
// perform pre-arm checks and set
|
||||
static void pre_arm_checks()
|
||||
{
|
||||
// exit immediately if we've already successfully performed the pre-arm check
|
||||
if( ap.pre_arm_check ) {
|
||||
return;
|
||||
}
|
||||
|
||||
// check if radio has been calibrated
|
||||
if(!g.rc_3.radio_min.load()) {
|
||||
return;
|
||||
}
|
||||
|
||||
// check accelerometers have been calibrated
|
||||
if(!ins.calibrated()) {
|
||||
return;
|
||||
}
|
||||
|
||||
// if we've gotten this far then pre arm checks have completed
|
||||
ap.pre_arm_check = true;
|
||||
}
|
||||
|
||||
static void init_disarm_motors()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user