From bcb9519fd7461233fcaa9129e57c3eb46114d3fd Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 11 Nov 2012 22:42:10 +0900 Subject: [PATCH] ArduCopter: renamed system bitmap to ap_system to resolve desktop compile issues --- ArduCopter/ArduCopter.pde | 26 +++++++++++++------------- ArduCopter/GCS_Mavlink.pde | 2 +- ArduCopter/control_modes.pde | 22 +++++++++++----------- ArduCopter/leds.pde | 14 +++++++------- ArduCopter/motors.pde | 2 +- ArduCopter/radio.pde | 2 +- ArduCopter/system.pde | 12 ++++++------ ArduCopter/toy.pde | 6 +++--- 8 files changed, 43 insertions(+), 43 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index c256eec258..13782b3c62 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -403,12 +403,12 @@ static struct AP_System{ uint8_t new_radio_frame : 1; // 3 // Set true if we have new PWM data to act on from the Radio uint8_t nav_ok : 1; // 4 // deprecated uint8_t CH7_flag : 1; // 5 // manages state of the ch7 toggle switch - uint8_t usb_connected : 1; // 6 // manages state of the ch7 toggle switch + uint8_t usb_connected : 1; // 6 // true if APM is powered from USB connection uint8_t run_50hz_loop : 1; // 7 // toggles the 100hz loop for 50hz uint8_t alt_sensor_flag : 1; // 8 // used to track when to read sensors vs estimate alt uint8_t yaw_stopped : 1; // 9 // Used to manage the Yaw hold capabilities -}system; +} ap_system; //////////////////////////////////////////////////////////////////////////////// @@ -972,9 +972,9 @@ void loop() fast_loop(); // run the 50hz loop 1/2 the time - system.run_50hz_loop = !system.run_50hz_loop; + ap_system.run_50hz_loop = !ap_system.run_50hz_loop; - if(system.run_50hz_loop) { + if(ap_system.run_50hz_loop) { #if DEBUG_MED_LOOP == ENABLED Log_Write_Data(DATA_MED_LOOP, (int32_t)(timer - fiftyhz_loopTimer)); @@ -1143,7 +1143,7 @@ static void medium_loop() } } - system.alt_sensor_flag = true; + ap_system.alt_sensor_flag = true; break; // This case deals with sending high rate telemetry @@ -1491,7 +1491,7 @@ static void update_GPS(void) #if HIL_MODE == HIL_MODE_ATTITUDE // only execute in HIL mode //update_altitude(); - system.alt_sensor_flag = true; + ap_system.alt_sensor_flag = true; #endif } @@ -1572,7 +1572,7 @@ void update_roll_pitch_mode(void) case ROLL_PITCH_STABLE: // apply SIMPLE mode transform - if(ap.simple_mode && system.new_radio_frame) { + if(ap.simple_mode && ap_system.new_radio_frame) { update_simple_mode(); } @@ -1586,7 +1586,7 @@ void update_roll_pitch_mode(void) case ROLL_PITCH_AUTO: // apply SIMPLE mode transform - if(ap.simple_mode && system.new_radio_frame) { + if(ap.simple_mode && ap_system.new_radio_frame) { update_simple_mode(); } // mix in user control with Nav control @@ -1602,7 +1602,7 @@ void update_roll_pitch_mode(void) case ROLL_PITCH_STABLE_OF: // apply SIMPLE mode transform - if(ap.simple_mode && system.new_radio_frame) { + if(ap.simple_mode && ap_system.new_radio_frame) { update_simple_mode(); } @@ -1632,9 +1632,9 @@ void update_roll_pitch_mode(void) //reset_stability_I(); //} - if(system.new_radio_frame) { + if(ap_system.new_radio_frame) { // clear new radio frame info - system.new_radio_frame = false; + ap_system.new_radio_frame = false; // These values can be used to scale the PID gains // This allows for a simple gain scheduling implementation @@ -1954,9 +1954,9 @@ static void update_altitude() static void update_altitude_est() { - if(system.alt_sensor_flag) { + if(ap_system.alt_sensor_flag) { update_altitude(); - system.alt_sensor_flag = false; + ap_system.alt_sensor_flag = false; if(g.log_bitmask & MASK_LOG_CTUN && motors.armed()) { Log_Write_Control_Tuning(); diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 27d744b07c..de055e3eb9 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -471,7 +471,7 @@ static bool telemetry_delayed(mavlink_channel_t chan) return false; } #if USB_MUX_PIN > 0 - if (chan == MAVLINK_COMM_0 && system.usb_connected) { + if (chan == MAVLINK_COMM_0 && ap_system.usb_connected) { // this is an APM2 with USB telemetry return false; } diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index a35bfc3126..05cfc602ed 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -65,26 +65,26 @@ static void read_trim_switch() set_simple_mode(g.rc_7.radio_in > CH_7_PWM_TRIGGER); }else if (option == CH7_FLIP) { - if (system.CH7_flag == false && g.rc_7.radio_in > CH_7_PWM_TRIGGER) { - system.CH7_flag = true; + if (ap_system.CH7_flag == false && g.rc_7.radio_in > CH_7_PWM_TRIGGER) { + ap_system.CH7_flag = true; // don't flip if we accidentally engaged flip, but didn't notice and tried to takeoff if(g.rc_3.control_in != 0 && ap.takeoff_complete) { init_flip(); } } - if (system.CH7_flag == true && g.rc_7.control_in < 800) { - system.CH7_flag = false; + if (ap_system.CH7_flag == true && g.rc_7.control_in < 800) { + ap_system.CH7_flag = false; } }else if (option == CH7_RTL) { - if (system.CH7_flag == false && g.rc_7.radio_in > CH_7_PWM_TRIGGER) { - system.CH7_flag = true; + if (ap_system.CH7_flag == false && g.rc_7.radio_in > CH_7_PWM_TRIGGER) { + ap_system.CH7_flag = true; set_mode(RTL); } - if (system.CH7_flag == true && g.rc_7.control_in < 800) { - system.CH7_flag = false; + if (ap_system.CH7_flag == true && g.rc_7.control_in < 800) { + ap_system.CH7_flag = false; if (control_mode == RTL || control_mode == LOITER) { reset_control_switch(); } @@ -92,11 +92,11 @@ static void read_trim_switch() }else if (option == CH7_SAVE_WP) { if (g.rc_7.radio_in > CH_7_PWM_TRIGGER) { // switch is engaged - system.CH7_flag = true; + ap_system.CH7_flag = true; }else{ // switch is disengaged - if(system.CH7_flag) { - system.CH7_flag = false; + if(ap_system.CH7_flag) { + ap_system.CH7_flag = false; if(control_mode == AUTO) { // reset the mission diff --git a/ArduCopter/leds.pde b/ArduCopter/leds.pde index 8957a133f7..18b2232629 100644 --- a/ArduCopter/leds.pde +++ b/ArduCopter/leds.pde @@ -28,8 +28,8 @@ static void update_GPS_light(void) case (1): if (g_gps->valid_read == true) { - system.GPS_light = !system.GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock - if (system.GPS_light) { + ap_system.GPS_light = !ap_system.GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock + if (ap_system.GPS_light) { digitalWrite(C_LED_PIN, LED_OFF); }else{ digitalWrite(C_LED_PIN, LED_ON); @@ -47,17 +47,17 @@ static void update_GPS_light(void) static void update_motor_light(void) { if(motors.armed() == false) { - system.motor_light = !system.motor_light; + ap_system.motor_light = !ap_system.motor_light; // blink - if(system.motor_light) { + if(ap_system.motor_light) { digitalWrite(A_LED_PIN, LED_ON); }else{ digitalWrite(A_LED_PIN, LED_OFF); } }else{ - if(!system.motor_light) { - system.motor_light = true; + if(!ap_system.motor_light) { + ap_system.motor_light = true; digitalWrite(A_LED_PIN, LED_ON); } } @@ -93,7 +93,7 @@ static void clear_leds() digitalWrite(A_LED_PIN, LED_OFF); digitalWrite(B_LED_PIN, LED_OFF); digitalWrite(C_LED_PIN, LED_OFF); - system.motor_light = false; + ap_system.motor_light = false; led_mode = NORMAL_LEDS; } diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index dca40fd953..0aa6d0fe7a 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -143,7 +143,7 @@ static void init_arm_motors() #endif // temp hack - system.motor_light = true; + ap_system.motor_light = true; digitalWrite(A_LED_PIN, LED_ON); // go back to normal AHRS gains diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 2dc9be1ee3..8c5e761ef5 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -127,7 +127,7 @@ void output_min() static void read_radio() { if (APM_RC.GetState() == 1) { - system.new_radio_frame = true; + ap_system.new_radio_frame = true; g.rc_1.set_pwm(APM_RC.InputCh(CH_1)); g.rc_2.set_pwm(APM_RC.InputCh(CH_2)); diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 910235f82e..9d29d41f5e 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -62,8 +62,8 @@ static void init_ardupilot() // USB_MUX_PIN pinMode(USB_MUX_PIN, INPUT); - system.usb_connected = !digitalRead(USB_MUX_PIN); - if (!system.usb_connected) { + ap_system.usb_connected = !digitalRead(USB_MUX_PIN); + if (!ap_system.usb_connected) { // USB is not connected, this means UART0 may be a Xbee, with // its darned bricking problem. We can't write to it for at // least one second after powering up. Simplest solution for @@ -163,7 +163,7 @@ static void init_ardupilot() gcs0.init(&Serial); #if USB_MUX_PIN > 0 - if (!system.usb_connected) { + if (!ap_system.usb_connected) { // we are not connected via USB, re-init UART0 with right // baud rate Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD)); @@ -640,13 +640,13 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud) static void check_usb_mux(void) { bool usb_check = !digitalRead(USB_MUX_PIN); - if (usb_check == system.usb_connected) { + if (usb_check == ap_system.usb_connected) { return; } // the user has switched to/from the telemetry port - system.usb_connected = usb_check; - if (system.usb_connected) { + ap_system.usb_connected = usb_check; + if (ap_system.usb_connected) { Serial.begin(SERIAL0_BAUD); } else { Serial.begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD)); diff --git a/ArduCopter/toy.pde b/ArduCopter/toy.pde index a0a7a88bb5..11ee199bfb 100644 --- a/ArduCopter/toy.pde +++ b/ArduCopter/toy.pde @@ -110,15 +110,15 @@ void roll_pitch_toy() if(g.rc_1.control_in != 0) { // roll get_acro_yaw(yaw_rate/2); - system.yaw_stopped = false; + ap_system.yaw_stopped = false; yaw_timer = 150; - }else if (!system.yaw_stopped) { + }else if (!ap_system.yaw_stopped) { get_acro_yaw(0); yaw_timer--; if((yaw_timer == 0) || (fabs(omega.z) < .17)) { - system.yaw_stopped = true; + ap_system.yaw_stopped = true; nav_yaw = ahrs.yaw_sensor; } }else{