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

development.xml: RADIO_RC_CHANNELS message #343

26 changes: 26 additions & 0 deletions message_definitions/v1.0/development.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,12 @@
<description>True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control.</description>
</entry>
</enum>
<enum name="RADIO_RC_CHANNELS_FLAGS" bitmask="true">
<description>RADIO_RC_CHANNELS flags (bitmask).</description>
<entry value="1" name="RADIO_RC_CHANNELS_FLAGS_FAILSAFE">
<description>Failsafe is active.</description>

Choose a reason for hiding this comment

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

What is failsafe? When is it triggered? What should receiver do?

Copy link

Choose a reason for hiding this comment

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

that's really up to the receiver. All is - IMHO - relevant here is that such a thing like a failsafe can happen and that the recipient wants to react on it. "Failsafe" has here the same meaning as with every rc receiver too. Typically it would be connection lost, whatever this means to the particular link.

Copy link

@hamishwillee hamishwillee Jan 31, 2024

Choose a reason for hiding this comment

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

The problem here is #343 (comment) - nowhere do you say this is "like a typical RC receiver" so this could mean anything. Perhaps that's correct, but either way I like to spell out what this might mean and how the recipient should react.

From above "1. frame with valid rc data received, 2. a frame is missed (which isn't equal to a failsafe!), ergo no fresh rc data in that time slot, 3. failsafe. ". So failsafe means "connection lost" right? If it always means "connection lost" can we name it that?

Otherwise maybe

Suggested change
<description>Failsafe is active.</description>
<description>Failsafe is active. This is sent when the receiver has lost connection (is not receiving or able to parse data from the sender).</description>

Choose a reason for hiding this comment

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

@olliw42 Is this correct ^^^. If so, merge? I don't have rights to merge here.

</entry>
</enum>
</enums>
<messages>
<message id="53" name="MISSION_CHECKSUM">
Expand All @@ -38,5 +44,25 @@
<field type="float" name="raw_press" units="hPa">Raw differential pressure. NaN for value unknown/not supplied.</field>
<field type="uint8_t" name="flags" enum="AIRSPEED_SENSOR_FLAGS">Airspeed sensor flags.</field>
</message>
<message id="420" name="RADIO_RC_CHANNELS">
<description>RC channel inputs for a flight controller and associated components; the message does not replace the RC_CHANNELS and similar output messages.

Choose a reason for hiding this comment

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

What rates do we think this should be sent at?

Copy link

Choose a reason for hiding this comment

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

that's really up to the receiver ... it can be "anything" the link can or wants to offer.

Choose a reason for hiding this comment

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

See #343 (comment) > This is not sufficient for "most people" to understand that this is the output of an Rx receiver, replacing other protocols.

Supports up to 32 channels. Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500.
The target_system field should normally be set to the system id of the system to control, typically the flight controller.
The target_component field can normally be set to 0, so that all components of the system can receive the message.
Copy link

@hamishwillee hamishwillee Jan 31, 2024

Choose a reason for hiding this comment

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

Worth saying perhaps that this might allow targeting of what is effectively a second RC controller to command a a specific mavlink component - i.e. allow having separate RC for gimbal and autopilot flight control?

What if we want to target a vehicle attached gimbal using a separate RC?

Copy link

Choose a reason for hiding this comment

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

IMHO that's what targets are generally for in a MAVLink system

Choose a reason for hiding this comment

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

Right, but since you've explicitly said it can normally go everywhere, my thought was that it makes sense to say what case would make you not send it everywhere. Had you said nothing I would probably have left it. I do like spelling things out.

The time_last_update_ms field indicates the time, in the sender's time domain, when the RC channels data were last updated. If this time is significantly shorter
than the expected update time for this message, then the RC channels data can be considered invalid, and the RC channels data should carry the last valid data.
Copy link

@hamishwillee hamishwillee Jan 31, 2024

Choose a reason for hiding this comment

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

Shorter or longer? What is doing the "considering invalid".

What is the sender here - GCS? What is the receiver - Autopilot?

I "think" from a year ago that you were talking about a system where this is like a normal RC Rx/Tx setup but instead of talking a common RC protocol such as sbus you would use this message. So probably when you say "sender" you mean the Rx unit that is sending this mavlink message. But you might not. Should be spelled out.

Once that is clear, then I can interpret how the timeout and RC loss/ and data invalid work.

Copy link

Choose a reason for hiding this comment

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

You make a very valid observation, that with regards to targets and this timestamp quite something has changed here, and I will comment to this big picture below.

As regards the mechansim, I think it's pretty simple and common (even though maybe not totally trivial to implement). First note that we have 3 situations: 1. frame with valid rc data received, 2. a frame is missed (which isn't equal to a failsafe!), ergo no fresh rc data in that time slot, 3. failsafe. So we need "something" to indicate case 2. In sbus language it would be called "missed frame". Instead of a 2nd flag (which was the original proposal) ,this field was introduced upon @tridge 's request, and is supoposed to help in case of a lossy network. So, the basic is the assumption that not all messages are receiveed but some are lost.

Choose a reason for hiding this comment

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

Thanks.

If this time is significantly shorter than the expected update time for this message, then the RC channels data can be considered invalid, and the RC channels data should carry the last valid data."

The timestamp would be small if the sender rebooted or similar - so is this to catch the case where the sender rebooted and you can no longer use the delta between two timestamps to determine the time between the last two updates?

In the case of a failsafe (when the RADIO_RC_CHANNELS_FLAGS_FAILSAFE bit set in the flags field), the RC channels data can be frozen and carried forward, e.g.,
the last valid data or failsafe values configured in the sender of the message. The exact behavior is not defined by the protocol but up to the implementation
of the sender; the default is to carry the last valid data.
Note: The RC channels fields are extensions to ensure that they are located at the end of the serialized payload and subject to MAVLink's trailing-zero trimming.
</description>
<field type="uint8_t" name="target_system">System ID (can be 0 for broadcast, but this is discouraged).</field>
<field type="uint8_t" name="target_component">Component ID (normally 0 for broadcast).</field>
<field type="uint32_t" name="time_last_update_ms" units="ms">Time when RC channels were last updated (time since boot in the sender's time domain).</field>
<field type="uint16_t" name="flags" enum="RADIO_RC_CHANNELS_FLAGS" display="bitmask">Radio RC channels status flags.</field>
<field type="uint8_t" name="count">Total number of RC channels being received. This can be larger than 32, indicating that more channels are available but not given in this message.</field>
Copy link

@hamishwillee hamishwillee Jan 31, 2024

Choose a reason for hiding this comment

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

If we can conceivably want more than 32 channels, would we be better to use an index and a count for this message? And in that case you could have a smaller array if you wanted.

Or if we're agreeing that truncation is actually important enough here to force reordering and never extending, why don't we make this a full length array (i.e use up the rest of the packet).

Copy link

Choose a reason for hiding this comment

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

I thought about this. We could add a field with the first channel in the message, which would allow sending several. Also, sure one could make it as large as possible (and I increased already from 24 to 32).
But: I really think we should not overdo it ...

My first impulse: REALLY? I would argue if really more than 32 RC channles are needed really something is wrong with the setup and what this person wants to do. There should then be a more appropriate "microservoce". I.e., the only reason I can see one may want more than 32 channels is to missuse it for something which is not existing. Just put 32 switches on your radio ... I won't believe you that you will know them all just 2 weeks later.

This message can be emitted by the receiver at relatively high rate, let's say 100 Hz (depending on the receiver)! Again, I doubt one ever will need that many rc channels at high rate, and all it tells is that oen wants to do something this message isn't for.

I VERY STRONGLY advice to not make this a message which is supposed to do everything and cure all issues in this world.

Choose a reason for hiding this comment

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

All very logical, but we've said "that'll be all we need" so many times I don't believe it any more. We recently had someone come up with a joystick with more than 32 widgets on it, and history tells me that this will grow.

But anyhow, the main reason I want this it to use up all the remaining bits so that no one can extend it - that's for the same reason you have - to stop it being reused and extended at will.

Copy link
Collaborator

Choose a reason for hiding this comment

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

I don't think more than 32 R/C channels is useful

<extensions/>

Choose a reason for hiding this comment

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

Suggested change
<extensions/>

No reason to make these extensions AFAICS.

trailing-zero-in-payload-trimming happens regardless of extension/not extension.

Copy link

Choose a reason for hiding this comment

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

IMHO incorrect. The sequence of fields is reordered, such that the larger fields come first. So the unit8 fields would be at the back, and zero trim would not work for the channel fields

Choose a reason for hiding this comment

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

Good call!

Could we get a comment instead, please?

Copy link

Choose a reason for hiding this comment

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

done

Choose a reason for hiding this comment

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

If we do this we're saying we will never extend this message. Is that a shared understanding?

Copy link
Collaborator

Choose a reason for hiding this comment

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

yes

<field type="int16_t[32]" name="channels">RC channels. Channels that are above the field count should be set to 0, to benefit from MAVLink's trailing-zero trimming.</field>

Choose a reason for hiding this comment

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

My assumption here is that these reflect full range of an input centred on 0 - effectively a normalized input - i.e. no direct concept of mapping to a particular PWM range? If so, it should say that here.

Copy link

@hamishwillee hamishwillee Jan 31, 2024

Choose a reason for hiding this comment

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

Ah, I see you have done that above "Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500."

Would there be any benefit to normalizing this and completely moving away from PWM? I'm kind of hoping we might head towards a single mechanism for setting manual control input ranges across joystick and RC so there is just one handling path.

Copy link

Choose a reason for hiding this comment

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

I'm very against it, since the whole ecosystem around it is just not like that. All radios I'm aware off think in terms of us or %. All receivers I'm aware of do so too. You just would introduce yet another unit system and create confusion as regards how they scale, and relate to the old units. Also it's hard to truncate, it's just too common to set the radio to e.g. +-120% or even +-150%. And what is the benfit at all?

I personally am also VERY against making this a "eierlegende Wollmilchsau" (google translates to egg-laying jack of all trades LOL). More on this below.

Choose a reason for hiding this comment

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

Normalizing to a whole range is not a complicated rescaling, but I do understand that if this is single-purpose it is unnecessary.

If there is no interest I have no objection.

</message>
</messages>
</mavlink>
Loading