Copter: move handling of RC switches into RC_Channel

This commit is contained in:
Peter Barker 2018-06-04 13:06:32 +10:00 committed by Randy Mackay
parent 747fc3814d
commit e7e56dde7a
14 changed files with 394 additions and 625 deletions

View File

@ -34,7 +34,8 @@ bool AP_Arming_Copter::pre_arm_checks(bool display_failure)
// check if motor interlock and Emergency Stop aux switches are used // check if motor interlock and Emergency Stop aux switches are used
// at the same time. This cannot be allowed. // at the same time. This cannot be allowed.
if (copter.check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK) && copter.check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){ if (rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_INTERLOCK) &&
rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_ESTOP)){
check_failed(ARMING_CHECK_NONE, display_failure, "Interlock/E-Stop Conflict"); check_failed(ARMING_CHECK_NONE, display_failure, "Interlock/E-Stop Conflict");
return false; return false;
} }
@ -159,8 +160,8 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
// check various parameter values // check various parameter values
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS)) { if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS)) {
// ensure ch7 and ch8 have different functions // ensure all rc channels have different functions
if (copter.check_duplicate_auxsw()) { if (rc().duplicate_options_exist()) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Duplicate Aux Switch Options"); check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Duplicate Aux Switch Options");
return false; return false;
} }
@ -203,7 +204,8 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
return false; return false;
} }
// Inverted flight feature disabled for Heli Single and Dual frames // Inverted flight feature disabled for Heli Single and Dual frames
if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD && (copter.g.ch7_option == 43 || copter.g.ch8_option == 43 || copter.g.ch9_option == 43 || copter.g.ch10_option == 43 || copter.g.ch11_option == 43 || copter.g.ch12_option == 43)) { if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD &&
rc().find_channel_for_option(RC_Channel::aux_func_t::INVERTED) != nullptr) {
if (display_failure) { if (display_failure) {
gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Inverted flight option not supported"); gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Inverted flight option not supported");
} }
@ -556,10 +558,10 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::ArmingMethod
// if we are not using Emergency Stop switch option, force Estop false to ensure motors // if we are not using Emergency Stop switch option, force Estop false to ensure motors
// can run normally // can run normally
if (!copter.check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){ if (!rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_ESTOP)){
copter.set_motor_emergency_stop(false); copter.set_motor_emergency_stop(false);
// if we are using motor Estop switch, it must not be in Estop position // if we are using motor Estop switch, it must not be in Estop position
} else if (copter.check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && copter.ap.motor_emergency_stop){ } else if (rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_ESTOP) && copter.ap.motor_emergency_stop){
gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped"); gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped");
return false; return false;
} }

View File

@ -86,7 +86,7 @@ void Copter::update_using_interlock()
#else #else
// check if we are using motor interlock control on an aux switch or are in throw mode // check if we are using motor interlock control on an aux switch or are in throw mode
// which uses the interlock to stop motors while the copter is being thrown // which uses the interlock to stop motors while the copter is being thrown
ap.using_interlock = check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK); ap.using_interlock = rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_INTERLOCK) != nullptr;
#endif #endif
} }

View File

@ -90,7 +90,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(update_optical_flow, 200, 160), SCHED_TASK(update_optical_flow, 200, 160),
#endif #endif
SCHED_TASK(update_batt_compass, 10, 120), SCHED_TASK(update_batt_compass, 10, 120),
SCHED_TASK(read_aux_switches, 10, 50), SCHED_TASK(read_aux_all, 10, 50),
SCHED_TASK(arm_motors_check, 10, 50), SCHED_TASK(arm_motors_check, 10, 50),
#if TOY_MODE_ENABLED == ENABLED #if TOY_MODE_ENABLED == ENABLED
SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50), SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50),
@ -193,6 +193,12 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#endif #endif
}; };
void Copter::read_aux_all()
{
copter.g2.rc_channels.read_aux_all();
}
constexpr int8_t Copter::_failsafe_priorities[7]; constexpr int8_t Copter::_failsafe_priorities[7];
void Copter::setup() void Copter::setup()
@ -270,7 +276,7 @@ void Copter::rc_loop()
// Read radio and 3-position switch on radio // Read radio and 3-position switch on radio
// ----------------------------------------- // -----------------------------------------
read_radio(); read_radio();
read_control_switch(); rc().read_mode_switch();
} }
// throttle_loop - should be run at 50 hz // throttle_loop - should be run at 50 hz

View File

@ -55,7 +55,6 @@
#include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library #include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library
#include <AC_AttitudeControl/AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter #include <AC_AttitudeControl/AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library #include <AC_AttitudeControl/AC_PosControl.h> // Position control library
#include <RC_Channel/RC_Channel.h> // RC Channel Library
#include <AP_Motors/AP_Motors.h> // AP Motors library #include <AP_Motors/AP_Motors.h> // AP Motors library
#include <AP_Stats/AP_Stats.h> // statistics library #include <AP_Stats/AP_Stats.h> // statistics library
#include <AP_RSSI/AP_RSSI.h> // RSSI Library #include <AP_RSSI/AP_RSSI.h> // RSSI Library
@ -88,6 +87,8 @@
#include "defines.h" #include "defines.h"
#include "config.h" #include "config.h"
#include "RC_Channel.h" // RC Channel Library
#include "GCS_Mavlink.h" #include "GCS_Mavlink.h"
#include "GCS_Copter.h" #include "GCS_Copter.h"
#include "AP_Rally.h" // Rally point library #include "AP_Rally.h" // Rally point library
@ -194,6 +195,8 @@ public:
#endif #endif
friend class AP_Arming_Copter; friend class AP_Arming_Copter;
friend class ToyMode; friend class ToyMode;
friend class RC_Channel_Copter;
friend class RC_Channels_Copter;
Copter(void); Copter(void);
@ -233,6 +236,7 @@ private:
// flight modes convenience array // flight modes convenience array
AP_Int8 *flight_modes; AP_Int8 *flight_modes;
const uint8_t num_flight_modes = 6;
AP_Baro barometer; AP_Baro barometer;
Compass compass; Compass compass;
@ -353,19 +357,6 @@ private:
control_mode_t prev_control_mode; control_mode_t prev_control_mode;
mode_reason_t prev_control_mode_reason = MODE_REASON_UNKNOWN; mode_reason_t prev_control_mode_reason = MODE_REASON_UNKNOWN;
// Structure used to detect changes in the flight mode control switch
struct {
int8_t debounced_switch_position; // currently used switch position
int8_t last_switch_position; // switch position in previous iteration
uint32_t last_edge_time_ms; // system time that switch position was last changed
} control_switch_state;
// de-bounce counters for switches.cpp
struct debounce {
uint8_t count;
uint8_t ch_flag;
} aux_debounce[(CH_12 - CH_7)+1];
RCMapper rcmap; RCMapper rcmap;
// intertial nav alt when we armed // intertial nav alt when we armed
@ -664,6 +655,7 @@ private:
void rc_loop(); void rc_loop();
void throttle_loop(); void throttle_loop();
void update_batt_compass(void); void update_batt_compass(void);
void read_aux_all(void);
void fourhundred_hz_logging(); void fourhundred_hz_logging();
void ten_hz_logging_loop(); void ten_hz_logging_loop();
void twentyfive_hz_logging(); void twentyfive_hz_logging();
@ -892,15 +884,6 @@ private:
// switches.cpp // switches.cpp
void read_control_switch(); void read_control_switch();
bool check_if_auxsw_mode_used(uint8_t auxsw_mode_check);
bool check_duplicate_auxsw(void);
void reset_control_switch();
uint8_t read_3pos_switch(uint8_t chan);
void read_aux_switches();
void init_aux_switches();
void init_aux_switch_function(int8_t ch_option, uint8_t ch_flag);
void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag);
bool debounce_aux_switch(uint8_t chan, uint8_t ch_flag);
void save_trim(); void save_trim();
void auto_trim(); void auto_trim();

View File

@ -366,48 +366,6 @@ const AP_Param::Info Copter::var_info[] = {
// @RebootRequired: True // @RebootRequired: True
GSCALAR(frame_type, "FRAME_TYPE", AP_Motors::MOTOR_FRAME_TYPE_X), GSCALAR(frame_type, "FRAME_TYPE", AP_Motors::MOTOR_FRAME_TYPE_X),
// @Param: CH7_OPT
// @DisplayName: Channel 7 option
// @Description: Select which function is performed when CH7 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:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
// @User: Standard
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
// @Param: CH8_OPT
// @DisplayName: Channel 8 option
// @Description: Select which function is 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:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
// @User: Standard
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
// @Param: CH9_OPT
// @DisplayName: Channel 9 option
// @Description: Select which function is performed when CH9 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:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
// @User: Standard
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
// @Param: CH10_OPT
// @DisplayName: Channel 10 option
// @Description: Select which function is performed when CH10 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:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
// @User: Standard
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
// @Param: CH11_OPT
// @DisplayName: Channel 11 option
// @Description: Select which function is performed when CH11 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:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
// @User: Standard
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
// @Param: CH12_OPT
// @DisplayName: Channel 12 option
// @Description: Select which function is performed when CH12 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:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
// @User: Standard
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
// @Group: ARMING_ // @Group: ARMING_
// @Path: ../libraries/AP_Arming/AP_Arming.cpp // @Path: ../libraries/AP_Arming/AP_Arming.cpp
GOBJECT(arming, "ARMING_", AP_Arming_Copter), GOBJECT(arming, "ARMING_", AP_Arming_Copter),
@ -922,7 +880,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Group: RC // @Group: RC
// @Path: ../libraries/RC_Channel/RC_Channels.cpp // @Path: ../libraries/RC_Channel/RC_Channels.cpp
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels), AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Copter),
#if VISUAL_ODOMETRY_ENABLED == ENABLED #if VISUAL_ODOMETRY_ENABLED == ENABLED
// @Group: VISO // @Group: VISO
@ -1046,6 +1004,13 @@ const AP_Param::ConversionInfo conversion_table[] = {
{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_INT8, "BATT_FS_LOW_VOLT" }, { Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_INT8, "BATT_FS_LOW_VOLT" },
{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_INT8, "BATT_FS_LOW_MAH" }, { Parameters::k_param_fs_batt_mah, 0, AP_PARAM_INT8, "BATT_FS_LOW_MAH" },
{ Parameters::k_param_failsafe_battery_enabled,0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" }, { Parameters::k_param_failsafe_battery_enabled,0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" },
{ Parameters::Parameters::k_param_ch7_option_old, 0, AP_PARAM_INT8, "RC7_OPTION" },
{ Parameters::Parameters::k_param_ch8_option_old, 0, AP_PARAM_INT8, "RC8_OPTION" },
{ Parameters::Parameters::k_param_ch9_option_old, 0, AP_PARAM_INT8, "RC9_OPTION" },
{ Parameters::Parameters::k_param_ch10_option_old, 0, AP_PARAM_INT8, "RC10_OPTION" },
{ Parameters::Parameters::k_param_ch11_option_old, 0, AP_PARAM_INT8, "RC11_OPTION" },
{ Parameters::Parameters::k_param_ch12_option_old, 0, AP_PARAM_INT8, "RC12_OPTION" },
}; };
void Copter::load_parameters(void) void Copter::load_parameters(void)

View File

@ -94,7 +94,7 @@ public:
k_param_pilot_speed_up, // renamed from k_param_pilot_velocity_z_max k_param_pilot_speed_up, // renamed from k_param_pilot_velocity_z_max
k_param_circle_rate, // deprecated - remove k_param_circle_rate, // deprecated - remove
k_param_rangefinder_gain, k_param_rangefinder_gain,
k_param_ch8_option, k_param_ch8_option_old, // deprecated
k_param_arming_check_old, // deprecated - remove k_param_arming_check_old, // deprecated - remove
k_param_sprayer, k_param_sprayer,
k_param_angle_max, k_param_angle_max,
@ -203,10 +203,10 @@ public:
k_param_serial2_baud_old, // deprecated k_param_serial2_baud_old, // deprecated
k_param_serial2_protocol, // deprecated k_param_serial2_protocol, // deprecated
k_param_serial_manager, k_param_serial_manager,
k_param_ch9_option, k_param_ch9_option_old,
k_param_ch10_option, k_param_ch10_option_old,
k_param_ch11_option, k_param_ch11_option_old,
k_param_ch12_option, k_param_ch12_option_old,
k_param_takeoff_trigger_dz, k_param_takeoff_trigger_dz,
k_param_gcs3, k_param_gcs3,
k_param_gcs_pid_mask, // 126 k_param_gcs_pid_mask, // 126
@ -233,7 +233,7 @@ public:
k_param_frame_type, k_param_frame_type,
k_param_optflow_enabled, // deprecated k_param_optflow_enabled, // deprecated
k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor
k_param_ch7_option, k_param_ch7_option_old,
k_param_auto_slew_rate, // deprecated - can be deleted k_param_auto_slew_rate, // deprecated - can be deleted
k_param_rangefinder_type_old, // deprecated k_param_rangefinder_type_old, // deprecated
k_param_super_simple = 155, k_param_super_simple = 155,
@ -432,12 +432,6 @@ public:
AP_Int16 radio_tuning_high; AP_Int16 radio_tuning_high;
AP_Int16 radio_tuning_low; AP_Int16 radio_tuning_low;
AP_Int8 frame_type; AP_Int8 frame_type;
AP_Int8 ch7_option;
AP_Int8 ch8_option;
AP_Int8 ch9_option;
AP_Int8 ch10_option;
AP_Int8 ch11_option;
AP_Int8 ch12_option;
AP_Int8 disarm_delay; AP_Int8 disarm_delay;
AP_Int8 land_repositioning; AP_Int8 land_repositioning;
@ -551,7 +545,7 @@ public:
AP_Int8 frame_class; AP_Int8 frame_class;
// RC input channels // RC input channels
RC_Channels rc_channels; RC_Channels_Copter rc_channels;
// control over servo output ranges // control over servo output ranges
SRV_Channels servo_channels; SRV_Channels servo_channels;

49
ArduCopter/RC_Channel.h Normal file
View File

@ -0,0 +1,49 @@
#pragma once
#include <RC_Channel/RC_Channel.h>
#include "Copter.h"
class RC_Channel_Copter : public RC_Channel
{
public:
protected:
void init_aux_function(aux_func_t ch_option, aux_switch_pos_t) override;
void do_aux_function(aux_func_t ch_option, aux_switch_pos_t) override;
private:
void do_aux_function_change_mode(const control_mode_t mode,
const aux_switch_pos_t ch_flag);
// called when the mode switch changes position:
void mode_switch_changed(modeswitch_pos_t new_pos) override;
};
class RC_Channels_Copter : public RC_Channels
{
public:
// this must be implemented for the AP_Scheduler functor to work:
void read_aux_all() override {
RC_Channels::read_aux_all();
}
bool has_valid_input() const override;
RC_Channel_Copter obj_channels[NUM_RC_CHANNELS];
RC_Channel_Copter *channel(const uint8_t chan) override {
if (chan > NUM_RC_CHANNELS) {
return nullptr;
}
return &obj_channels[chan];
}
protected:
int8_t flight_mode_channel_number() const override;
};

View File

@ -21,66 +21,6 @@ enum autopilot_yaw_mode {
AUTO_YAW_RATE = 6, // turn at a specified rate (held in auto_yaw_rate) AUTO_YAW_RATE = 6, // turn at a specified rate (held in auto_yaw_rate)
}; };
// Ch6... Ch12 aux switch control
#define AUX_SWITCH_PWM_TRIGGER_HIGH 1800 // pwm value above which the ch7 or ch8 option will be invoked
#define AUX_SWITCH_PWM_TRIGGER_LOW 1200 // pwm value below which the ch7 or ch8 option will be disabled
// values used by the ap.ch7_opt and ap.ch8_opt flags
#define AUX_SWITCH_LOW 0 // indicates auxiliary switch is in the low position (pwm <1200)
#define AUX_SWITCH_MIDDLE 1 // indicates auxiliary switch is in the middle position (pwm >1200, <1800)
#define AUX_SWITCH_HIGH 2 // indicates auxiliary switch is in the high position (pwm >1800)
// Aux Switch enumeration
enum aux_sw_func {
AUXSW_DO_NOTHING = 0, // aux switch disabled
AUXSW_FLIP = 2, // flip
AUXSW_SIMPLE_MODE = 3, // change to simple mode
AUXSW_RTL = 4, // change to RTL flight mode
AUXSW_SAVE_TRIM = 5, // save current position as level
AUXSW_SAVE_WP = 7, // save mission waypoint or RTL if in auto mode
AUXSW_CAMERA_TRIGGER = 9, // trigger camera servo or relay
AUXSW_RANGEFINDER = 10, // allow enabling or disabling rangefinder in flight which helps avoid surface tracking when you are far above the ground
AUXSW_FENCE = 11, // allow enabling or disabling fence in flight
AUXSW_RESETTOARMEDYAW = 12, // UNUSED
AUXSW_SUPERSIMPLE_MODE = 13, // change to simple mode in middle, super simple at top
AUXSW_ACRO_TRAINER = 14, // low = disabled, middle = leveled, high = leveled and limited
AUXSW_SPRAYER = 15, // enable/disable the crop sprayer
AUXSW_AUTO = 16, // change to auto flight mode
AUXSW_AUTOTUNE = 17, // auto tune
AUXSW_LAND = 18, // change to LAND flight mode
AUXSW_GRIPPER = 19, // Operate cargo grippers low=off, middle=neutral, high=on
AUXSW_PARACHUTE_ENABLE = 21, // Parachute enable/disable
AUXSW_PARACHUTE_RELEASE = 22, // Parachute release
AUXSW_PARACHUTE_3POS = 23, // Parachute disable, enable, release with 3 position switch
AUXSW_MISSION_RESET = 24, // Reset auto mission to start from first command
AUXSW_ATTCON_FEEDFWD = 25, // enable/disable the roll and pitch rate feed forward
AUXSW_ATTCON_ACCEL_LIM = 26, // enable/disable the roll, pitch and yaw accel limiting
AUXSW_RETRACT_MOUNT = 27, // Retract Mount
AUXSW_RELAY = 28, // Relay pin on/off (only supports first relay)
AUXSW_LANDING_GEAR = 29, // Landing gear controller
AUXSW_LOST_COPTER_SOUND = 30, // Play lost copter sound
AUXSW_MOTOR_ESTOP = 31, // Emergency Stop Switch
AUXSW_MOTOR_INTERLOCK = 32, // Motor On/Off switch
AUXSW_BRAKE = 33, // Brake flight mode
AUXSW_RELAY2 = 34, // Relay2 pin on/off (in Mission planner set CH8_OPT = 34)
AUXSW_RELAY3 = 35, // Relay3 pin on/off (in Mission planner set CH9_OPT = 35)
AUXSW_RELAY4 = 36, // Relay4 pin on/off (in Mission planner set CH10_OPT = 36)
AUXSW_THROW = 37, // change to THROW flight mode
AUXSW_AVOID_ADSB = 38, // enable AP_Avoidance library
AUXSW_PRECISION_LOITER = 39, // enable precision loiter
AUXSW_AVOID_PROXIMITY = 40, // enable object avoidance using proximity sensors (ie. horizontal lidar)
AUXSW_ARMDISARM = 41, // arm or disarm vehicle
AUXSW_SMART_RTL = 42, // change to SmartRTL flight mode
AUXSW_INVERTED = 43, // enable inverted flight
AUXSW_WINCH_ENABLE = 44, // winch enable/disable
AUXSW_WINCH_CONTROL = 45, // winch control
AUXSW_RC_OVERRIDE_ENABLE = 46, // enable RC Override
AUXSW_USER_FUNC1 = 47, // user function #1
AUXSW_USER_FUNC2 = 48, // user function #2
AUXSW_USER_FUNC3 = 49, // user function #3
AUXSW_SWITCH_MAX,
};
// Frame types // Frame types
#define UNDEFINED_FRAME 0 #define UNDEFINED_FRAME 0
#define MULTICOPTER_FRAME 1 #define MULTICOPTER_FRAME 1

View File

@ -6,7 +6,7 @@
* Adapted and updated for AC2 in 2011 by Jason Short * Adapted and updated for AC2 in 2011 by Jason Short
* *
* Controls: * Controls:
* CH7_OPT - CH12_OPT parameter must be set to "Flip" (AUXSW_FLIP) which is "2" * RC7_OPTION - RC12_OPTION parameter must be set to "Flip" (AUXSW_FLIP) which is "2"
* Pilot switches to Stabilize, Acro or AltHold flight mode and puts ch7/ch8 switch to ON position * Pilot switches to Stabilize, Acro or AltHold flight mode and puts ch7/ch8 switch to ON position
* Vehicle will Roll right by default but if roll or pitch stick is held slightly left, forward or back it will flip in that direction * Vehicle will Roll right by default but if roll or pitch stick is held slightly left, forward or back it will flip in that direction
* Vehicle should complete the roll within 2.5sec and will then return to the original flight mode it was in before flip was triggered * Vehicle should complete the roll within 2.5sec and will then return to the original flight mode it was in before flip was triggered

View File

@ -342,7 +342,7 @@ void Copter::lost_vehicle_check()
static uint8_t soundalarm_counter; static uint8_t soundalarm_counter;
// disable if aux switch is setup to vehicle alarm as the two could interfere // disable if aux switch is setup to vehicle alarm as the two could interfere
if (check_if_auxsw_mode_used(AUXSW_LOST_COPTER_SOUND)) { if (rc().find_channel_for_option(RC_Channel::aux_func::LOST_COPTER_SOUND)) {
return; return;
} }

View File

@ -11,20 +11,20 @@ void Copter::default_dead_zones()
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
channel_throttle->set_default_dead_zone(10); channel_throttle->set_default_dead_zone(10);
channel_yaw->set_default_dead_zone(15); channel_yaw->set_default_dead_zone(15);
RC_Channels::rc_channel(CH_6)->set_default_dead_zone(10); rc().channel(CH_6)->set_default_dead_zone(10);
#else #else
channel_throttle->set_default_dead_zone(30); channel_throttle->set_default_dead_zone(30);
channel_yaw->set_default_dead_zone(20); channel_yaw->set_default_dead_zone(20);
#endif #endif
RC_Channels::rc_channel(CH_6)->set_default_dead_zone(0); rc().channel(CH_6)->set_default_dead_zone(0);
} }
void Copter::init_rc_in() void Copter::init_rc_in()
{ {
channel_roll = RC_Channels::rc_channel(rcmap.roll()-1); channel_roll = rc().channel(rcmap.roll()-1);
channel_pitch = RC_Channels::rc_channel(rcmap.pitch()-1); channel_pitch = rc().channel(rcmap.pitch()-1);
channel_throttle = RC_Channels::rc_channel(rcmap.throttle()-1); channel_throttle = rc().channel(rcmap.throttle()-1);
channel_yaw = RC_Channels::rc_channel(rcmap.yaw()-1); channel_yaw = rc().channel(rcmap.yaw()-1);
// set rc channel ranges // set rc channel ranges
channel_roll->set_angle(ROLL_PITCH_YAW_INPUT_MAX); channel_roll->set_angle(ROLL_PITCH_YAW_INPUT_MAX);
@ -33,10 +33,10 @@ void Copter::init_rc_in()
channel_throttle->set_range(1000); channel_throttle->set_range(1000);
//set auxiliary servo ranges //set auxiliary servo ranges
RC_Channels::rc_channel(CH_5)->set_range(1000); rc().channel(CH_5)->set_range(1000);
RC_Channels::rc_channel(CH_6)->set_range(1000); rc().channel(CH_6)->set_range(1000);
RC_Channels::rc_channel(CH_7)->set_range(1000); rc().channel(CH_7)->set_range(1000);
RC_Channels::rc_channel(CH_8)->set_range(1000); rc().channel(CH_8)->set_range(1000);
// set default dead zones // set default dead zones
default_dead_zones(); default_dead_zones();
@ -95,7 +95,7 @@ void Copter::read_radio()
{ {
uint32_t tnow_ms = millis(); uint32_t tnow_ms = millis();
if (RC_Channels::read_input()) { if (rc().read_input()) {
ap.new_radio_frame = true; ap.new_radio_frame = true;
set_throttle_and_failsafe(channel_throttle->get_radio_in()); set_throttle_and_failsafe(channel_throttle->get_radio_in());

File diff suppressed because it is too large Load Diff

View File

@ -251,10 +251,8 @@ void Copter::init_ardupilot()
#endif #endif
DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void)); DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void));
// initialise the flight mode and aux switch // initialise rc channels including setting mode
// --------------------------- rc().init();
reset_control_switch();
init_aux_switches();
startup_INS_ground(); startup_INS_ground();

View File

@ -8,7 +8,7 @@
// tuning - updates parameters based on the ch6 tuning knob's position // tuning - updates parameters based on the ch6 tuning knob's position
// should be called at 3.3hz // should be called at 3.3hz
void Copter::tuning() { void Copter::tuning() {
RC_Channel *rc6 = RC_Channels::rc_channel(CH_6); RC_Channel *rc6 = rc().channel(CH_6);
// exit immediately if not using tuning function, or when radio failsafe is invoked, so tuning values are not set to zero // exit immediately if not using tuning function, or when radio failsafe is invoked, so tuning values are not set to zero
if ((g.radio_tuning <= 0) || failsafe.radio || failsafe.radio_counter != 0 || rc6->get_radio_in() == 0) { if ((g.radio_tuning <= 0) || failsafe.radio || failsafe.radio_counter != 0 || rc6->get_radio_in() == 0) {