2011-03-19 07:20:11 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2011-03-03 07:39:52 -04:00
|
|
|
|
2011-07-17 07:32:00 -03:00
|
|
|
static void read_control_switch()
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2011-09-04 21:15:36 -03:00
|
|
|
static bool switch_debouncer = false;
|
2010-12-19 12:40:33 -04:00
|
|
|
byte switchPosition = readSwitch();
|
2011-02-21 00:30:56 -04:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
if (oldSwitchPosition != switchPosition){
|
2011-09-04 21:15:36 -03:00
|
|
|
if(switch_debouncer){
|
|
|
|
// remember the prev location for GS
|
|
|
|
prev_WP = current_loc;
|
|
|
|
oldSwitchPosition = switchPosition;
|
|
|
|
switch_debouncer = false;
|
|
|
|
|
|
|
|
set_mode(flight_modes[switchPosition]);
|
2011-09-14 17:58:18 -03:00
|
|
|
|
2011-12-03 21:54:57 -04:00
|
|
|
if(g.ch7_option != CH7_SIMPLE_MODE){
|
|
|
|
// set Simple mode using stored paramters from Mission planner
|
|
|
|
// rather than by the control switch
|
2011-09-17 01:33:01 -03:00
|
|
|
do_simple = (g.simple_modes & (1 << switchPosition));
|
2011-11-29 02:41:12 -04:00
|
|
|
}
|
2011-09-04 21:15:36 -03:00
|
|
|
}else{
|
|
|
|
switch_debouncer = true;
|
|
|
|
}
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2011-07-17 07:32:00 -03:00
|
|
|
static byte readSwitch(void){
|
2011-05-14 23:02:09 -03:00
|
|
|
int pulsewidth = g.rc_5.radio_in; // default for Arducopter
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
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;
|
|
|
|
}
|
|
|
|
|
2011-07-17 07:32:00 -03:00
|
|
|
static void reset_control_switch()
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
|
|
|
oldSwitchPosition = -1;
|
|
|
|
read_control_switch();
|
|
|
|
}
|
|
|
|
|
|
|
|
// read at 10 hz
|
|
|
|
// set this to your trainer switch
|
2011-07-17 07:32:00 -03:00
|
|
|
static void read_trim_switch()
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2011-10-15 20:34:57 -03:00
|
|
|
#if CH7_OPTION == CH7_FLIP
|
2011-11-09 16:06:55 -04:00
|
|
|
if (g.rc_7.control_in > 800 && g.rc_3.control_in != 0){
|
|
|
|
do_flip = true;
|
|
|
|
}
|
2011-08-05 13:21:55 -03:00
|
|
|
|
2011-10-15 20:34:57 -03:00
|
|
|
#elif CH7_OPTION == CH7_SIMPLE_MODE
|
2011-11-09 16:06:55 -04:00
|
|
|
//Serial.println(g.rc_7.control_in, DEC);
|
2011-09-14 17:58:18 -03:00
|
|
|
|
2011-10-15 20:34:57 -03:00
|
|
|
#elif CH7_OPTION == CH7_SET_HOVER
|
2011-11-09 16:06:55 -04:00
|
|
|
// switch is engaged
|
|
|
|
if (g.rc_7.control_in > 800){
|
|
|
|
trim_flag = true;
|
2011-02-21 00:30:56 -04:00
|
|
|
|
2011-11-09 16:06:55 -04:00
|
|
|
}else{ // switch is disengaged
|
2011-02-21 00:30:56 -04:00
|
|
|
|
2011-11-09 16:06:55 -04:00
|
|
|
if(trim_flag){
|
2011-11-13 01:40:58 -04:00
|
|
|
trim_flag = false;
|
2011-07-02 19:44:59 -03:00
|
|
|
|
2011-11-09 16:06:55 -04:00
|
|
|
// set the throttle nominal
|
|
|
|
if(g.rc_3.control_in > 150){
|
|
|
|
g.throttle_cruise.set_and_save(g.rc_3.control_in);
|
|
|
|
//Serial.printf("tnom %d\n", g.throttle_cruise.get());
|
|
|
|
}
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
}
|
2011-10-15 20:34:57 -03:00
|
|
|
|
2011-11-26 17:21:16 -04:00
|
|
|
#elif CH7_OPTION == CH7_ADC_FILTER
|
|
|
|
if (g.rc_7.control_in > 800){
|
|
|
|
adc.filter_result = true;
|
|
|
|
}else{
|
|
|
|
adc.filter_result = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
#elif CH7_OPTION == CH7_AUTO_TRIM
|
2011-11-09 16:06:55 -04:00
|
|
|
if (g.rc_7.control_in > 800){
|
2011-11-26 17:21:16 -04:00
|
|
|
auto_level_counter = 10;
|
|
|
|
}
|
|
|
|
|
|
|
|
#else
|
|
|
|
|
|
|
|
// this is the normal operation set by the mission planner
|
|
|
|
|
|
|
|
if(g.ch7_option == CH7_SIMPLE_MODE){
|
|
|
|
do_simple = (g.rc_7.control_in > 800);
|
|
|
|
|
|
|
|
}else if (g.ch7_option == CH7_RTL){
|
|
|
|
if (trim_flag == false && g.rc_7.control_in > 800){
|
2011-11-09 16:06:55 -04:00
|
|
|
trim_flag = true;
|
2011-11-26 17:21:16 -04:00
|
|
|
set_mode(RTL);
|
|
|
|
}
|
2011-10-18 21:59:45 -03:00
|
|
|
|
2011-11-26 17:21:16 -04:00
|
|
|
if (trim_flag == true && g.rc_7.control_in < 800){
|
|
|
|
trim_flag = false;
|
|
|
|
if (control_mode == RTL || control_mode == LOITER){
|
|
|
|
reset_control_switch();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
}else if (g.ch7_option == CH7_SAVE_WP){
|
|
|
|
if (g.rc_7.control_in > 800){ // switch is engaged
|
|
|
|
trim_flag = true;
|
2011-10-18 21:59:45 -03:00
|
|
|
|
2011-11-26 17:21:16 -04:00
|
|
|
}else{ // switch is disengaged
|
2011-11-09 16:06:55 -04:00
|
|
|
if(trim_flag){
|
2011-11-13 01:40:58 -04:00
|
|
|
trim_flag = false;
|
|
|
|
// increment index
|
2011-11-09 16:06:55 -04:00
|
|
|
CH7_wp_index++;
|
2011-11-13 01:40:58 -04:00
|
|
|
|
|
|
|
// set the next_WP, 0 is Home so we don't set that
|
|
|
|
// max out at 100 since I think we need to stay under the EEPROM limit
|
|
|
|
CH7_wp_index = constrain(CH7_wp_index, 1, 100);
|
|
|
|
|
|
|
|
// set our location ID to 16, MAV_CMD_NAV_WAYPOINT
|
2011-11-09 16:06:55 -04:00
|
|
|
current_loc.id = MAV_CMD_NAV_WAYPOINT;
|
2011-11-13 01:40:58 -04:00
|
|
|
|
|
|
|
// save command
|
2011-11-20 03:24:14 -04:00
|
|
|
set_cmd_with_index(current_loc, CH7_wp_index);
|
2011-11-13 01:40:58 -04:00
|
|
|
|
|
|
|
// save the index
|
|
|
|
g.command_total.set_and_save(CH7_wp_index + 1);
|
2011-11-09 16:06:55 -04:00
|
|
|
}
|
2011-10-18 21:59:45 -03:00
|
|
|
}
|
2011-11-26 17:21:16 -04:00
|
|
|
}
|
2011-10-15 20:34:57 -03:00
|
|
|
#endif
|
2011-09-21 20:24:09 -03:00
|
|
|
|
2011-01-15 22:37:35 -04:00
|
|
|
}
|
|
|
|
|
2011-07-17 07:32:00 -03:00
|
|
|
static void auto_trim()
|
2011-06-16 14:03:26 -03:00
|
|
|
{
|
|
|
|
if(auto_level_counter > 0){
|
2011-09-05 02:09:07 -03:00
|
|
|
//g.rc_1.dead_zone = 60; // 60 = .6 degrees
|
|
|
|
//g.rc_2.dead_zone = 60;
|
2011-07-02 19:44:59 -03:00
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
auto_level_counter--;
|
|
|
|
trim_accel();
|
|
|
|
led_mode = AUTO_TRIM_LEDS;
|
|
|
|
|
|
|
|
if(auto_level_counter == 1){
|
2011-09-05 02:09:07 -03:00
|
|
|
//g.rc_1.dead_zone = 0; // 60 = .6 degrees
|
|
|
|
//g.rc_2.dead_zone = 0;
|
2011-06-16 14:03:26 -03:00
|
|
|
led_mode = NORMAL_LEDS;
|
|
|
|
clear_leds();
|
|
|
|
imu.save();
|
2011-10-27 15:34:00 -03:00
|
|
|
|
2011-10-02 15:36:23 -03:00
|
|
|
//Serial.println("Done");
|
2011-06-16 14:03:26 -03:00
|
|
|
auto_level_counter = 0;
|
2011-10-27 15:34:00 -03:00
|
|
|
|
|
|
|
// set TC
|
|
|
|
init_throttle_cruise();
|
2011-06-16 14:03:26 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2011-01-15 22:37:35 -04:00
|
|
|
|
2011-07-17 07:32:00 -03:00
|
|
|
static void trim_accel()
|
2011-01-15 22:37:35 -04:00
|
|
|
{
|
2011-09-04 21:15:36 -03:00
|
|
|
g.pi_stabilize_roll.reset_I();
|
|
|
|
g.pi_stabilize_pitch.reset_I();
|
2011-06-16 14:03:26 -03:00
|
|
|
|
2011-09-22 19:25:07 -03:00
|
|
|
if(g.rc_1.control_in > 0){ // Roll RIght
|
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-09-22 19:25:07 -03:00
|
|
|
if(g.rc_2.control_in > 0){ // Pitch Back
|
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
|
|
|
}
|
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
/*
|
|
|
|
Serial.printf_P(PSTR("r:%ld p:%ld ax:%f, ay:%f, az:%f\n"),
|
2011-03-26 03:35:52 -03:00
|
|
|
dcm.roll_sensor,
|
|
|
|
dcm.pitch_sensor,
|
2011-06-16 14:03:26 -03:00
|
|
|
(float)imu.ax(),
|
|
|
|
(float)imu.ay(),
|
|
|
|
(float)imu.az());
|
|
|
|
//*/
|
2011-01-15 22:37:35 -04:00
|
|
|
}
|
|
|
|
|