diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 313eb75862..071df1ef7b 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -23,18 +23,19 @@ jobs: components: clippy - uses: actions-rs-plus/clippy-check@v2 with: - args: --all --all-targets --features format-generated-code + args: --all --all-targets --features format-generated-code --features signing --features tokio-1 internal-tests: runs-on: ubuntu-latest strategy: matrix: dialect: ["ardupilotmega", "asluav", "matrixpilot", "minimal", "paparazzi", "python_array_test", "slugs", "standard", "test", "ualberta", "uavionix", "icarous", "common"] + signing: ["", "--features signing"] steps: - uses: actions/checkout@master - uses: dtolnay/rust-toolchain@stable - name: Run internal tests - run: cargo test --verbose --features ${{ matrix.dialect }} -- --nocapture + run: cargo test --verbose --features ${{ matrix.dialect }} ${{ matrix.signing }} -- --nocapture mavlink-dump: runs-on: ubuntu-latest @@ -46,6 +47,9 @@ jobs: msrv: runs-on: ubuntu-latest + strategy: + matrix: + signing: ["", "--features signing"] steps: - uses: actions/checkout@master - uses: dtolnay/rust-toolchain@master @@ -59,7 +63,7 @@ jobs: with: use-cross: true command: check - args: --all --all-targets + args: --all --all-targets ${{ matrix.signing }} build: needs: [formatting, linting, internal-tests, mavlink-dump, msrv] diff --git a/mavlink-core/Cargo.toml b/mavlink-core/Cargo.toml index 246c657537..d276b2c44e 100644 --- a/mavlink-core/Cargo.toml +++ b/mavlink-core/Cargo.toml @@ -27,6 +27,7 @@ serde = { version = "1.0.115", optional = true, features = ["derive"] } serde_arrays = { version = "0.1.0", optional = true } serial = { version = "0.4", optional = true } tokio = { version = "1.0", default-features = false, features = ["io-util"], optional = true } +sha2 = { version = "0.10", optional = true } [features] "std" = ["byteorder/std"] @@ -40,4 +41,5 @@ tokio = { version = "1.0", default-features = false, features = ["io-util"], opt "embedded-hal-02" = ["dep:nb", "dep:embedded-hal-02"] "serde" = ["dep:serde", "dep:serde_arrays"] "tokio-1" = ["dep:tokio"] +"signing" = ["dep:sha2"] default = ["std", "tcp", "udp", "direct-serial", "serde"] diff --git a/mavlink-core/src/connection/direct_serial.rs b/mavlink-core/src/connection/direct_serial.rs index a3a33a0fa6..2954b98107 100644 --- a/mavlink-core/src/connection/direct_serial.rs +++ b/mavlink-core/src/connection/direct_serial.rs @@ -2,7 +2,7 @@ use crate::connection::MavConnection; use crate::peek_reader::PeekReader; -use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message}; +use crate::{MavHeader, MavlinkVersion, Message}; use core::ops::DerefMut; use std::io; use std::sync::Mutex; @@ -10,6 +10,11 @@ use std::sync::Mutex; use crate::error::{MessageReadError, MessageWriteError}; use serial::{prelude::*, SystemPort}; +#[cfg(not(feature = "signing"))] +use crate::{read_versioned_msg, write_versioned_msg}; +#[cfg(feature = "signing")] +use crate::{read_versioned_msg_signed, write_versioned_msg_signed, SigningConfig, SigningData}; + pub fn open(settings: &str) -> io::Result { let settings_toks: Vec<&str> = settings.split(':').collect(); if settings_toks.len() < 2 { @@ -45,6 +50,8 @@ pub fn open(settings: &str) -> io::Result { port: Mutex::new(PeekReader::new(port)), sequence: Mutex::new(0), protocol_version: MavlinkVersion::V2, + #[cfg(feature = "signing")] + signing_data: None, }) } @@ -52,13 +59,23 @@ pub struct SerialConnection { port: Mutex>, sequence: Mutex, protocol_version: MavlinkVersion, + #[cfg(feature = "signing")] + signing_data: Option, } impl MavConnection for SerialConnection { fn recv(&self) -> Result<(MavHeader, M), MessageReadError> { let mut port = self.port.lock().unwrap(); loop { - match read_versioned_msg(port.deref_mut(), self.protocol_version) { + #[cfg(not(feature = "signing"))] + let result = read_versioned_msg(port.deref_mut(), self.protocol_version); + #[cfg(feature = "signing")] + let result = read_versioned_msg_signed( + port.deref_mut(), + self.protocol_version, + self.signing_data.as_ref(), + ); + match result { ok @ Ok(..) => { return ok; } @@ -84,7 +101,17 @@ impl MavConnection for SerialConnection { *sequence = sequence.wrapping_add(1); - write_versioned_msg(port.reader_mut(), self.protocol_version, header, data) + #[cfg(not(feature = "signing"))] + let result = write_versioned_msg(port.reader_mut(), self.protocol_version, header, data); + #[cfg(feature = "signing")] + let result = write_versioned_msg_signed( + port.reader_mut(), + self.protocol_version, + header, + data, + self.signing_data.as_ref(), + ); + result } fn set_protocol_version(&mut self, version: MavlinkVersion) { @@ -94,4 +121,9 @@ impl MavConnection for SerialConnection { fn protocol_version(&self) -> MavlinkVersion { self.protocol_version } + + #[cfg(feature = "signing")] + fn setup_signing(&mut self, signing_data: Option) { + self.signing_data = signing_data.map(SigningData::from_config) + } } diff --git a/mavlink-core/src/connection/file.rs b/mavlink-core/src/connection/file.rs index 85444bb6ae..7258259347 100644 --- a/mavlink-core/src/connection/file.rs +++ b/mavlink-core/src/connection/file.rs @@ -3,24 +3,33 @@ use crate::connection::MavConnection; use crate::error::{MessageReadError, MessageWriteError}; use crate::peek_reader::PeekReader; -use crate::{read_versioned_msg, MavHeader, MavlinkVersion, Message}; +use crate::{MavHeader, MavlinkVersion, Message}; use core::ops::DerefMut; use std::fs::File; use std::io; use std::sync::Mutex; +#[cfg(not(feature = "signing"))] +use crate::read_versioned_msg; +#[cfg(feature = "signing")] +use crate::{read_versioned_msg_signed, SigningConfig, SigningData}; + pub fn open(file_path: &str) -> io::Result { let file = File::open(file_path)?; Ok(FileConnection { file: Mutex::new(PeekReader::new(file)), protocol_version: MavlinkVersion::V2, + #[cfg(feature = "signing")] + signing_data: None, }) } pub struct FileConnection { file: Mutex>, protocol_version: MavlinkVersion, + #[cfg(feature = "signing")] + signing_data: Option, } impl MavConnection for FileConnection { @@ -30,7 +39,15 @@ impl MavConnection for FileConnection { let mut file = self.file.lock().unwrap(); loop { - match read_versioned_msg(file.deref_mut(), self.protocol_version) { + #[cfg(not(feature = "signing"))] + let result = read_versioned_msg(file.deref_mut(), self.protocol_version); + #[cfg(feature = "signing")] + let result = read_versioned_msg_signed( + file.deref_mut(), + self.protocol_version, + self.signing_data.as_ref(), + ); + match result { ok @ Ok(..) => { return ok; } @@ -55,4 +72,9 @@ impl MavConnection for FileConnection { fn protocol_version(&self) -> MavlinkVersion { self.protocol_version } + + #[cfg(feature = "signing")] + fn setup_signing(&mut self, signing_data: Option) { + self.signing_data = signing_data.map(SigningData::from_config) + } } diff --git a/mavlink-core/src/connection/mod.rs b/mavlink-core/src/connection/mod.rs index 035f63eb28..e60386a6aa 100644 --- a/mavlink-core/src/connection/mod.rs +++ b/mavlink-core/src/connection/mod.rs @@ -11,6 +11,9 @@ mod udp; #[cfg(feature = "direct-serial")] mod direct_serial; +#[cfg(feature = "signing")] +use crate::SigningConfig; + mod file; /// A MAVLink connection @@ -47,6 +50,10 @@ pub trait MavConnection { let header = MavHeader::default(); self.send(&header, data) } + + /// Setup secret key used for message signing, or disable message signing + #[cfg(feature = "signing")] + fn setup_signing(&mut self, signing_data: Option); } /// Connect to a MAVLink node by address string. diff --git a/mavlink-core/src/connection/tcp.rs b/mavlink-core/src/connection/tcp.rs index 35b7f09084..d362a5664a 100644 --- a/mavlink-core/src/connection/tcp.rs +++ b/mavlink-core/src/connection/tcp.rs @@ -2,7 +2,7 @@ use crate::connection::MavConnection; use crate::peek_reader::PeekReader; -use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message}; +use crate::{MavHeader, MavlinkVersion, Message}; use core::ops::DerefMut; use std::io; use std::net::ToSocketAddrs; @@ -12,6 +12,12 @@ use std::time::Duration; use super::get_socket_addr; +#[cfg(not(feature = "signing"))] +use crate::{read_versioned_msg, write_versioned_msg}; + +#[cfg(feature = "signing")] +use crate::{read_versioned_msg_signed, write_versioned_msg_signed, SigningConfig, SigningData}; + pub fn select_protocol( address: &str, ) -> io::Result + Sync + Send>> { @@ -42,6 +48,8 @@ pub fn tcpout(address: T) -> io::Result { sequence: 0, }), protocol_version: MavlinkVersion::V2, + #[cfg(feature = "signing")] + signing_data: None, }) } @@ -60,6 +68,8 @@ pub fn tcpin(address: T) -> io::Result { sequence: 0, }), protocol_version: MavlinkVersion::V2, + #[cfg(feature = "signing")] + signing_data: None, }) } Err(e) => { @@ -78,6 +88,8 @@ pub struct TcpConnection { reader: Mutex>, writer: Mutex, protocol_version: MavlinkVersion, + #[cfg(feature = "signing")] + signing_data: Option, } struct TcpWrite { @@ -88,7 +100,15 @@ struct TcpWrite { impl MavConnection for TcpConnection { fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> { let mut reader = self.reader.lock().unwrap(); - read_versioned_msg(reader.deref_mut(), self.protocol_version) + #[cfg(not(feature = "signing"))] + let result = read_versioned_msg(reader.deref_mut(), self.protocol_version); + #[cfg(feature = "signing")] + let result = read_versioned_msg_signed( + reader.deref_mut(), + self.protocol_version, + self.signing_data.as_ref(), + ); + result } fn send(&self, header: &MavHeader, data: &M) -> Result { @@ -101,7 +121,17 @@ impl MavConnection for TcpConnection { }; lock.sequence = lock.sequence.wrapping_add(1); - write_versioned_msg(&mut lock.socket, self.protocol_version, header, data) + #[cfg(not(feature = "signing"))] + let result = write_versioned_msg(&mut lock.socket, self.protocol_version, header, data); + #[cfg(feature = "signing")] + let result = write_versioned_msg_signed( + &mut lock.socket, + self.protocol_version, + header, + data, + self.signing_data.as_ref(), + ); + result } fn set_protocol_version(&mut self, version: MavlinkVersion) { @@ -111,4 +141,9 @@ impl MavConnection for TcpConnection { fn protocol_version(&self) -> MavlinkVersion { self.protocol_version } + + #[cfg(feature = "signing")] + fn setup_signing(&mut self, signing_data: Option) { + self.signing_data = signing_data.map(SigningData::from_config) + } } diff --git a/mavlink-core/src/connection/udp.rs b/mavlink-core/src/connection/udp.rs index 3ec739d3f5..75e5be3c48 100644 --- a/mavlink-core/src/connection/udp.rs +++ b/mavlink-core/src/connection/udp.rs @@ -4,7 +4,7 @@ use std::collections::VecDeque; use crate::connection::MavConnection; use crate::peek_reader::PeekReader; -use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message}; +use crate::{MavHeader, MavlinkVersion, Message}; use core::ops::DerefMut; use std::io::{self, Read}; use std::net::ToSocketAddrs; @@ -13,6 +13,12 @@ use std::sync::Mutex; use super::get_socket_addr; +#[cfg(not(feature = "signing"))] +use crate::{read_versioned_msg, write_versioned_msg}; + +#[cfg(feature = "signing")] +use crate::{read_versioned_msg_signed, write_versioned_msg_signed, SigningConfig, SigningData}; + pub fn select_protocol( address: &str, ) -> io::Result + Sync + Send>> { @@ -91,6 +97,8 @@ pub struct UdpConnection { writer: Mutex, protocol_version: MavlinkVersion, server: bool, + #[cfg(feature = "signing")] + signing_data: Option, } impl UdpConnection { @@ -108,6 +116,8 @@ impl UdpConnection { sequence: 0, }), protocol_version: MavlinkVersion::V2, + #[cfg(feature = "signing")] + signing_data: None, }) } } @@ -117,7 +127,14 @@ impl MavConnection for UdpConnection { let mut reader = self.reader.lock().unwrap(); loop { + #[cfg(not(feature = "signing"))] let result = read_versioned_msg(reader.deref_mut(), self.protocol_version); + #[cfg(feature = "signing")] + let result = read_versioned_msg_signed( + reader.deref_mut(), + self.protocol_version, + self.signing_data.as_ref(), + ); if self.server { if let addr @ Some(_) = reader.reader_ref().last_recv_address { self.writer.lock().unwrap().dest = addr; @@ -143,7 +160,16 @@ impl MavConnection for UdpConnection { let len = if let Some(addr) = state.dest { let mut buf = Vec::new(); + #[cfg(not(feature = "signing"))] write_versioned_msg(&mut buf, self.protocol_version, header, data)?; + #[cfg(feature = "signing")] + write_versioned_msg_signed( + &mut buf, + self.protocol_version, + header, + data, + self.signing_data.as_ref(), + )?; state.socket.send_to(&buf, addr)? } else { 0 @@ -159,6 +185,11 @@ impl MavConnection for UdpConnection { fn protocol_version(&self) -> MavlinkVersion { self.protocol_version } + + #[cfg(feature = "signing")] + fn setup_signing(&mut self, signing_data: Option) { + self.signing_data = signing_data.map(SigningData::from_config) + } } #[cfg(test)] diff --git a/mavlink-core/src/lib.rs b/mavlink-core/src/lib.rs index e6e7aec97a..12d470b614 100644 --- a/mavlink-core/src/lib.rs +++ b/mavlink-core/src/lib.rs @@ -54,6 +54,15 @@ pub mod embedded; #[cfg(any(feature = "embedded", feature = "embedded-hal-02"))] use embedded::{Read, Write}; +#[cfg(not(feature = "signing"))] +type SigningData = (); +#[cfg(feature = "signing")] +mod signing; +#[cfg(feature = "signing")] +pub use self::signing::{SigningConfig, SigningData}; +#[cfg(feature = "signing")] +use sha2::{Digest, Sha256}; + pub const MAX_FRAME_SIZE: usize = 280; pub trait Message @@ -252,6 +261,18 @@ pub fn read_versioned_msg( } } +#[cfg(feature = "signing")] +pub fn read_versioned_msg_signed( + r: &mut PeekReader, + version: MavlinkVersion, + signing_data: Option<&SigningData>, +) -> Result<(MavHeader, M), error::MessageReadError> { + match version { + MavlinkVersion::V2 => read_v2_msg_inner(r, signing_data), + MavlinkVersion::V1 => read_v1_msg(r), + } +} + #[derive(Debug, Copy, Clone, PartialEq, Eq)] // Follow protocol definition: `` pub struct MAVLinkV1MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2]); @@ -550,6 +571,11 @@ impl MAVLinkV2MessageRaw { self.0[2] } + #[inline] + pub fn incompatibility_flags_mut(&mut self) -> &mut u8 { + &mut self.0[2] + } + #[inline] pub fn compatibility_flags(&self) -> u8 { self.0[3] @@ -590,6 +616,67 @@ impl MAVLinkV2MessageRaw { ]) } + #[cfg(feature = "signing")] + #[inline] + pub fn checksum_bytes(&self) -> &[u8] { + let checksum_offset = 1 + Self::HEADER_SIZE + self.payload_length() as usize; + &self.0[checksum_offset..(checksum_offset + 2)] + } + + #[cfg(feature = "signing")] + #[inline] + pub fn signature_link_id(&self) -> u8 { + let payload_length: usize = self.payload_length().into(); + self.0[1 + Self::HEADER_SIZE + payload_length + 2] + } + + #[cfg(feature = "signing")] + #[inline] + pub fn signature_link_id_mut(&mut self) -> &mut u8 { + let payload_length: usize = self.payload_length().into(); + &mut self.0[1 + Self::HEADER_SIZE + payload_length + 2] + } + + #[cfg(feature = "signing")] + #[inline] + pub fn signature_timestamp_bytes(&self) -> &[u8] { + let payload_length: usize = self.payload_length().into(); + let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3; + &self.0[timestamp_start..(timestamp_start + 6)] + } + + #[cfg(feature = "signing")] + #[inline] + pub fn signature_timestamp_bytes_mut(&mut self) -> &mut [u8] { + let payload_length: usize = self.payload_length().into(); + let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3; + &mut self.0[timestamp_start..(timestamp_start + 6)] + } + + #[cfg(feature = "signing")] + #[inline] + pub fn signature_timestamp(&self) -> u64 { + let mut timestamp_bytes = [0u8; 8]; + timestamp_bytes[0..6].copy_from_slice(self.signature_timestamp_bytes()); + u64::from_le_bytes(timestamp_bytes) + } + + #[cfg(feature = "signing")] + #[inline] + pub fn signature_value(&self) -> &[u8] { + let payload_length: usize = self.payload_length().into(); + let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6; + &self.0[signature_start..(signature_start + 6)] + } + + #[cfg(feature = "signing")] + #[inline] + pub fn signature_value_mut(&mut self) -> &mut [u8] { + let payload_length: usize = self.payload_length().into(); + let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6; + &mut self.0[signature_start..(signature_start + 6)] + } + fn mut_payload_and_checksum_and_sign(&mut self) -> &mut [u8] { let payload_length: usize = self.payload_length().into(); @@ -614,6 +701,19 @@ impl MAVLinkV2MessageRaw { ) } + #[cfg(feature = "signing")] + pub fn calculate_signature(&self, secret_key: &[u8], target_buffer: &mut [u8; 6]) { + let mut hasher = Sha256::new(); + hasher.update(secret_key); + hasher.update([MAV_STX_V2]); + hasher.update(self.header()); + hasher.update(self.payload()); + hasher.update(self.checksum_bytes()); + hasher.update([self.signature_link_id()]); + hasher.update(self.signature_timestamp_bytes()); + target_buffer.copy_from_slice(&hasher.finalize()[0..6]); + } + pub fn raw_bytes(&self) -> &[u8] { let payload_length = self.payload_length() as usize; @@ -632,6 +732,7 @@ impl MAVLinkV2MessageRaw { msgid: u32, payload_length: usize, extra_crc: u8, + incompat_flags: u8, ) { self.0[0] = MAV_STX_V2; let msgid_bytes = msgid.to_le_bytes(); @@ -639,7 +740,7 @@ impl MAVLinkV2MessageRaw { let header_buf = self.mut_header(); header_buf.copy_from_slice(&[ payload_length as u8, - 0, //incompat_flags + incompat_flags, 0, //compat_flags header.sequence, header.system_id, @@ -668,6 +769,21 @@ impl MAVLinkV2MessageRaw { message_id, payload_length, M::extra_crc(message_id), + 0, + ); + } + + pub fn serialize_message_for_signing(&mut self, header: MavHeader, message: &M) { + let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)]; + let payload_length = message.ser(MavlinkVersion::V2, payload_buf); + + let message_id = message.message_id(); + self.serialize_stx_and_header_and_crc( + header, + message_id, + payload_length, + M::extra_crc(message_id), + 0x01, ); } @@ -675,14 +791,35 @@ impl MAVLinkV2MessageRaw { let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)]; let payload_length = message_data.ser(MavlinkVersion::V2, payload_buf); - self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC); + self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC, 0); } } /// Return a raw buffer with the mavlink message +/// /// V2 maximum size is 280 bytes: `` +#[inline] pub fn read_v2_raw_message( reader: &mut PeekReader, +) -> Result { + read_v2_raw_message_inner::(reader, None) +} + +/// Return a raw buffer with the mavlink message with signing support +/// +/// V2 maximum size is 280 bytes: `` +#[cfg(feature = "signing")] +#[inline] +pub fn read_v2_raw_message_signed( + reader: &mut PeekReader, + signing_data: Option<&SigningData>, +) -> Result { + read_v2_raw_message_inner::(reader, signing_data) +} + +fn read_v2_raw_message_inner( + reader: &mut PeekReader, + signing_data: Option<&SigningData>, ) -> Result { loop { loop { @@ -712,17 +849,39 @@ pub fn read_v2_raw_message( .copy_from_slice(payload_and_checksum_and_sign); if message.has_valid_crc::() { + // even if the signature turn out to be invalid the valid crc shows that the received data presents a valid message as opposed to random bytes reader.consume(message.raw_bytes().len() - 1); - return Ok(message); + } else { + continue; + } + + #[cfg(feature = "signing")] + if let Some(signing_data) = signing_data { + if !signing_data.verify_signature(&message) { + continue; + } } + + return Ok(message); } } /// Async read a raw buffer with the mavlink message +/// /// V2 maximum size is 280 bytes: `` #[cfg(feature = "tokio-1")] pub async fn read_v2_raw_message_async( reader: &mut R, +) -> Result { + read_v2_raw_message_async_inner::(reader, None).await +} + +/// Async read a raw buffer with the mavlink message +/// V2 maximum size is 280 bytes: `` +#[cfg(feature = "tokio-1")] +async fn read_v2_raw_message_async_inner( + reader: &mut R, + signing_data: Option<&SigningData>, ) -> Result { loop { loop { @@ -747,12 +906,31 @@ pub async fn read_v2_raw_message_async() { - return Ok(message); + if !message.has_valid_crc::() { + continue; } + + #[cfg(feature = "signing")] + if let Some(signing_data) = signing_data { + if !signing_data.verify_signature(&message) { + continue; + } + } + + return Ok(message); } } +/// Async read a raw buffer with the mavlink message with signing support +/// V2 maximum size is 280 bytes: `` +#[cfg(all(feature = "tokio-1", feature = "signing"))] +pub async fn read_v2_raw_message_async_signed( + reader: &mut R, + signing_data: Option<&SigningData>, +) -> Result { + read_v2_raw_message_async_inner::(reader, signing_data).await +} + /// Async read a raw buffer with the mavlink message /// V2 maximum size is 280 bytes: `` /// @@ -802,10 +980,28 @@ pub async fn read_v2_raw_message_async( } /// Read a MAVLink v2 message from a Read stream. +#[inline] pub fn read_v2_msg( read: &mut PeekReader, ) -> Result<(MavHeader, M), error::MessageReadError> { - let message = read_v2_raw_message::(read)?; + read_v2_msg_inner(read, None) +} + +/// Read a MAVLink v2 message from a Read stream. +#[cfg(feature = "signing")] +#[inline] +pub fn read_v2_msg_signed( + read: &mut PeekReader, + signing_data: Option<&SigningData>, +) -> Result<(MavHeader, M), error::MessageReadError> { + read_v2_msg_inner(read, signing_data) +} + +fn read_v2_msg_inner( + read: &mut PeekReader, + signing_data: Option<&SigningData>, +) -> Result<(MavHeader, M), error::MessageReadError> { + let message = read_v2_raw_message_inner::(read, signing_data)?; Ok(( MavHeader { @@ -871,6 +1067,21 @@ pub fn write_versioned_msg( } } +/// Write a message with signing support using the given mavlink version +#[cfg(feature = "signing")] +pub fn write_versioned_msg_signed( + w: &mut W, + version: MavlinkVersion, + header: MavHeader, + data: &M, + signing_data: Option<&SigningData>, +) -> Result { + match version { + MavlinkVersion::V2 => write_v2_msg_signed(w, header, data, signing_data), + MavlinkVersion::V1 => write_v1_msg(w, header, data), + } +} + /// Async write a message using the given mavlink version #[cfg(feature = "tokio-1")] pub async fn write_versioned_msg_async( @@ -919,6 +1130,39 @@ pub fn write_v2_msg( Ok(len) } +/// Write a MAVLink v2 message to a Write stream with signing support. +#[cfg(feature = "signing")] +pub fn write_v2_msg_signed( + w: &mut W, + header: MavHeader, + data: &M, + signing_data: Option<&SigningData>, +) -> Result { + let mut message_raw = MAVLinkV2MessageRaw::new(); + + let signature_len = if let Some(signing_data) = signing_data { + if signing_data.config.sign_outgoing { + //header.incompat_flags |= MAVLINK_IFLAG_SIGNED; + message_raw.serialize_message_for_signing(header, data); + signing_data.sign_message(&mut message_raw); + MAVLinkV2MessageRaw::SIGNATURE_SIZE + } else { + message_raw.serialize_message(header, data); + 0 + } + } else { + message_raw.serialize_message(header, data); + 0 + }; + + let payload_length: usize = message_raw.payload_length().into(); + let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len; + + w.write_all(&message_raw.0[..len])?; + + Ok(len) +} + /// Async write a MAVLink v2 message to a Write stream. #[cfg(feature = "tokio-1")] pub async fn write_v2_msg_async( diff --git a/mavlink-core/src/signing.rs b/mavlink-core/src/signing.rs new file mode 100644 index 0000000000..f1b129037c --- /dev/null +++ b/mavlink-core/src/signing.rs @@ -0,0 +1,139 @@ +use crate::MAVLinkV2MessageRaw; + +use std::time::SystemTime; +use std::{collections::HashMap, sync::Mutex}; + +use crate::MAVLINK_IFLAG_SIGNED; + +/// Configuration used for MAVLink 2 messages signing as defined in . +#[derive(Debug, Clone)] +pub struct SigningConfig { + secret_key: [u8; 32], + link_id: u8, + pub(crate) sign_outgoing: bool, + allow_unsigned: bool, +} + +// mutable state of signing per connection +pub(crate) struct SigningState { + timestamp: u64, + stream_timestamps: HashMap<(u8, u8, u8), u64>, +} + +/// MAVLink 2 message signing data. +pub struct SigningData { + pub(crate) config: SigningConfig, + pub(crate) state: Mutex, +} + +impl SigningConfig { + pub fn new( + secret_key: [u8; 32], + link_id: u8, + sign_outgoing: bool, + allow_unsigned: bool, + ) -> Self { + Self { + secret_key, + link_id, + sign_outgoing, + allow_unsigned, + } + } +} + +impl SigningData { + pub fn from_config(config: SigningConfig) -> Self { + Self { + config, + state: Mutex::new(SigningState { + timestamp: 0, + stream_timestamps: HashMap::new(), + }), + } + } + + /// Verify the signature of a MAVLink 2 message. + pub fn verify_signature(&self, message: &MAVLinkV2MessageRaw) -> bool { + // The code that holds the mutex lock is not expected to panic, therefore the expect is justified. + // The only issue that might cause a panic, presuming the opertions on the message buffer are sound, + // is the `SystemTime::now()` call in `get_current_timestamp()`. + let mut state = self + .state + .lock() + .expect("Code holding MutexGuard should not panic."); + if message.incompatibility_flags() & MAVLINK_IFLAG_SIGNED > 0 { + state.timestamp = u64::max(state.timestamp, Self::get_current_timestamp()); + let timestamp = message.signature_timestamp(); + let src_system = message.system_id(); + let src_component = message.component_id(); + let stream_key = (message.signature_link_id(), src_system, src_component); + match state.stream_timestamps.get(&stream_key) { + Some(stream_timestamp) => { + if timestamp <= *stream_timestamp { + // reject old timestamp + return false; + } + } + None => { + if timestamp + 60 * 1000 * 100 < state.timestamp { + // bad new stream, more then a minute older the the last one + return false; + } + } + } + + let mut signature_buffer = [0u8; 6]; + message.calculate_signature(&self.config.secret_key, &mut signature_buffer); + let result = signature_buffer == message.signature_value(); + if result { + // if signature is valid update timestamps + state.stream_timestamps.insert(stream_key, timestamp); + state.timestamp = u64::max(state.timestamp, timestamp) + } + result + } else { + self.config.allow_unsigned + } + } + + /// Sign a MAVLink 2 message if its incompatibility flag is set accordingly. + pub fn sign_message(&self, message: &mut MAVLinkV2MessageRaw) { + if message.incompatibility_flags() & MAVLINK_IFLAG_SIGNED > 0 { + // The code that holds the mutex lock is not expected to panic, therefore the expect is justified. + // The only issue that might cause a panic, presuming the opertions on the message buffer are sound, + // is the `SystemTime::now()` call in `get_current_timestamp()`. + let mut state = self + .state + .lock() + .expect("Code holding MutexGuard should not panic."); + state.timestamp = u64::max(state.timestamp, Self::get_current_timestamp()); + let ts_bytes = u64::to_le_bytes(state.timestamp); + message + .signature_timestamp_bytes_mut() + .copy_from_slice(&ts_bytes[0..6]); + *message.signature_link_id_mut() = self.config.link_id; + + let mut signature_buffer = [0u8; 6]; + message.calculate_signature(&self.config.secret_key, &mut signature_buffer); + + message + .signature_value_mut() + .copy_from_slice(&signature_buffer); + state.timestamp += 1; + } + } + + fn get_current_timestamp() -> u64 { + // fallback to 0 if the system time appears to be before epoch + let now = SystemTime::now() + .duration_since(SystemTime::UNIX_EPOCH) + .map(|n| n.as_micros()) + .unwrap_or(0); + // use 1st January 2015 GMT as offset, fallback to 0 if before that date, the used 48bit of this will overflow in 2104 + ((now + .checked_sub(1420070400u128 * 1000000u128) + .unwrap_or_default()) + / 10u128) as u64 + } +} diff --git a/mavlink/Cargo.toml b/mavlink/Cargo.toml index 46896b017c..0573047572 100644 --- a/mavlink/Cargo.toml +++ b/mavlink/Cargo.toml @@ -92,6 +92,7 @@ serde_arrays = { version = "0.1.0", optional = true } "std" = ["mavlink-core/std"] "udp" = ["mavlink-core/udp"] "tcp" = ["mavlink-core/tcp"] +"signing" = ["mavlink-core/signing"] "direct-serial" = ["mavlink-core/direct-serial"] # NOTE: Only one of 'embedded' and 'embedded-hal-02' features can be enabled. # Use "embedded' feature to enable embedded-hal=1.0 (embedded-io and embedded-io-async is part of embedded-hal). diff --git a/mavlink/tests/signing.rs b/mavlink/tests/signing.rs new file mode 100644 index 0000000000..52ca63cd46 --- /dev/null +++ b/mavlink/tests/signing.rs @@ -0,0 +1,100 @@ +mod test_shared; + +#[cfg(feature = "signing")] +mod signing { + use mavlink::{ + common::HEARTBEAT_DATA, peek_reader::PeekReader, read_v2_raw_message, MAVLinkV2MessageRaw, + MavHeader, SigningConfig, SigningData, MAV_STX_V2, + }; + + use crate::test_shared::SECRET_KEY; + + const HEARTBEAT_SIGNED: &[u8] = &[ + MAV_STX_V2, + 0x09, + 0x01, // MAVLINK_IFLAG_SIGNED + 0x00, + crate::test_shared::COMMON_MSG_HEADER.sequence, + crate::test_shared::COMMON_MSG_HEADER.system_id, + crate::test_shared::COMMON_MSG_HEADER.component_id, + 0x00, // msg ID + 0x00, + 0x00, + 0x05, // payload + 0x00, + 0x00, + 0x00, + 0x02, + 0x03, + 0x59, + 0x03, + 0x03, + 0xc9, // checksum + 0x8b, + 0x00, // link_id + 0xff, // use max timestamp to ensure test will never fail against current time + 0xff, + 0xff, + 0xff, + 0xff, + 0xff, + 0x27, // signature + 0x18, + 0xb1, + 0x68, + 0xcc, + 0xf5, + ]; + + #[test] + pub fn test_verify() { + let signing_cfg = SigningConfig::new(SECRET_KEY, 0, true, false); + let signing_data = SigningData::from_config(signing_cfg); + let mut r = PeekReader::new(HEARTBEAT_SIGNED); + let msg = read_v2_raw_message::(&mut r).unwrap(); + assert!( + signing_data.verify_signature(&msg), + "Message verification failed" + ); + } + + #[test] + pub fn test_invalid_ts() { + let signing_cfg = SigningConfig::new(SECRET_KEY, 0, true, false); + let signing_data = SigningData::from_config(signing_cfg); + let mut r = PeekReader::new(HEARTBEAT_SIGNED); + let mut msg = read_v2_raw_message::(&mut r).unwrap(); + msg.signature_timestamp_bytes_mut() + .copy_from_slice(&[0, 0, 0, 0, 0, 0]); // set timestamp to min causing the timestamp test to fail + assert!( + !signing_data.verify_signature(&msg), + "Invalid message verified" + ); + } + + #[test] + pub fn test_sign_verify() { + use mavlink::common::MavMessage; + let heartbeat_message = MavMessage::HEARTBEAT(HEARTBEAT_DATA::default()); + let mut message = MAVLinkV2MessageRaw::new(); + let header = MavHeader { + system_id: 4, + component_id: 3, + sequence: 42, + }; + message.serialize_message_for_signing(header, &heartbeat_message); + + let signing_cfg = SigningConfig::new(SECRET_KEY, 0, true, false); + let signing_data = SigningData::from_config(signing_cfg); + signing_data.sign_message(&mut message); + assert!( + signing_data.verify_signature(&message), + "Message verification failed" + ); + // the same message must not be allowed to be verified again + assert!( + !signing_data.verify_signature(&message), + "Invalid message verified" + ); + } +} diff --git a/mavlink/tests/tcp_loopback_tests.rs b/mavlink/tests/tcp_loopback_tests.rs index abea99598b..170189cb97 100644 --- a/mavlink/tests/tcp_loopback_tests.rs +++ b/mavlink/tests/tcp_loopback_tests.rs @@ -4,14 +4,28 @@ mod test_shared; mod test_tcp_connections { use std::thread; - /// Test whether we can send a message via TCP and receive it OK + #[cfg(feature = "signing")] + use crate::test_shared; + #[cfg(feature = "signing")] + use mavlink::SigningConfig; + + /// Test whether we can send a message via TCP and receive it OK. This also test signing as a property of a MavConnection if the signing feature is enabled. #[test] pub fn test_tcp_loopback() { const RECEIVE_CHECK_COUNT: i32 = 5; + #[cfg(feature = "signing")] + let singing_cfg_server = SigningConfig::new(test_shared::SECRET_KEY, 0, true, false); + #[cfg(feature = "signing")] + let singing_cfg_client = singing_cfg_server.clone(); + let server_thread = thread::spawn(move || { //TODO consider using get_available_port to use a random port - let server = mavlink::connect("tcpin:0.0.0.0:14550").expect("Couldn't create server"); + let mut server = + mavlink::connect("tcpin:0.0.0.0:14550").expect("Couldn't create server"); + + #[cfg(feature = "signing")] + server.setup_signing(Some(singing_cfg_server)); let mut recv_count = 0; for _i in 0..RECEIVE_CHECK_COUNT { @@ -40,8 +54,12 @@ mod test_tcp_connections { thread::spawn(move || { let msg = mavlink::common::MavMessage::HEARTBEAT(crate::test_shared::get_heartbeat_msg()); - let client = + let mut client = mavlink::connect("tcpout:127.0.0.1:14550").expect("Couldn't create client"); + + #[cfg(feature = "signing")] + client.setup_signing(Some(singing_cfg_client)); + for _i in 0..RECEIVE_CHECK_COUNT { client.send_default(&msg).ok(); } diff --git a/mavlink/tests/test_shared/mod.rs b/mavlink/tests/test_shared/mod.rs index 4cba46907a..90f019cebd 100644 --- a/mavlink/tests/test_shared/mod.rs +++ b/mavlink/tests/test_shared/mod.rs @@ -6,6 +6,12 @@ pub const COMMON_MSG_HEADER: mavlink::MavHeader = mavlink::MavHeader { component_id: 2, }; +#[cfg(feature = "signing")] +pub const SECRET_KEY: [u8; 32] = [ + 0x00, 0x01, 0xf2, 0xe3, 0xd4, 0xc5, 0xb6, 0xa7, 0x98, 0x00, 0x70, 0x76, 0x34, 0x32, 0x00, 0x16, + 0x22, 0x42, 0x00, 0xcc, 0xff, 0x7a, 0x00, 0x52, 0x75, 0x73, 0x74, 0x00, 0x4d, 0x41, 0x56, 0xb3, +]; + #[cfg(feature = "common")] pub fn get_heartbeat_msg() -> mavlink::common::HEARTBEAT_DATA { mavlink::common::HEARTBEAT_DATA {