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

ardupilotmega.xml: Add NAV_CONTROLLER_PROGRESS message #366

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions message_definitions/v1.0/ardupilotmega.xml
Original file line number Diff line number Diff line change
Expand Up @@ -1886,5 +1886,18 @@
<field type="uint16_t[4]" name="rpm" units="rpm">RPM (eRPM).</field>
<field type="uint16_t[4]" name="count">count of telemetry packets received (wraps at 65535).</field>
</message>
<message id="11045" name="NAV_CONTROLLER_PROGRESS">
<description>Progress of the current Nav Controller item.</description>
<field type="uint8_t" name="percentage_complete" invalid="UINT8_MAX">Percentage complete. Set to UINT8_MAX if unknown.</field>
<field type="float" name="distance_remaining" units="m" invalid="NaN">Distance remaining (in metres) until the current Nav Controller item is complete. Set to NaN if unknown, or not applicable.</field>
<field type="float" name="time_remaining" units="s" invalid="NaN">Time remaining (in seconds) until the current Nav Controller item is complete. Set to NaN if unknown, or not applicable.</field>
<field type="float" name="count_remaining" invalid="NaN">Count remaining until the current Nav Controller item is complete. Set to NaN if unknown, or not applicable.</field>
<field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission item type.</field>
<field type="uint16_t" name="seq">Sequence (mission item number). Set to 0 if not a mission item.</field>
<field type="int32_t" name="target_x" invalid="INT32_MAX">X pos/Latitude of nav target. Set to INT32_MAX if no target, or to use the location of the corresponding mission item.</field>
<field type="int32_t" name="target_y" invalid="INT32_MAX">Y pos/Longitude of nav target. Set to INT32_MAX if no target, or to use the location of the corresponding mission item.</field>
<field type="float" name="target_z" units="m" invalid="NaN">Z pos/Altitude of nav target. Set to NaN if no target, or to use the location of the corresponding mission item.</field>
<field type="uint8_t" name="target_frame" enum="MAV_FRAME">Coordinate frame of target.</field>
</message>
</messages>
</mavlink>
Loading