mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: Move Aux Switch flags into new Enum
This commit is contained in:
parent
8610da7fbc
commit
a357ef43a4
@ -341,24 +341,18 @@ static union {
|
||||
uint8_t logging_started : 1; // 6 // true if dataflash logging has started
|
||||
uint8_t land_complete : 1; // 7 // true if we have detected a landing
|
||||
uint8_t new_radio_frame : 1; // 8 // Set true if we have new PWM data to act on from the Radio
|
||||
uint8_t CH7_flag : 2; // 9,10 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH8_flag : 2; // 11,12 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH9_flag : 2; // 13,14 // ch9 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH10_flag : 2; // 15,16 // ch10 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH11_flag : 2; // 17,18 // ch11 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH12_flag : 2; // 19,20 // ch12 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t usb_connected : 1; // 21 // true if APM is powered from USB connection
|
||||
uint8_t rc_receiver_present : 1; // 22 // true if we have an rc receiver present (i.e. if we've ever received an update
|
||||
uint8_t compass_mot : 1; // 23 // true if we are currently performing compassmot calibration
|
||||
uint8_t motor_test : 1; // 24 // true if we are currently performing the motors test
|
||||
uint8_t initialised : 1; // 25 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
|
||||
uint8_t land_complete_maybe : 1; // 26 // true if we may have landed (less strict version of land_complete)
|
||||
uint8_t throttle_zero : 1; // 27 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
|
||||
uint8_t system_time_set : 1; // 28 // true if the system time has been set from the GPS
|
||||
uint8_t gps_base_pos_set : 1; // 29 // true when the gps base position has been set (used for RTK gps only)
|
||||
enum HomeState home_state : 2; // 30,31 // home status (unset, set, locked)
|
||||
uint8_t using_interlock : 1; // 32 // aux switch motor interlock function is in use
|
||||
uint8_t motor_estop : 1; // 33 // motor estop switch, shuts off motors when enabled
|
||||
uint8_t usb_connected : 1; // 9 // true if APM is powered from USB connection
|
||||
uint8_t rc_receiver_present : 1; // 10 // true if we have an rc receiver present (i.e. if we've ever received an update
|
||||
uint8_t compass_mot : 1; // 11 // true if we are currently performing compassmot calibration
|
||||
uint8_t motor_test : 1; // 12 // true if we are currently performing the motors test
|
||||
uint8_t initialised : 1; // 13 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
|
||||
uint8_t land_complete_maybe : 1; // 14 // true if we may have landed (less strict version of land_complete)
|
||||
uint8_t throttle_zero : 1; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
|
||||
uint8_t system_time_set : 1; // 16 // true if the system time has been set from the GPS
|
||||
uint8_t gps_base_pos_set : 1; // 17 // true when the gps base position has been set (used for RTK gps only)
|
||||
enum HomeState home_state : 2; // 18,19 // home status (unset, set, locked)
|
||||
uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use
|
||||
uint8_t motor_estop : 1; // 21 // motor estop switch, shuts off motors when enabled
|
||||
};
|
||||
uint32_t value;
|
||||
} ap;
|
||||
|
@ -2,6 +2,20 @@
|
||||
|
||||
#define CONTROL_SWITCH_DEBOUNCE_TIME_MS 200
|
||||
|
||||
//Documentation of Aux Switch Flags:
|
||||
static union {
|
||||
struct {
|
||||
uint8_t CH6_flag : 2; // 0, 1 // ch6 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH7_flag : 2; // 2, 3 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH8_flag : 2; // 4, 5 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH9_flag : 2; // 6, 7 // ch9 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH10_flag : 2; // 8, 9 // ch10 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH11_flag : 2; // 10,11 // ch11 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
uint8_t CH12_flag : 2; // 12,13 // ch12 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
||||
};
|
||||
uint32_t value;
|
||||
} aux_con;
|
||||
|
||||
static void read_control_switch()
|
||||
{
|
||||
uint32_t tnow_ms = millis();
|
||||
@ -115,65 +129,65 @@ static void read_aux_switches()
|
||||
|
||||
// check if ch7 switch has changed position
|
||||
switch_position = read_3pos_switch(g.rc_7.radio_in);
|
||||
if (ap.CH7_flag != switch_position) {
|
||||
if (aux_con.CH7_flag != switch_position) {
|
||||
// set the CH7 flag
|
||||
ap.CH7_flag = switch_position;
|
||||
aux_con.CH7_flag = switch_position;
|
||||
|
||||
// invoke the appropriate function
|
||||
do_aux_switch_function(g.ch7_option, ap.CH7_flag);
|
||||
do_aux_switch_function(g.ch7_option, aux_con.CH7_flag);
|
||||
}
|
||||
|
||||
// check if Ch8 switch has changed position
|
||||
switch_position = read_3pos_switch(g.rc_8.radio_in);
|
||||
if (ap.CH8_flag != switch_position) {
|
||||
if (aux_con.CH8_flag != switch_position) {
|
||||
// set the CH8 flag
|
||||
ap.CH8_flag = switch_position;
|
||||
aux_con.CH8_flag = switch_position;
|
||||
|
||||
// invoke the appropriate function
|
||||
do_aux_switch_function(g.ch8_option, ap.CH8_flag);
|
||||
do_aux_switch_function(g.ch8_option, aux_con.CH8_flag);
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
// check if Ch9 switch has changed position
|
||||
switch_position = read_3pos_switch(g.rc_9.radio_in);
|
||||
if (ap.CH9_flag != switch_position) {
|
||||
if (aux_con.CH9_flag != switch_position) {
|
||||
// set the CH9 flag
|
||||
ap.CH9_flag = switch_position;
|
||||
aux_con.CH9_flag = switch_position;
|
||||
|
||||
// invoke the appropriate function
|
||||
do_aux_switch_function(g.ch9_option, ap.CH9_flag);
|
||||
do_aux_switch_function(g.ch9_option, aux_con.CH9_flag);
|
||||
}
|
||||
#endif
|
||||
|
||||
// check if Ch10 switch has changed position
|
||||
switch_position = read_3pos_switch(g.rc_10.radio_in);
|
||||
if (ap.CH10_flag != switch_position) {
|
||||
if (aux_con.CH10_flag != switch_position) {
|
||||
// set the CH10 flag
|
||||
ap.CH10_flag = switch_position;
|
||||
aux_con.CH10_flag = switch_position;
|
||||
|
||||
// invoke the appropriate function
|
||||
do_aux_switch_function(g.ch10_option, ap.CH10_flag);
|
||||
do_aux_switch_function(g.ch10_option, aux_con.CH10_flag);
|
||||
}
|
||||
|
||||
// check if Ch11 switch has changed position
|
||||
switch_position = read_3pos_switch(g.rc_11.radio_in);
|
||||
if (ap.CH11_flag != switch_position) {
|
||||
if (aux_con.CH11_flag != switch_position) {
|
||||
// set the CH11 flag
|
||||
ap.CH11_flag = switch_position;
|
||||
aux_con.CH11_flag = switch_position;
|
||||
|
||||
// invoke the appropriate function
|
||||
do_aux_switch_function(g.ch11_option, ap.CH11_flag);
|
||||
do_aux_switch_function(g.ch11_option, aux_con.CH11_flag);
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
// check if Ch12 switch has changed position
|
||||
switch_position = read_3pos_switch(g.rc_12.radio_in);
|
||||
if (ap.CH12_flag != switch_position) {
|
||||
if (aux_con.CH12_flag != switch_position) {
|
||||
// set the CH12 flag
|
||||
ap.CH12_flag = switch_position;
|
||||
aux_con.CH12_flag = switch_position;
|
||||
|
||||
// invoke the appropriate function
|
||||
do_aux_switch_function(g.ch12_option, ap.CH12_flag);
|
||||
do_aux_switch_function(g.ch12_option, aux_con.CH12_flag);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
@ -182,27 +196,27 @@ static void read_aux_switches()
|
||||
static void init_aux_switches()
|
||||
{
|
||||
// set the CH7 ~ CH12 flags
|
||||
ap.CH7_flag = read_3pos_switch(g.rc_7.radio_in);
|
||||
ap.CH8_flag = read_3pos_switch(g.rc_8.radio_in);
|
||||
ap.CH10_flag = read_3pos_switch(g.rc_10.radio_in);
|
||||
ap.CH11_flag = read_3pos_switch(g.rc_11.radio_in);
|
||||
aux_con.CH7_flag = read_3pos_switch(g.rc_7.radio_in);
|
||||
aux_con.CH8_flag = read_3pos_switch(g.rc_8.radio_in);
|
||||
aux_con.CH10_flag = read_3pos_switch(g.rc_10.radio_in);
|
||||
aux_con.CH11_flag = read_3pos_switch(g.rc_11.radio_in);
|
||||
|
||||
// ch9, ch12 only supported on some boards
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
ap.CH9_flag = read_3pos_switch(g.rc_9.radio_in);
|
||||
ap.CH12_flag = read_3pos_switch(g.rc_12.radio_in);
|
||||
aux_con.CH9_flag = read_3pos_switch(g.rc_9.radio_in);
|
||||
aux_con.CH12_flag = read_3pos_switch(g.rc_12.radio_in);
|
||||
#endif
|
||||
|
||||
// initialise functions assigned to switches
|
||||
init_aux_switch_function(g.ch7_option, ap.CH7_flag);
|
||||
init_aux_switch_function(g.ch8_option, ap.CH8_flag);
|
||||
init_aux_switch_function(g.ch10_option, ap.CH10_flag);
|
||||
init_aux_switch_function(g.ch11_option, ap.CH11_flag);
|
||||
init_aux_switch_function(g.ch7_option, aux_con.CH7_flag);
|
||||
init_aux_switch_function(g.ch8_option, aux_con.CH8_flag);
|
||||
init_aux_switch_function(g.ch10_option, aux_con.CH10_flag);
|
||||
init_aux_switch_function(g.ch11_option, aux_con.CH11_flag);
|
||||
|
||||
// ch9, ch12 only supported on some boards
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
init_aux_switch_function(g.ch9_option, ap.CH9_flag);
|
||||
init_aux_switch_function(g.ch12_option, ap.CH12_flag);
|
||||
init_aux_switch_function(g.ch9_option, aux_con.CH9_flag);
|
||||
init_aux_switch_function(g.ch12_option, aux_con.CH12_flag);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user