2010-12-19 12:40:33 -04:00
|
|
|
void read_control_switch()
|
|
|
|
{
|
|
|
|
byte switchPosition = readSwitch();
|
|
|
|
//motor_armed = (switchPosition < 5);
|
|
|
|
|
|
|
|
if (oldSwitchPosition != switchPosition){
|
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
set_mode(g.flight_modes[switchPosition]);
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
oldSwitchPosition = switchPosition;
|
|
|
|
|
|
|
|
// reset navigation integrators
|
|
|
|
// -------------------------
|
|
|
|
reset_I();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
byte readSwitch(void){
|
|
|
|
#if FLIGHT_MODE_CHANNEL == CH_5
|
2011-02-17 03:09:13 -04:00
|
|
|
int pulsewidth = g.rc_5.radio_in; // default for Arducopter
|
2010-12-19 12:40:33 -04:00
|
|
|
#elif FLIGHT_MODE_CHANNEL == CH_6
|
2011-02-17 03:09:13 -04:00
|
|
|
int pulsewidth = g.rc_6.radio_in; //
|
2010-12-19 12:40:33 -04:00
|
|
|
#elif FLIGHT_MODE_CHANNEL == CH_7
|
2011-02-17 03:09:13 -04:00
|
|
|
int pulsewidth = g.rc_7.radio_in; //
|
2010-12-19 12:40:33 -04:00
|
|
|
#elif FLIGHT_MODE_CHANNEL == CH_8
|
2011-02-17 03:09:13 -04:00
|
|
|
int pulsewidth = g.rc_8.radio_in; // default for Ardupilot. Don't use for Arducopter! it has a hardware failsafe mux!
|
2010-12-19 12:40:33 -04:00
|
|
|
#else
|
|
|
|
# error Must define FLIGHT_MODE_CHANNEL as CH_5 - CH_8
|
|
|
|
#endif
|
|
|
|
|
|
|
|
if (pulsewidth > 1230 && pulsewidth <= 1360) return 1;
|
|
|
|
if (pulsewidth > 1360 && pulsewidth <= 1490) return 2;
|
|
|
|
if (pulsewidth > 1490 && pulsewidth <= 1620) return 3;
|
|
|
|
if (pulsewidth > 1620 && pulsewidth <= 1749) return 4; // Software Manual
|
|
|
|
if (pulsewidth >= 1750) return 5; // Hardware Manual
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
void reset_control_switch()
|
|
|
|
{
|
|
|
|
oldSwitchPosition = -1;
|
|
|
|
read_control_switch();
|
|
|
|
//Serial.print("MSG: reset_control_switch");
|
|
|
|
//Serial.println(oldSwitchPosition , DEC);
|
|
|
|
}
|
|
|
|
|
|
|
|
void update_servo_switches()
|
|
|
|
{
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
boolean trim_flag;
|
|
|
|
unsigned long trim_timer;
|
|
|
|
|
|
|
|
// read at 10 hz
|
|
|
|
// set this to your trainer switch
|
|
|
|
void read_trim_switch()
|
|
|
|
{
|
|
|
|
// switch is engaged
|
2011-02-17 03:09:13 -04:00
|
|
|
if (g.rc_7.control_in > 800){
|
2010-12-19 12:40:33 -04:00
|
|
|
if(trim_flag == false){
|
|
|
|
// called once
|
|
|
|
trim_timer = millis();
|
|
|
|
}
|
2011-01-15 22:37:35 -04:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
trim_flag = true;
|
2011-01-15 22:37:35 -04:00
|
|
|
trim_accel();
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
}else{ // switch is disengaged
|
|
|
|
|
|
|
|
if(trim_flag){
|
|
|
|
// switch was just released
|
|
|
|
if((millis() - trim_timer) > 2000){
|
2011-02-18 23:59:58 -04:00
|
|
|
imu.save();
|
2011-01-15 22:37:35 -04:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
} else {
|
|
|
|
// set the throttle nominal
|
2011-02-17 03:09:13 -04:00
|
|
|
if(g.rc_3.control_in > 50){
|
2011-02-18 23:59:58 -04:00
|
|
|
g.throttle_cruise.set(g.rc_3.control_in);
|
|
|
|
Serial.printf("tnom %d\n", g.throttle_cruise.get());
|
|
|
|
save_EEPROM_throttle_cruise();
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
trim_flag = false;
|
|
|
|
}
|
|
|
|
}
|
2011-01-15 22:37:35 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
void trim_accel()
|
|
|
|
{
|
2011-02-17 03:09:13 -04:00
|
|
|
if(g.rc_1.control_in > 0){
|
2011-01-15 22:44:30 -04:00
|
|
|
imu.ay(imu.ay() + 1);
|
2011-02-17 03:09:13 -04:00
|
|
|
}else if (g.rc_1.control_in < 0){
|
2011-01-22 20:35:51 -04:00
|
|
|
imu.ay(imu.ay() - 1);
|
2011-01-15 22:37:35 -04:00
|
|
|
}
|
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
if(g.rc_2.control_in > 0){
|
2011-01-15 22:44:30 -04:00
|
|
|
imu.ax(imu.ax() + 1);
|
2011-02-17 03:09:13 -04:00
|
|
|
}else if (g.rc_2.control_in < 0){
|
2011-01-22 20:35:51 -04:00
|
|
|
imu.ax(imu.ax() - 1);
|
2011-01-15 22:37:35 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
Serial.printf("r:%ld p:%ld ax:%d, ay:%d, az:%d\n", dcm.roll_sensor, dcm.pitch_sensor, imu.ax(), imu.ay(), imu.az());
|
|
|
|
}
|
|
|
|
|