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

40 changes: 40 additions & 0 deletions message_definitions/v1.0/development.xml
Expand Up @@ -14,6 +14,15 @@
<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. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent.</description>
</entry>
<entry value="2" name="RADIO_RC_CHANNELS_FLAGS_OUTDATED">
<description>Content of the RC channels field in the RADIO_RC_CHANNELS message does not contain the current/latest RC data but the last RC data received.</description>

Choose a reason for hiding this comment

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

is specified to be set whenever the timestamp does not match the current time of the message but lags behind, and the channels data are not fresh. This makes interpreting/using the timestamp much easier.

So to be clear, this is when the receiver has detected data from the transmitter but can't parse it. So Rx is sending channels and data that is known to be old. old data. This is more a hint to the recipient since the data in the channels is still all valid at the timestamp.

Suggested change
<description>Content of the RC channels field in the RADIO_RC_CHANNELS message does not contain the current/latest RC data but the last RC data received.</description>
<description>Channel data may be out of date (recipients should check the timestamp to decide if the data can still be used). This is set when the receiver is unable to parse incoming data from the transmitter and has therefore resent the last data it was able to process.</description>

</entry>
</enum>
</enums>
<messages>
<message id="53" name="MISSION_CHECKSUM">
Expand All @@ -38,5 +47,36 @@
<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 outputs from a MAVLink RC receiver for input to a flight controller or other components
(allows an RC receiver to connect via MAVLink instead of some other protocol such as PPM-Sum or S.BUS).
Note that this is not intended to be an over-the-air format, and does not replace RC_CHANNELS and similar
messages reported by the flight controller. 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.
The channels array field can publish up to 32 channels; the number of channel items used in the array is
specified in the count field.
The time_last_update_ms field contains the timestamp of the last received valid channels data in the
receiver's time domain, and the channel items up to count holds the last valid data.
If the channels data are not up-to-date and do not hold the current/latest data, the RADIO_RC_CHANNELS_FLAGS_OUTDATED
flag is set by the receiver.
The RADIO_RC_CHANNELS_FLAGS_FAILSAFE failsafe flag is set by the receiver if the receiver's failsafe condition
is met (implementation dependent, e.g., connection to the RC radio is lost). In this case time_last_update_ms
still contains the timestamp of the last valid channels data, but the content of the channels data is not
defined by the protocol but is up to the implementation of the receiver. For instance, the channels data could
contain failsafe values configured in the receiver; 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>

Choose a reason for hiding this comment

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

This makes relatively minor modifications for English, not for the behaviour.

  1. Sentence line breaks - make it easier to read (for me) than arbitrary line breaks.
  2. Reworded the text around RADIO_RC_CHANNELS_FLAGS_OUTDATED - meaning is the same.
  3. Restructured to say "The count field indicates the first index of the channel array that holds invalid data.". I've assumed MAVLink uses array indexing from 0 but perhaps we should never assume and just say "this is the count of items that are used" because different programming languages take different conventions.
Suggested change
<description>RC channel outputs from a MAVLink RC receiver for input to a flight controller or other components
(allows an RC receiver to connect via MAVLink instead of some other protocol such as PPM-Sum or S.BUS).
Note that this is not intended to be an over-the-air format, and does not replace RC_CHANNELS and similar
messages reported by the flight controller. 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.
The channels array field can publish up to 32 channels; the number of channel items used in the array is
specified in the count field.
The time_last_update_ms field contains the timestamp of the last received valid channels data in the
receiver's time domain, and the channel items up to count holds the last valid data.
If the channels data are not up-to-date and do not hold the current/latest data, the RADIO_RC_CHANNELS_FLAGS_OUTDATED
flag is set by the receiver.
The RADIO_RC_CHANNELS_FLAGS_FAILSAFE failsafe flag is set by the receiver if the receiver's failsafe condition
is met (implementation dependent, e.g., connection to the RC radio is lost). In this case time_last_update_ms
still contains the timestamp of the last valid channels data, but the content of the channels data is not
defined by the protocol but is up to the implementation of the receiver. For instance, the channels data could
contain failsafe values configured in the receiver; 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>
<description>RC channel outputs from a MAVLink RC receiver for input to a flight controller or other components (allows an RC receiver to connect via MAVLink instead of some other protocol such as PPM-Sum or S.BUS).
Note that this is not intended to be an over-the-air format, and does not replace RC_CHANNELS and similar
messages reported by the flight controller.
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.
The channels array field can publish up to 32 channels; the number of channel items used in the array is specified in the count field.
The time_last_update_ms field contains the timestamp of the last received valid channels data in the receiver's time domain.
The count field indicates the first index of the channel array that holds invalid data.
The RADIO_RC_CHANNELS_FLAGS_OUTDATED is set by the receiver if the channels data is not up-to-date (for example, if new data from the transmitter could not be decoded so the previous data is resent).
The RADIO_RC_CHANNELS_FLAGS_FAILSAFE failsafe flag is set by the receiver if the receiver's failsafe condition is met (implementation dependent, e.g., connection to the RC radio is lost).
In this case time_last_update_ms still contains the timestamp of the last valid channels data, but the content of the channels data is not defined by the protocol (it is up to the implementation of the receiver).
For instance, the channels data could contain failsafe values configured in the receiver; 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 (ID of target system, normally flight controller).</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 the data in the channels field were last updated (time since boot in the receiver'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

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" minValue="-4096" maxValue="4096">RC 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.
Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming.</field>
</message>
</messages>
</mavlink>