diff --git a/msg/manual_control_setpoint.msg b/msg/manual_control_setpoint.msg index 253aa327a8ee..11895b6a54d5 100644 --- a/msg/manual_control_setpoint.msg +++ b/msg/manual_control_setpoint.msg @@ -48,18 +48,16 @@ float32 aux3 # default function: camera trigger float32 aux4 # default function: camera roll float32 aux5 # default function: payload drop -uint8 mode_switch # main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO uint8 return_switch # return to launch 2 position switch (mandatory): _NORMAL_, RTL -uint8 rattitude_switch # rattitude control 2 position switch (optional): _MANUAL, RATTITUDE -uint8 posctl_switch # position control 2 position switch (optional): _ALTCTL_, POSCTL uint8 loiter_switch # loiter 2 position switch (optional): _MISSION_, LOITER -uint8 acro_switch # acro 2 position switch (optional): _MANUAL_, ACRO uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD uint8 kill_switch # throttle kill: _NORMAL_, KILL uint8 arm_switch # arm/disarm switch: _DISARMED_, ARMED uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGHT uint8 gear_switch # landing gear switch: _DOWN_, UP + int8 mode_slot # the slot a specific model selector is in + uint8 data_source # where this input is coming from uint8 stab_switch # stabilize switch (only relevant for fixed wings, optional): _MANUAL, STABILIZED uint8 man_switch # manual switch (only relevant for fixed wings, optional): _STABILIZED_, MANUAL diff --git a/msg/rc_channels.msg b/msg/rc_channels.msg index 6d31e9d5a8de..4d1d0330fb36 100644 --- a/msg/rc_channels.msg +++ b/msg/rc_channels.msg @@ -2,12 +2,9 @@ uint8 RC_CHANNELS_FUNCTION_THROTTLE=0 uint8 RC_CHANNELS_FUNCTION_ROLL=1 uint8 RC_CHANNELS_FUNCTION_PITCH=2 uint8 RC_CHANNELS_FUNCTION_YAW=3 -uint8 RC_CHANNELS_FUNCTION_MODE=4 uint8 RC_CHANNELS_FUNCTION_RETURN=5 -uint8 RC_CHANNELS_FUNCTION_POSCTL=6 uint8 RC_CHANNELS_FUNCTION_LOITER=7 uint8 RC_CHANNELS_FUNCTION_OFFBOARD=8 -uint8 RC_CHANNELS_FUNCTION_ACRO=9 uint8 RC_CHANNELS_FUNCTION_FLAPS=10 uint8 RC_CHANNELS_FUNCTION_AUX_1=11 uint8 RC_CHANNELS_FUNCTION_AUX_2=12 @@ -17,13 +14,10 @@ uint8 RC_CHANNELS_FUNCTION_AUX_5=15 uint8 RC_CHANNELS_FUNCTION_PARAM_1=16 uint8 RC_CHANNELS_FUNCTION_PARAM_2=17 uint8 RC_CHANNELS_FUNCTION_PARAM_3_5=18 -uint8 RC_CHANNELS_FUNCTION_RATTITUDE=19 uint8 RC_CHANNELS_FUNCTION_KILLSWITCH=20 uint8 RC_CHANNELS_FUNCTION_TRANSITION=21 uint8 RC_CHANNELS_FUNCTION_GEAR=22 uint8 RC_CHANNELS_FUNCTION_ARMSWITCH=23 -uint8 RC_CHANNELS_FUNCTION_STAB=24 -uint8 RC_CHANNELS_FUNCTION_MAN=25 uint64 timestamp_last_valid # Timestamp of last valid RC signal float32[18] channels # Scaled to -1..1 (throttle: 0..1) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 30308dd8b69c..51a6fbdbda9e 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1523,7 +1523,8 @@ PX4IO::io_set_rc_config() } /* MAIN MODE SWITCH */ - param_get(param_find("RC_MAP_MODE_SW"), &ichan); + // TODO: make the px4io aware of the MANUAL override position + //param_get(param_find("RC_MAP_MODE_SW"), &ichan); if ((ichan > 0) && (ichan <= (int)_max_rc_input)) { /* use out of normal bounds index to indicate special channel */ diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 7fd16e27a365..29fbe35671b6 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -3045,10 +3045,6 @@ Commander::set_main_state_rc(const vehicle_status_s &status_local, const vehicle && (((_last_sp_man.timestamp != 0) && (_last_sp_man.timestamp == sp_man.timestamp)) || ((_last_sp_man.offboard_switch == sp_man.offboard_switch) && (_last_sp_man.return_switch == sp_man.return_switch) && - (_last_sp_man.mode_switch == sp_man.mode_switch) && - (_last_sp_man.acro_switch == sp_man.acro_switch) && - (_last_sp_man.rattitude_switch == sp_man.rattitude_switch) && - (_last_sp_man.posctl_switch == sp_man.posctl_switch) && (_last_sp_man.loiter_switch == sp_man.loiter_switch) && (_last_sp_man.mode_slot == sp_man.mode_slot) && (_last_sp_man.stab_switch == sp_man.stab_switch) && @@ -3267,143 +3263,6 @@ Commander::set_main_state_rc(const vehicle_status_s &status_local, const vehicle return res; } - /* offboard and RTL switches off or denied, check main mode switch */ - switch (sp_man.mode_switch) { - case manual_control_setpoint_s::SWITCH_POS_NONE: - res = TRANSITION_NOT_CHANGED; - break; - - case manual_control_setpoint_s::SWITCH_POS_OFF: // MANUAL - if (sp_man.stab_switch == manual_control_setpoint_s::SWITCH_POS_NONE && - sp_man.man_switch == manual_control_setpoint_s::SWITCH_POS_NONE) { - /* - * Legacy mode: - * Acro switch being used as stabilized switch in FW. - */ - if (sp_man.acro_switch == manual_control_setpoint_s::SWITCH_POS_ON) { - /* manual mode is stabilized already for multirotors, so switch to acro - * for any non-manual mode - */ - if (status.is_rotary_wing && !status.is_vtol) { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_ACRO, status_flags, &internal_state); - - } else if (!status.is_rotary_wing) { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_STAB, status_flags, &internal_state); - - } else { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags, &internal_state); - } - - } else if (sp_man.rattitude_switch == manual_control_setpoint_s::SWITCH_POS_ON) { - /* Similar to acro transitions for multirotors. FW aircraft don't need a - * rattitude mode.*/ - if (status.is_rotary_wing) { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_RATTITUDE, status_flags, &internal_state); - - } else { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_STAB, status_flags, &internal_state); - } - - } else { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags, &internal_state); - } - - } else { - /* New mode: - * - Acro is Acro - * - Manual is not default anymore when the manaul switch is assigned - */ - if (sp_man.man_switch == manual_control_setpoint_s::SWITCH_POS_ON) { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags, &internal_state); - - } else if (sp_man.acro_switch == manual_control_setpoint_s::SWITCH_POS_ON) { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_ACRO, status_flags, &internal_state); - - } else if (sp_man.rattitude_switch == manual_control_setpoint_s::SWITCH_POS_ON) { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_RATTITUDE, status_flags, &internal_state); - - } else if (sp_man.stab_switch == manual_control_setpoint_s::SWITCH_POS_ON) { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_STAB, status_flags, &internal_state); - - } else if (sp_man.man_switch == manual_control_setpoint_s::SWITCH_POS_NONE) { - // default to MANUAL when no manual switch is set - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags, &internal_state); - - } else { - // default to STAB when the manual switch is assigned (but off) - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_STAB, status_flags, &internal_state); - } - } - - // TRANSITION_DENIED is not possible here - break; - - case manual_control_setpoint_s::SWITCH_POS_MIDDLE: // ASSIST - if (sp_man.posctl_switch == manual_control_setpoint_s::SWITCH_POS_ON) { - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_POSCTL, status_flags, &internal_state); - - if (res != TRANSITION_DENIED) { - break; // changed successfully or already in this state - } - - print_reject_mode("POSITION CONTROL"); - } - - // fallback to ALTCTL - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_ALTCTL, status_flags, &internal_state); - - if (res != TRANSITION_DENIED) { - break; // changed successfully or already in this mode - } - - if (sp_man.posctl_switch != manual_control_setpoint_s::SWITCH_POS_ON) { - print_reject_mode("ALTITUDE CONTROL"); - } - - // fallback to MANUAL - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags, &internal_state); - // TRANSITION_DENIED is not possible here - break; - - case manual_control_setpoint_s::SWITCH_POS_ON: // AUTO - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_AUTO_MISSION, status_flags, &internal_state); - - if (res != TRANSITION_DENIED) { - break; // changed successfully or already in this state - } - - print_reject_mode("AUTO MISSION"); - - // fallback to LOITER if home position not set - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_AUTO_LOITER, status_flags, &internal_state); - - if (res != TRANSITION_DENIED) { - break; // changed successfully or already in this state - } - - // fallback to POSCTL - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_POSCTL, status_flags, &internal_state); - - if (res != TRANSITION_DENIED) { - break; // changed successfully or already in this state - } - - // fallback to ALTCTL - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_ALTCTL, status_flags, &internal_state); - - if (res != TRANSITION_DENIED) { - break; // changed successfully or already in this state - } - - // fallback to MANUAL - res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags, &internal_state); - // TRANSITION_DENIED is not possible here - break; - - default: - break; - } - return res; } diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index c8f6c6f5bde6..bf264ac64b3d 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -3031,11 +3031,11 @@ class MavlinkStreamManualControl : public MavlinkStream msg.r = manual.r * 1000; unsigned shift = 2; msg.buttons = 0; - msg.buttons |= (manual.mode_switch << (shift * 0)); + //msg.buttons |= (manual.mode_switch << (shift * 0)); msg.buttons |= (manual.return_switch << (shift * 1)); - msg.buttons |= (manual.posctl_switch << (shift * 2)); + //msg.buttons |= (manual.posctl_switch << (shift * 2)); msg.buttons |= (manual.loiter_switch << (shift * 3)); - msg.buttons |= (manual.acro_switch << (shift * 4)); + //msg.buttons |= (manual.acro_switch << (shift * 4)); msg.buttons |= (manual.offboard_switch << (shift * 5)); mavlink_msg_manual_control_send_struct(_mavlink->get_channel(), &msg); diff --git a/src/modules/sensors/parameters.cpp b/src/modules/sensors/parameters.cpp index cd7261b72a7f..1f7393c78cc4 100644 --- a/src/modules/sensors/parameters.cpp +++ b/src/modules/sensors/parameters.cpp @@ -78,23 +78,16 @@ void initialize_parameter_handles(ParameterHandles ¶meter_handles) parameter_handles.rc_map_failsafe = param_find("RC_MAP_FAILSAFE"); /* mandatory mode switches, mapped to channel 5 and 6 per default */ - parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW"); parameter_handles.rc_map_return_sw = param_find("RC_MAP_RETURN_SW"); parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS"); /* optional mode switches, not mapped per default */ - parameter_handles.rc_map_rattitude_sw = param_find("RC_MAP_RATT_SW"); - parameter_handles.rc_map_posctl_sw = param_find("RC_MAP_POSCTL_SW"); - parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW"); - parameter_handles.rc_map_acro_sw = param_find("RC_MAP_ACRO_SW"); parameter_handles.rc_map_offboard_sw = param_find("RC_MAP_OFFB_SW"); parameter_handles.rc_map_kill_sw = param_find("RC_MAP_KILL_SW"); parameter_handles.rc_map_arm_sw = param_find("RC_MAP_ARM_SW"); parameter_handles.rc_map_trans_sw = param_find("RC_MAP_TRANS_SW"); parameter_handles.rc_map_gear_sw = param_find("RC_MAP_GEAR_SW"); - parameter_handles.rc_map_stab_sw = param_find("RC_MAP_STAB_SW"); - parameter_handles.rc_map_man_sw = param_find("RC_MAP_MAN_SW"); parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1"); parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2"); @@ -114,20 +107,13 @@ void initialize_parameter_handles(ParameterHandles ¶meter_handles) /* RC thresholds */ parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR"); - parameter_handles.rc_assist_th = param_find("RC_ASSIST_TH"); - parameter_handles.rc_auto_th = param_find("RC_AUTO_TH"); - parameter_handles.rc_rattitude_th = param_find("RC_RATT_TH"); - parameter_handles.rc_posctl_th = param_find("RC_POSCTL_TH"); + parameter_handles.rc_return_th = param_find("RC_RETURN_TH"); - parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH"); - parameter_handles.rc_acro_th = param_find("RC_ACRO_TH"); parameter_handles.rc_offboard_th = param_find("RC_OFFB_TH"); parameter_handles.rc_killswitch_th = param_find("RC_KILLSWITCH_TH"); parameter_handles.rc_armswitch_th = param_find("RC_ARMSWITCH_TH"); parameter_handles.rc_trans_th = param_find("RC_TRANS_TH"); parameter_handles.rc_gear_th = param_find("RC_GEAR_TH"); - parameter_handles.rc_stab_th = param_find("RC_STAB_TH"); - parameter_handles.rc_man_th = param_find("RC_MAN_TH"); /* RC low pass filter configuration */ parameter_handles.rc_flt_smp_rate = param_find("RC_FLT_SMP_RATE"); @@ -252,30 +238,10 @@ int update_parameters(const ParameterHandles ¶meter_handles, Parameters &par PX4_WARN("%s", paramerr); } - if (param_get(parameter_handles.rc_map_mode_sw, &(parameters.rc_map_mode_sw)) != OK) { - PX4_WARN("%s", paramerr); - } - if (param_get(parameter_handles.rc_map_return_sw, &(parameters.rc_map_return_sw)) != OK) { PX4_WARN("%s", paramerr); } - if (param_get(parameter_handles.rc_map_rattitude_sw, &(parameters.rc_map_rattitude_sw)) != OK) { - PX4_WARN("%s", paramerr); - } - - if (param_get(parameter_handles.rc_map_posctl_sw, &(parameters.rc_map_posctl_sw)) != OK) { - PX4_WARN("%s", paramerr); - } - - if (param_get(parameter_handles.rc_map_loiter_sw, &(parameters.rc_map_loiter_sw)) != OK) { - PX4_WARN("%s", paramerr); - } - - if (param_get(parameter_handles.rc_map_acro_sw, &(parameters.rc_map_acro_sw)) != OK) { - PX4_WARN("%s", paramerr); - } - if (param_get(parameter_handles.rc_map_offboard_sw, &(parameters.rc_map_offboard_sw)) != OK) { PX4_WARN("%s", paramerr); } @@ -300,14 +266,6 @@ int update_parameters(const ParameterHandles ¶meter_handles, Parameters &par PX4_WARN("%s", paramerr); } - if (param_get(parameter_handles.rc_map_stab_sw, &(parameters.rc_map_stab_sw)) != OK) { - PX4_WARN("%s", paramerr); - } - - if (param_get(parameter_handles.rc_map_man_sw, &(parameters.rc_map_man_sw)) != OK) { - PX4_WARN("%s", paramerr); - } - param_get(parameter_handles.rc_map_aux1, &(parameters.rc_map_aux1)); param_get(parameter_handles.rc_map_aux2, &(parameters.rc_map_aux2)); param_get(parameter_handles.rc_map_aux3, &(parameters.rc_map_aux3)); @@ -321,27 +279,11 @@ int update_parameters(const ParameterHandles ¶meter_handles, Parameters &par param_get(parameter_handles.rc_map_flightmode, &(parameters.rc_map_flightmode)); param_get(parameter_handles.rc_fails_thr, &(parameters.rc_fails_thr)); - param_get(parameter_handles.rc_assist_th, &(parameters.rc_assist_th)); - parameters.rc_assist_inv = (parameters.rc_assist_th < 0); - parameters.rc_assist_th = fabsf(parameters.rc_assist_th); - param_get(parameter_handles.rc_auto_th, &(parameters.rc_auto_th)); - parameters.rc_auto_inv = (parameters.rc_auto_th < 0); - parameters.rc_auto_th = fabsf(parameters.rc_auto_th); - param_get(parameter_handles.rc_rattitude_th, &(parameters.rc_rattitude_th)); - parameters.rc_rattitude_inv = (parameters.rc_rattitude_th < 0); - parameters.rc_rattitude_th = fabsf(parameters.rc_rattitude_th); - param_get(parameter_handles.rc_posctl_th, &(parameters.rc_posctl_th)); - parameters.rc_posctl_inv = (parameters.rc_posctl_th < 0); - parameters.rc_posctl_th = fabsf(parameters.rc_posctl_th); + param_get(parameter_handles.rc_return_th, &(parameters.rc_return_th)); parameters.rc_return_inv = (parameters.rc_return_th < 0); parameters.rc_return_th = fabsf(parameters.rc_return_th); - param_get(parameter_handles.rc_loiter_th, &(parameters.rc_loiter_th)); - parameters.rc_loiter_inv = (parameters.rc_loiter_th < 0); - parameters.rc_loiter_th = fabsf(parameters.rc_loiter_th); - param_get(parameter_handles.rc_acro_th, &(parameters.rc_acro_th)); - parameters.rc_acro_inv = (parameters.rc_acro_th < 0); - parameters.rc_acro_th = fabsf(parameters.rc_acro_th); + param_get(parameter_handles.rc_offboard_th, &(parameters.rc_offboard_th)); parameters.rc_offboard_inv = (parameters.rc_offboard_th < 0); parameters.rc_offboard_th = fabsf(parameters.rc_offboard_th); @@ -357,12 +299,6 @@ int update_parameters(const ParameterHandles ¶meter_handles, Parameters &par param_get(parameter_handles.rc_gear_th, &(parameters.rc_gear_th)); parameters.rc_gear_inv = (parameters.rc_gear_th < 0); parameters.rc_gear_th = fabsf(parameters.rc_gear_th); - param_get(parameter_handles.rc_stab_th, &(parameters.rc_stab_th)); - parameters.rc_stab_inv = (parameters.rc_stab_th < 0); - parameters.rc_stab_th = fabsf(parameters.rc_stab_th); - param_get(parameter_handles.rc_man_th, &(parameters.rc_man_th)); - parameters.rc_man_inv = (parameters.rc_man_th < 0); - parameters.rc_man_th = fabsf(parameters.rc_man_th); param_get(parameter_handles.rc_flt_smp_rate, &(parameters.rc_flt_smp_rate)); parameters.rc_flt_smp_rate = math::max(1.0f, parameters.rc_flt_smp_rate); diff --git a/src/modules/sensors/parameters.h b/src/modules/sensors/parameters.h index b769c12eddba..2f2fc627e841 100644 --- a/src/modules/sensors/parameters.h +++ b/src/modules/sensors/parameters.h @@ -78,19 +78,13 @@ struct Parameters { int32_t rc_map_throttle; int32_t rc_map_failsafe; - int32_t rc_map_mode_sw; int32_t rc_map_return_sw; - int32_t rc_map_rattitude_sw; - int32_t rc_map_posctl_sw; int32_t rc_map_loiter_sw; - int32_t rc_map_acro_sw; int32_t rc_map_offboard_sw; int32_t rc_map_kill_sw; int32_t rc_map_arm_sw; int32_t rc_map_trans_sw; int32_t rc_map_gear_sw; - int32_t rc_map_stab_sw; - int32_t rc_map_man_sw; int32_t rc_map_flaps; int32_t rc_map_aux1; @@ -104,35 +98,20 @@ struct Parameters { int32_t rc_map_flightmode; int32_t rc_fails_thr; - float rc_assist_th; - float rc_auto_th; - float rc_rattitude_th; - float rc_posctl_th; float rc_return_th; float rc_loiter_th; - float rc_acro_th; float rc_offboard_th; float rc_killswitch_th; float rc_armswitch_th; float rc_trans_th; float rc_gear_th; - float rc_stab_th; - float rc_man_th; - bool rc_assist_inv; - bool rc_auto_inv; - bool rc_rattitude_inv; - bool rc_posctl_inv; bool rc_return_inv; - bool rc_loiter_inv; - bool rc_acro_inv; bool rc_offboard_inv; bool rc_killswitch_inv; bool rc_armswitch_inv; bool rc_trans_inv; bool rc_gear_inv; - bool rc_stab_inv; - bool rc_man_inv; float rc_flt_smp_rate; float rc_flt_cutoff; @@ -169,20 +148,14 @@ struct ParameterHandles { param_t rc_map_throttle; param_t rc_map_failsafe; - param_t rc_map_mode_sw; param_t rc_map_return_sw; - param_t rc_map_rattitude_sw; - param_t rc_map_posctl_sw; param_t rc_map_loiter_sw; - param_t rc_map_acro_sw; param_t rc_map_offboard_sw; param_t rc_map_kill_sw; param_t rc_map_arm_sw; param_t rc_map_trans_sw; param_t rc_map_gear_sw; param_t rc_map_flaps; - param_t rc_map_stab_sw; - param_t rc_map_man_sw; param_t rc_map_aux1; param_t rc_map_aux2; @@ -199,20 +172,14 @@ struct ParameterHandles { param_t rc_map_flightmode; param_t rc_fails_thr; - param_t rc_assist_th; - param_t rc_auto_th; - param_t rc_rattitude_th; - param_t rc_posctl_th; + param_t rc_return_th; param_t rc_loiter_th; - param_t rc_acro_th; param_t rc_offboard_th; param_t rc_killswitch_th; param_t rc_armswitch_th; param_t rc_trans_th; param_t rc_gear_th; - param_t rc_stab_th; - param_t rc_man_th; param_t rc_flt_smp_rate; param_t rc_flt_cutoff; diff --git a/src/modules/sensors/rc_params.c b/src/modules/sensors/rc_params.c index c045b5371934..b821692a4ec1 100644 --- a/src/modules/sensors/rc_params.c +++ b/src/modules/sensors/rc_params.c @@ -1326,39 +1326,6 @@ PARAM_DEFINE_INT32(RC_MAP_YAW, 0); */ PARAM_DEFINE_INT32(RC_MAP_FLTMODE, 0); -/** - * Mode switch channel mapping. - * - * This is the main flight mode selector. - * The channel index (starting from 1 for channel 1) indicates - * which channel should be used for deciding about the main mode. - * A value of zero indicates the switch is not assigned. - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0); - /** * Return switch channel * @@ -1387,62 +1354,6 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0); */ PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0); -/** - * Rattitude switch channel - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_RATT_SW, 0); - -/** - * Position Control switch channel - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0); - /** * Loiter switch channel * @@ -1471,34 +1382,6 @@ PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0); */ PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0); -/** - * Acro switch channel - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0); - /** * Offboard switch channel * @@ -1667,62 +1550,6 @@ PARAM_DEFINE_INT32(RC_MAP_TRANS_SW, 0); */ PARAM_DEFINE_INT32(RC_MAP_GEAR_SW, 0); -/** - * Stabilize switch channel mapping. - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_STAB_SW, 0); - -/** - * Manual switch channel mapping. - * - * @min 0 - * @max 18 - * @group Radio Switches - * @value 0 Unassigned - * @value 1 Channel 1 - * @value 2 Channel 2 - * @value 3 Channel 3 - * @value 4 Channel 4 - * @value 5 Channel 5 - * @value 6 Channel 6 - * @value 7 Channel 7 - * @value 8 Channel 8 - * @value 9 Channel 9 - * @value 10 Channel 10 - * @value 11 Channel 11 - * @value 12 Channel 12 - * @value 13 Channel 13 - * @value 14 Channel 14 - * @value 15 Channel 15 - * @value 16 Channel 16 - * @value 17 Channel 17 - * @value 18 Channel 18 - */ -PARAM_DEFINE_INT32(RC_MAP_MAN_SW, 0); - /** * AUX1 Passthrough RC channel * @@ -1975,70 +1802,6 @@ PARAM_DEFINE_INT32(RC_MAP_PARAM3, 0); */ PARAM_DEFINE_INT32(RC_FAILS_THR, 0); -/** - * Threshold for selecting assist mode - * - * 0-1 indicate where in the full channel range the threshold sits - * 0 : min - * 1 : max - * sign indicates polarity of comparison - * positive : true when channel>th - * negative : true when channelth - * negative : true when channelth - * negative : true when channelth - * negative : true when channelth - * negative : true when channelth - * negative : true when channelth - * negative : true when channel