mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
uncrustify ArduCopter/system.pde
This commit is contained in:
parent
4ae0b9dc8a
commit
06031868d8
@ -1,9 +1,9 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
/*****************************************************************************
|
/*****************************************************************************
|
||||||
The init_ardupilot function processes everything we need for an in - air restart
|
* The init_ardupilot function processes everything we need for an in - air restart
|
||||||
We will determine later if we are actually on the ground and process a
|
* We will determine later if we are actually on the ground and process a
|
||||||
ground start in that case.
|
* ground start in that case.
|
||||||
|
*
|
||||||
*****************************************************************************/
|
*****************************************************************************/
|
||||||
|
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
@ -82,11 +82,11 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
// GPS serial port.
|
// GPS serial port.
|
||||||
//
|
//
|
||||||
#if GPS_PROTOCOL != GPS_PROTOCOL_IMU
|
#if GPS_PROTOCOL != GPS_PROTOCOL_IMU
|
||||||
// standard gps running. Note that we need a 256 byte buffer for some
|
// standard gps running. Note that we need a 256 byte buffer for some
|
||||||
// GPS types (eg. UBLOX)
|
// GPS types (eg. UBLOX)
|
||||||
Serial1.begin(38400, 256, 16);
|
Serial1.begin(38400, 256, 16);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
|
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
|
||||||
"\n\nFree RAM: %u\n"),
|
"\n\nFree RAM: %u\n"),
|
||||||
@ -143,7 +143,7 @@ static void init_ardupilot()
|
|||||||
pinMode(COPTER_LED_7, OUTPUT); //Motor or GPS LED
|
pinMode(COPTER_LED_7, OUTPUT); //Motor or GPS LED
|
||||||
pinMode(COPTER_LED_8, OUTPUT); //Motor or GPS LED
|
pinMode(COPTER_LED_8, OUTPUT); //Motor or GPS LED
|
||||||
|
|
||||||
if ( !bitRead(g.copter_leds_mode, 3) ){
|
if ( !bitRead(g.copter_leds_mode, 3) ) {
|
||||||
piezo_beep();
|
piezo_beep();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -181,22 +181,22 @@ static void init_ardupilot()
|
|||||||
gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS"));
|
gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS"));
|
||||||
do_erase_logs();
|
do_erase_logs();
|
||||||
}
|
}
|
||||||
if (g.log_bitmask != 0){
|
if (g.log_bitmask != 0) {
|
||||||
DataFlash.start_new_log();
|
DataFlash.start_new_log();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef RADIO_OVERRIDE_DEFAULTS
|
#ifdef RADIO_OVERRIDE_DEFAULTS
|
||||||
{
|
{
|
||||||
int16_t rc_override[8] = RADIO_OVERRIDE_DEFAULTS;
|
int16_t rc_override[8] = RADIO_OVERRIDE_DEFAULTS;
|
||||||
APM_RC.setHIL(rc_override);
|
APM_RC.setHIL(rc_override);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
motors.servo_manual = false;
|
motors.servo_manual = false;
|
||||||
motors.init_swash(); // heli initialisation
|
motors.init_swash(); // heli initialisation
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
RC_Channel::set_apm_rc(&APM_RC);
|
RC_Channel::set_apm_rc(&APM_RC);
|
||||||
init_rc_in(); // sets up rc channels from radio
|
init_rc_in(); // sets up rc channels from radio
|
||||||
@ -208,10 +208,10 @@ static void init_ardupilot()
|
|||||||
AP_AnalogSource_Arduino::init_timer(&timer_scheduler);
|
AP_AnalogSource_Arduino::init_timer(&timer_scheduler);
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
#if CONFIG_ADC == ENABLED
|
#if CONFIG_ADC == ENABLED
|
||||||
// begin filtering the ADC Gyros
|
// begin filtering the ADC Gyros
|
||||||
adc.Init(&timer_scheduler); // APM ADC library initialization
|
adc.Init(&timer_scheduler); // APM ADC library initialization
|
||||||
#endif // CONFIG_ADC
|
#endif // CONFIG_ADC
|
||||||
|
|
||||||
barometer.init(&timer_scheduler);
|
barometer.init(&timer_scheduler);
|
||||||
|
|
||||||
@ -255,11 +255,11 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
GPS_enabled = false;
|
GPS_enabled = false;
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_DISABLED
|
#if HIL_MODE == HIL_MODE_DISABLED
|
||||||
// Read in the GPS
|
// Read in the GPS
|
||||||
for (byte counter = 0; ; counter++) {
|
for (byte counter = 0;; counter++) {
|
||||||
g_gps->update();
|
g_gps->update();
|
||||||
if (g_gps->status() != 0){
|
if (g_gps->status() != 0) {
|
||||||
GPS_enabled = true;
|
GPS_enabled = true;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -269,9 +269,9 @@ static void init_ardupilot()
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
GPS_enabled = true;
|
GPS_enabled = true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// lengthen the idle timeout for gps Auto_detect
|
// lengthen the idle timeout for gps Auto_detect
|
||||||
// ---------------------------------------------
|
// ---------------------------------------------
|
||||||
@ -281,16 +281,16 @@ static void init_ardupilot()
|
|||||||
// --------------------
|
// --------------------
|
||||||
report_gps();
|
report_gps();
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
// read Baro pressure at ground
|
// read Baro pressure at ground
|
||||||
//-----------------------------
|
//-----------------------------
|
||||||
init_barometer();
|
init_barometer();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// initialise sonar
|
// initialise sonar
|
||||||
#if CONFIG_SONAR == ENABLED
|
#if CONFIG_SONAR == ENABLED
|
||||||
init_sonar();
|
init_sonar();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// initialize commands
|
// initialize commands
|
||||||
// -------------------
|
// -------------------
|
||||||
@ -302,9 +302,9 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
// init the Z damopener
|
// init the Z damopener
|
||||||
// --------------------
|
// --------------------
|
||||||
#if ACCEL_ALT_HOLD != 0
|
#if ACCEL_ALT_HOLD != 0
|
||||||
init_z_damper();
|
init_z_damper();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
startup_ground();
|
startup_ground();
|
||||||
@ -378,14 +378,14 @@ static void startup_ground(void)
|
|||||||
{
|
{
|
||||||
gcs_send_text_P(SEVERITY_LOW,PSTR("GROUND START"));
|
gcs_send_text_P(SEVERITY_LOW,PSTR("GROUND START"));
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
// Warm up and read Gyro offsets
|
// Warm up and read Gyro offsets
|
||||||
// -----------------------------
|
// -----------------------------
|
||||||
imu.init(IMU::COLD_START, mavlink_delay, flash_leds, &timer_scheduler);
|
imu.init(IMU::COLD_START, mavlink_delay, flash_leds, &timer_scheduler);
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
report_imu();
|
report_imu();
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// initialise ahrs (may push imu calibration into the mpu6000 if using that device).
|
// initialise ahrs (may push imu calibration into the mpu6000 if using that device).
|
||||||
ahrs.init();
|
ahrs.init();
|
||||||
@ -403,36 +403,36 @@ static void startup_ground(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
#define YAW_HOLD 0
|
* #define YAW_HOLD 0
|
||||||
#define YAW_ACRO 1
|
* #define YAW_ACRO 1
|
||||||
#define YAW_AUTO 2
|
* #define YAW_AUTO 2
|
||||||
#define YAW_LOOK_AT_HOME 3
|
* #define YAW_LOOK_AT_HOME 3
|
||||||
|
*
|
||||||
#define ROLL_PITCH_STABLE 0
|
* #define ROLL_PITCH_STABLE 0
|
||||||
#define ROLL_PITCH_ACRO 1
|
* #define ROLL_PITCH_ACRO 1
|
||||||
#define ROLL_PITCH_AUTO 2
|
* #define ROLL_PITCH_AUTO 2
|
||||||
|
*
|
||||||
#define THROTTLE_MANUAL 0
|
* #define THROTTLE_MANUAL 0
|
||||||
#define THROTTLE_HOLD 1
|
* #define THROTTLE_HOLD 1
|
||||||
#define THROTTLE_AUTO 2
|
* #define THROTTLE_AUTO 2
|
||||||
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
static void set_mode(byte mode)
|
static void set_mode(byte mode)
|
||||||
{
|
{
|
||||||
// if we don't have GPS lock
|
// if we don't have GPS lock
|
||||||
if(home_is_set == false){
|
if(home_is_set == false) {
|
||||||
// THOR
|
// THOR
|
||||||
// We don't care about Home if we don't have lock yet in Toy mode
|
// We don't care about Home if we don't have lock yet in Toy mode
|
||||||
if(mode == TOY_A || mode == TOY_M || mode == OF_LOITER){
|
if(mode == TOY_A || mode == TOY_M || mode == OF_LOITER) {
|
||||||
// nothing
|
// nothing
|
||||||
}else if (mode > ALT_HOLD){
|
}else if (mode > ALT_HOLD) {
|
||||||
mode = STABILIZE;
|
mode = STABILIZE;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// nothing but OF_LOITER for OptFlow only
|
// nothing but OF_LOITER for OptFlow only
|
||||||
if (g.optflow_enabled && GPS_enabled == false){
|
if (g.optflow_enabled && GPS_enabled == false) {
|
||||||
if (mode > ALT_HOLD && mode != OF_LOITER)
|
if (mode > ALT_HOLD && mode != OF_LOITER)
|
||||||
mode = STABILIZE;
|
mode = STABILIZE;
|
||||||
}
|
}
|
||||||
@ -579,7 +579,7 @@ static void set_mode(byte mode)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(failsafe){
|
if(failsafe) {
|
||||||
// this is to allow us to fly home without interactive throttle control
|
// this is to allow us to fly home without interactive throttle control
|
||||||
throttle_mode = THROTTLE_AUTO;
|
throttle_mode = THROTTLE_AUTO;
|
||||||
// does not wait for us to be in high throttle, since the
|
// does not wait for us to be in high throttle, since the
|
||||||
@ -587,7 +587,7 @@ static void set_mode(byte mode)
|
|||||||
motors.auto_armed(true);
|
motors.auto_armed(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
if(roll_pitch_mode <= ROLL_PITCH_ACRO){
|
if(roll_pitch_mode <= ROLL_PITCH_ACRO) {
|
||||||
// We are under manual attitude control
|
// We are under manual attitude control
|
||||||
// remove the navigation from roll and pitch command
|
// remove the navigation from roll and pitch command
|
||||||
reset_nav_params();
|
reset_nav_params();
|
||||||
@ -604,13 +604,13 @@ static void set_failsafe(boolean mode)
|
|||||||
{
|
{
|
||||||
// only act on changes
|
// only act on changes
|
||||||
// -------------------
|
// -------------------
|
||||||
if(failsafe != mode){
|
if(failsafe != mode) {
|
||||||
|
|
||||||
// store the value so we don't trip the gate twice
|
// store the value so we don't trip the gate twice
|
||||||
// -----------------------------------------------
|
// -----------------------------------------------
|
||||||
failsafe = mode;
|
failsafe = mode;
|
||||||
|
|
||||||
if (failsafe == false){
|
if (failsafe == false) {
|
||||||
// We've regained radio contact
|
// We've regained radio contact
|
||||||
// ----------------------------
|
// ----------------------------
|
||||||
failsafe_off_event();
|
failsafe_off_event();
|
||||||
@ -631,7 +631,7 @@ init_simple_bearing()
|
|||||||
|
|
||||||
static void update_throttle_cruise(int16_t tmp)
|
static void update_throttle_cruise(int16_t tmp)
|
||||||
{
|
{
|
||||||
if(tmp != 0){
|
if(tmp != 0) {
|
||||||
g.throttle_cruise += tmp;
|
g.throttle_cruise += tmp;
|
||||||
reset_throttle_I();
|
reset_throttle_I();
|
||||||
}
|
}
|
||||||
@ -650,7 +650,7 @@ check_startup_for_CLI()
|
|||||||
#endif // CLI_ENABLED
|
#endif // CLI_ENABLED
|
||||||
|
|
||||||
/*
|
/*
|
||||||
map from a 8 bit EEPROM baud rate to a real baud rate
|
* map from a 8 bit EEPROM baud rate to a real baud rate
|
||||||
*/
|
*/
|
||||||
static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
||||||
{
|
{
|
||||||
@ -688,13 +688,13 @@ static void check_usb_mux(void)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
called by gyro/accel init to flash LEDs so user
|
* called by gyro/accel init to flash LEDs so user
|
||||||
has some mesmerising lights to watch while waiting
|
* has some mesmerising lights to watch while waiting
|
||||||
*/
|
*/
|
||||||
void flash_leds(bool on)
|
void flash_leds(bool on)
|
||||||
{
|
{
|
||||||
digitalWrite(A_LED_PIN, on?LED_OFF:LED_ON);
|
digitalWrite(A_LED_PIN, on ? LED_OFF : LED_ON);
|
||||||
digitalWrite(C_LED_PIN, on?LED_ON:LED_OFF);
|
digitalWrite(C_LED_PIN, on ? LED_ON : LED_OFF);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifndef DESKTOP_BUILD
|
#ifndef DESKTOP_BUILD
|
||||||
|
Loading…
Reference in New Issue
Block a user