Copter: ch8 aux switch
Ch8 can be used as an aux switch like ch7. Has all the same options as ch7 and there is a safety check to ensure both switches aren't set to the same function so as to avoid interfering with each other
This commit is contained in:
parent
566daf883a
commit
38239c652a
@ -386,10 +386,11 @@ static union {
|
||||
|
||||
|
||||
static struct AP_System{
|
||||
uint8_t GPS_light : 1; // 1 // Solid indicates we have full 3D lock and can navigate, flash = read
|
||||
uint8_t motor_light : 1; // 2 // Solid indicates Armed state
|
||||
uint8_t new_radio_frame : 1; // 3 // Set true if we have new PWM data to act on from the Radio
|
||||
uint8_t CH7_flag : 1; // 4 // manages state of the ch7 toggle switch
|
||||
uint8_t GPS_light : 1; // 0 // Solid indicates we have full 3D lock and can navigate, flash = read
|
||||
uint8_t motor_light : 1; // 1 // Solid indicates Armed state
|
||||
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 : 1; // 3 // true if ch7 aux switch is high
|
||||
uint8_t CH8_flag : 1; // 4 // true if ch8 aux switch is high
|
||||
uint8_t usb_connected : 1; // 5 // true if APM is powered from USB connection
|
||||
uint8_t yaw_stopped : 1; // 6 // Used to manage the Yaw hold capabilities
|
||||
|
||||
@ -586,11 +587,11 @@ static uint32_t loiter_time;
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// CH7 control
|
||||
// CH7 and CH8 save waypoint control
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// This register tracks the current Mission Command index when writing
|
||||
// a mission using CH7 in flight
|
||||
static int8_t CH7_wp_index;
|
||||
// a mission using Ch7 or Ch8 aux switches in flight
|
||||
static int8_t aux_switch_wp_index;
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -1102,10 +1103,8 @@ static void medium_loop()
|
||||
case 4:
|
||||
medium_loopCounter = 0;
|
||||
|
||||
// Accel trims = hold > 2 seconds
|
||||
// Throttle cruise = switch less than 1 second
|
||||
// --------------------------------------------
|
||||
read_trim_switch();
|
||||
// check ch7 and ch8 aux switches
|
||||
read_aux_switches();
|
||||
|
||||
// Check for engine arming
|
||||
// -----------------------
|
||||
|
@ -82,7 +82,8 @@ public:
|
||||
k_param_acro_trainer_enabled,
|
||||
k_param_pilot_velocity_z_max,
|
||||
k_param_circle_rate,
|
||||
k_param_sonar_gain, // 30
|
||||
k_param_sonar_gain,
|
||||
k_param_ch8_option, // 31
|
||||
|
||||
// 65: AP_Limits Library
|
||||
k_param_limits = 65, // deprecated - remove
|
||||
@ -337,6 +338,7 @@ public:
|
||||
AP_Int16 radio_tuning_low;
|
||||
AP_Int8 frame_orientation;
|
||||
AP_Int8 ch7_option;
|
||||
AP_Int8 ch8_option;
|
||||
AP_Int16 auto_slew_rate;
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
|
@ -412,6 +412,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
||||
|
||||
// @Param: CH8_OPT
|
||||
// @DisplayName: Channel 8 option
|
||||
// @Description: Select which function if performed when CH8 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:Sonar
|
||||
// @User: Standard
|
||||
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
||||
|
||||
// @Param: AUTO_SLEW
|
||||
// @DisplayName: Auto Slew Rate
|
||||
// @Description: This restricts the rate of change of the roll and pitch attitude commanded by the auto pilot
|
||||
|
@ -310,13 +310,16 @@
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Channel 7 default option
|
||||
// Channel 7 and 8 default options
|
||||
//
|
||||
|
||||
#ifndef CH7_OPTION
|
||||
# define CH7_OPTION CH7_SAVE_WP
|
||||
# define CH7_OPTION AUX_SWITCH_SAVE_WP
|
||||
#endif
|
||||
|
||||
#ifndef CH8_OPTION
|
||||
# define CH8_OPTION AUX_SWITCH_DO_NOTHING
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// HIL_MODE OPTIONAL
|
||||
|
@ -17,7 +17,7 @@ static void read_control_switch()
|
||||
if( !ap.failsafe_radio ) {
|
||||
set_mode(flight_modes[switchPosition]);
|
||||
|
||||
if(g.ch7_option != CH7_SIMPLE_MODE) {
|
||||
if(g.ch7_option != AUX_SWITCH_SIMPLE_MODE && g.ch8_option != AUX_SWITCH_SIMPLE_MODE) {
|
||||
// set Simple mode using stored paramters from Mission planner
|
||||
// rather than by the control switch
|
||||
set_simple_mode(BIT_IS_SET(g.simple_modes, switchPosition));
|
||||
@ -48,47 +48,62 @@ static void reset_control_switch()
|
||||
read_control_switch();
|
||||
}
|
||||
|
||||
// read at 10 hz
|
||||
// set this to your trainer switch
|
||||
static void read_trim_switch()
|
||||
// read_aux_switches - checks aux switch positions and invokes configured actions
|
||||
static void read_aux_switches()
|
||||
{
|
||||
// return immediately if the CH7 switch has not changed position
|
||||
if (ap_system.CH7_flag == (g.rc_7.radio_in >= CH7_PWM_TRIGGER)) {
|
||||
// check if ch7 switch has changed position
|
||||
if (ap_system.CH7_flag != (g.rc_7.radio_in >= AUX_SWITCH_PWM_TRIGGER)) {
|
||||
// set the ch7 flag
|
||||
ap_system.CH7_flag = (g.rc_7.radio_in >= AUX_SWITCH_PWM_TRIGGER);
|
||||
|
||||
// invoke the appropriate function
|
||||
do_aux_switch_function(g.ch7_option, ap_system.CH7_flag);
|
||||
}
|
||||
|
||||
// safety check to ensure we ch7 and ch8 have different functions
|
||||
if (g.ch7_option == g.ch8_option) {
|
||||
return;
|
||||
}
|
||||
|
||||
// set the ch7 flag
|
||||
ap_system.CH7_flag = (g.rc_7.radio_in >= CH7_PWM_TRIGGER);
|
||||
// check if ch8 switch has changed position
|
||||
if (ap_system.CH8_flag != (g.rc_8.radio_in >= AUX_SWITCH_PWM_TRIGGER)) {
|
||||
// set the ch8 flag
|
||||
ap_system.CH8_flag = (g.rc_8.radio_in >= AUX_SWITCH_PWM_TRIGGER);
|
||||
// invoke the appropriate function
|
||||
do_aux_switch_function(g.ch8_option, ap_system.CH8_flag);
|
||||
}
|
||||
}
|
||||
|
||||
// multi-mode
|
||||
int8_t option;
|
||||
// do_aux_switch_function - implement the function invoked by the ch7 or ch8 switch
|
||||
static void do_aux_switch_function(int8_t ch_function, bool ch_flag)
|
||||
{
|
||||
int8_t tmp_function = ch_function;
|
||||
|
||||
if(g.ch7_option == CH7_MULTI_MODE) {
|
||||
// multi mode check
|
||||
if(ch_function == AUX_SWITCH_MULTI_MODE) {
|
||||
if (g.rc_6.radio_in < CH6_PWM_TRIGGER_LOW) {
|
||||
option = CH7_FLIP;
|
||||
tmp_function = AUX_SWITCH_FLIP;
|
||||
}else if (g.rc_6.radio_in > CH6_PWM_TRIGGER_HIGH) {
|
||||
option = CH7_SAVE_WP;
|
||||
tmp_function = AUX_SWITCH_SAVE_WP;
|
||||
}else{
|
||||
option = CH7_RTL;
|
||||
tmp_function = AUX_SWITCH_RTL;
|
||||
}
|
||||
}else{
|
||||
option = g.ch7_option;
|
||||
}
|
||||
|
||||
switch(option) {
|
||||
case CH7_FLIP:
|
||||
switch(tmp_function) {
|
||||
case AUX_SWITCH_FLIP:
|
||||
// flip if switch is on, positive throttle and we're actually flying
|
||||
if(ap_system.CH7_flag && g.rc_3.control_in >= 0 && ap.takeoff_complete) {
|
||||
if(ch_flag && g.rc_3.control_in >= 0 && ap.takeoff_complete) {
|
||||
init_flip();
|
||||
}
|
||||
break;
|
||||
|
||||
case CH7_SIMPLE_MODE:
|
||||
set_simple_mode(ap_system.CH7_flag);
|
||||
case AUX_SWITCH_SIMPLE_MODE:
|
||||
set_simple_mode(ch_flag);
|
||||
break;
|
||||
|
||||
case CH7_RTL:
|
||||
if (ap_system.CH7_flag) {
|
||||
case AUX_SWITCH_RTL:
|
||||
if (ch_flag) {
|
||||
// engage RTL
|
||||
set_mode(RTL);
|
||||
}else{
|
||||
@ -99,28 +114,28 @@ static void read_trim_switch()
|
||||
}
|
||||
break;
|
||||
|
||||
case CH7_SAVE_TRIM:
|
||||
if(ap_system.CH7_flag && control_mode <= ACRO && g.rc_3.control_in == 0) {
|
||||
case AUX_SWITCH_SAVE_TRIM:
|
||||
if(ch_flag && control_mode <= ACRO && g.rc_3.control_in == 0) {
|
||||
save_trim();
|
||||
}
|
||||
break;
|
||||
|
||||
case CH7_SAVE_WP:
|
||||
// save when CH7 switch is switched off
|
||||
if (ap_system.CH7_flag == false) {
|
||||
case AUX_SWITCH_SAVE_WP:
|
||||
// save waypoint when switch is switched off
|
||||
if (ch_flag == false) {
|
||||
|
||||
// if in auto mode, reset the mission
|
||||
if(control_mode == AUTO) {
|
||||
CH7_wp_index = 0;
|
||||
aux_switch_wp_index = 0;
|
||||
g.command_total.set_and_save(1);
|
||||
set_mode(RTL);
|
||||
return;
|
||||
}
|
||||
|
||||
if(CH7_wp_index == 0) {
|
||||
if(aux_switch_wp_index == 0) {
|
||||
// this is our first WP, let's save WP 1 as a takeoff
|
||||
// increment index to WP index of 1 (home is stored at 0)
|
||||
CH7_wp_index = 1;
|
||||
aux_switch_wp_index = 1;
|
||||
|
||||
Location temp = home;
|
||||
// set our location ID to 16, MAV_CMD_NAV_WAYPOINT
|
||||
@ -131,15 +146,15 @@ static void read_trim_switch()
|
||||
// we use the current altitude to be the target for takeoff.
|
||||
// only altitude will matter to the AP mission script for takeoff.
|
||||
// If we are above the altitude, we will skip the command.
|
||||
set_cmd_with_index(temp, CH7_wp_index);
|
||||
set_cmd_with_index(temp, aux_switch_wp_index);
|
||||
}
|
||||
|
||||
// increment index
|
||||
CH7_wp_index++;
|
||||
aux_switch_wp_index++;
|
||||
|
||||
// set the next_WP (home is stored at 0)
|
||||
// max out at 100 since I think we need to stay under the EEPROM limit
|
||||
CH7_wp_index = constrain_int16(CH7_wp_index, 1, 100);
|
||||
aux_switch_wp_index = constrain_int16(aux_switch_wp_index, 1, 100);
|
||||
|
||||
if(g.rc_3.control_in > 0) {
|
||||
// set our location ID to 16, MAV_CMD_NAV_WAYPOINT
|
||||
@ -150,7 +165,7 @@ static void read_trim_switch()
|
||||
}
|
||||
|
||||
// save command
|
||||
set_cmd_with_index(current_loc, CH7_wp_index);
|
||||
set_cmd_with_index(current_loc, aux_switch_wp_index);
|
||||
|
||||
// Cause the CopterLEDs to blink twice to indicate saved waypoint
|
||||
copter_leds_nav_blink = 10;
|
||||
@ -158,22 +173,22 @@ static void read_trim_switch()
|
||||
break;
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
case CH7_CAMERA_TRIGGER:
|
||||
if(ap_system.CH7_flag) {
|
||||
case AUX_SWITCH_CAMERA_TRIGGER:
|
||||
if(ch_flag) {
|
||||
do_take_picture();
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
case CH7_SONAR:
|
||||
case AUX_SWITCH_SONAR:
|
||||
// enable or disable the sonar
|
||||
g.sonar_enabled = ap_system.CH7_flag;
|
||||
g.sonar_enabled = ch_flag;
|
||||
break;
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
case CH7_FENCE:
|
||||
case AUX_SWITCH_FENCE:
|
||||
// enable or disable the fence
|
||||
fence.enable(ap_system.CH7_flag);
|
||||
fence.enable(ch_flag);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
@ -44,23 +44,23 @@
|
||||
#define SONAR_SOURCE_ADC 1
|
||||
#define SONAR_SOURCE_ANALOG_PIN 2
|
||||
|
||||
// CH 7 control
|
||||
#define CH7_PWM_TRIGGER 1800 // pwm value above which the channel 7 option will be invoked
|
||||
#define CH6_PWM_TRIGGER_HIGH 1800
|
||||
#define CH6_PWM_TRIGGER_LOW 1200
|
||||
// Ch7 and Ch8 aux switch control
|
||||
#define AUX_SWITCH_PWM_TRIGGER 1800 // pwm value above which the ch7 or ch8 option will be invoked
|
||||
#define CH6_PWM_TRIGGER_HIGH 1800
|
||||
#define CH6_PWM_TRIGGER_LOW 1200
|
||||
|
||||
#define CH7_DO_NOTHING 0
|
||||
#define CH7_SET_HOVER 1 // deprecated
|
||||
#define CH7_FLIP 2
|
||||
#define CH7_SIMPLE_MODE 3
|
||||
#define CH7_RTL 4
|
||||
#define CH7_SAVE_TRIM 5
|
||||
#define CH7_ADC_FILTER 6 // deprecated
|
||||
#define CH7_SAVE_WP 7
|
||||
#define CH7_MULTI_MODE 8
|
||||
#define CH7_CAMERA_TRIGGER 9
|
||||
#define CH7_SONAR 10 // allow enabling or disabling sonar in flight which helps avoid surface tracking when you are far above the ground
|
||||
#define CH7_FENCE 11 // allow enabling or disabling fence in flight
|
||||
#define AUX_SWITCH_DO_NOTHING 0 // aux switch disabled
|
||||
#define AUX_SWITCH_SET_HOVER 1 // deprecated
|
||||
#define AUX_SWITCH_FLIP 2 // flip
|
||||
#define AUX_SWITCH_SIMPLE_MODE 3 // change to simple mode
|
||||
#define AUX_SWITCH_RTL 4 // change to RTL flight mode
|
||||
#define AUX_SWITCH_SAVE_TRIM 5 // save current position as level
|
||||
#define AUX_SWITCH_ADC_FILTER 6 // deprecated
|
||||
#define AUX_SWITCH_SAVE_WP 7 // save mission waypoint or RTL if in auto mode
|
||||
#define AUX_SWITCH_MULTI_MODE 8 // depending upon CH6 position Flip (if ch6 is low), RTL (if ch6 in middle) or Save WP (if ch6 is high)
|
||||
#define AUX_SWITCH_CAMERA_TRIGGER 9 // trigger camera servo or relay
|
||||
#define AUX_SWITCH_SONAR 10 // allow enabling or disabling sonar in flight which helps avoid surface tracking when you are far above the ground
|
||||
#define AUX_SWITCH_FENCE 11 // allow enabling or disabling fence in flight
|
||||
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user