关于 mavproxy 中消息签名的补充

发布于:2025-02-25 ⋅ 阅读:(18) ⋅ 点赞:(0)

Ardupilot模拟器配置与使用基础 的最后一节中,我介绍了如何在 mavproxy 中启用消息签名,因为我在开发一个地面站的项目,在没有硬件的情况下,只能先用模拟器来测试。
但是当我在 mavproxy 中设置了签名密钥之后,地面站这边解析消息签名时却出现了问题,经过一番斗智斗勇,发现问题并不简单,所以在此扒一扒其中的细节,作为前面文章的补充,因为那篇文章也修改好几次了,因此还是决定单开一篇,专门讲讲关于消息签名的问题。

首先 mavlink 的消息签名这个东西并不是必须的,只有 mavlink2 协议才支持,但是作为一个完整的地面站软件应该支持完整的 mavlink2 协议,而且我们也是有安全性要求的。

mavlink2 中的消息签名

在这里插入图片描述
带签名的 mavlink 消息的 INC FLAGS 值为1,不带签名的值为0。此外相比于不带签名的消息,最后多了 13 个字节。这 13 个字节分为三个部分:

数据 长度(字节) 描述
link id 1 逻辑信道,也就是 channel,在解析 mavlink 消息时传入的 chan 参数
timestamp 6 消息的时间戳
signature 6 消息签名

link id 不必多说,他就是 mavlink 中的逻辑信道。

时间戳是最神奇的,它有两个神奇的地方:

  • 首先是它的单位,是微秒( 秒 × 1 0 6 秒 \times 10^6 ×106)的十分之一,也就是( 秒 × 1 0 5 秒 \times 10^5 ×105)。
  • 其次它的起始时间是 2015年1月1日零时。而我们正常用的时间戳是从 1970年1月1日开始。

在编程中,我们可以先正常获取当前秒级时间戳,然后减去 1420070400,再换算成 微秒 10 \frac{微秒}{10} 10微秒。这样做也是为了减少传输字节数,时间戳只给了 6 个字节,完整时间戳是 8字节。

另外需要注意的是这里的时间戳并不一定是消息发出的时间戳。mavlink 会记录每个逻辑信道上最后一条消息的时间戳,并且要求后面收到的消息的时间戳大于记录的时间戳,否则应该丢弃这条消息。基于此,mavlink 协议要求每发送一条消息时间戳都应该加1,也就是说每条消息的时间戳都应该大于之前的消息的时间戳。如果消息发送的频率大于10条/微秒,那么这个时间戳就会超过当前的时间。

这里我们就能看出来为什么 mavlink 选择了这么一个奇怪的时间戳单位,因为要兼顾消息频率和编码长度。既要保证在高频通信时时间戳的严格递增,同时尽量减少时间戳编码后的长度。

签名使用的是 SHA256 算法,加密内容是密钥+消息(不包括签名)。SHA256 的结果是 32 字节,但是签名只取前 6 个字节。

signature = SHA256_48(secret + [msg - signature])

有关签名的详细内容可以参考官方文档。这里建议大家还是尽量看英文的,因为官方的中文文档是有错误的。下面是同一段内容的中英文文档对比:
在这里插入图片描述
可以看到时间是不一样的。

mavproxy 中的签名设置

mavproxy 中设置签名的命令是 signing setup KEY。但是这里有一个小问题,举个例子:

signing setuo aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa

mavlink 的签名密钥是32字节,我们希望将密钥设置为32个a。但是实际上 mavproxy 设置的密钥并不是这个,而是它的 SHA256 签名!!!

这个问题也是在我看过 mavproxy 的 signing 模块源码之后才发现的。setup 命令对应的函数如下:

def cmd_signing_setup(self, args):
	'''setup signing key on board'''
	if len(args) == 0:
	    print("usage: signing setup passphrase")
	    return
	if not self.master.mavlink20():
	    print("You must be using MAVLink2 for signing")
	    return
	passphrase = args[0]
	key = self.passphrase_to_key(passphrase)
	secret_key = []
	for b in key:
	    if sys.version_info[0] >= 3:
	        secret_key.append(b)
	    else:
	        secret_key.append(ord(b))
	
	epoch_offset = 1420070400
	now = max(time.time(), epoch_offset)
	initial_timestamp = int((now - epoch_offset)*1e5)
	self.master.mav.setup_signing_send(self.target_system, self.target_component,
	                                   secret_key, initial_timestamp)
	print("Sent secret_key")
	self.cmd_signing_key([passphrase])

passphrase 是我们通过命令输入的密钥,然后通过 passphrase_to_key 函数转化成了 key ,之后 key 又复制给了 secret_key。而 secret_key 才是 mavproxy 最终使用的签名密钥。passphrase_to_key 函数源码如下:

def passphrase_to_key(self, passphrase):
	'''convert a passphrase to a 32 byte key'''
	import hashlib
	h = hashlib.new('sha256')
	if sys.version_info[0] >= 3:
	    passphrase = passphrase.encode('ascii')
	h.update(passphrase)
	return h.digest()

这个函数就是对输入做了一个 SHA256 加密。mavproxy 在这里这样处理的一个原因可能是为了保证密钥长度一定是32字节,因为完全依赖用户输入的话,是很难保证用户一定输入一个32字节长的密钥的。设置完密钥之后,mavproxy 会把密钥发给无人机和其他地面站。

此外我们看到 cmd_signing_setup 函数的最后还调用了 cmd_signing_setup 函数,它其实是 signing key KEY 这个命令。这样看来我在之前的文章里其实说的也不准确。输入 signing setup KEY 命令后,再调用一下 set allow_unsigned False 应该就可以让 mavproxy 只接受带签名的消息了。不过还需要进一步验证。

mavproxy 的官网并未对此做出说明,导致我在调试地面站时消息始终解析失败,因为我没有接收 mavproxy 的密钥消息,而是自己手动设置的密钥。

mavlink c SDK 设置签名

在使用 mavlink c sdk 时,要启用签名功能只需要在 mavlink_status_t 中设置两个结构体就可以了。一个是 mavlink_signing_t,另一个是 mavlink_signing_streams_t

mavlink_signing_t中设置的是 link id,时间戳和密钥等。而 mavlink_signing_streams_t 中也是记录时间戳,它记录的是每个逻辑信道上最后一个消息的时间戳。

初始化签名密钥代码如下:

mavlink_signing_t signing;
mavlink_signing_streams_t signing_streams;
// 初始化签名密钥设置
// 创建 QCryptographicHash 对象,指定算法为 SHA-256
QCryptographicHash hash(QCryptographicHash::Sha256);
// 添加数据到哈希对象
hash.addData("ojvg4orBwGeB3rYmneVC0FIgLOvBvpRS");
// 获取最终的哈希结果
QByteArray result = hash.result();

// qDebug() << result.toHex();

qint64 epoch_offset = 1420070400;
// 获取当前时间
QDateTime now = QDateTime::currentDateTime();
qint64 timestamp = qMax(now.toSecsSinceEpoch(), epoch_offset);
timestamp = qint64((timestamp - epoch_offset) * 1e5);

memset(&signing, 0, sizeof(signing));
memcpy(signing.secret_key, result, 32);
signing.timestamp = timestamp;
signing.link_id = MAVLINK_COMM_0;
signing.flags = MAVLINK_SIGNING_FLAG_SIGN_OUTGOING;
signing.accept_unsigned_callback = NULL;

signing_streams.num_signing_streams = 1;
signing_streams.stream[0].sysid = 1;
signing_streams.stream[0].compid = 1;
signing_streams.stream[0].link_id = 0;
memcpy(signing_streams.stream[0].timestamp_bytes, &timestamp, 6);

mavlink_status_t* status = mavlink_get_channel_status(0);
status->signing = &signing;
status->signing_streams = &signing_streams;

因为我现在并没有去接收 mavproxy 发送的密钥消息,所以这里我将密钥做了一次 SHA256 哈希之后才设置给 mavlink sdk。这个地方确实坑了我一段时间。另外就是 mavlink_signing_streams_t 也要初始化并设置,在验证签名的过程中会拿它的数据来做一些验证。mavlink c sdk 中验证签名的函数是 mavlink_helpers.h 中的 mavlink_signature_check ,感兴趣的可以去看一看它的源码。