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

20 changes: 20 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.</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

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>
<entry value="2" name="RADIO_RC_CHANNELS_FLAGS_FRAME_MISSED">
Copy link
Collaborator

Choose a reason for hiding this comment

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

this can't be filled in accurately without the sender knowing if any mavlink frames were lost, as we can't know if this is new data or not.
Much better to have an 8 bit number of how many 10s of milliseconds since we received the last valid message from the receiver

Copy link
Collaborator

Choose a reason for hiding this comment

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

could also be a 16bit or 32 bit millisecond timestamp in the senders time domain

Copy link
Collaborator

Choose a reason for hiding this comment

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

decided on call we will use a 32 bit ms timestamp since boot on the senders time domain, and remove the FRAME_MISSED flag

Copy link

Choose a reason for hiding this comment

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

THX
will be done

<description>Indicates that the current frame has not been received. Channel values are frozen.</description>
</entry>
</enum>

Choose a reason for hiding this comment

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

Do we need both of these? A "channels are valid" flag might be sufficient? Could we clarify or rename entry 2 to mean exactly that, with any other bits set jsut being additional information, perhaps?

The ArduPilot implementation was only looking at one of the two existing bits, but it seems to me we should be ignoring input if either is set. I'd prefer a singlet bit to indicate whether we should be trusting the channel values ata all.

Copy link

Choose a reason for hiding this comment

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

we sure don't necessarily need FRAME_MISSED, but I considered it usefull (even if it may not be used in AP code)
it's kind of mirroing sbus
we could also rename it to CHANNELS_INVALID, even though I'm not sure I see what it improves.

Copy link

Choose a reason for hiding this comment

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

per dev call decission, flag will be removed

</enums>
<messages>
<message id="53" name="MISSION_CHECKSUM">
Expand All @@ -38,5 +47,16 @@
<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>Radio channels. Supports up to 32 channels. Channel values are in centered 13 bit format. Range is [-4096,4096], center is 0. Conversion to PWM is x * 5/32 + 1500.
Copy link
Collaborator

Choose a reason for hiding this comment

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

should mention that this is an set of RC channel inputs for a flight controller, it does not replace the RC_CHANNELS output message

Copy link

Choose a reason for hiding this comment

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

Thx, will be done

The target_system field should normally be set to the system id of system the radio receiver is connected to, the target_component field can be normally set to 0.
</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="uint8_t" name="count">Total number of RC channels being received. This can be larger than 24, indicating that more channels are available but not given in this message.</field>
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
<field type="uint16_t" name="flags" enum="RADIO_RC_CHANNELS_FLAGS" display="bitmask">Radio rc channels status flags.</field>
<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 above count should be set to 0, to benefit from MAVLink's zero padding.</field>

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[32]" name="channels">RC channels. Channels above count should be set to 0, to benefit from MAVLink's zero padding.</field>
<field type="int16_t[32]" name="channels">RC channels. Channels above count should be set to 0, to benefit from MAVLink's trailing-zero trimming.</field>

Copy link

Choose a reason for hiding this comment

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

THX, will be done

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