use core::cmp::min;
use core::fmt::{Debug, Formatter};
#[cfg(feature = "std")]
use std::time::{SystemTime, UNIX_EPOCH};
use crate::consts::{
SIGNATURE_LENGTH, SIGNATURE_LINK_ID_LENGTH, SIGNATURE_SECRET_KEY_LENGTH,
SIGNATURE_TIMESTAMP_LENGTH, SIGNATURE_TIMESTAMP_OFFSET, SIGNATURE_VALUE_LENGTH,
};
use crate::protocol::{
Frame, MaybeVersioned, SignatureBytes, SignatureTimestampBytes, SignatureValue, SignedLinkId,
V2,
};
#[derive(Clone, Copy, Debug)]
#[cfg_attr(feature = "specta", derive(specta::Type))]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct Signature {
pub link_id: SignedLinkId,
pub timestamp: MavTimestamp,
pub value: SignatureValue,
}
#[derive(Clone, Copy, Debug, Default)]
#[cfg_attr(feature = "specta", derive(specta::Type))]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct MavTimestamp {
raw: u64,
}
pub trait Sign {
fn reset(&mut self);
fn digest(&mut self, bytes: &[u8]);
fn produce(&self) -> SignatureValue;
}
pub struct Signer<'a>(&'a mut dyn Sign);
#[derive(Clone, Debug)]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct SigningConf {
pub link_id: SignedLinkId,
pub timestamp: MavTimestamp,
#[cfg_attr(feature = "serde", serde(skip_serializing))]
pub secret: SecretKey,
}
impl<'a> Signer<'a> {
pub fn new(signer: &'a mut dyn Sign) -> Self {
Self(signer)
}
pub fn calculate<V: MaybeVersioned>(
&mut self,
frame: &Frame<V>,
link_id: SignedLinkId,
timestamp: MavTimestamp,
key: &SecretKey,
) -> SignatureValue {
self.0.reset();
self.0.digest(key.value());
self.0.digest(frame.header().serialize().as_slice());
self.0.digest(frame.payload().bytes());
self.0.digest(&frame.checksum().to_le_bytes());
self.0.digest(&[link_id]);
self.0.digest(×tamp.to_bytes_array());
self.0.produce()
}
pub fn validate<V: MaybeVersioned>(
&mut self,
frame: &Frame<V>,
signature: &Signature,
key: &SecretKey,
) -> bool {
let expected_value = self.calculate(&frame, signature.link_id, signature.timestamp, key);
expected_value == signature.value
}
}
impl SigningConf {
pub fn apply<V: MaybeVersioned>(&self, frame: &mut Frame<V>, signer: &mut dyn Sign) {
if !frame.matches_version(V2) {
return;
}
frame.header.set_is_signed(true);
let mut signer = Signer::new(signer);
let value = signer.calculate(frame, self.link_id, self.timestamp, &self.secret);
frame.signature = Some(Signature {
link_id: self.link_id,
timestamp: self.timestamp,
value,
});
}
}
#[derive(Clone, Default)]
#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))]
pub struct SecretKey([u8; SIGNATURE_SECRET_KEY_LENGTH]);
impl Debug for SecretKey {
fn fmt(&self, f: &mut Formatter<'_>) -> core::fmt::Result {
f.debug_struct("SecretKey").finish_non_exhaustive()
}
}
impl From<[u8; SIGNATURE_SECRET_KEY_LENGTH]> for SecretKey {
fn from(value: [u8; SIGNATURE_SECRET_KEY_LENGTH]) -> Self {
Self(value)
}
}
impl From<&[u8]> for SecretKey {
fn from(value: &[u8]) -> Self {
let len = min(value.len(), SIGNATURE_SECRET_KEY_LENGTH);
let mut key = [0u8; SIGNATURE_SECRET_KEY_LENGTH];
key[0..len].copy_from_slice(&value[0..len]);
Self(key)
}
}
impl From<&str> for SecretKey {
fn from(value: &str) -> Self {
value.as_bytes().into()
}
}
#[cfg(feature = "alloc")]
impl From<alloc::string::String> for SecretKey {
fn from(value: alloc::string::String) -> Self {
value.as_str().into()
}
}
#[cfg(feature = "alloc")]
impl From<&alloc::string::String> for SecretKey {
fn from(value: &alloc::string::String) -> Self {
value.as_str().into()
}
}
impl SecretKey {
pub fn value(&self) -> &[u8] {
self.0.as_slice()
}
}
impl From<SignatureBytes> for Signature {
#[inline]
fn from(value: SignatureBytes) -> Self {
Self::from_byte_array(value)
}
}
impl From<Signature> for SignatureBytes {
#[inline]
fn from(value: Signature) -> Self {
value.to_byte_array()
}
}
impl Default for SigningConf {
fn default() -> Self {
Self {
link_id: 0,
timestamp: Default::default(),
secret: [0xff; SIGNATURE_SECRET_KEY_LENGTH].into(),
}
}
}
impl Signature {
#[inline(always)]
pub fn link_id(&self) -> SignedLinkId {
self.link_id
}
#[inline]
pub fn timestamp(&self) -> MavTimestamp {
self.timestamp
}
#[inline]
pub fn value(&self) -> SignatureValue {
self.value
}
#[inline(always)]
pub fn from_byte_array(bytes: SignatureBytes) -> Self {
Self::from_slice(bytes.as_slice())
}
pub fn to_byte_array(&self) -> SignatureBytes {
let mut bytes: SignatureBytes = Default::default();
let timestamp_offset = SIGNATURE_LINK_ID_LENGTH;
let signature_value_offset = SIGNATURE_LINK_ID_LENGTH + SIGNATURE_TIMESTAMP_LENGTH;
bytes[0] = self.link_id;
bytes[timestamp_offset..signature_value_offset]
.copy_from_slice(&self.timestamp.to_bytes_array());
bytes[signature_value_offset..SIGNATURE_LENGTH].copy_from_slice(&self.value);
bytes
}
pub(crate) fn from_slice(bytes: &[u8]) -> Self {
let link_id = bytes[0];
let mut timestamp_bytes: SignatureTimestampBytes = Default::default();
let mut signature: SignatureValue = Default::default();
let timestamp_start = SIGNATURE_LINK_ID_LENGTH;
let timestamp_end = timestamp_start + SIGNATURE_TIMESTAMP_LENGTH;
timestamp_bytes.copy_from_slice(&bytes[timestamp_start..timestamp_end]);
let timestamp: MavTimestamp = timestamp_bytes.into();
let value_start = timestamp_end;
let value_end = value_start + SIGNATURE_VALUE_LENGTH;
signature.copy_from_slice(&bytes[timestamp_end..value_end]);
Self {
link_id,
timestamp,
value: signature,
}
}
}
#[cfg(feature = "std")]
impl From<SystemTime> for MavTimestamp {
#[inline(always)]
fn from(value: SystemTime) -> Self {
Self::from_system_time(value)
}
}
impl From<u64> for MavTimestamp {
#[inline(always)]
fn from(value: u64) -> Self {
Self::from_raw_u64(value)
}
}
impl From<SignatureTimestampBytes> for MavTimestamp {
#[inline(always)]
fn from(bytes: SignatureTimestampBytes) -> Self {
Self::from_bytes(&bytes)
}
}
impl From<MavTimestamp> for SignatureTimestampBytes {
#[inline(always)]
fn from(timestamp: MavTimestamp) -> Self {
timestamp.to_bytes_array()
}
}
impl MavTimestamp {
pub fn from_millis(value: u64) -> Self {
let mut timestamp = MavTimestamp::default();
timestamp.set_millis(value);
timestamp
}
pub fn from_micros(value: u128) -> Self {
let mut timestamp = MavTimestamp::default();
timestamp.set_micros(value);
timestamp
}
#[cfg(feature = "std")]
pub fn from_system_time(value: SystemTime) -> Self {
Self::from_micros(value.duration_since(UNIX_EPOCH).unwrap().as_micros())
}
pub fn from_raw_u64(value: u64) -> Self {
let raw = value & 0xffffffffffff;
Self { raw }
}
pub fn from_bytes(bytes: &SignatureTimestampBytes) -> Self {
let mut bytes_u64 = [0u8; 8];
bytes_u64[0..SIGNATURE_TIMESTAMP_LENGTH].copy_from_slice(bytes);
Self {
raw: u64::from_le_bytes(bytes_u64),
}
}
#[inline(always)]
pub fn as_raw_u64(&self) -> u64 {
self.raw
}
#[inline(always)]
pub fn set_raw_u64(&mut self, raw: u64) -> &mut Self {
self.raw = raw & 0xffffffffffff;
self
}
#[inline(always)]
pub fn as_millis_mavlink(&self) -> u64 {
self.raw / 100
}
#[inline(always)]
pub fn set_millis_mavlink(&mut self, millis_mavlink: u64) -> &mut Self {
self.raw = (millis_mavlink * 100) & 0xffffffffffff;
self
}
#[inline(always)]
pub fn as_millis(&self) -> u64 {
(self.raw + SIGNATURE_TIMESTAMP_OFFSET * 100_000) / 100
}
#[inline(always)]
pub fn set_millis(&mut self, millis: u64) -> &mut Self {
self.set_millis_mavlink(millis - SIGNATURE_TIMESTAMP_OFFSET * 1000);
self
}
#[inline(always)]
pub fn as_micros_mavlink(&self) -> u128 {
self.raw as u128 * 10
}
#[inline(always)]
pub fn set_micros_mavlink(&mut self, micros_mavlink: u128) -> &mut Self {
self.raw = (micros_mavlink / 10) as u64 & 0xffffffffffff;
self
}
#[inline(always)]
pub fn as_micros(&self) -> u128 {
(self.raw as u128 + SIGNATURE_TIMESTAMP_OFFSET as u128 * 100_000) * 10
}
#[inline(always)]
pub fn set_micros(&mut self, micros: u128) -> &mut Self {
self.set_micros_mavlink(micros - SIGNATURE_TIMESTAMP_OFFSET as u128 * 1_000_000);
self
}
pub fn to_bytes_array(&self) -> SignatureTimestampBytes {
let bytes_u64: [u8; 8] = self.raw.to_le_bytes();
let mut bytes = [0u8; SIGNATURE_TIMESTAMP_LENGTH];
bytes.copy_from_slice(&bytes_u64[0..SIGNATURE_TIMESTAMP_LENGTH]);
bytes
}
}
#[cfg(test)]
mod tests {
use super::*;
#[test]
fn key_from_array() {
let key = SecretKey::from([1u8; SIGNATURE_SECRET_KEY_LENGTH]);
assert_eq!(key.value(), [1u8; SIGNATURE_SECRET_KEY_LENGTH].as_slice());
}
#[test]
fn key_from_slice() {
let key = SecretKey::from([1u8; SIGNATURE_SECRET_KEY_LENGTH].as_slice());
assert_eq!(key.value(), [1u8; SIGNATURE_SECRET_KEY_LENGTH].as_slice());
let key = SecretKey::from([1u8; SIGNATURE_SECRET_KEY_LENGTH + 10].as_slice());
assert_eq!(key.value(), [1u8; SIGNATURE_SECRET_KEY_LENGTH].as_slice());
let key = SecretKey::from([1u8; SIGNATURE_SECRET_KEY_LENGTH - 10].as_slice());
let mut expected = [0u8; SIGNATURE_SECRET_KEY_LENGTH];
expected[0..SIGNATURE_SECRET_KEY_LENGTH - 10]
.copy_from_slice(&[1u8; SIGNATURE_SECRET_KEY_LENGTH - 10]);
assert_eq!(key.value(), expected);
}
#[test]
#[cfg(feature = "alloc")]
fn key_from_strings() {
let expected = {
let mut expected = [0u8; SIGNATURE_SECRET_KEY_LENGTH];
expected[0..6].copy_from_slice("abcdef".as_bytes());
expected
};
let key_str = alloc::string::String::from("abcdef");
let key = SecretKey::from(key_str.as_str());
assert_eq!(key.value(), expected);
let key = SecretKey::from(&key_str);
assert_eq!(key.value(), expected);
let key = SecretKey::from(key_str);
assert_eq!(key.value(), expected);
}
#[test]
#[cfg(feature = "std")]
fn timestamp_std_basics() {
let now = SystemTime::now();
let timestamp = MavTimestamp::from(now);
assert_eq!(
timestamp.as_millis(),
now.duration_since(UNIX_EPOCH).unwrap().as_millis() as u64
);
assert_eq!(
timestamp.as_micros(),
now.duration_since(UNIX_EPOCH).unwrap().as_micros() / 10 * 10
);
}
}