-
Notifications
You must be signed in to change notification settings - Fork 1.9k
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
Changes to standard flight modes #1915
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -142,6 +142,21 @@ | |
</description> | ||
</entry> | ||
</enum> | ||
<enum name="MAV_MODE_PROPERTY" bitmask="true"> | ||
<description>Mode properties. | ||
</description> | ||
<entry value="1" name="MAV_MODE_PROPERTY_ADVANCED"> | ||
<description>If set, this mode is an advanced mode. | ||
For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. | ||
A GCS can optionally use this flag to configure the UI for its intended users. | ||
</description> | ||
</entry> | ||
<entry value="2" name="MAV_MODE_PROPERTY_NOT_USER_SELECTABLE"> | ||
<description>If set, this mode should not be added to the list of selectable modes. | ||
The mode might still be selected by the FC directly (for example as part of a failsafe). | ||
</description> | ||
</entry> | ||
</enum> | ||
<!-- The MAV_CMD enum entries describe either: --> | ||
<!-- * the data payload of mission items (as used in the MISSION_ITEM_INT message) --> | ||
<!-- * the data payload of mavlink commands (as used in the COMMAND_INT and COMMAND_LONG messages) --> | ||
|
@@ -480,18 +495,18 @@ | |
<field type="uint8_t" name="number_modes">The total number of available modes for the current vehicle type.</field> | ||
<field type="uint8_t" name="mode_index">The current mode index within number_modes, indexed from 1.</field> | ||
<field type="uint8_t" name="standard_mode" enum="MAV_STANDARD_MODE">Standard mode.</field> | ||
<field type="uint8_t" name="base_mode" enum="MAV_MODE_FLAG" display="bitmask">System mode bitmap.</field> | ||
<field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags</field> | ||
<field type="char[50]" name="mode_name">Name of custom mode, with null termination character. Should be omitted for standard modes.</field> | ||
<field type="uint32_t" name="properties" enum="MAV_MODE_PROPERTY">Mode properties.</field> | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @bkueng FMI, and sorry if I already asked, but is 32 bits too many, or just right? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I guess it doesn't matter - these are only emitted on request. Ignore. |
||
<field type="char[35]" name="mode_name">Name of custom mode, with null termination character. Should be omitted for standard modes.</field> | ||
</message> | ||
<message id="436" name="CURRENT_MODE"> | ||
<description>Get the current mode. | ||
This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). | ||
It may be requested using MAV_CMD_REQUEST_MESSAGE. | ||
</description> | ||
<field type="uint8_t" name="standard_mode" enum="MAV_STANDARD_MODE">Standard mode.</field> | ||
<field type="uint8_t" name="base_mode" enum="MAV_MODE_FLAG" display="bitmask">System mode bitmap.</field> | ||
hamishwillee marked this conversation as resolved.
Show resolved
Hide resolved
|
||
<field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags</field> | ||
<field type="uint32_t" name="intended_custom_mode" invalid="0">The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied</field> | ||
</message> | ||
<!-- Target info from a sensor on the target --> | ||
<message id="510" name="TARGET_ABSOLUTE"> | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@bkueng My understanding is that this is not needed to identify a mode and is independent of the custom mode, so on that basis we do not need it, because it provides no identity.
However if you have a custom mode, does it tell you anything useful you might otherwise have to query for in some other way?
For example, might you use https://mavlink.io/en/messages/common.html#MAV_MODE_FLAG to know that the mode is automatic, and would it be useful to know that about an unknown custom mode?
If we stripped it out of the heartbeat, would we want it in the CURRENT_MODE? i.e. does having it here give us a path to one day having a simpler heartbeat?
My gut feeling is no but I wanted to confirm if you see any reason to leave it.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I did not think it's useful.
That's a possibility. Given the heartbeat is such a central message, I don't consider changing it is an option, but that's not up to me.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I don't think it is either. FYI, I created a PR to update RFC assuming this PR goes in mavlink/rfcs#24
Chatting to James about it tonight hopefully.