- # alternative to creating custom mavlink messages
- # defining custom mavlink messages
- # receiving custom mavlink messages
- # set streaming rate
- # testing
- Additional checks
- Command decoding
- Examples
- Getting libraries
- Lets break it down…
- Message signing
- Multiple streams (“channels”)
- Parsing packets
- Receiving
- Transmitting
- Upgrading library from mavlink 1
- -waddress-of-packed-member
- # sending custom mavlink messages
# alternative to creating custom mavlink messages
Sometimes there is the need for a custom MAVLink message with content that is not fully defined.
# defining custom mavlink messages
PX4 includes the mavlink/mavlink(opens new window) repo as a submodule under /src/modules/mavlink(opens new window), and generates the MAVLink 2 C header files at build time.
There are are number of XML dialect files in /mavlink/messages/1.0/(opens new window).
The dialect that is built is specified using the variable MAVLINK_DIALECT in /src/modules/mavlink/CMakeLists.txt(opens new window); by default this is development.xml(opens new window).
The files are generated into the build directory: /build/<build target>/mavlink/.
In order to add your message we recommend that you create your messages in a new dialect file in the same directory, for example PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0/custom_messages.xml, and set MAVLINK_DIALECT to build the new file.
This dialect file should include development.xml.
You can alternatively add your messages to common.xml or development.xml.
Whatever dialect file you use must eventually be built in QGroundControl (or whatever software you use to communicate with PX4).
The MAVLink developer guide explains how to define new messages in How to Define MAVLink Messages & Enums(opens new window).
You can check that your new messages are built by inspecting the headers generated in the build directory.
If your messages are not built they may be incorrectly formatted, or use clashing ids.
Inspect the build log for information.
# receiving custom mavlink messages
This section explains how to receive a message over MAVLink and publish it to uORB.
Add a function that handles the incoming MAVLink message in
mavlink_receiver.h(opens new window)
Add a function that handles the incoming MAVLink message in the MavlinkReceiver class in
mavlink_receiver.h(opens new window)
Add an uORB publisher in the MavlinkReceiver class in
mavlink_receiver.h(opens new window)
Implement the handle_message_ca_trajectory_msg function in mavlink_receiver.cpp(opens new window)
and finally make sure it is called in MavlinkReceiver::handle_message()(opens new window)
# set streaming rate
Sometimes it is useful to increase the streaming rate of individual topics (e.g. for inspection in QGC).
This can be achieved by typing the following line in the shell:
You can get the port number with mavlink status which will output (amongst others) transport protocol: UDP (<port number>).
An example would be:
# testing
Ultimately you’ll want to test your new MAVLink interface is working by providing the corresponding ground station or MAVSDK implemention.
As a first step, and while debugging, commonly you’ll just want to confirm that any messages you’ve created are being sent/recieved as you expect.
There are several approaches you can use to view traffic:
Additional checks
The library have a number of #define values that you can set to enable various features:
MAVLINK_CHECK_MESSAGE_LENGTH
: Enable this option to check the length of each message. This allows invalid messages to be caught much sooner. Use if the transmission medium is prone to missing (or extra) characters (e.g. a radio that fades in and out). Only use if the channel will only contain messages types listed in the headers.
Command decoding
A MAVLink Command encodes a command defined in a MAV_CMD enum value into a COMMAND_INT or COMMAND_LONG message.
Command packets are parsed and decoded in the same way as any other payload – i.e. you switch on message id of MAVLINK_MSG_ID_COMMAND_INT/MAVLINK_MSG_ID_COMMAND_LONG and call the decoder functions mavlink_msg_command_int_decode()/mavlink_msg_command_long_decode() (respectively) to get a C struct mapping the original message.
The message types differ in that COMMAND_INT
has int32
types for parameter fields 6 and 7 (instead of float
) and also includes a field for the geometric frame of reference of any positional information in the command.
Examples
The following examples show the use of the API.
In addition, the C library is used in numerous open source systems:
Getting libraries
If you are using a standard dialect then download the MAVLink 2 library from Github: c_library_v2.
Lets break it down…
So lets break down the static inline statement shown above starting from the first variable right after the ‘(‘ symbol.
The ‘uint8_t’ defines the type of data in the variable next to it. So uint8_t system_id is asking for a type of unsigned integer of 8 bits long under the system_id variable. Like-wise for all the other variables in the static inline statement. We now just need to provide the appropriate data to populate the variables in the correct order specified in the statement for the library to pack the message in a Mavlink compatible command.
In Arduino code, it would look like this:
// STREAMS that can be requested
/*
* Definitions are in common.h: enum MAV_DATA_STREAM and more importantly at:
https://radiocopter.ru/en/messages/common.html#MAV_DATA_STREAM
*
* MAV_DATA_STREAM_ALL=0, // Enable all data streams
* MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.
* MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
* MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
* MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.
* MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
* MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot
* MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot
* MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot
* MAV_DATA_STREAM_ENUM_END=13,
*
* Data in PixHawk available in:
* – Battery, amperage and voltage (SYS_STATUS) in MAV_DATA_STREAM_EXTENDED_STATUS
* – Gyro info (IMU_SCALED) in MAV_DATA_STREAM_EXTRA1
*/
// Initialize the required buffers
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
// Pack the message
mavlink_msg_request_data_stream_pack(_system_id, _component_id, &msg, _target_system, _target_component, _req_stream_id, _req_message_rate, _start_stop);
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); // Send the message (.write sends as bytes)
Serial1.write(buf, len); //Write data to serial port
}
voidrequest_datastream(){ //Request Data from Pixhawk uint8_t _system_id=255;// id of computer which is sending the command (ground control software has id of 255) uint8_t _component_id=2;// seems like it can be any # except the number of what Pixhawk sys_id is uint8_t _target_system=1;// Id # of Pixhawk (should be 1) uint8_t _target_component=0;// Target component, 0 = all (seems to work with 0 or 1) uint8_t _req_stream_id=MAV_DATA_STREAM_ALL; uint16_t _req_message_rate=0x01;//number of times per second to request the data in hex uint8_t _start_stop=1;// 1 = start, 0 = stop // STREAMS that can be requested /* * Definitions are in common.h: enum MAV_DATA_STREAM and more importantly at: https://radiocopter.ru/en/messages/common.html#MAV_DATA_STREAM * * MAV_DATA_STREAM_ALL=0, // Enable all data streams * MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. * MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS * MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW * MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. * MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. * MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot * MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot * MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot * MAV_DATA_STREAM_ENUM_END=13, * * Data in PixHawk available in: * – Battery, amperage and voltage (SYS_STATUS) in MAV_DATA_STREAM_EXTENDED_STATUS * – Gyro info (IMU_SCALED) in MAV_DATA_STREAM_EXTRA1 */ // Initialize the required buffers mavlink_message_t msg; uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // Pack the message mavlink_msg_request_data_stream_pack(_system_id,_component_id,&msg,_target_system,_target_component,_req_stream_id,_req_message_rate,_start_stop); uint16_t len=mavlink_msg_to_send_buffer(buf,&msg); // Send the message (.write sends as bytes) Serial1.write(buf,len);//Write data to serial port } |
You dont need to specify any variables like I did at the top of the sketch if you do not wish to, and instead just write them directly into the mavlink_msg_request_data_stream_pack() statement. Variables were defined to further aid in understanding how things work in the function.
Message signing
Message Signing (authentication) allows a MAVLink 2 system to verify that messages originate from a trusted source.
The C libraries generated by mavgen provide almost everything needed to support message signing in your MAVLink system. The topic C Message Signing explains the remaining code that a system must implement to enable signing using the C library.
Multiple streams (“channels”)
The C MAVLink library utilizes a “channel” metaphor to allow for simultaneous processing of multiple, independent MAVLink streams in the same program. All receiving and transmitting functions provided by this library require a channel, and it is important to use the correct channel for each operation.
By default up to 16 channels may be defined on Windows, Linux and macOS, and up to 4 channels may be define on other systems. Systems can specify a different maximum number of channels/comms buffers using MAVLINK_COMM_NUM_BUFFERS (for example, this might be reduced to 1 if running MAVLink on very memory constrained hardware).
If only one MAVLink stream exists, channel 0 should be used by specifying the MAVLINK_COMM_0 constant.
Parsing packets
The mavlink_parse_char(…) convenience function (mavlink_helpers.h) is used to parse incoming MAVLink data. The function parses the data one byte at a time, returning 0 (MAVLINK_FRAMING_INCOMPLETE) as it progresses, and 1 (MAVLINK_FRAMING_OK) on successful decoding of a packet.
The r_mavlink_status parameter is updated with the channel status/errors as decoding progresses (you can check mavlink_status_t.msg_received to get the current byte’s decode status/error and mavlink_status_t.parse_state for the current parse state).
The function prototype and parameters are shown below:
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
Parameters:
Returns: 0 if the packet decoding is incomplete. 1 if the packet successfully decoded.
The code fragment below shows the typical use of this function when reading data from a serial port (serial):
Receiving
MAVLink reception/decoding is done in a number of phases:
- Parse the incoming stream into objects representing each packet (
mavlink_message_t
). - Decode the MAVLink message contained in the packet payload into a C struct (that has fields mapping the original XML definition).
These steps are demonstrated below.
Transmitting
Transmitting messages can be done by using the mavlink_msg_*_pack() function, where one is defined for every message. The packed message can then be serialized with mavlink_helpers.h:mavlink_msg_to_send_buffer() and then writing the resultant byte array out over the appropriate serial interface.
It is possible to simplify the above by writing wrappers around the transmitting/receiving code. A multi-byte writing macro can be defined, MAVLINK_SEND_UART_BYTES(), or a single-byte function can be defined, comm_send_ch(), that wrap the low-level driver for transmitting the data. If this is done, MAVLINK_USE_CONVENIENCE_FUNCTIONS must be defined.
Upgrading library from mavlink 1
The MAVLink 1 pre-built library mavlink/c_library_v1 can be upgraded by simply dropping in the MAVLink 2 library from Github: mavlink/c_library_v2.
The MAVLink 2 C library offers the same range of APIs as was offered by MAVLink 1.
The major change from an API perspective is that you don’t need to provide a message CRC table any more, or message length table. These have been folded into a single packed table, replacing the old table which was indexed by msgId
. That was necessary to cope with the much larger 24 bit namespace of message IDs.
-waddress-of-packed-member
Building the headers may result in warnings like:
mavlink/common/../mavlink_helpers.h:86:24: warning: taking address of packed member of ‘__mavlink_message’ may result in an unaligned pointer value [-Waddress-of-packed-member]
86 | crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
These can be ignored because MAVLink re-orders packed structures such that values are properly aligned. Specifically all 4-byte values are aligned on 4-byte boundaries (by putting them first), all 2-byte values come after those and are hence also aligned, and last of all come the the 1-byte values.
You can supress the warnings in CMake using target_compile_options(mavlink_c INTERFACE -Wno-address-of-packed-member -Wno-cast-align).
# sending custom mavlink messages
This section explains how to use a custom uORB message and send it as a MAVLink message.
Add the headers of the MAVLink and uORB messages to
mavlink_messages.cpp(opens new window)
Create a new class in mavlink_messages.cpp(opens new window)