Browse Source

Copter: integrate Toshiba_LED_PX4

mission-4.1.18
Randy Mackay 12 years ago committed by Andrew Tridgell
parent
commit
52ef77393c
  1. 11
      ArduCopter/AP_State.pde
  2. 6
      ArduCopter/ArduCopter.pde
  3. 4
      ArduCopter/control_modes.pde
  4. 2
      ArduCopter/leds.pde
  5. 4
      ArduCopter/motors.pde
  6. 2
      ArduCopter/radio.pde
  7. 2
      ArduCopter/setup.pde

11
ArduCopter/AP_State.pde

@ -127,3 +127,14 @@ void set_compass_healthy(bool b) @@ -127,3 +127,14 @@ void set_compass_healthy(bool b)
}
ap.compass_status = b;
}
// ---------------------------------------------
void set_pre_arm_check(bool b)
{
if(ap.pre_arm_check != b) {
ap.pre_arm_check = b;
AP_Notify::flags.pre_arm_check = b;
}
}

6
ArduCopter/ArduCopter.pde

@ -107,6 +107,7 @@ @@ -107,6 +107,7 @@
#include <AP_Scheduler.h> // main loop scheduler
#include <AP_RCMapper.h> // RC input mapping library
#include <ToshibaLED.h> // ToshibaLED library
#include <ToshibaLED_PX4.h> // ToshibaLED library
// AP_HAL to Arduino compatibility layer
#include "compat.h"
@ -150,7 +151,12 @@ static AP_Scheduler scheduler; @@ -150,7 +151,12 @@ static AP_Scheduler scheduler;
static AP_BoardLED board_led;
// Toshiba LED instance
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
static ToshibaLED_PX4 toshiba_led;
#else
static ToshibaLED toshiba_led;
#endif
////////////////////////////////////////////////////////////////////////////////
// prototypes

4
ArduCopter/control_modes.pde

@ -295,7 +295,7 @@ static void auto_trim() @@ -295,7 +295,7 @@ static void auto_trim()
auto_trim_counter--;
// flash the leds
notify.flags.save_trim = true;
AP_Notify::flags.save_trim = true;
// calculate roll trim adjustment
float roll_trim_adjustment = ToRad((float)g.rc_1.control_in / 4000.0f);
@ -313,7 +313,7 @@ static void auto_trim() @@ -313,7 +313,7 @@ static void auto_trim()
// on last iteration restore leds and accel gains to normal
if(auto_trim_counter == 0) {
ahrs.set_fast_gains(false);
notify.flags.save_trim = false;
AP_Notify::flags.save_trim = false;
}
}
}

2
ArduCopter/leds.pde

@ -4,7 +4,7 @@ @@ -4,7 +4,7 @@
// should be called at 50hz ~ 100hz
static void update_toshiba_led()
{
toshiba_led.update();
AP_Notify::update();
}
/////////////////////////////////////////////////////////////////////////////////////////////

4
ArduCopter/motors.pde

@ -217,7 +217,7 @@ static void pre_arm_checks(bool display_failure) @@ -217,7 +217,7 @@ static void pre_arm_checks(bool display_failure)
// succeed if pre arm checks are disabled
if(!g.arming_check_enabled) {
ap.pre_arm_check = true;
set_pre_arm_check(true);
return;
}
@ -328,7 +328,7 @@ static void pre_arm_checks(bool display_failure) @@ -328,7 +328,7 @@ static void pre_arm_checks(bool display_failure)
}
// if we've gotten this far then pre arm checks have completed
ap.pre_arm_check = true;
set_pre_arm_check(true);
}
// perform pre_arm_rc_checks checks and set ap.pre_arm_rc_check flag

2
ArduCopter/radio.pde

@ -75,7 +75,7 @@ static void init_rc_out() @@ -75,7 +75,7 @@ static void init_rc_out()
// display message on console
cliSerial->printf_P(PSTR("Entering ESC Calibration: please restart APM.\n"));
// turn on esc calibration notification
notify.flags.esc_calibration = true;
AP_Notify::flags.esc_calibration = true;
// block until we restart
while(1) {}
}else{

2
ArduCopter/setup.pde

@ -1356,7 +1356,7 @@ init_esc() @@ -1356,7 +1356,7 @@ init_esc()
while(1) {
read_radio();
delay(100);
notify.flags.esc_calibration = true;
AP_Notify::flags.esc_calibration = true;
motors.throttle_pass_through();
}
}

Loading…
Cancel
Save