Skip to content

Add support for MAV_CMD_REQUEST_OPERATOR_CONTROL#33332

Draft
peterbarker wants to merge 5 commits into
ArduPilot:masterfrom
peterbarker:pr-claude/MAV_CMD_REQUEST_OPERATOR_CONTROL
Draft

Add support for MAV_CMD_REQUEST_OPERATOR_CONTROL#33332
peterbarker wants to merge 5 commits into
ArduPilot:masterfrom
peterbarker:pr-claude/MAV_CMD_REQUEST_OPERATOR_CONTROL

Conversation

@peterbarker

Copy link
Copy Markdown
Contributor

Summary

Adds support for development.xml messages (still under review) to pass control of the system from one GCS to another (or several)

Classification & Testing (check all that apply and add your own)

  • Checked by a human programmer
  • Non-functional change
  • No-binary change
  • Infrastructure change (e.g. unit tests, helper scripts)
  • Automated test(s) verify changes (e.g. unit test, autotest)
  • Tested manually, description below (e.g. SITL)
  • Tested on hardware
  • Logs attached
  • Logs available on request

Description

Much discussion in various places, most notably in the mavlink PR.

There's a MAVProxy PR adding support

QGC has support in the codebase but (a) it is not enabled by default and (b) the message set that QGC compiles against by default has an older version of this message.

peterbarker and others added 5 commits June 5, 2026 20:50
Task #9 — takeover notification: when a takeover request is rejected
(allow_takeover=0), broadcast MAV_CMD_REQUEST_OPERATOR_CONTROL on all
active channels to notify the current owner so they can release or
grant permission.

Task #10 — heartbeat disconnect releases control: rate-limited check
(1 Hz) in GCS::update_receive() releases operator control when the
operator's heartbeat has been absent for GCS_OPERATOR_HEARTBEAT_TIMEOUT_MS
(5 s). Uses the global sysid_mygcs_last_seen_time_ms() timestamp which
is updated by any GCS in the operator range, so control is only
released when ALL owners in a range disconnect simultaneously.

Task #11 — gcs_secondary in CONTROL_STATUS: track secondary connected
GCS sysids (sysids in the operator range that are not gcs_main) via
heartbeats in a small per-GCS array. Populate gcs_secondary[] in
CONTROL_STATUS from recently-seen secondaries so multi-owner range
mode is correctly reflected.

Autotest additions: notification forwarded to owner on takeover reject,
heartbeat disconnect releases control after timeout, gcs_secondary
populated when range operator is active.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
…ation send

Restrict RC_CHANNELS_OVERRIDE and MANUAL_CONTROL to the primary operator
(gcs_main) only. Secondaries can send state-changing MAVLink commands but
not manual stick input, matching the spec: "only one GCS owner can control
manual input of the vehicle".

Fix operator control takeover notification: the original direct call to
mavlink_msg_command_long_send() was silently dropped when the TX buffer
was momentarily full (comm_send_lock sets chan_discard=true). Route the
notification through the queued send_message()/try_send_message() path
(MSG_OPERATOR_CONTROL_NOTIFICATION) so it goes out as soon as TX space
is available, like all other deferred messages.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>

@Georacer Georacer left a comment

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

This one's looking good, Peter! Thank you for your work!

I've left a couple of comments. I'll try to test it with MAVProxy next.

Comment on lines +2804 to +2810
if (now_ms - _operator_control_last_hb_check_ms >= 1000) {
_operator_control_last_hb_check_ms = now_ms;
if (_operator_control_sysid != 0) {
const uint32_t last_seen = sysid_mygcs_last_seen_time_ms();
if (last_seen != 0 &&
now_ms - last_seen > GCS_OPERATOR_HEARTBEAT_TIMEOUT_MS) {
set_operator_control(0, 0, false);

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

I read here:
"Every 1s, check _operator_control_sysid. If it's not 0 and I have ever seen any of my GCSs, then release the control.
That doesn't sound right. Am I reading this wrong?

I guess the intention is that if the controlling GCS goes away for more than 1s, then the operator control will be released?
And the sysid_is_gcs() logic will fall back to sysid ranges.

flags |= GCS_CONTROL_STATUS_FLAGS_TAKEOVER_ALLOWED;
}
uint8_t gcs_secondary[10] {};
gcs().get_secondary_gcs(gcs_secondary);

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

The MAVLink spec part "It should only include IDs for connected GCS" must have been a major pain.

We're essentially maintaining this secondaries list just to report it, IIUC.

@Georacer

Copy link
Copy Markdown
Contributor

I gave this a test today, using the modified MAVProxy.

I went through the 3 scenarios outlined in mavlink/mavlink#2158.

They all seem to work... most of the time.

Here are 3 successful .tlogs:
scenario1.tlog.txt
scenario2.tlog.txt
scenario3.tlog.txt

I haven't actually verified that both GCSs have been logged in there.

And some of the time I would get this. It would switch control and then immediately release it:
Screenshot from 2026-06-11 13-40-28

Here are two failed .tlogs with that issue:
failure.tlog.txt
failure2.tlog.txt

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants