Skip to content

Commit

Permalink
Update embedded-hal to 1.0.
Browse files Browse the repository at this point in the history
Add async methods.
Add async example (Embassy executor).
  • Loading branch information
qwerty19106 authored and patrickelectric committed Jun 20, 2024
1 parent f47c61f commit 8c342c1
Show file tree
Hide file tree
Showing 11 changed files with 403 additions and 20 deletions.
10 changes: 8 additions & 2 deletions mavlink-core/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,10 @@ rust-version = "1.65.0"
[dependencies]
crc-any = { workspace = true, default-features = false }
byteorder = { workspace = true, default-features = false }
embedded-hal = { version = "0.2", optional = true }
nb = { version = "1.0", optional = true }
embedded-hal-02 = { version = "0.2", optional = true, package = "embedded-hal" }
embedded-io = { version = "0.6.1", optional = true }
embedded-io-async = { version = "0.6.1", optional = true }
serde = { version = "1.0.115", optional = true, features = ["derive"] }
serde_arrays = { version = "0.1.0", optional = true }
serial = { version = "0.4", optional = true }
Expand All @@ -30,6 +32,10 @@ serial = { version = "0.4", optional = true }
"udp" = []
"tcp" = []
"direct-serial" = ["serial"]
"embedded" = ["embedded-hal", "nb"]
# 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).
# Use 'embedded-hal-0.2' feature to enable deprecated embedded-hal=0.2.3 (some hals is not supports embedded-hal=1.0 yet).
"embedded" = ["dep:embedded-io", "dep:embedded-io-async"]
"embedded-hal-02" = ["dep:nb", "dep:embedded-hal-02"]
"serde" = ["dep:serde", "dep:serde_arrays"]
default = ["std", "tcp", "udp", "direct-serial", "serde"]
33 changes: 24 additions & 9 deletions mavlink-core/src/embedded.rs
Original file line number Diff line number Diff line change
@@ -1,30 +1,45 @@
use crate::error::*;

#[cfg(all(feature = "embedded", feature = "embedded-hal-02"))]
const _: () = panic!("Only one of 'embedded' and 'embedded-hal-02' features can be enabled.");

/// Replacement for std::io::Read + byteorder::ReadBytesExt in no_std envs
pub trait Read {
fn read_u8(&mut self) -> Result<u8, MessageReadError>;
fn read_exact(&mut self, buf: &mut [u8]) -> Result<(), MessageReadError>;
}

#[cfg(all(feature = "embedded", not(feature = "embedded-hal-02")))]
impl<R: embedded_io::Read> Read for R {
fn read_exact(&mut self, buf: &mut [u8]) -> Result<(), MessageReadError> {
embedded_io::Read::read_exact(self, buf).map_err(|_| MessageReadError::Io)
}
}

#[cfg(all(feature = "embedded-hal-02", not(feature = "embedded")))]
impl<R: embedded_hal_02::serial::Read<u8>> Read for R {
fn read_exact(&mut self, buf: &mut [u8]) -> Result<(), MessageReadError> {
for byte in buf {
*byte = self.read_u8()?;
*byte = nb::block!(self.read()).map_err(|_| MessageReadError::Io)?;
}

Ok(())
}
}

impl<R: embedded_hal::serial::Read<u8>> Read for R {
fn read_u8(&mut self) -> Result<u8, MessageReadError> {
nb::block!(self.read()).map_err(|_| MessageReadError::Io)
}
}

/// Replacement for std::io::Write + byteorder::WriteBytesExt in no_std envs
pub trait Write {
fn write_all(&mut self, buf: &[u8]) -> Result<(), MessageWriteError>;
}

impl<W: embedded_hal::serial::Write<u8>> Write for W {
#[cfg(all(feature = "embedded", not(feature = "embedded-hal-02")))]
impl<W: embedded_io::Write> Write for W {
fn write_all(&mut self, buf: &[u8]) -> Result<(), MessageWriteError> {
embedded_io::Write::write_all(self, buf).map_err(|_| MessageWriteError::Io)
}
}

#[cfg(all(feature = "embedded-hal-02", not(feature = "embedded")))]
impl<W: embedded_hal_02::serial::Write<u8>> Write for W {
fn write_all(&mut self, buf: &[u8]) -> Result<(), MessageWriteError> {
for byte in buf {
nb::block!(self.write(*byte)).map_err(|_| MessageWriteError::Io)?;
Expand Down
8 changes: 4 additions & 4 deletions mavlink-core/src/error.rs
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ impl Error for ParserError {}
pub enum MessageReadError {
#[cfg(feature = "std")]
Io(std::io::Error),
#[cfg(feature = "embedded")]
#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
Io,
Parse(ParserError),
}
Expand All @@ -42,7 +42,7 @@ impl Display for MessageReadError {
match self {
#[cfg(feature = "std")]
Self::Io(e) => write!(f, "Failed to read message: {e:#?}"),
#[cfg(feature = "embedded")]
#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
Self::Io => write!(f, "Failed to read message"),
Self::Parse(e) => write!(f, "Failed to read message: {e:#?}"),
}
Expand All @@ -69,7 +69,7 @@ impl From<ParserError> for MessageReadError {
pub enum MessageWriteError {
#[cfg(feature = "std")]
Io(std::io::Error),
#[cfg(feature = "embedded")]
#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
Io,
}

Expand All @@ -78,7 +78,7 @@ impl Display for MessageWriteError {
match self {
#[cfg(feature = "std")]
Self::Io(e) => write!(f, "Failed to write message: {e:#?}"),
#[cfg(feature = "embedded")]
#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
Self::Io => write!(f, "Failed to write message"),
}
}
Expand Down
209 changes: 206 additions & 3 deletions mavlink-core/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,9 @@ pub mod error;
#[cfg(feature = "std")]
pub use self::connection::{connect, MavConnection};

#[cfg(feature = "embedded")]
#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
pub mod embedded;
#[cfg(feature = "embedded")]
#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
use embedded::{Read, Write};

pub const MAX_FRAME_SIZE: usize = 280;
Expand Down Expand Up @@ -395,7 +395,49 @@ pub fn read_v1_raw_message<M: Message, R: Read>(
}
}

/// Read a MAVLink v1 message from a Read stream.
/// Async read a raw buffer with the mavlink message
/// V1 maximum size is 263 bytes: `<https://mavlink.io/en/guide/serialization.html>`
///
/// # Example
/// See mavlink/examples/embedded-async-read full example for details.
#[cfg(feature = "embedded")]
pub async fn read_v1_raw_message_async<M: Message>(
reader: &mut impl embedded_io_async::Read,
) -> Result<MAVLinkV1MessageRaw, error::MessageReadError> {
loop {
// search for the magic framing value indicating start of mavlink message
let mut byte = [0u8];
loop {
reader
.read_exact(&mut byte)
.await
.map_err(|_| error::MessageReadError::Io)?;
if byte[0] == MAV_STX {
break;
}
}

let mut message = MAVLinkV1MessageRaw::new();

message.0[0] = MAV_STX;
reader
.read_exact(message.mut_header())
.await
.map_err(|_| error::MessageReadError::Io)?;
reader
.read_exact(message.mut_payload_and_checksum())
.await
.map_err(|_| error::MessageReadError::Io)?;

// retry if CRC failed after previous STX
// (an STX byte may appear in the middle of a message)
if message.has_valid_crc::<M>() {
return Ok(message);
}
}
}

/// Read a MAVLink v1 message from a Read stream.
pub fn read_v1_msg<M: Message, R: Read>(
r: &mut PeekReader<R>,
) -> Result<(MavHeader, M), error::MessageReadError> {
Expand All @@ -419,6 +461,34 @@ pub fn read_v1_msg<M: Message, R: Read>(
.map_err(|err| err.into())
}

/// Async read a MAVLink v1 message from a Read stream.
///
/// NOTE: it will be add ~80KB to firmware flash size because all *_DATA::deser methods will be add to firmware.
/// Use `*_DATA::ser` methods manually to prevent it.
#[cfg(feature = "embedded")]
pub async fn read_v1_msg_async<M: Message>(
r: &mut impl embedded_io_async::Read,
) -> Result<(MavHeader, M), error::MessageReadError> {
let message = read_v1_raw_message_async::<M>(r).await?;

M::parse(
MavlinkVersion::V1,
u32::from(message.message_id()),
message.payload(),
)
.map(|msg| {
(
MavHeader {
sequence: message.sequence(),
system_id: message.system_id(),
component_id: message.component_id(),
},
msg,
)
})
.map_err(|err| err.into())
}

const MAVLINK_IFLAG_SIGNED: u8 = 0x01;

#[derive(Debug, Copy, Clone, PartialEq, Eq)]
Expand Down Expand Up @@ -621,6 +691,48 @@ pub fn read_v2_raw_message<M: Message, R: Read>(
}
}

/// Async read a raw buffer with the mavlink message
/// V2 maximum size is 280 bytes: `<https://mavlink.io/en/guide/serialization.html>`
///
/// # Example
/// See mavlink/examples/embedded-async-read full example for details.
#[cfg(feature = "embedded")]
pub async fn read_v2_raw_message_async<M: Message>(
reader: &mut impl embedded_io_async::Read,
) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
loop {
// search for the magic framing value indicating start of mavlink message
let mut byte = [0u8];
loop {
reader
.read_exact(&mut byte)
.await
.map_err(|_| error::MessageReadError::Io)?;
if byte[0] == MAV_STX_V2 {
break;
}
}

let mut message = MAVLinkV2MessageRaw::new();

message.0[0] = MAV_STX;
reader
.read_exact(message.mut_header())
.await
.map_err(|_| error::MessageReadError::Io)?;
reader
.read_exact(message.mut_payload_and_checksum_and_sign())
.await
.map_err(|_| error::MessageReadError::Io)?;

// retry if CRC failed after previous STX
// (an STX byte may appear in the middle of a message)
if message.has_valid_crc::<M>() {
return Ok(message);
}
}
}

/// Read a MAVLink v2 message from a Read stream.
pub fn read_v2_msg<M: Message, R: Read>(
read: &mut PeekReader<R>,
Expand All @@ -641,6 +753,34 @@ pub fn read_v2_msg<M: Message, R: Read>(
.map_err(|err| err.into())
}

/// Async read a MAVLink v2 message from a Read stream.
///
/// NOTE: it will be add ~80KB to firmware flash size because all *_DATA::deser methods will be add to firmware.
/// Use `*_DATA::deser` methods manually to prevent it.
#[cfg(feature = "embedded")]
pub async fn read_v2_msg_async<M: Message, R: embedded_io_async::Read>(
r: &mut R,
) -> Result<(MavHeader, M), error::MessageReadError> {
let message = read_v2_raw_message_async::<M>(r).await?;

M::parse(
MavlinkVersion::V2,
u32::from(message.message_id()),
message.payload(),
)
.map(|msg| {
(
MavHeader {
sequence: message.sequence(),
system_id: message.system_id(),
component_id: message.component_id(),
},
msg,
)
})
.map_err(|err| err.into())
}

/// Write a message using the given mavlink version
pub fn write_versioned_msg<M: Message, W: Write>(
w: &mut W,
Expand All @@ -654,6 +794,23 @@ pub fn write_versioned_msg<M: Message, W: Write>(
}
}

/// Async write a message using the given mavlink version
///
/// NOTE: it will be add ~70KB to firmware flash size because all *_DATA::ser methods will be add to firmware.
/// Use `*_DATA::ser` methods manually to prevent it.
#[cfg(feature = "embedded")]
pub async fn write_versioned_msg_async<M: Message>(
w: &mut impl embedded_io_async::Write,
version: MavlinkVersion,
header: MavHeader,
data: &M,
) -> Result<usize, error::MessageWriteError> {
match version {
MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
}
}

/// Write a MAVLink v2 message to a Write stream.
pub fn write_v2_msg<M: Message, W: Write>(
w: &mut W,
Expand All @@ -671,6 +828,29 @@ pub fn write_v2_msg<M: Message, W: Write>(
Ok(len)
}

/// Async write a MAVLink v2 message to a Write stream.
///
/// NOTE: it will be add ~70KB to firmware flash size because all *_DATA::ser methods will be add to firmware.
/// Use `*_DATA::ser` methods manually to prevent it.
#[cfg(feature = "embedded")]
pub async fn write_v2_msg_async<M: Message>(
w: &mut impl embedded_io_async::Write,
header: MavHeader,
data: &M,
) -> Result<usize, error::MessageWriteError> {
let mut message_raw = MAVLinkV2MessageRaw::new();
message_raw.serialize_message(header, data);

let payload_length: usize = message_raw.payload_length().into();
let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;

w.write_all(&message_raw.0[..len])
.await
.map_err(|_| error::MessageWriteError::Io)?;

Ok(len)
}

/// Write a MAVLink v1 message to a Write stream.
pub fn write_v1_msg<M: Message, W: Write>(
w: &mut W,
Expand All @@ -687,3 +867,26 @@ pub fn write_v1_msg<M: Message, W: Write>(

Ok(len)
}

/// Write a MAVLink v1 message to a Write stream.
///
/// NOTE: it will be add ~70KB to firmware flash size because all *_DATA::ser methods will be add to firmware.
/// Use `*_DATA::ser` methods manually to prevent it.
#[cfg(feature = "embedded")]
pub async fn write_v1_msg_async<M: Message>(
w: &mut impl embedded_io_async::Write,
header: MavHeader,
data: &M,
) -> Result<usize, error::MessageWriteError> {
let mut message_raw = MAVLinkV1MessageRaw::new();
message_raw.serialize_message(header, data);

let payload_length: usize = message_raw.payload_length().into();
let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;

w.write_all(&message_raw.0[..len])
.await
.map_err(|_| error::MessageWriteError::Io)?;

Ok(len)
}
2 changes: 1 addition & 1 deletion mavlink-core/src/peek_reader.rs
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
//! The main type `PeekReader`does not implement [`std::io::Read`] itself, as there is no added benefit
//! in doing so.
//!
#[cfg(feature = "embedded")]
#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
use crate::embedded::Read;

#[cfg(feature = "std")]
Expand Down
4 changes: 4 additions & 0 deletions mavlink/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,11 @@ serde_arrays = { version = "0.1.0", optional = true }
"udp" = ["mavlink-core/udp"]
"tcp" = ["mavlink-core/tcp"]
"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).
# Use 'embedded-hal-0.2' feature to enable deprecated embedded-hal=0.2.3 (some hals is not supports embedded-hal=1.0 yet).
"embedded" = ["mavlink-core/embedded"]
"embedded-hal-02" = ["mavlink-core/embedded-hal-02"]
"serde" = ["mavlink-core/serde", "dep:serde", "dep:serde_arrays"]
default = ["std", "tcp", "udp", "direct-serial", "serde", "ardupilotmega"]

Expand Down
Loading

0 comments on commit 8c342c1

Please sign in to comment.