Copter: Use new RC_Channel AUX_FUNC

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2019-04-03 13:25:47 -03:00 committed by Tom Pittenger
parent 70fa8bc8c0
commit 86633e45ff
5 changed files with 83 additions and 83 deletions

View File

@ -34,8 +34,8 @@ bool AP_Arming_Copter::pre_arm_checks(bool display_failure)
// check if motor interlock and Emergency Stop aux switches are used
// at the same time. This cannot be allowed.
if (rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_INTERLOCK) &&
rc().find_channel_for_option(RC_Channel::aux_func::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");
return false;
}
@ -484,10 +484,10 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method
// if we are not using Emergency Stop switch option, force Estop false to ensure motors
// can run normally
if (!rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_ESTOP)){
if (!rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP)){
SRV_Channels::set_emergency_stop(false);
// if we are using motor Estop switch, it must not be in Estop position
} else if (rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_ESTOP) && SRV_Channels::get_emergency_stop()){
} else if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP) && SRV_Channels::get_emergency_stop()){
gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped");
return false;
}

View File

@ -86,6 +86,6 @@ void Copter::update_using_interlock()
#else
// 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
ap.using_interlock = rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_INTERLOCK) != nullptr;
ap.using_interlock = rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) != nullptr;
#endif
}

View File

@ -34,8 +34,8 @@ void RC_Channel_Copter::mode_switch_changed(modeswitch_pos_t new_pos)
AP_Notify::events.user_mode_change = 1;
}
if (!rc().find_channel_for_option(SIMPLE_MODE) &&
!rc().find_channel_for_option(SUPERSIMPLE_MODE)) {
if (!rc().find_channel_for_option(AUX_FUNC::SIMPLE_MODE) &&
!rc().find_channel_for_option(AUX_FUNC::SUPERSIMPLE_MODE)) {
// if none of the Aux Switches are set to Simple or Super Simple Mode then
// set Simple Mode using stored parameters from EEPROM
if (BIT_IS_SET(copter.g.super_simple, new_pos)) {
@ -63,47 +63,47 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_
{
// init channel options
switch(ch_option) {
case SIMPLE_MODE:
case RANGEFINDER:
case FENCE:
case SUPERSIMPLE_MODE:
case ACRO_TRAINER:
case PARACHUTE_ENABLE:
case PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
case RETRACT_MOUNT:
case MISSION_RESET:
case ATTCON_FEEDFWD:
case ATTCON_ACCEL_LIM:
case MOTOR_INTERLOCK:
case AVOID_ADSB:
case PRECISION_LOITER:
case INVERTED:
case WINCH_ENABLE:
case AUX_FUNC::SIMPLE_MODE:
case AUX_FUNC::RANGEFINDER:
case AUX_FUNC::FENCE:
case AUX_FUNC::SUPERSIMPLE_MODE:
case AUX_FUNC::ACRO_TRAINER:
case AUX_FUNC::PARACHUTE_ENABLE:
case AUX_FUNC::PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
case AUX_FUNC::RETRACT_MOUNT:
case AUX_FUNC::MISSION_RESET:
case AUX_FUNC::ATTCON_FEEDFWD:
case AUX_FUNC::ATTCON_ACCEL_LIM:
case AUX_FUNC::MOTOR_INTERLOCK:
case AUX_FUNC::AVOID_ADSB:
case AUX_FUNC::PRECISION_LOITER:
case AUX_FUNC::INVERTED:
case AUX_FUNC::WINCH_ENABLE:
do_aux_function(ch_option, ch_flag);
break;
// the following functions do not need to be initialised:
case FLIP:
case RTL:
case SAVE_TRIM:
case SAVE_WP:
case RESETTOARMEDYAW:
case AUTO:
case AUTOTUNE:
case LAND:
case BRAKE:
case THROW:
case SMART_RTL:
case GUIDED:
case LOITER:
case FOLLOW:
case PARACHUTE_RELEASE:
case ARMDISARM:
case WINCH_CONTROL:
case USER_FUNC1:
case USER_FUNC2:
case USER_FUNC3:
case ZIGZAG:
case ZIGZAG_SaveWP:
case AUX_FUNC::FLIP:
case AUX_FUNC::RTL:
case AUX_FUNC::SAVE_TRIM:
case AUX_FUNC::SAVE_WP:
case AUX_FUNC::RESETTOARMEDYAW:
case AUX_FUNC::AUTO:
case AUX_FUNC::AUTOTUNE:
case AUX_FUNC::LAND:
case AUX_FUNC::BRAKE:
case AUX_FUNC::THROW:
case AUX_FUNC::SMART_RTL:
case AUX_FUNC::GUIDED:
case AUX_FUNC::LOITER:
case AUX_FUNC::FOLLOW:
case AUX_FUNC::PARACHUTE_RELEASE:
case AUX_FUNC::ARMDISARM:
case AUX_FUNC::WINCH_CONTROL:
case AUX_FUNC::USER_FUNC1:
case AUX_FUNC::USER_FUNC2:
case AUX_FUNC::USER_FUNC3:
case AUX_FUNC::ZIGZAG:
case AUX_FUNC::ZIGZAG_SaveWP:
break;
default:
RC_Channel::init_aux_function(ch_option, ch_flag);
@ -142,36 +142,36 @@ void RC_Channel_Copter::do_aux_function_change_mode(const control_mode_t mode,
void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
{
switch(ch_option) {
case FLIP:
case AUX_FUNC::FLIP:
// flip if switch is on, positive throttle and we're actually flying
if (ch_flag == aux_switch_pos_t::HIGH) {
copter.set_mode(control_mode_t::FLIP, MODE_REASON_TX_COMMAND);
}
break;
case SIMPLE_MODE:
case AUX_FUNC::SIMPLE_MODE:
// low = simple mode off, middle or high position turns simple mode on
copter.set_simple_mode(ch_flag == HIGH || ch_flag == MIDDLE);
break;
case SUPERSIMPLE_MODE:
case AUX_FUNC::SUPERSIMPLE_MODE:
// low = simple mode off, middle = simple mode, high = super simple mode
copter.set_simple_mode(ch_flag);
break;
case RTL:
case AUX_FUNC::RTL:
#if MODE_RTL_ENABLED == ENABLED
do_aux_function_change_mode(control_mode_t::RTL, ch_flag);
#endif
break;
case SAVE_TRIM:
case AUX_FUNC::SAVE_TRIM:
if ((ch_flag == HIGH) && (copter.control_mode <= control_mode_t::ACRO) && (copter.channel_throttle->get_control_in() == 0)) {
copter.save_trim();
}
break;
case SAVE_WP:
case AUX_FUNC::SAVE_WP:
#if MODE_AUTO_ENABLED == ENABLED
// save waypoint when switch is brought high
if (ch_flag == HIGH) {
@ -223,7 +223,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case MISSION_RESET:
case AUX_FUNC::MISSION_RESET:
#if MODE_AUTO_ENABLED == ENABLED
if (ch_flag == HIGH) {
copter.mode_auto.mission.reset();
@ -231,13 +231,13 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case AUTO:
case AUX_FUNC::AUTO:
#if MODE_AUTO_ENABLED == ENABLED
do_aux_function_change_mode(control_mode_t::AUTO, ch_flag);
#endif
break;
case RANGEFINDER:
case AUX_FUNC::RANGEFINDER:
// enable or disable the rangefinder
#if RANGEFINDER_ENABLED == ENABLED
if ((ch_flag == HIGH) && copter.rangefinder.has_orientation(ROTATION_PITCH_270)) {
@ -248,7 +248,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case FENCE:
case AUX_FUNC::FENCE:
#if AC_FENCE == ENABLED
// enable or disable the fence
if (ch_flag == HIGH) {
@ -261,7 +261,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case ACRO_TRAINER:
case AUX_FUNC::ACRO_TRAINER:
#if MODE_ACRO_ENABLED == ENABLED
switch(ch_flag) {
case LOW:
@ -280,36 +280,36 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case AUTOTUNE:
case AUX_FUNC::AUTOTUNE:
#if AUTOTUNE_ENABLED == ENABLED
do_aux_function_change_mode(control_mode_t::AUTOTUNE, ch_flag);
#endif
break;
case LAND:
case AUX_FUNC::LAND:
do_aux_function_change_mode(control_mode_t::LAND, ch_flag);
break;
case GUIDED:
case AUX_FUNC::GUIDED:
do_aux_function_change_mode(control_mode_t::GUIDED, ch_flag);
break;
case LOITER:
case AUX_FUNC::LOITER:
do_aux_function_change_mode(control_mode_t::LOITER, ch_flag);
break;
case FOLLOW:
case AUX_FUNC::FOLLOW:
do_aux_function_change_mode(control_mode_t::FOLLOW, ch_flag);
break;
case PARACHUTE_ENABLE:
case AUX_FUNC::PARACHUTE_ENABLE:
#if PARACHUTE == ENABLED
// Parachute enable/disable
copter.parachute.enabled(ch_flag == HIGH);
#endif
break;
case PARACHUTE_RELEASE:
case AUX_FUNC::PARACHUTE_RELEASE:
#if PARACHUTE == ENABLED
if (ch_flag == HIGH) {
copter.parachute_manual_release();
@ -317,7 +317,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case PARACHUTE_3POS:
case AUX_FUNC::PARACHUTE_3POS:
#if PARACHUTE == ENABLED
// Parachute disable, enable, release with 3 position switch
switch (ch_flag) {
@ -337,17 +337,17 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case ATTCON_FEEDFWD:
case AUX_FUNC::ATTCON_FEEDFWD:
// enable or disable feed forward
copter.attitude_control->bf_feedforward(ch_flag == HIGH);
break;
case ATTCON_ACCEL_LIM:
case AUX_FUNC::ATTCON_ACCEL_LIM:
// enable or disable accel limiting by restoring defaults
copter.attitude_control->accel_limiting(ch_flag == HIGH);
break;
case RETRACT_MOUNT:
case AUX_FUNC::RETRACT_MOUNT:
#if MOUNT == ENABLE
switch (ch_flag) {
case HIGH:
@ -363,25 +363,25 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case MOTOR_INTERLOCK:
case AUX_FUNC::MOTOR_INTERLOCK:
// Turn on when above LOW, because channel will also be used for speed
// control signal in tradheli
copter.ap.motor_interlock_switch = (ch_flag == HIGH || ch_flag == MIDDLE);
break;
case BRAKE:
case AUX_FUNC::BRAKE:
#if MODE_BRAKE_ENABLED == ENABLED
do_aux_function_change_mode(control_mode_t::BRAKE, ch_flag);
#endif
break;
case THROW:
case AUX_FUNC::THROW:
#if MODE_THROW_ENABLED == ENABLED
do_aux_function_change_mode(control_mode_t::THROW, ch_flag);
#endif
break;
case AVOID_ADSB:
case AUX_FUNC::AVOID_ADSB:
#if ADSB_ENABLED == ENABLED
// enable or disable AP_Avoidance
if (ch_flag == HIGH) {
@ -394,7 +394,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case PRECISION_LOITER:
case AUX_FUNC::PRECISION_LOITER:
#if PRECISION_LANDING == ENABLED && MODE_LOITER_ENABLED == ENABLED
switch (ch_flag) {
case HIGH:
@ -410,7 +410,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case ARMDISARM:
case AUX_FUNC::ARMDISARM:
// arm or disarm the vehicle
switch (ch_flag) {
case HIGH:
@ -427,13 +427,13 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
}
break;
case SMART_RTL:
case AUX_FUNC::SMART_RTL:
#if MODE_SMARTRTL_ENABLED == ENABLED
do_aux_function_change_mode(control_mode_t::SMART_RTL, ch_flag);
#endif
break;
case INVERTED:
case AUX_FUNC::INVERTED:
#if FRAME_CONFIG == HELI_FRAME
switch (ch_flag) {
case HIGH:
@ -453,7 +453,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case WINCH_ENABLE:
case AUX_FUNC::WINCH_ENABLE:
#if WINCH_ENABLED == ENABLED
switch (ch_flag) {
case HIGH:
@ -470,7 +470,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
#endif
break;
case WINCH_CONTROL:
case AUX_FUNC::WINCH_CONTROL:
#if WINCH_ENABLED == ENABLED
switch (ch_flag) {
case LOW:
@ -492,23 +492,23 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
case USER_FUNC1:
userhook_auxSwitch1(ch_flag);
break;
case USER_FUNC2:
userhook_auxSwitch2(ch_flag);
break;
case USER_FUNC3:
userhook_auxSwitch3(ch_flag);
break;
#endif
case ZIGZAG:
case AUX_FUNC::ZIGZAG:
#if MODE_ZIGZAG_ENABLED == ENABLED
do_aux_function_change_mode(control_mode_t::ZIGZAG, ch_flag);
#endif
break;
case ZIGZAG_SaveWP:
case AUX_FUNC::ZIGZAG_SaveWP:
#if MODE_ZIGZAG_ENABLED == ENABLED
if (copter.flightmode == &copter.mode_zigzag) {
switch (ch_flag) {

View File

@ -140,7 +140,7 @@ void Copter::heli_update_rotor_speed_targets()
// get rotor control method
uint8_t rsc_control_mode = motors->get_rsc_mode();
float rsc_control_deglitched = 0.0f;
RC_Channel *rc_ptr = rc().find_channel_for_option(RC_Channel::aux_func::MOTOR_INTERLOCK);
RC_Channel *rc_ptr = rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK);
if (rc_ptr != nullptr) {
rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)rc_ptr->get_control_in()) * 0.001f;
}

View File

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