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

Add and use new ModeReason::AUX_FUNCTION #27271

Merged
merged 5 commits into from
Jun 17, 2024
Merged
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
4 changes: 2 additions & 2 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
switch(ch_flag) {
case AuxSwitchPos::HIGH: {
// engage mode (if not possible we remain in current flight mode)
copter.set_mode(mode, ModeReason::RC_COMMAND);
copter.set_mode(mode, ModeReason::AUX_FUNCTION);
break;
}
default:
Expand All @@ -163,7 +163,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
case AUX_FUNC::FLIP:
// flip if switch is on, positive throttle and we're actually flying
if (ch_flag == AuxSwitchPos::HIGH) {
copter.set_mode(Mode::Number::FLIP, ModeReason::RC_COMMAND);
copter.set_mode(Mode::Number::FLIP, ModeReason::AUX_FUNCTION);
}
break;

Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ void RC_Channel_Plane::do_aux_function_change_mode(const Mode::Number number,
switch(ch_flag) {
case AuxSwitchPos::HIGH: {
// engage mode (if not possible we remain in current flight mode)
plane.set_mode_by_number(number, ModeReason::RC_COMMAND);
plane.set_mode_by_number(number, ModeReason::AUX_FUNCTION);
break;
}
default:
Expand Down
2 changes: 1 addition & 1 deletion Blimp/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ void RC_Channel_Blimp::do_aux_function_change_mode(const Mode::Number mode,
switch (ch_flag) {
case AuxSwitchPos::HIGH: {
// engage mode (if not possible we remain in current flight mode)
const bool success = blimp.set_mode(mode, ModeReason::RC_COMMAND);
const bool success = blimp.set_mode(mode, ModeReason::AUX_FUNCTION);
if (blimp.ap.initialised) {
if (success) {
AP_Notify::events.user_mode_change = 1;
Expand Down
2 changes: 1 addition & 1 deletion Rover/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ void RC_Channel_Rover::do_aux_function_change_mode(Mode &mode,
{
switch (ch_flag) {
case AuxSwitchPos::HIGH:
rover.set_mode(mode, ModeReason::RC_COMMAND);
rover.set_mode(mode, ModeReason::AUX_FUNCTION);
break;
case AuxSwitchPos::MIDDLE:
// do nothing
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Vehicle/ModeReason.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,4 +70,5 @@ enum class ModeReason : uint8_t {
DEADRECKON_FAILSAFE = 50,
MODE_TAKEOFF_FAILSAFE = 51,
DDS_COMMAND = 52,
AUX_FUNCTION = 53,
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
};
Loading