2011-03-19 07:20:11 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2011-01-23 22:04:44 -04:00
|
|
|
|
2011-11-05 01:41:51 -03:00
|
|
|
// 10 = 1 second
|
2012-01-23 18:10:03 -04:00
|
|
|
#define ARM_DELAY 20
|
2011-11-05 01:41:51 -03:00
|
|
|
#define DISARM_DELAY 20
|
2012-12-19 11:06:20 -04:00
|
|
|
#define AUTO_TRIM_DELAY 100
|
2011-01-23 22:04:44 -04:00
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
|
|
|
|
// called at 10hz
|
2011-07-17 07:32:00 -03:00
|
|
|
static void arm_motors()
|
2011-01-23 22:04:44 -04:00
|
|
|
{
|
2012-08-21 23:19:50 -03:00
|
|
|
static int16_t arming_counter;
|
|
|
|
|
|
|
|
// don't allow arming/disarming in anything but manual
|
2012-11-05 00:32:38 -04:00
|
|
|
if (g.rc_3.control_in > 0) {
|
2012-08-21 23:19:50 -03:00
|
|
|
arming_counter = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2013-04-22 12:01:20 -03:00
|
|
|
// ensure pre-arm checks have been successful
|
|
|
|
if(!ap.pre_arm_check) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// ensure we are in Stabilize, Acro or TOY mode
|
2012-08-21 23:19:50 -03:00
|
|
|
if ((control_mode > ACRO) && ((control_mode != TOY_A) && (control_mode != TOY_M))) {
|
|
|
|
arming_counter = 0;
|
|
|
|
return;
|
|
|
|
}
|
2012-11-26 20:03:28 -04:00
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
if ((motors.rsc_mode > 0) && (g.rc_8.control_in >= 10)){
|
|
|
|
arming_counter = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif // HELI_FRAME
|
2012-08-21 23:19:50 -03:00
|
|
|
|
|
|
|
#if TOY_EDF == ENABLED
|
|
|
|
int16_t tmp = g.rc_1.control_in;
|
|
|
|
#else
|
|
|
|
int16_t tmp = g.rc_4.control_in;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// full right
|
|
|
|
if (tmp > 4000) {
|
2012-07-14 23:26:17 -03:00
|
|
|
|
2012-12-19 11:06:20 -04:00
|
|
|
// increase the arming counter to a maximum of 1 beyond the auto trim counter
|
|
|
|
if( arming_counter <= AUTO_TRIM_DELAY ) {
|
|
|
|
arming_counter++;
|
|
|
|
}
|
|
|
|
|
|
|
|
// arm the motors and configure for flight
|
|
|
|
if (arming_counter == ARM_DELAY && !motors.armed()) {
|
|
|
|
init_arm_motors();
|
|
|
|
}
|
2012-07-14 23:26:17 -03:00
|
|
|
|
2012-12-19 11:06:20 -04:00
|
|
|
// arm the motors and configure for flight
|
|
|
|
if (arming_counter == AUTO_TRIM_DELAY && motors.armed()) {
|
|
|
|
auto_trim_counter = 250;
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
|
|
|
|
2012-12-19 11:06:20 -04:00
|
|
|
// full left
|
2012-08-21 23:19:50 -03:00
|
|
|
}else if (tmp < -4000) {
|
2012-12-19 11:06:20 -04:00
|
|
|
|
|
|
|
// increase the counter to a maximum of 1 beyond the disarm delay
|
|
|
|
if( arming_counter <= DISARM_DELAY ) {
|
2012-08-21 23:19:50 -03:00
|
|
|
arming_counter++;
|
|
|
|
}
|
|
|
|
|
2012-12-19 11:06:20 -04:00
|
|
|
// disarm the motors
|
|
|
|
if (arming_counter == DISARM_DELAY && motors.armed()) {
|
|
|
|
init_disarm_motors();
|
|
|
|
}
|
|
|
|
|
|
|
|
// Yaw is centered so reset arming counter
|
2012-08-21 23:19:50 -03:00
|
|
|
}else{
|
|
|
|
arming_counter = 0;
|
|
|
|
}
|
2011-01-23 22:04:44 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2011-11-05 01:41:51 -03:00
|
|
|
static void init_arm_motors()
|
|
|
|
{
|
2012-11-10 01:55:51 -04:00
|
|
|
// arming marker
|
2012-08-21 23:19:50 -03:00
|
|
|
// Flag used to track if we have armed the motors the first time.
|
|
|
|
// This is used to decide if we should run the ground_start routine
|
|
|
|
// which calibrates the IMU
|
|
|
|
static bool did_ground_start = false;
|
2012-01-03 14:24:51 -04:00
|
|
|
|
2012-10-09 00:30:17 -03:00
|
|
|
// disable failsafe because initialising everything takes a while
|
|
|
|
failsafe_disable();
|
|
|
|
|
2012-11-21 02:08:03 -04:00
|
|
|
//cliSerial->printf("\nARM\n");
|
2012-12-18 06:15:11 -04:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
2012-08-21 23:19:50 -03:00
|
|
|
gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS"));
|
|
|
|
#endif
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-03-30 03:05:44 -03:00
|
|
|
// we don't want writes to the serial port to cause us to pause
|
|
|
|
// mid-flight, so set the serial ports non-blocking once we arm
|
|
|
|
// the motors
|
2012-12-12 21:25:09 -04:00
|
|
|
hal.uartA->set_blocking_writes(false);
|
2012-03-30 03:05:44 -03:00
|
|
|
if (gcs3.initialised) {
|
2012-12-12 21:25:09 -04:00
|
|
|
hal.uartC->set_blocking_writes(false);
|
2012-03-30 03:05:44 -03:00
|
|
|
}
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
#if COPTER_LEDS == ENABLED
|
2013-04-01 01:10:12 -03:00
|
|
|
piezo_beep_twice();
|
2012-08-21 23:19:50 -03:00
|
|
|
#endif
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// Remember Orientation
|
|
|
|
// --------------------
|
|
|
|
init_simple_bearing();
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// Reset home position
|
|
|
|
// -------------------
|
2012-11-10 01:55:51 -04:00
|
|
|
if(ap.home_is_set)
|
2012-08-21 23:19:50 -03:00
|
|
|
init_home();
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// all I terms are invalid
|
|
|
|
// -----------------------
|
2012-01-20 14:11:56 -04:00
|
|
|
reset_I_all();
|
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
if(did_ground_start == false) {
|
|
|
|
did_ground_start = true;
|
|
|
|
startup_ground();
|
|
|
|
}
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
|
|
// read Baro pressure at ground -
|
|
|
|
// this resets Baro for more accuracy
|
|
|
|
//-----------------------------------
|
|
|
|
init_barometer();
|
|
|
|
#endif
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// temp hack
|
2012-11-11 09:42:10 -04:00
|
|
|
ap_system.motor_light = true;
|
2012-08-21 23:19:50 -03:00
|
|
|
digitalWrite(A_LED_PIN, LED_ON);
|
2012-08-21 02:38:31 -03:00
|
|
|
|
|
|
|
// go back to normal AHRS gains
|
|
|
|
ahrs.set_fast_gains(false);
|
2012-09-29 12:25:40 -03:00
|
|
|
#if SECONDARY_DMP_ENABLED == ENABLED
|
|
|
|
ahrs2.set_fast_gains(false);
|
|
|
|
#endif
|
2012-10-09 00:30:17 -03:00
|
|
|
|
|
|
|
// finally actually arm the motors
|
|
|
|
motors.armed(true);
|
2012-11-10 01:55:51 -04:00
|
|
|
set_armed(true);
|
2012-10-09 00:30:17 -03:00
|
|
|
|
|
|
|
// reenable failsafe
|
|
|
|
failsafe_enable();
|
2011-11-05 01:41:51 -03:00
|
|
|
}
|
|
|
|
|
2013-04-22 12:01:20 -03:00
|
|
|
// 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;
|
|
|
|
}
|
|
|
|
|
2013-04-27 11:50:40 -03:00
|
|
|
// check the compass is healthy
|
|
|
|
if(!compass.healthy) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2013-04-26 06:51:07 -03:00
|
|
|
#if AC_FENCE == ENABLED
|
|
|
|
// check fence is initialised
|
|
|
|
if(!fence.pre_arm_check()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2013-04-22 12:01:20 -03:00
|
|
|
// if we've gotten this far then pre arm checks have completed
|
|
|
|
ap.pre_arm_check = true;
|
|
|
|
}
|
2011-11-05 01:41:51 -03:00
|
|
|
|
|
|
|
static void init_disarm_motors()
|
|
|
|
{
|
2012-12-18 06:15:11 -04:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
2012-08-21 23:19:50 -03:00
|
|
|
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
|
|
|
|
#endif
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
motors.armed(false);
|
2012-11-10 01:55:51 -04:00
|
|
|
set_armed(false);
|
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
compass.save_offsets();
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
g.throttle_cruise.save();
|
2012-01-14 15:43:52 -04:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// we are not in the air
|
2012-11-10 01:55:51 -04:00
|
|
|
set_takeoff_complete(false);
|
2012-01-03 14:24:51 -04:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
#if COPTER_LEDS == ENABLED
|
2013-04-01 01:10:12 -03:00
|
|
|
piezo_beep();
|
2012-08-21 23:19:50 -03:00
|
|
|
#endif
|
2012-08-21 02:38:31 -03:00
|
|
|
|
|
|
|
// setup fast AHRS gains to get right attitude
|
|
|
|
ahrs.set_fast_gains(true);
|
2012-09-29 12:25:40 -03:00
|
|
|
#if SECONDARY_DMP_ENABLED == ENABLED
|
|
|
|
ahrs2.set_fast_gains(true);
|
|
|
|
#endif
|
2011-11-05 01:41:51 -03:00
|
|
|
}
|
|
|
|
|
2011-01-23 22:04:44 -04:00
|
|
|
/*****************************************
|
2012-08-21 23:19:50 -03:00
|
|
|
* Set the flight control servos based on the current calculated values
|
|
|
|
*****************************************/
|
2011-07-17 07:32:00 -03:00
|
|
|
static void
|
2011-01-25 01:53:36 -04:00
|
|
|
set_servos_4()
|
2011-01-23 22:04:44 -04:00
|
|
|
{
|
2012-12-17 02:29:11 -04:00
|
|
|
#if FRAME_CONFIG == TRI_FRAME
|
|
|
|
// To-Do: implement improved stability patch for tri so that we do not need to limit throttle input to motors
|
2012-08-21 23:19:50 -03:00
|
|
|
g.rc_3.servo_out = min(g.rc_3.servo_out, 800);
|
2012-11-26 19:44:03 -04:00
|
|
|
#endif
|
2012-08-21 23:19:50 -03:00
|
|
|
motors.output();
|
2012-01-01 16:46:32 -04:00
|
|
|
}
|
|
|
|
|