Copter: remove unused flags and consolidate ap and ap_system

This commit is contained in:
Randy Mackay 2013-10-08 15:25:14 +09:00
parent 2bb497703c
commit 9435eb4a15
8 changed files with 30 additions and 58 deletions

View File

@ -123,22 +123,6 @@ void set_land_complete(bool b)
// ---------------------------------------------
void set_compass_healthy(bool b)
{
if(ap.compass_status != b) {
if(b) {
// compass has just recovered so log to the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_ERROR_RESOLVED);
}else{
// compass has just failed so log an error to the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_COMPASS_FAILED_TO_READ);
}
}
ap.compass_status = b;
}
// ---------------------------------------------
void set_pre_arm_check(bool b)
{
if(ap.pre_arm_check != b) {

View File

@ -388,25 +388,16 @@ static union {
uint8_t do_flip : 1; // 7 // Used to enable flip code
uint8_t takeoff_complete : 1; // 8
uint8_t land_complete : 1; // 9 // true if we have detected a landing
uint8_t compass_status : 1; // 10 // unused remove
uint8_t gps_status : 1; // 11 // unused remove
uint8_t new_radio_frame : 1; // 10 // Set true if we have new PWM data to act on from the Radio
uint8_t CH7_flag : 2; // 11,12 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH8_flag : 2; // 13,14 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t usb_connected : 1; // 15 // true if APM is powered from USB connection
uint8_t yaw_stopped : 1; // 16 // Used to manage the Yaw hold capabilities
};
uint32_t value;
} ap;
static struct AP_System{
uint8_t GPS_light : 1; // 0 // Solid indicates we have full 3D lock and can navigate, flash = read
uint8_t arming_light : 1; // 1 // Solid indicates armed state, flashing is disarmed, double flashing is disarmed and failing pre-arm checks
uint8_t new_radio_frame : 1; // 2 // Set true if we have new PWM data to act on from the Radio
uint8_t CH7_flag : 2; // 3,4 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t CH8_flag : 2; // 5,6 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high
uint8_t usb_connected : 1; // 7 // true if APM is powered from USB connection
uint8_t yaw_stopped : 1; // 8 // Used to manage the Yaw hold capabilities
uint8_t : 7; // 9-15 // Fill bit field to 16 bits
} ap_system;
////////////////////////////////////////////////////////////////////////////////
// Radio
////////////////////////////////////////////////////////////////////////////////
@ -1230,9 +1221,6 @@ static void slow_loop()
// check if we've lost contact with the ground station
failsafe_gcs_check();
// record if the compass is healthy
set_compass_healthy(compass.healthy);
if(superslow_loopCounter > 1200) {
#if HIL_MODE != HIL_MODE_ATTITUDE
if(g.rc_3.control_in == 0 && control_mode == STABILIZE && g.compass_enabled) {
@ -1814,7 +1802,7 @@ void update_roll_pitch_mode(void)
#if AUTOTUNE == ENABLED
case ROLL_PITCH_AUTOTUNE:
// apply SIMPLE mode transform
if(ap.simple_mode && ap_system.new_radio_frame) {
if(ap.simple_mode && ap.new_radio_frame) {
update_simple_mode();
}
@ -1837,9 +1825,9 @@ void update_roll_pitch_mode(void)
}
#endif //HELI_FRAME
if(ap_system.new_radio_frame) {
if(ap.new_radio_frame) {
// clear new radio frame info
ap_system.new_radio_frame = false;
ap.new_radio_frame = false;
}
}
@ -1867,7 +1855,7 @@ void update_simple_mode(void)
float rollx, pitchx;
// exit immediately if no new radio frame or not in simple mode
if (ap.simple_mode == 0 || !ap_system.new_radio_frame) {
if (ap.simple_mode == 0 || !ap.new_radio_frame) {
return;
}

View File

@ -73,22 +73,22 @@ static void read_aux_switches()
// check if ch7 switch has changed position
switch_position = read_3pos_switch(g.rc_7.radio_in);
if (ap_system.CH7_flag != switch_position) {
if (ap.CH7_flag != switch_position) {
// set the CH7 flag
ap_system.CH7_flag = switch_position;
ap.CH7_flag = switch_position;
// invoke the appropriate function
do_aux_switch_function(g.ch7_option, ap_system.CH7_flag);
do_aux_switch_function(g.ch7_option, ap.CH7_flag);
}
// check if Ch8 switch has changed position
switch_position = read_3pos_switch(g.rc_8.radio_in);
if (ap_system.CH8_flag != switch_position) {
if (ap.CH8_flag != switch_position) {
// set the CH8 flag
ap_system.CH8_flag = switch_position;
ap.CH8_flag = switch_position;
// invoke the appropriate function
do_aux_switch_function(g.ch8_option, ap_system.CH8_flag);
do_aux_switch_function(g.ch8_option, ap.CH8_flag);
}
}
@ -96,8 +96,8 @@ static void read_aux_switches()
static void init_aux_switches()
{
// set the CH7 flag
ap_system.CH7_flag = read_3pos_switch(g.rc_7.radio_in);
ap_system.CH8_flag = read_3pos_switch(g.rc_8.radio_in);
ap.CH7_flag = read_3pos_switch(g.rc_7.radio_in);
ap.CH8_flag = read_3pos_switch(g.rc_8.radio_in);
// init channel 7 options
switch(g.ch7_option) {
@ -108,7 +108,7 @@ static void init_aux_switches()
case AUX_SWITCH_SUPERSIMPLE_MODE:
case AUX_SWITCH_ACRO_TRAINER:
case AUX_SWITCH_SPRAYER:
do_aux_switch_function(g.ch7_option, ap_system.CH7_flag);
do_aux_switch_function(g.ch7_option, ap.CH7_flag);
break;
}
// init channel 8 option
@ -120,7 +120,7 @@ static void init_aux_switches()
case AUX_SWITCH_SUPERSIMPLE_MODE:
case AUX_SWITCH_ACRO_TRAINER:
case AUX_SWITCH_SPRAYER:
do_aux_switch_function(g.ch8_option, ap_system.CH8_flag);
do_aux_switch_function(g.ch8_option, ap.CH8_flag);
break;
}
}

View File

@ -118,7 +118,7 @@ static void update_copter_leds(void)
// AUX led control
if (g.copter_leds_mode & COPTER_LEDS_BITMASK_AUX) {
if (ap_system.CH7_flag) {
if (ap.CH7_flag) {
copter_leds_aux_on(); //if sub-control of Ch7 is high, turn Aux LED on
} else {
copter_leds_aux_off(); //if sub-control of Ch7 is low, turn Aux LED off

View File

@ -117,7 +117,7 @@ static void read_radio()
static uint32_t last_update = 0;
if (hal.rcin->valid_channels() > 0) {
last_update = millis();
ap_system.new_radio_frame = true;
ap.new_radio_frame = true;
uint16_t periods[8];
hal.rcin->read(periods,8);
g.rc_1.set_pwm(periods[rcmap.roll()-1]);

View File

@ -110,7 +110,7 @@ static void read_battery(void)
// check for low voltage or current if the low voltage check hasn't already been triggered
// we only check when we're not powered by USB to avoid false alarms during bench tests
if (!ap_system.usb_connected && !failsafe.low_battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
if (!ap.usb_connected && !failsafe.low_battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
low_battery_event();
}
}

View File

@ -135,7 +135,7 @@ static void init_ardupilot()
// we start by assuming USB connected, as we initialed the serial
// port with SERIAL0_BAUD. check_usb_mux() fixes this if need be.
ap_system.usb_connected = true;
ap.usb_connected = true;
check_usb_mux();
#if CONFIG_HAL_BOARD != HAL_BOARD_APM2
@ -526,19 +526,19 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
static void check_usb_mux(void)
{
bool usb_check = hal.gpio->usb_connected();
if (usb_check == ap_system.usb_connected) {
if (usb_check == ap.usb_connected) {
return;
}
// the user has switched to/from the telemetry port
ap_system.usb_connected = usb_check;
ap.usb_connected = usb_check;
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
// the APM2 has a MUX setup where the first serial port switches
// between USB and a TTL serial connection. When on USB we use
// SERIAL0_BAUD, but when connected as a TTL serial port we run it
// at SERIAL3_BAUD.
if (ap_system.usb_connected) {
if (ap.usb_connected) {
hal.uartA->begin(SERIAL0_BAUD);
} else {
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD));

View File

@ -97,15 +97,15 @@ void roll_pitch_toy()
if(g.rc_1.control_in != 0) { // roll
get_acro_yaw(yaw_rate/2);
ap_system.yaw_stopped = false;
ap.yaw_stopped = false;
yaw_timer = 150;
}else if (!ap_system.yaw_stopped) {
}else if (!ap.yaw_stopped) {
get_acro_yaw(0);
yaw_timer--;
if((yaw_timer == 0) || (fabsf(omega.z) < 0.17f)) {
ap_system.yaw_stopped = true;
ap.yaw_stopped = true;
nav_yaw = ahrs.yaw_sensor;
}
}else{