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

GCS_MAVLink: correct response codes when mode change fails #14255

Merged
merged 2 commits into from
Nov 23, 2020
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
18 changes: 15 additions & 3 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -3476,13 +3476,25 @@ def fly_manual_throttle_mode_change(self):
self.watch_altitude_maintained(-1, 0.2) # should not take off in guided
self.run_cmd_do_set_mode(
"ACRO",
want_result=mavutil.mavlink.MAV_RESULT_UNSUPPORTED) # should fix this result code!
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
self.run_cmd_do_set_mode(
"STABILIZE",
want_result=mavutil.mavlink.MAV_RESULT_UNSUPPORTED) # should fix this result code!
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
self.run_cmd_do_set_mode(
"DRIFT",
want_result=mavutil.mavlink.MAV_RESULT_UNSUPPORTED) # should fix this result code!
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
self.progress("Check setting an invalid mode")
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MODE,
mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
126,
0,
0,
0,
0,
0,
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
timeout=1
)
self.set_rc(3, 1000)
self.run_cmd_do_set_mode("ACRO")
self.wait_disarmed()
Expand Down
25 changes: 17 additions & 8 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2169,27 +2169,36 @@ void GCS_MAVLINK::handle_set_mode(const mavlink_message_t &msg)
*/
MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32_t _custom_mode)
{
MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
// only accept custom modes because there is no easy mapping from Mavlink flight modes to AC flight modes
if (uint32_t(_base_mode) & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
if (AP::vehicle()->set_mode(_custom_mode, ModeReason::GCS_COMMAND)) {
result = MAV_RESULT_ACCEPTED;
if (!AP::vehicle()->set_mode(_custom_mode, ModeReason::GCS_COMMAND)) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

if a has_mode() check coudl be done, and it's true, but we fail to set the mode, then we could return MAV_RESULT_TEMPORARILY_REJECTED

// often we should be returning DENIED rather than FAILED
// here. Perhaps a "has_mode" callback on AP_::vehicle()
// would do?
return MAV_RESULT_FAILED;
}
} else if (_base_mode == (MAV_MODE)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
return MAV_RESULT_ACCEPTED;
}

if (_base_mode == (MAV_MODE)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
// set the safety switch position. Must be in a command by itself
if (_custom_mode == 0) {
// turn safety off (pwm outputs flow to the motors)
hal.rcout->force_safety_off();
result = MAV_RESULT_ACCEPTED;
} else if (_custom_mode == 1) {
return MAV_RESULT_ACCEPTED;
}
if (_custom_mode == 1) {
// turn safety on (no pwm outputs to the motors)
if (hal.rcout->force_safety_on()) {
result = MAV_RESULT_ACCEPTED;
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
}
return MAV_RESULT_DENIED;
}

return result;
// Command is invalid (is supported but has invalid parameters)
return MAV_RESULT_DENIED;
}

/*
Expand Down