Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

delete old style mode switches #8999

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 2 additions & 4 deletions msg/manual_control_setpoint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -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
6 changes: 0 additions & 6 deletions msg/rc_channels.msg
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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)
Expand Down
3 changes: 2 additions & 1 deletion src/drivers/px4io/px4io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 */
Expand Down
141 changes: 0 additions & 141 deletions src/modules/commander/commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) &&
Expand Down Expand Up @@ -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;
}

Expand Down
6 changes: 3 additions & 3 deletions src/modules/mavlink/mavlink_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
70 changes: 3 additions & 67 deletions src/modules/sensors/parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,23 +78,16 @@ void initialize_parameter_handles(ParameterHandles &parameter_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");
Expand All @@ -114,20 +107,13 @@ void initialize_parameter_handles(ParameterHandles &parameter_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");
Expand Down Expand Up @@ -252,30 +238,10 @@ int update_parameters(const ParameterHandles &parameter_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);
}
Expand All @@ -300,14 +266,6 @@ int update_parameters(const ParameterHandles &parameter_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));
Expand All @@ -321,27 +279,11 @@ int update_parameters(const ParameterHandles &parameter_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);
Expand All @@ -357,12 +299,6 @@ int update_parameters(const ParameterHandles &parameter_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);
Expand Down
Loading