Rover: removed flash_leds() calls

This commit is contained in:
Andrew Tridgell 2013-09-19 18:32:57 +10:00
parent e1aa6e3ff1
commit 95c2e11b5a
4 changed files with 8 additions and 51 deletions

View File

@ -60,11 +60,6 @@
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
# define CONFIG_INS_TYPE CONFIG_INS_OILPAN
# define CONFIG_COMPASS AP_COMPASS_HMC5843
# define A_LED_PIN 37
# define B_LED_PIN 36
# define C_LED_PIN 35
# define LED_ON HIGH
# define LED_OFF LOW
# define SLIDE_SWITCH_PIN 40
# define PUSHBUTTON_PIN 41
# define BATTERY_PIN_1 0
@ -73,11 +68,6 @@
# define CONFIG_INS_TYPE CONFIG_INS_MPU6000
# define CONFIG_COMPASS AP_COMPASS_HMC5843
# define CONFIG_PUSHBUTTON DISABLED
# define A_LED_PIN 27
# define B_LED_PIN 26
# define C_LED_PIN 25
# define LED_ON LOW
# define LED_OFF HIGH
# define SLIDE_SWITCH_PIN (-1)
# define PUSHBUTTON_PIN (-1)
# define CLI_SLIDER_ENABLED DISABLED
@ -87,11 +77,6 @@
# define CONFIG_INS_TYPE CONFIG_INS_STUB
# define CONFIG_COMPASS AP_COMPASS_HIL
# define CONFIG_PUSHBUTTON DISABLED
# define A_LED_PIN 27
# define B_LED_PIN 26
# define C_LED_PIN 25
# define LED_ON LOW
# define LED_OFF HIGH
# define SLIDE_SWITCH_PIN (-1)
# define PUSHBUTTON_PIN (-1)
# define CLI_SLIDER_ENABLED DISABLED
@ -101,11 +86,6 @@
# define CONFIG_INS_TYPE CONFIG_INS_PX4
# define CONFIG_COMPASS AP_COMPASS_PX4
# define CONFIG_PUSHBUTTON DISABLED
# define A_LED_PIN 27
# define B_LED_PIN 26
# define C_LED_PIN 25
# define LED_ON LOW
# define LED_OFF HIGH
# define SLIDE_SWITCH_PIN (-1)
# define PUSHBUTTON_PIN (-1)
# define CLI_SLIDER_ENABLED DISABLED

View File

@ -411,10 +411,9 @@ setup_accel_scale(uint8_t argc, const Menu::arg *argv)
cliSerial->println_P(PSTR("Initialising gyros"));
ahrs.init();
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
flash_leds);
ins_sample_rate);
AP_InertialSensor_UserInteractStream interact(hal.console);
if(ins.calibrate_accel(flash_leds, &interact, trim_roll, trim_pitch)) {
if(ins.calibrate_accel(&interact, trim_roll, trim_pitch)) {
// reset ahrs's trim to suggested values from calibration routine
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
}
@ -428,9 +427,8 @@ setup_level(uint8_t argc, const Menu::arg *argv)
cliSerial->println_P(PSTR("Initialising gyros"));
ahrs.init();
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
flash_leds);
ins.init_accel(flash_leds);
ins_sample_rate);
ins.init_accel();
ahrs.set_trim(Vector3f(0, 0, 0));
return(0);
}

View File

@ -178,9 +178,6 @@ static void init_ardupilot()
init_rc_in(); // sets up rc channels from radio
init_rc_out(); // sets up the timer libs
pinMode(C_LED_PIN, OUTPUT); // GPS status LED
pinMode(A_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
@ -203,7 +200,6 @@ static void init_ardupilot()
//
#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
cliSerial->printf_P(PSTR("\n"
"Entering interactive setup mode...\n"
"\n"
@ -373,21 +369,16 @@ static void startup_INS_ground(bool force_accel_level)
ahrs.init();
ahrs.set_fly_forward(true);
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
flash_leds);
ins_sample_rate);
if (force_accel_level) {
// when MANUAL_LEVEL is set to 1 we don't do accelerometer
// levelling on each boot, and instead rely on the user to do
// it once via the ground station
ins.init_accel(flash_leds);
ins.init_accel();
ahrs.set_trim(Vector3f(0, 0, 0));
}
ahrs.reset();
digitalWrite(B_LED_PIN, LED_ON); // Set LED B high to indicate INS ready
digitalWrite(A_LED_PIN, LED_OFF);
digitalWrite(C_LED_PIN, LED_OFF);
}
// updates the notify state
@ -447,16 +438,6 @@ static void check_usb_mux(void)
/*
called by gyro/accel init to flash LEDs so user
has some mesmerising lights to watch while waiting
*/
void flash_leds(bool on)
{
digitalWrite(A_LED_PIN, on?LED_OFF:LED_ON);
digitalWrite(C_LED_PIN, on?LED_ON:LED_OFF);
}
/*
* Read board voltage in millivolts
*/

View File

@ -371,8 +371,7 @@ test_ins(uint8_t argc, const Menu::arg *argv)
ahrs.init();
ahrs.set_fly_forward(true);
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
flash_leds);
ins_sample_rate);
ahrs.reset();
print_hit_enter();
@ -437,8 +436,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
// we need the AHRS initialised for this test
ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate,
flash_leds);
ins_sample_rate);
ahrs.reset();
int counter = 0;