mavlinkdialect
Parse and store MAVLink dialect XML
Description
The mavlinkdialect
object parses and stores message and enum
definitions extracted from a MAVLink message definition file (.xml
). The
message definition files define the messages supported for this specific dialect. The
structure of the message definitions is defined by the MAVLink message
protocol.
Creation
Syntax
Description
creates a MAVLink dialect using the dialect
= mavlinkdialect("common.xml")common.xml
file for standard
MAVLink messages.
specifies the XML file for parsing the message definitions. The input sets the
dialect
= mavlinkdialect(dialectXML)DialectXML
property.
additionally specifies the MAVLink protocol version. The inputs set the
dialect
= mavlinkdialect(dialectXML,version)DialectXML
and Version
properties,
respectively.
uses the MAVLink signing channel dialect
= mavlinkdialect(___,SigningChannel=channel
)channel
.
Input Arguments
channel
— MAVLink signing channel
structure
MAVLink signing channel, specified as a structure containing these fields:
Stream
— Signing stream, specified as amavlinksigning
object.SystemID
— System ID, specified by an integer in the range [0, 255].ComponentID
— Component ID, specified by an integer in the range [0, 255].LinkID
— Link ID, specified by an integer in the range [0, 255].Key
— Key, specified by as a string.Timestamp
— Time passed since2015-01-01 UTC
. Unit is 10 microseconds.CreationTime
— Time of creation, specified as adatetime
array.
You can create this structure by adding the signing channel using the
addChannel
object function of the mavlinksigning
object.
Properties
DialectXML
— MAVLink dialect name
string
MAVLink dialect name, specified as a string. This name is based on the XML file name.
Example:
"ardupilotmega"
Data Types: char
| string
Version
— MAVLink protocol version
2
(default) | 1
MAVLink protocol version, specified as either 1 or 2.
Data Types: double
Object Functions
Examples
Parse and Use MAVLink Dialect
This example shows how to parse a MAVLink XML file and create messages and commands from the definitions.
Parse and store the MAVLink dialect XML. Specify the XML path. The default "common.xml"
dialect is provided. This XML file contains all the message and enum definitions.
dialect = mavlinkdialect("common.xml");
Create a MAVLink command from the MAV_CMD
enum, which is an enum of MAVLink commands to send to the UAV. Specify the setting as "int"
or "long"
, and the type as an integer or string.
cmdMsg = createcmd(dialect,"long",22)
cmdMsg = struct with fields:
MsgID: 76
Payload: [1x1 struct]
Verify the command name using num2enum
. Command 22 is a take-off command for the UAV. You can convert back to an ID using enum2num
. Your dialect can contain many different enums with different names and IDs.
cmdName = num2enum(dialect,"MAV_CMD",22)
cmdName = "MAV_CMD_NAV_TAKEOFF"
cmdID = enum2num(dialect,"MAV_CMD",cmdName)
cmdID = 22
Use enuminfo
to view the table of the MAV_CMD
enum entries.
info = enuminfo(dialect,"MAV_CMD");
info.Entries{:}
ans=148×3 table
Name Value Description
_____________________________________ _____ _______________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________
"MAV_CMD_NAV_WAYPOINT" 16 "Navigate to waypoint."
"MAV_CMD_NAV_LOITER_UNLIM" 17 "Loiter around this waypoint an unlimited amount of time"
"MAV_CMD_NAV_LOITER_TURNS" 18 "Loiter around this waypoint for X turns"
"MAV_CMD_NAV_LOITER_TIME" 19 "Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint."
"MAV_CMD_NAV_RETURN_TO_LAUNCH" 20 "Return to launch location"
"MAV_CMD_NAV_LAND" 21 "Land at location."
"MAV_CMD_NAV_TAKEOFF" 22 "Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode."
"MAV_CMD_NAV_LAND_LOCAL" 23 "Land at local position (local frame only)"
"MAV_CMD_NAV_TAKEOFF_LOCAL" 24 "Takeoff from local position (local frame only)"
"MAV_CMD_NAV_FOLLOW" 25 "Vehicle following, i.e. this waypoint represents the position of a moving vehicle"
"MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT" 30 "Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached."
"MAV_CMD_NAV_LOITER_TO_ALT" 31 "Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint."
"MAV_CMD_DO_FOLLOW" 32 "Begin following a target"
"MAV_CMD_DO_FOLLOW_REPOSITION" 33 "Reposition the MAV after a follow target command has been sent"
"MAV_CMD_DO_ORBIT" 34 "Start orbiting on the circumference of a circle defined by the parameters. Setting any value NaN results in using defaults."
"MAV_CMD_NAV_ROI" 80 "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."
⋮
Query the dialect for a specific message ID. Create a blank MAVLink message using the message ID.
info = msginfo(dialect,"HEARTBEAT")
info=1×4 table
MessageID MessageName Description Fields
_________ ___________ _____________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________________ ___________
0 "HEARTBEAT" "The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html" {6x6 table}
msg = createmsg(dialect,info.MessageID);
Version History
Introduced in R2019a
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)