APM: removed cli slider and dipswitch options

use mavlink/eeprom for all config
This commit is contained in:
Andrew Tridgell 2012-08-07 13:44:43 +10:00
parent 3d6d013c55
commit b366205172
8 changed files with 1 additions and 124 deletions

View File

@ -906,10 +906,6 @@ static void slow_loop()
case 1: case 1:
slow_loopCounter++; slow_loopCounter++;
// Read Control Surfaces/Mix switches
// ----------------------------------
update_servo_switches();
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1 #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8); update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
#else #else

View File

@ -54,7 +54,7 @@ public:
// Misc // Misc
// //
k_param_auto_trim, k_param_auto_trim,
k_param_switch_enable, k_param_switch_enable, // UNUSED
k_param_log_bitmask, k_param_log_bitmask,
k_param_pitch_trim, k_param_pitch_trim,
k_param_mix_mode, k_param_mix_mode,
@ -331,7 +331,6 @@ public:
// Misc // Misc
// //
AP_Int8 auto_trim; AP_Int8 auto_trim;
AP_Int8 switch_enable;
AP_Int8 mix_mode; AP_Int8 mix_mode;
AP_Int8 reverse_elevons; AP_Int8 reverse_elevons;
AP_Int8 reverse_ch1_elevon; AP_Int8 reverse_ch1_elevon;

View File

@ -329,13 +329,6 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard // @User: Standard
GSCALAR(auto_trim, "TRIM_AUTO", AUTO_TRIM), GSCALAR(auto_trim, "TRIM_AUTO", AUTO_TRIM),
// @Param: SWITCH_ENABLE
// @DisplayName: Switch enable
// @Description: Enable dip switches on APM1
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR(switch_enable, "SWITCH_ENABLE", REVERSE_SWITCH),
// @Param: MIX_MODE // @Param: MIX_MODE
// @DisplayName: Elevon mixing // @DisplayName: Elevon mixing
// @Description: Enable elevon mixing // @Description: Enable elevon mixing

View File

@ -68,7 +68,6 @@
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000 # define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED # define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD # define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN # define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
@ -96,8 +95,6 @@
# define C_LED_PIN 35 # define C_LED_PIN 35
# define LED_ON HIGH # define LED_ON HIGH
# define LED_OFF LOW # define LED_OFF LOW
# define SLIDE_SWITCH_PIN 40
# define PUSHBUTTON_PIN 41
# define USB_MUX_PIN -1 # define USB_MUX_PIN -1
# define CONFIG_RELAY ENABLED # define CONFIG_RELAY ENABLED
# define BATTERY_PIN_1 0 # define BATTERY_PIN_1 0
@ -108,9 +105,6 @@
# define C_LED_PIN 25 # define C_LED_PIN 25
# define LED_ON LOW # define LED_ON LOW
# define LED_OFF HIGH # define LED_OFF HIGH
# define SLIDE_SWITCH_PIN (-1)
# define PUSHBUTTON_PIN (-1)
# define CLI_SLIDER_ENABLED DISABLED
#if TELEMETRY_UART2 == ENABLED #if TELEMETRY_UART2 == ENABLED
# define USB_MUX_PIN -1 # define USB_MUX_PIN -1
#else #else
@ -448,13 +442,6 @@
# define ENABLE_AIR_START DISABLED # define ENABLE_AIR_START DISABLED
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// ENABLE REVERSE_SWITCH
//
#ifndef REVERSE_SWITCH
# define REVERSE_SWITCH ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// ENABLE ELEVON_MIXING // ENABLE ELEVON_MIXING
// //
@ -842,11 +829,6 @@
# define CLI_ENABLED ENABLED # define CLI_ENABLED ENABLED
#endif #endif
// use this to disable the CLI slider switch
#ifndef CLI_SLIDER_ENABLED
# define CLI_SLIDER_ENABLED ENABLED
#endif
// delay to prevent Xbee bricking, in milliseconds // delay to prevent Xbee bricking, in milliseconds
#ifndef MAVLINK_TELEMETRY_PORT_DELAY #ifndef MAVLINK_TELEMETRY_PORT_DELAY
# define MAVLINK_TELEMETRY_PORT_DELAY 2000 # define MAVLINK_TELEMETRY_PORT_DELAY 2000

View File

@ -65,25 +65,3 @@ static void reset_control_switch()
read_control_switch(); read_control_switch();
} }
static void update_servo_switches()
{
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
if (!g.switch_enable) {
// switches are disabled in EEPROM (see SWITCH_ENABLE option)
// this means the EEPROM control of all channel reversal is enabled
return;
}
// up is reverse
// up is elevon
g.mix_mode = (PINL & 128) ? 1 : 0; // 1 for elevon mode
if (g.mix_mode == 0) {
g.channel_roll.set_reverse((PINE & 128) ? true : false);
g.channel_pitch.set_reverse((PINE & 64) ? true : false);
g.channel_rudder.set_reverse((PINL & 64) ? true : false);
} else {
g.reverse_elevons = (PINE & 128) ? true : false;
g.reverse_ch1_elevon = (PINE & 64) ? true : false;
g.reverse_ch2_elevon = (PINL & 64) ? true : false;
}
#endif
}

View File

@ -9,9 +9,6 @@ extern RC_Channel* rc_ch[NUM_CHANNELS];
static void init_rc_in() static void init_rc_in()
{ {
// set rc reversing
update_servo_switches();
// set rc channel ranges // set rc channel ranges
g.channel_roll.set_angle(SERVO_MAX); g.channel_roll.set_angle(SERVO_MAX);
g.channel_pitch.set_angle(SERVO_MAX); g.channel_pitch.set_angle(SERVO_MAX);

View File

@ -202,12 +202,6 @@ static void init_ardupilot()
pinMode(C_LED_PIN, OUTPUT); // GPS status LED pinMode(C_LED_PIN, OUTPUT); // GPS status LED
pinMode(A_LED_PIN, OUTPUT); // GPS status LED pinMode(A_LED_PIN, OUTPUT); // GPS status LED
pinMode(B_LED_PIN, OUTPUT); // GPS status LED pinMode(B_LED_PIN, OUTPUT); // GPS status LED
#if SLIDE_SWITCH_PIN > 0
pinMode(SLIDE_SWITCH_PIN, INPUT); // To enter interactive mode
#endif
#if CONFIG_PUSHBUTTON == ENABLED
pinMode(PUSHBUTTON_PIN, INPUT); // unused
#endif
#if CONFIG_RELAY == ENABLED #if CONFIG_RELAY == ENABLED
DDRL |= B00000100; // Set Port L, pin 2 to output for the relay DDRL |= B00000100; // Set Port L, pin 2 to output for the relay
#endif #endif
@ -223,31 +217,7 @@ static void init_ardupilot()
*/ */
timer_scheduler.set_failsafe(failsafe_check); timer_scheduler.set_failsafe(failsafe_check);
// If the switch is in 'menu' mode, run the main menu.
//
// Since we can't be sure that the setup or test mode won't leave
// the system in an odd state, we don't let the user exit the top
// menu; they must reset in order to fly.
//
#if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED
if (digitalRead(SLIDE_SWITCH_PIN) == 0) {
digitalWrite(A_LED_PIN,LED_ON); // turn on setup-mode LED
Serial.printf_P(PSTR("\n"
"Entering interactive setup mode...\n"
"\n"
"If using the Arduino Serial Monitor, ensure Line Ending is set to Carriage Return.\n"
"Type 'help' to list commands, 'exit' to leave a submenu.\n"
"Visit the 'setup' menu for first-time configuration.\n"));
Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n"));
run_cli();
}
#else
Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n")); Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n"));
#endif // CLI_ENABLED
// read in the flight switches
update_servo_switches();
if (ENABLE_AIR_START == 1) { if (ENABLE_AIR_START == 1) {
// Perform an air start and get back to flying // Perform an air start and get back to flying

View File

@ -23,9 +23,6 @@ static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
static int8_t test_eedump(uint8_t argc, const Menu::arg *argv); static int8_t test_eedump(uint8_t argc, const Menu::arg *argv);
static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv); static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
static int8_t test_modeswitch(uint8_t argc, const Menu::arg *argv); static int8_t test_modeswitch(uint8_t argc, const Menu::arg *argv);
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
static int8_t test_dipswitches(uint8_t argc, const Menu::arg *argv);
#endif
static int8_t test_logging(uint8_t argc, const Menu::arg *argv); static int8_t test_logging(uint8_t argc, const Menu::arg *argv);
// Creates a constant array of structs representing menu options // Creates a constant array of structs representing menu options
@ -175,7 +172,6 @@ test_radio(uint8_t argc, const Menu::arg *argv)
while(1){ while(1){
delay(20); delay(20);
read_radio(); read_radio();
update_servo_switches();
g.channel_roll.calc_pwm(); g.channel_roll.calc_pwm();
g.channel_pitch.calc_pwm(); g.channel_pitch.calc_pwm();
@ -419,40 +415,6 @@ test_logging(uint8_t argc, const Menu::arg *argv)
return 0; return 0;
} }
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
static int8_t
test_dipswitches(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
if (!g.switch_enable) {
Serial.println_P(PSTR("dip switches disabled, using EEPROM"));
}
while(1){
delay(100);
update_servo_switches();
if (g.mix_mode == 0) {
Serial.printf_P(PSTR("Mix:standard \trev roll:%d, rev pitch:%d, rev rudder:%d\n"),
(int)g.channel_roll.get_reverse(),
(int)g.channel_pitch.get_reverse(),
(int)g.channel_rudder.get_reverse());
} else {
Serial.printf_P(PSTR("Mix:elevons \trev elev:%d, rev ch1:%d, rev ch2:%d\n"),
(int)g.reverse_elevons,
(int)g.reverse_ch1_elevon,
(int)g.reverse_ch2_elevon);
}
if(Serial.available() > 0){
return (0);
}
}
}
#endif // CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
//------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------
// tests in this section are for real sensors or sensors that have been simulated // tests in this section are for real sensors or sensors that have been simulated