C Message Signing (mavgen)

One of the key features of MAVLink 2 is support for Message Signing (authentication).

The C libraries generated by mavgen provide almost everything needed to support signing in your MAVLink system. You will need to add some code to:

  • Handle the SETUP_SIGNING message.
  • Setup and teardown signing on a link.
  • Save and load the secret key and timestamp in persistent storage
  • Implement a callback to define which (if any) unsigned messages will be accepted.

Secret Key Management (SETUP_SIGNING)

A secret key is 32 bytes of binary data that are used to create message signatures that can be verified by other holders of the key. The general requirements for creating, storing, logging and sharing keys are covered in: Message Signing > Secret Key Management.

The section Enabling Signing on a Channel below shows how to set the secret key used by each channel.

Handling Timestamps

The timestamp is a 48 bit number with units of 10 microseconds since 1st January 2015 GMT. The general requirements for managing timestamps are covered in Message Signing > Timestamp Handling.

The library automatically handles some of the rules:

  • timestamps are incremented by one on every message send from a link.
  • timestamps are updated to match that of the last accepted incoming message (if it is greater than the current local timestamp).
  • messages are rejected if the timestamp of a message on a channel is before the last message received on that channel.

It is the responsibility of each MAVLink system to store and restore the timestamp into persistent storage (this is critical for the security of the signing system). The section Enabling Signing on a Channel below shows how to set the timestamp.

Enabling Signing on a Channel

To enable signing on a channel you need to fill in two pointers in the status structure for the channel. The two pointers are:

mavlink_signing_t *signing;
mavlink_signing_streams_t *signing_streams;

The signing pointer controls signing for this stream. It is per-stream, and contains the secret key, the timestamp and a set of flags, plus an optional callback function for accepting unsigned packets. Typical setup would be:

mavlink_signing_t signing;
memset(&signing, 0, sizeof(signing));
memcpy(signing.secret_key, key.secret_key, 32);
signing.link_id = (uint8_t)chan;
signing.timestamp = key.timestamp;
signing.flags = MAVLINK_SIGNING_FLAG_SIGN_OUTGOING;
signing.accept_unsigned_callback = accept_unsigned_callback;

mavlink_status_t *status = mavlink_get_channel_status(chan);
status.signing = &signing;

The signing_streams pointer is a structure used to record the previous timestamp for a (linkId,srcSystem,SrcComponent) tuple. This must point to a structure that is common to all channels in order to prevent inter-channel replay attacks. Typical setup is:

mavlink_status_t *status = mavlink_get_channel_status(chan);
status.signing_streams = &signing_streams;

The maximum number of signing streams supported is given by the MAVLINK_MAX_SIGNING_STREAMS macro. This defaults to 16, but it may be worth raising this for GCS implementations. If the C implementation runs out of signing streams then new streams will be rejected.

Using accept_unsigned_callback

Message Signing > Accepting Unsigned Packets and Accepting Incorrectly Signed Packets specify that a message signing implementation should provide mechanisms such that library users can choose to conditionally accept unsigned or incorrectly signed packets.

The C implementation provides the accept_unsigned_callback() function pointer for this purpose, which may optionally be set in the signing structure. The C prototype for this function is:

bool accept_unsigned_callback(const mavlink_status_t *status, uint32_t msgId);

If set then this function will be called on any unsigned packet (including all MAVLink 1 packets) or any packet where the signature is incorrect. The function offers a way for the implementation to allow unsigned packets to be accepted (and incorrectly signed packets, which might be accepted under some circumstances).

The rules for what unsigned packets should be accepted is implementation specific, but it is suggested the following rules be considered:

  • have a mechanism for marking a particular communication channel as being secure (such as a USB connection) to allow for signing setup.
  • always accept RADIO_STATUS packets for feedback from 3DR radios (which don't do signing)

For example:

static const uint32_t unsigned_messages[] = {
    MAVLINK_MSG_ID_RADIO_STATUS
};

static bool accept_unsigned_callback(const mavlink_status_t *status, uint32_t message_id)
{
    // Make the assumption that channel 0 is USB and should always be accessible
    if (status == mavlink_get_channel_status(MAVLINK_COMM_0)) {
        return true;
    }

    for (unsigned i = 0; i < sizeof(unsigned_messages) / sizeof(unsigned_messages[0]); i++) {
        if (unsigned_messages[i] == message_id) {
            return true;
        }
    }

    return false;
}

The purpose of the link_id field in the MAVLink 2 signing structure is to prevent cross-channel replay attacks. Without the link_id an attacker could record a packet (such as a disarm request) on one channel, then play it back on a different channel.

The intention with the link IDs is that each channel of communication between an autopilot and a GCS uses a different link ID. There is no requirement that the same link ID be used in both directions however.

For C implementations the obvious mechanism is to use the MAVLink channel number as the link ID. That works well for an autopilot, but runs into an issue for a GCS implementation. The issue is that a user may launch multiple GCS instances talking to the same autopilot via different communication links (such as two radios, or USB and a radio). These multiple GCS instances will not be aware of each other, and so may choose the same link ID. If that happens then a large number of correctly signed packets will be rejected by the autopilot as they will have timestamps that are older than the timestamp received for the same stream tuple on the other communication link.

The solution adopted for MAVProxy is shown below:

if (msg.get_signed() and
    self.mav.signing.link_id == 0 and
    msg.get_link_id() != 0 and
    self.target_system == msg.get_srcSystem() and
    self.target_component == msg.get_srcComponent()):
    # change to link_id from incoming packet
    self.mav.signing.link_id = msg.get_link_id()

What that says is that if the current link ID in use by MAVProxy is zero, and it receives a correctly signed packet with a non-zero link ID then it switches link ID to the one from the incoming packet.

This has the effect of making the GCS slave its link ID to the link ID of the autopilot.

results matching ""

    No results matching ""