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-09-17 15:25:31 -03:00
|
|
|
#define ARM_DELAY 10 // one second
|
|
|
|
#define DISARM_DELAY 10 // one second
|
2011-06-16 14:03:26 -03:00
|
|
|
#define LEVEL_DELAY 120 // twelve seconds
|
2011-09-05 02:09:07 -03:00
|
|
|
#define AUTO_LEVEL_DELAY 150 // twentyfive seconds
|
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
|
|
|
{
|
2011-06-16 14:03:26 -03:00
|
|
|
static int arming_counter;
|
2011-03-21 04:35:54 -03:00
|
|
|
|
2011-01-23 22:04:44 -04:00
|
|
|
// Arm motor output : Throttle down and full yaw right for more than 2 seconds
|
2011-03-21 04:35:54 -03:00
|
|
|
if (g.rc_3.control_in == 0){
|
2011-06-16 14:03:26 -03:00
|
|
|
|
2011-04-13 13:33:06 -03:00
|
|
|
// full right
|
|
|
|
if (g.rc_4.control_in > 4000) {
|
2011-06-16 14:03:26 -03:00
|
|
|
|
2011-07-30 17:42:54 -03:00
|
|
|
// don't allow arming in anything but manual
|
2011-06-24 01:37:54 -03:00
|
|
|
if (control_mode < ALT_HOLD){
|
2011-06-16 14:03:26 -03:00
|
|
|
|
2011-06-24 01:37:54 -03:00
|
|
|
if (arming_counter > AUTO_LEVEL_DELAY){
|
2011-07-30 17:42:54 -03:00
|
|
|
auto_level_counter = 155;
|
2011-06-24 01:37:54 -03:00
|
|
|
arming_counter = 0;
|
2011-04-15 13:45:47 -03:00
|
|
|
|
2011-06-24 01:37:54 -03:00
|
|
|
}else if (arming_counter == ARM_DELAY){
|
2011-08-14 15:54:29 -03:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
2011-08-02 10:34:27 -03:00
|
|
|
hil.send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS"));
|
2011-08-14 15:54:29 -03:00
|
|
|
#endif
|
2011-06-24 01:37:54 -03:00
|
|
|
motor_armed = true;
|
|
|
|
arming_counter = ARM_DELAY;
|
2011-04-15 13:45:47 -03:00
|
|
|
|
2011-09-18 21:12:28 -03:00
|
|
|
#if PIEZO_ARMING == 1
|
|
|
|
piezo_beep();
|
|
|
|
piezo_beep();
|
|
|
|
#endif
|
|
|
|
|
2011-09-04 21:15:36 -03:00
|
|
|
// Tune down DCM
|
2011-07-30 17:42:54 -03:00
|
|
|
// -------------------
|
2011-09-04 21:15:36 -03:00
|
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
2011-09-11 15:22:01 -03:00
|
|
|
dcm.kp_roll_pitch(0.030000);
|
|
|
|
dcm.ki_roll_pitch(0.00001278), // 50 hz I term
|
|
|
|
//dcm.ki_roll_pitch(0.000006);
|
2011-09-04 21:15:36 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// tune down compass
|
|
|
|
// -----------------
|
|
|
|
dcm.kp_yaw(0.08);
|
|
|
|
dcm.ki_yaw(0);
|
2011-07-30 17:42:54 -03:00
|
|
|
|
2011-06-24 01:37:54 -03:00
|
|
|
// Remember Orientation
|
2011-07-10 21:47:08 -03:00
|
|
|
// --------------------
|
2011-06-24 01:37:54 -03:00
|
|
|
init_simple_bearing();
|
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
// Reset home position
|
|
|
|
// ----------------------
|
|
|
|
if(home_is_set)
|
|
|
|
init_home();
|
|
|
|
|
2011-07-30 17:42:54 -03:00
|
|
|
if(did_ground_start == false){
|
|
|
|
did_ground_start = true;
|
|
|
|
startup_ground();
|
|
|
|
}
|
|
|
|
|
2011-09-04 21:15:36 -03:00
|
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
|
|
// read Baro pressure at ground -
|
|
|
|
// this resets Baro for more accuracy
|
|
|
|
//-----------------------------------
|
|
|
|
init_barometer();
|
|
|
|
#endif
|
|
|
|
|
2011-08-14 15:54:29 -03:00
|
|
|
// temp hack
|
|
|
|
motor_light = true;
|
|
|
|
digitalWrite(A_LED_PIN, HIGH);
|
|
|
|
|
2011-06-24 01:37:54 -03:00
|
|
|
arming_counter++;
|
|
|
|
} else{
|
|
|
|
arming_counter++;
|
|
|
|
}
|
2011-01-23 22:04:44 -04:00
|
|
|
}
|
2011-05-29 01:02:01 -03:00
|
|
|
|
2011-04-13 13:33:06 -03:00
|
|
|
// full left
|
|
|
|
}else if (g.rc_4.control_in < -4000) {
|
2011-06-16 14:03:26 -03:00
|
|
|
//Serial.print(arming_counter, DEC);
|
|
|
|
if (arming_counter > LEVEL_DELAY){
|
|
|
|
//Serial.print("init");
|
2011-08-01 05:08:52 -03:00
|
|
|
imu.init_accel(mavlink_delay);
|
2011-06-16 14:03:26 -03:00
|
|
|
arming_counter = 0;
|
|
|
|
|
|
|
|
}else if (arming_counter == DISARM_DELAY){
|
2011-09-04 21:15:36 -03:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
2011-08-02 10:34:27 -03:00
|
|
|
hil.send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
|
2011-09-04 21:15:36 -03:00
|
|
|
#endif
|
|
|
|
|
2011-04-13 13:33:06 -03:00
|
|
|
motor_armed = false;
|
|
|
|
arming_counter = DISARM_DELAY;
|
2011-05-29 01:02:01 -03:00
|
|
|
compass.save_offsets();
|
2011-07-30 17:42:54 -03:00
|
|
|
|
2011-09-18 21:12:28 -03:00
|
|
|
#if PIEZO_ARMING == 1
|
|
|
|
piezo_beep();
|
|
|
|
#endif
|
2011-09-04 21:15:36 -03:00
|
|
|
|
|
|
|
// Tune down DCM
|
|
|
|
// -------------------
|
|
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
2011-09-11 15:22:01 -03:00
|
|
|
dcm.kp_roll_pitch(0.12); // higher for fast recovery
|
|
|
|
//dcm.ki_roll_pitch(0.00000319); // 1/4 of the normal rate for 200 hz loop
|
2011-09-04 21:15:36 -03:00
|
|
|
#endif
|
|
|
|
|
2011-07-30 17:42:54 -03:00
|
|
|
// tune up compass
|
|
|
|
// -----------------
|
|
|
|
dcm.kp_yaw(0.8);
|
|
|
|
dcm.ki_yaw(0.00004);
|
|
|
|
|
|
|
|
// Clear throttle slew
|
|
|
|
// -------------------
|
2011-08-13 23:30:37 -03:00
|
|
|
//throttle_slew = 0;
|
2011-07-30 17:42:54 -03:00
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
arming_counter++;
|
2011-05-29 01:02:01 -03:00
|
|
|
|
2011-03-21 04:35:54 -03:00
|
|
|
}else{
|
|
|
|
arming_counter++;
|
2011-02-17 05:36:33 -04:00
|
|
|
}
|
2011-04-13 13:33:06 -03:00
|
|
|
// centered
|
2011-03-21 04:35:54 -03:00
|
|
|
}else{
|
|
|
|
arming_counter = 0;
|
2011-01-23 22:04:44 -04:00
|
|
|
}
|
2011-04-13 13:33:06 -03:00
|
|
|
}else{
|
|
|
|
arming_counter = 0;
|
2011-01-23 22:04:44 -04: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
|
|
|
{
|
2011-05-14 23:02:09 -03:00
|
|
|
if (motor_armed == true && motor_auto_armed == true) {
|
2011-01-23 22:04:44 -04:00
|
|
|
// creates the radio_out and pwm_out values
|
2011-05-14 23:02:09 -03:00
|
|
|
output_motors_armed();
|
|
|
|
} else{
|
|
|
|
output_motors_disarmed();
|
|
|
|
}
|
|
|
|
}
|