Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix lib.rs link format #183

Merged
merged 1 commit into from
Jul 12, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@ pub fn read_versioned_msg<M: Message, R: Read>(
}

#[derive(Debug, Copy, Clone, PartialEq, Eq)]
// Follow protocol definition: https://mavlink.io/en/guide/serialization.html#v1_packet_format
// Follow protocol definition: `<https://mavlink.io/en/guide/serialization.html#v1_packet_format>`
pub struct MAVLinkV1MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2]);

impl Default for MAVLinkV1MessageRaw {
Expand Down Expand Up @@ -319,7 +319,7 @@ impl MAVLinkV1MessageRaw {
}

/// Return a raw buffer with the mavlink message
/// V1 maximum size is 263 bytes: https://mavlink.io/en/guide/serialization.html
/// V1 maximum size is 263 bytes: `<https://mavlink.io/en/guide/serialization.html>`
pub fn read_v1_raw_message<R: Read>(
reader: &mut R,
) -> Result<MAVLinkV1MessageRaw, error::MessageReadError> {
Expand Down Expand Up @@ -371,7 +371,7 @@ pub fn read_v1_msg<M: Message, R: Read>(
const MAVLINK_IFLAG_SIGNED: u8 = 0x01;

#[derive(Debug, Copy, Clone, PartialEq, Eq)]
// Follow protocol definition: https://mavlink.io/en/guide/serialization.html#mavlink2_packet_format
// Follow protocol definition: `<https://mavlink.io/en/guide/serialization.html#mavlink2_packet_format>`
pub struct MAVLinkV2MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE]);

impl Default for MAVLinkV2MessageRaw {
Expand Down Expand Up @@ -505,7 +505,7 @@ impl MAVLinkV2MessageRaw {
}

/// Return a raw buffer with the mavlink message
/// V2 maximum size is 280 bytes: https://mavlink.io/en/guide/serialization.html
/// V2 maximum size is 280 bytes: `<https://mavlink.io/en/guide/serialization.html>`
pub fn read_v2_raw_message<R: Read>(
reader: &mut R,
) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
Expand Down
Loading