# MAVLink 메시징

MAVLink (opens new window)는 드론 생태계를 위하여 설계된 초경량 메시징 프로토콜입니다.

PX4는 MAVLink를 사용하여 QGroundControl등의 지상국과 통신하고, 비행 콘트롤러 외부의 드론 구성요소(보조 컴퓨터, MAVLink 지원 카메라)에 연결 통합 메커니즘으로 사용합니다.

이 프로토콜은 데이터 교환을 위한 다수의 표준 메시지 (opens new window)마이크로서비스 (opens new window)를 정의합니다(전부는 아니지만 다수의 메시지/서비스가 PX4에서 구현됨).

이 튜토리얼은 PX4에 새로운 "사용자 정의" 메시지를 추가하는 방법을 설명합니다.

Note

튜토리얼에서는 msg/ca_trajectory.msg맞춤 uORB ca_trajectory 메시지와 mavlink/include/mavlink/v2.0/custom_messages/mavlink_msg_ca_trajectory.h에 맞춤 MAVLink ca_trajectory 메시지가 있다고 가정합니다.

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). There are are number of XML dialect files in /mavlink/messages/1.0/ (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.

Note

The MAVLink Developer guide (opens new window) has more information about using the MAVLink toolchain.

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)

#include <uORB/topics/ca_trajectory.h>
#include <v2.0/custom_messages/mavlink.h>

Create a new class in mavlink_messages.cpp (opens new window)

class MavlinkStreamCaTrajectory : public MavlinkStream
{
public:
    const char *get_name() const
    {
        return MavlinkStreamCaTrajectory::get_name_static();
    }
    static const char *get_name_static()
    {
        return "CA_TRAJECTORY";
    }
    static uint16_t get_id_static()
    {
        return MAVLINK_MSG_ID_CA_TRAJECTORY;
    }
    uint16_t get_id()
    {
        return get_id_static();
    }
    static MavlinkStream *new_instance(Mavlink *mavlink)
    {
        return new MavlinkStreamCaTrajectory(mavlink);
    }
    unsigned get_size()
    {
        return MAVLINK_MSG_ID_CA_TRAJECTORY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
    }

private:
    uORB::Subscription _sub{ORB_ID(ca_trajectory)};

    /* do not allow top copying this class */
    MavlinkStreamCaTrajectory(MavlinkStreamCaTrajectory &);
    MavlinkStreamCaTrajectory& operator = (const MavlinkStreamCaTrajectory &);

protected:
    explicit MavlinkStreamCaTrajectory(Mavlink *mavlink) : MavlinkStream(mavlink)
    {}

    bool send() override
    {
        struct ca_traj_struct_s _ca_trajectory;    //make sure ca_traj_struct_s is the definition of your uORB topic

        if (_sub.update(&_ca_trajectory)) {
            mavlink_ca_trajectory_t _msg_ca_trajectory;  //make sure mavlink_ca_trajectory_t is the definition of your custom MAVLink message

            _msg_ca_trajectory.timestamp = _ca_trajectory.timestamp;
            _msg_ca_trajectory.time_start_usec = _ca_trajectory.time_start_usec;
            _msg_ca_trajectory.time_stop_usec  = _ca_trajectory.time_stop_usec;
            _msg_ca_trajectory.coefficients =_ca_trajectory.coefficients;
            _msg_ca_trajectory.seq_id = _ca_trajectory.seq_id;

            mavlink_msg_ca_trajectory_send_struct(_mavlink->get_channel(), &_msg_ca_trajectory);

            return true;
        }

        return false;
    }
};

Finally append the stream class to the streams_list at the bottom of mavlink_messages.cpp (opens new window)

StreamListItem *streams_list[] = {
...
create_stream_list_item<MavlinkStreamCaTrajectory>(),
...

Then make sure to enable the stream, for example by adding the following line to the startup script (e.g. /ROMFS/px4fmu_common/init.d-posix/rcS (opens new window) on NuttX or ROMFS/px4fmu_common/init.d-posix/rcS (opens new window)) on SITL. Note that -r configures the streaming rate and -u identifies the MAVLink channel on UDP port 14556).

mavlink stream -r 50 -s CA_TRAJECTORY -u 14556

TIP

You can use the uorb top [<message_name>] command to verify in real-time that your message is published and the rate (see uORB Messaging). This approach can also be used to test incoming messages that publish a uORB topic (for other messages you might use printf in your code and test in SITL).

To see the message on QGroundControl you will need to build it with your MAVLink library (opens new window), and then verify that the message is received using MAVLink Inspector Widget (opens new window) (or some other MAVLink tool).

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)

#include <uORB/topics/ca_trajectory.h>
#include <v2.0/custom_messages/mavlink_msg_ca_trajectory.h>

Add a function that handles the incoming MAVLink message in the MavlinkReceiver class in mavlink_receiver.h (opens new window)

void handle_message_ca_trajectory_msg(mavlink_message_t *msg);

Add an uORB publisher in the MavlinkReceiver class in mavlink_receiver.h (opens new window)

uORB::Publication<ca_trajectory_s>          _ca_traj_msg_pub{ORB_ID(ca_trajectory)};

Implement the handle_message_ca_trajectory_msg function in mavlink_receiver.cpp (opens new window)

void MavlinkReceiver::handle_message_ca_trajectory_msg(mavlink_message_t *msg)
{
    mavlink_ca_trajectory_t traj;
    mavlink_msg_ca_trajectory_decode(msg, &traj);

    struct ca_traj_struct_s f;
    memset(&f, 0, sizeof(f));

    f.timestamp = hrt_absolute_time();
    f.seq_id = traj.seq_id;
    f.time_start_usec = traj.time_start_usec;
    f.time_stop_usec = traj.time_stop_usec;
    for(int i=0;i<28;i++)
        f.coefficients[i] = traj.coefficients[i];

    _ca_traj_msg_pub.publish(f);
}

and finally make sure it is called in MavlinkReceiver::handle_message() (opens new window)

MavlinkReceiver::handle_message(mavlink_message_t *msg)
 {
    switch (msg->msgid) {
        ...
    case MAVLINK_MSG_ID_CA_TRAJECTORY:
        handle_message_ca_trajectory_msg(msg);
        break;
        ...
    }

Sometimes there is the need for a custom MAVLink message with content that is not fully defined.

For example when using MAVLink to interface PX4 with an embedded device, the messages that are exchanged between the autopilot and the device may go through several iterations before they are stabilized. In this case, it can be time-consuming and error-prone to regenerate the MAVLink headers, and make sure both devices use the same version of the protocol.

An alternative - and temporary - solution is to re-purpose debug messages. Instead of creating a custom MAVLink message CA_TRAJECTORY, you can send a message DEBUG_VECT with the string key CA_TRAJ and data in the x, y and z fields. See this tutorial. for an example usage of debug messages.

Note

This solution is not efficient as it sends character string over the network and involves comparison of strings. It should be used for development only!

# Testing

Ultimately you'll want to test your new MAVLink interface is working by providing the corresponding ground station or MAVSDK implementation. As a first step, and while debugging, commonly you'll just want to confirm that any messages you've created are being sent/received as you expect.

There are several approaches you can use to view traffic:

# General

# 스트리밍 속도 설정

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:

mavlink stream -u <port number> -s <mavlink topic name> -r <rate>

You can get the port number with mavlink status which will output (amongst others) transport protocol: UDP (<port number>). An example would be:

mavlink stream -u 14556 -s OPTICAL_FLOW_RAD -r 300