Skip to content

Conversation

@junwoo091400
Copy link

Description

Previously, the z component definition relied on having a knowledge of which direction the thrust would result in, depending on its value, which is tied to the vehicle's setup (e.g. Rover, which can take in reverse-throttle commands vs. conventional quadcopter with only positive throttle).

This is a bad practice because:

  1. With this definition, we need to tailor the MANUAL_CONTROL message for each different type of vehicle to use the 'correct' range of z. So having a GCS with a Joystick input will have to know which range of throttle would result in positive/negative thrust for each connected vehicle, which doesn't make sense.
  2. The concept of 'Manual Control' should be as simple as possible (just a Joystick command). And just how Joysticks all have min/max ranges, it would be simpler to not have the 'thrust' condition, but to just map the ranges simply to [-1, 1]

With this new definition, the MANUAL_CONTROL message will not be vehicle-specific and truly represent the Joystick / RC Transmitter's throttle position.

Alternatives

We could keep the convention as is 🤔

Discussion Points

  1. How do we make sure previous users who were sticking to this convention don't get affected? (Or is this inevitable?)

Context

This issue was discussed in a PX4 PR trying to standardize the range for throttle internally: PX4/PX4-Autopilot#15949 (comment)

Previously, the `z` component definition relied on having a knowledge of
which direction the thrust would result in, depending on it's value.

However this is a bad practice as the ManaulControl message itself
should be agnostic to a vehicle type (either reverse-thrustable ones
like Rover, or ones with only positive thrust like conventional
quadcopters).

With this new definition, the MANUAL_CONTROL message will not be
vehicle-specific and truly represent the Joystick / RC Transmitter's
throttle position
Copy link
Contributor

@MaEtUgR MaEtUgR left a comment

Choose a reason for hiding this comment

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

Most importantly remove:

Positive values are positive thrust, negative values are negative thrust.

That part causes ambiguity and confusion because what happens if the vehicle does not have any negative thrust? In practice, this message was designed and is broadly used to report joystick positions over MAVLink. But with this definition, it instead results in the MAVLink-enabled remotes needing to understand the thrust situation of the vehicle just to be able to report the throttle stick or slider position.

It's sad that the original easier to understand definition was abandoned in https://github.com/mavlink/mavlink/pull/64/files
but
https://github.com/mavlink/mavlink/pull/464/files
really started the confusion in my eyes.

I'd vote for a very clear definition like this:
https://github.com/PX4/PX4-Autopilot/blob/7977ba3217422b042a6848ef529d9ea61ba0b686/msg/ManualControlSetpoint.msg#L24-L27
but for this message, I think the ship has sailed and a new one would need to be added for backwards compatibility.

<field type="int16_t" name="x" invalid="INT16_MAX">X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.</field>
<field type="int16_t" name="y" invalid="INT16_MAX">Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.</field>
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.</field>
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to throttle high (1000) - throttle low (-1000) on a joystick. Centered throttle should result in value of 0 (center).</field>
Copy link
Contributor

@MaEtUgR MaEtUgR Nov 21, 2022

Choose a reason for hiding this comment

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

Suggested change
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to throttle high (1000) - throttle low (-1000) on a joystick. Centered throttle should result in value of 0 (center).</field>
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Joystick or slider fully down corresponds to -1000, fully up to 1000, the center position to 0.</field>

Copy link
Collaborator

Choose a reason for hiding this comment

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

Not sure about this. Before we were saying its another slider, now we're enforcing that the alignment of that slider is "up/down". I think the desired change is just to remove the emphasis on the positive/negative thrust. Something like.

Suggested change
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to throttle high (1000) - throttle low (-1000) on a joystick. Centered throttle should result in value of 0 (center).</field>
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally the axis is mapped to vehicle thrust. Vehicles that support only positive thrust map the range from maximum thrust (1000) to mininimum (-1000). Vehicles that support negative thrusts map the range from maximum positive thrust (1000) to maximum negative thrust (-1000), with 0 (centred) implying no thrust).</field>

Copy link
Contributor

Choose a reason for hiding this comment

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

Before we were saying its another slider

Conceptually it should represent an analog input axis be it slider, stick axis or whatever else someone would like to map. In most cases, it will be a stick axis which might be worth mentioning but certainly not enforcing.

now we're enforcing that the alignment of that slider is "up/down"

My wording is not general enough. I do not want to enforce that. The axis just needs to have a minimum and maximum if that's up, down, sideways or diagonal is up to the user. Again in most cases, I'm pretty sure it's up and down.

Generally the axis is mapped to vehicle thrust.

That is exactly the part that is in my eyes only half the story. Manual up, forward, gas is the first thing that comes to mind but often it's mapped to steer vertical or even horizontal speed. I'd try to avoid mentioning an exact use because even though it's true in certain scenarios it can be very confusing in others.

Vehicles that support only positive thrust map the range from maximum thrust (1000) to mininimum (-1000). Vehicles that support negative thrusts map the range from maximum positive thrust (1000) to maximum negative thrust (-1000), with 0 (centred) implying no thrust).

Very good wording. Whatever the thrust, speed or other desired quantity range is, should be mapped to the full available input range -1000 to 1000.

Copy link
Collaborator

@hamishwillee hamishwillee Dec 7, 2022

Choose a reason for hiding this comment

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

Whatever the thrust, speed or other desired quantity range is, should be mapped to the full available input range -1000 to 1000.

@MaEtUgR No, that's good wording ^^^ :-)

Perhaps we should make it that simple?

Suggested change
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to throttle high (1000) - throttle low (-1000) on a joystick. Centered throttle should result in value of 0 (center).</field>
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. The value may be mapped to thrust, speed, throttle, or any other property. The range of possible property values should be mapped across the full movement range of the axis.</field>

Similar changes could be made to the other axes

Copy link
Contributor

Choose a reason for hiding this comment

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

Coming back to this in 2025 after PX4/PX4-Autopilot#24576, which is a product of my suggested consistent use of the throttle/z range and the existing inconsistent use. I might slowly lean towards a completely new message defining the input in a specific consistent way because as much as I'd like to correct MANUAL_CONTROL I'm not sure how many use cases break if we clarify the definition and use it consistently 😬
If there's another easy way to ensure the transition is smooth, I'm eager to learn.

Copy link
Collaborator

@hamishwillee hamishwillee Apr 1, 2025

Choose a reason for hiding this comment

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

@MaEtUgR There's some appetite for improve messages here. The best way forward would be to create a PR that outlines the messages you'd like to see. I can then add to the dev call (I added, but only as a heads up, not a concrete proposal).

I'm not sure of the right split, but we've previously discussed splitting button press behavior from slider/axis control, basic axis + additional axis. Fixed axis + configurable axes. And so on. Open to suggestions that minimise bandwidth and allow for easy extension in future (or no need for extension in future).

Copy link
Collaborator

@hamishwillee hamishwillee Apr 10, 2025

Choose a reason for hiding this comment

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

I'm not sure how many use cases break if we clarify the definition and use it consistently

@MaEtUgR It looks like QGC is the only supplier, and both PX4 and ArduPilot map this "to the same effect". What this means is that we can really only clarify the definition to "what QGC does". How PX4/Ardupilot interprets that is the same, so we should capture that as well, at least as "in general". We should do that and nothing else here.

@hamishwillee
Copy link
Collaborator

As the wording is now "Positive values are positive thrust, negative values are negative thrust.". That implies that on a vehicle with only positive thrust you have to have a deadzone from the low position of the axis range to the centre. I bet that no one actually does that.

This is conceptually a breaking change from a MAVLink perspective but I think it makes sense, if we can get the wording right. I will take to the dev call this evening.

@MaEtUgR

  1. I don't like the "simpler definition". Refering to pitch, roll, yaw, throttle thrust is annoying unless that is how it maps to all vehicles. For example, pitch makes little sense in MC position mode right? That has always made our discussions of stick movements confusing. But, I'm not the boss of MAVLink and you know more than me about the practicalities of interpreting joysticks.
  2. But if you want to explore this, we are already thinking of how to iterate this message. We haven't really thought about the axis. The main concern is that currently we have a message that provides button mappings and the flight stack has to map those button mappings to functions - that's a lot of code in the flight stack, and requires that the GCS knows quite a bit about the flight stack it is taking to. What we're thinking about is removing the button array and having the ground station just send mavlink commands on button presses.

@peterbarker
Copy link
Contributor

2. But if you want to explore this, we are already thinking of how to iterate this message. We haven't really thought about the axis. The main concern is that currently we have a message that provides button mappings and the flight stack has to map those button mappings to functions - that's a lot of code in the flight stack, and requires that the GCS knows quite a bit about the flight stack it is taking to. What we're thinking about is removing the button array and having the ground station just send mavlink commands on button presses.

Oddly, I'm looking at doing the opposite in (non-Sub) ArduPilot (ArduPilot/ardupilot#22259) - actually taking action based on the buttons field in MANUAL_CONTROL. ArduPilot has a set of pre-canned "auxiliary functions" which I'll be using to provide the button functions - we use that list for physical buttons present on the vehicle, RC switches, mission items, lua script and direct mavlink calls, so reusing that list is making sense so far.

Turns out that MissionPlanner actually already does what you're suggesting here - makes mavlink calls rather than passing through the button bits (a small impediment to my little project).

@hamishwillee
Copy link
Collaborator

Turns out that MissionPlanner actually already does what you're suggesting here - makes mavlink calls rather than passing through the button bits (a small impediment to my little project).

Sounds daft unless the functions you want don't have corresponding mavlink messages, or can't do so for some reason. I understand that in Canberra they call you "Mad Peter" :-)

Currently

  • ArduPilot has parameters that map what buttons are, and GCS has to know what those parameters are
  • PX4 hard codes specific buttons in the message to specific functions, so the GCS needs to know what functions are used for each case and send that set of values in the message.

The send-a-mavlink-message approach seems much smarter and more flexible.

  • The GCS does not need to know anything about the flight stack than it already knows - what commands are supported. (and even those can be in many cases checked without side effects). It doesn't need to know what parameters the flight stack uses to map button presses or what functions are called.
  • The flight stack doesn't have to have special code paths to process instructions it is already processing through mavlink.
  • The manual control message doesn't have to cope with the possiblity of joysticks with more buttons than we expose.

@peterbarker
Copy link
Contributor

peterbarker commented Nov 30, 2022 via email

@hamishwillee
Copy link
Collaborator

@peterbarker There was an orthogonal discussion here #1848 which looks at the use case of a MAVLink joystick. This is a joystick that does not need to be connected to a GCS when used.

The idea was that a joystick would have a component metadata mechanism to configure its buttons a lot like the mavlink camera API - i.e. you'd query the joystick for its axes and buttons and get metadata back on what is supported. The buttons would have set options that map to parameter values - i.e. button 1 might have param_button_1 on the joystick with options "enable fence", "kill switch".
So you connect to a GCS once, use the config API to select the things you want on each button based on the options it supplies. The joystick then sends its messages direct to the autopilot node on the network (or other component ID) and when a button is pressed sends the appropriate MAVLink command.

My point is that the sending mavlink command mechanism is more flexible here too. Component information helps with the problem of knowing what the joystick can do, and means that the autopilot doesn't need to have any extra config to work.

It's just an idea at this time.

@hamishwillee
Copy link
Collaborator

hamishwillee commented Nov 30, 2022

Anyway, appreciate that you're probably making a pragmatic decision based on what mission planner does now (and PX4). Nothing is going to change in any sort of short timeframe so you can do what you like. But if you go with sending mavlink commands that will work whatever is done in future with the MANUAL_CONTROL message.

@hamishwillee
Copy link
Collaborator

Discussed this in the 20250410 dev call. This was explained to me as follows (capturing so I don't have to ask this all again!)

  1. MANUAL CONTROL is defined as a mapping of x, y, z, axes (FRD) with a statement that these generally map to pitch, roll, thrust.
  2. The intent of the design was that these actually map to an acceleration in each of the axis. The x, y, z are mapped as intended (to pitch, roll, thrust) on a multicopter vehicle.
  3. However this mapping is not observed for other vehicle types - the z axis is always mapped to thrust, which on a fixed wing vehicle would be forwards. So there is an inconsistency across vehicles.
  4. PX4 and ArduPilot both do this "wrong thing". PX4 maps directly to the thrust setpoint, and ArduPilot maps this through an RC_CHANNEL_OVERRIDE (Used by ArduSub).
  5. This "works" because QGC is the only thing that sends this, so it is consistent.

Upshot I am not sure how to change the messages but if we change anything we break everything.

I'm not sure how we'd fix this - presumably a similar message where the definitions are as intended by MANUAL_CONTROL and that is then implemented "properly".

@julianoes Is that about right? Feel free to edit this if I misunderstood!

@julianoes
Copy link
Collaborator

(FRD) with a statement that these generally map to pitch, roll, thrust.

That's debatable. The naming would indicate this but the way it is described and implemented does not.

Upshot I am not sure how to change the messages but if we change anything we break everything.

They way how I read this is that @junwoo091400 does not actually want to change/break anything but merely document how it is actually used and implemented in QGC.

@peterbarker
Copy link
Contributor

Ping @Williangalvani

@junwoo091400
Copy link
Author

junwoo091400 commented Apr 21, 2025

So here's the summary of the whole landscape on MANUAL_CONTROL:

QGC

  • Sends: [0, 1000] or [-1000, 1000] (PX4: Rover + Submarine, Ardupilot: Rover) depending on vehicle type
  • Receives: [x] (Only shows it in MAVLink Inspector)

PX4

Ardupilot

Thus, it seems fairly customized per vehicle type, and the unification of the definition won't be trivial (expected range already differs per vehicle in Firmwares), and will lead breaking changes (e.g. [-1000, 1000] range will be rejected for Arducopter, PX4, etc)

So I think there isn't really a solution here, and the best we could do is just to clarify this difference of MANUAL_CONTROL.z per vehile type in the MAVLink message definition, and support this legacy implementation.

Thoughts?

p.s. It's interesting that QGC originally allowed users to choose whether RC transmitter's throttle channel is spring loaded or not, but now that logic isn's used AFAIK (assumes not spring loaded): mavlink/qgroundcontrol#1827

Also, the Rover / Submarine control for PX4 through QGC is broken exactly due to this mismatch. So only the 'positive thrust' worked before, due to the (debatable) wrong implementation on Firmware side (not considering neative MANUAL_CONTROL.z range when Rover/Submarine)

<field type="int16_t" name="x" invalid="INT16_MAX">X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.</field>
<field type="int16_t" name="y" invalid="INT16_MAX">Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.</field>
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.</field>
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to throttle high (1000) - throttle low (-1000) on a joystick. Centered throttle should result in value of 0 (center).</field>
Copy link
Author

Choose a reason for hiding this comment

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

Suggested change
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to throttle high (1000) - throttle low (-1000) on a joystick. Centered throttle should result in value of 0 (center).</field>
<field type="int16_t" name="z" invalid="INT16_MAX">Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Due to legacy reasons, [0, 1000] is used for PX4, ArduCopter, ArduPlane and ArduSub, whereas [-1000, 1000] is used for ArduRover. However originally, it generally corresponds to throttle high (1000) - throttle low (-1000) on a joystick. Centered throttle should result in value of 0 (center).</field>

@Williangalvani
Copy link
Contributor

Williangalvani commented Apr 22, 2025

I stand with @junwoo091400's latest suggestion.

Many times I thought about ways of remapping (for the sole purpose of following the spec) ArduSub to [-1000,1000], but I never got to a solution that wouldn't brake things.
Given that most vehicle are using the [0,1000] range, I vote we just document it properly.

@MaEtUgR
Copy link
Contributor

MaEtUgR commented Apr 23, 2025

Thanks @junwoo091400 for the implementation overview!

Thus, it seems fairly customized per vehicle type, and the unification of the definition won't be trivial

I reached the same conclusion. Usage varies due to the ambiguous definition.

Initially, I aimed for a consistent across vehicle types and with the other axes [-1000, 1000] full range in PX4, but transitioning cleanly proved infeasible. PX4 now enforces a [0, 1000] range and clamps negative values in that field (not rejecting the entire message), aligning with what QGC mostly sends and others mimic.

the best we could do is just to clarify this difference of MANUAL_CONTROL.z per vehile type in the MAVLink message definition, and support this legacy implementation

I agree and like your very specific description of how the field is used but would leave away the last part However originally, it generally corresponds to throttle high (1000) - throttle low (-1000) on a joystick. Centered throttle should result in value of 0 (center). because it generates confusion around the original user of the field who we cannot name. There's still the original superset range of the field at the beginning and people reading this at least know that most use cases have for historical interpretation reasons (1567c0a) a different range.

Long-term, I plan to introduce a new message that clearly defines remote input axes without ambiguous ranges or assumptions about their use of different vehicle types and modes on the receiving end.

@julianoes
Copy link
Collaborator

julianoes commented Apr 29, 2025

Without having read everything, so how do you go backwards, or actively down?

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

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

6 participants