Giter Site home page Giter Site logo

rust-mavlink's Introduction

rust-mavlink

Build status Crate info Documentation

Rust implementation of the MAVLink UAV messaging protocol, with bindings for all message sets.

Add to your Cargo.toml:

mavlink = "0.12.2"

Examples

See examples/ for different usage examples.

mavlink-dump

examples/mavlink-dump contains an executable example that can be used to test message reception.

It can be executed directly by running:

cargo run --example mavlink-dump [options]

It's also possible to install the working example via cargo command line:

cargo install --path examples/mavlink-dump

It can then be executed by running:

mavlink-dump [options]

Execution call example:

mavlink-dump udpin:127.0.0.1:14540

Community projects

Check some projects built by the community:

License

Licensed under either of

rust-mavlink's People

Contributors

amsmith-pro avatar antonio-sc66 avatar bitsauce avatar bksalman avatar booo avatar danieleades avatar dependabot[bot] avatar erk- avatar g1gg1l3s avatar gabrieldertoni avatar grahamdennis avatar ihsenbouallegue avatar joaoantoniocardoso avatar joaofrf avatar jonathanplasse avatar kevinmehall avatar koffeinflummi avatar laptou avatar liamstask avatar lopsided98 avatar michael-p avatar nmsv avatar patrickelectric avatar podhrmic avatar pv42 avatar qwerty19106 avatar tb-me avatar tcr3dr avatar tjrmarques avatar tstellanova avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

rust-mavlink's Issues

A new release before multiple messages definitions

Right now we have the full common message definition available.
It's a good time to do a new release before the multiple message definition integration [ardupilotmega, autoquad, minimal, standard, ...].

Release 0.8.0 version

right now we have some new features that could be shipped in a new release version

Discussion: A better `Message` trait

Introduction

Currently the Message trait is defined like this

pub trait Message
where
    Self: Sized,
{
    fn message_id(&self) -> u32;
    fn message_name(&self) -> &'static str;

    /// Serialize **Message** into byte slice and return count of bytes written
    fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize;

    fn parse(
        version: MavlinkVersion,
        msgid: u32,
        payload: &[u8],
    ) -> Result<Self, error::ParserError>;

    fn message_id_from_name(name: &str) -> Result<u32, &'static str>;
    fn default_message_from_id(id: u32) -> Result<Self, &'static str>;
    fn extra_crc(id: u32) -> u8;
}

Then types implementing Message are structs of several *_DATA types that store the actual data for the message. Each of those types has ser and deser methods but no unifying trait to encompass this behaviour. They also have an associated constant ENCODED_LEN and implement Default.

Current limitations and issues

  1. Returning a Result<T, &'static str> isn't very helpfull in this case. There is a single reason for this to fail: the massage with the given name/id doesn't exist! However, the type indicates that many different error messages could be emitted. A better type would be Result<T, MessageDoesNotExist> or simply Option<T>.
  2. message_id_from_name, default_message_from_id, extra_crc, message_id and message_name are all trying to get some metadata about the message, though some do that with an instance of the message and others are static. We could instead return a &'static MessageMeta type that stores all the metadata in a single place. This would allow stuff like getting the message name from an id without having to construct the message. We would also avoid having to do multiple calls if we want multiple pieces of metadata. The metadata struct can also be passed around which is pretty usefull.
  3. In order to get a default instance of a message we need to construct it, even if we only need a reference to it. So, this MessageMeta struct could also store the default value for the message. Then we would have one MessageMeta static for every message *_DATA.
  4. Currently there is a mandatory dependency on heapless, but very little of the library is actually used (only Vec) and those uses could just be standard Rust arrays.
  5. Instead of implementing Bytes and BytesMut, use the bytes crate. It's a tiny crate that does pretty much the same as this crate's implementation, but uses a trait instead of a type, and implements the trait for slices.

A better interface

pub struct MessageMeta<M: Message> {
    pub id: u32,
    pub name: &'static str,
    pub extra_crc: u8,
    pub serialized_len: u8,
    pub default: M,
}

pub trait Message: Sized + 'static {
    fn meta(&self) -> &'static MessageMeta<Self>;
    fn meta_from_id(id: u32) -> Option<&'static MessageMeta<Self>>;
    fn meta_from_name(name: &str) -> Option<&'static MessageMeta<Self>>;

    fn serialize(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize;

    fn deserialize(
        version: MavlinkVersion,
        msgid: u32,
        payload: &[u8],
    ) -> Result<Self, error::ParserError>;
}

Additionaly, every message could implement another trait

pub trait MessageData<M: Message>: Default + Into<M> {
    fn meta() -> &'static MessageMeta<M>;

    fn serialize_payload(&self, version: MavlinkVersion, payload: &mut [u8]) -> usize;
    fn deserialize_payload(version: MavlinkVersion, payload: &[u8]) -> Result<Self, ParserError>;
}

this trait is parameterized on M: Message since a single *_DATA type can be used in multiple message enums. Issues 4 and 5 are about the internal message implementation and not the external interface, but switching to use them is pretty trivial. For serde, we can use serde_arrays which is also tiny, at least until serde supports const generics.

Also, using bytes might make it easier to integrate with other libraries in the future, such as tokio_util::codec::Decoder.

Final notes

I have implemented pretty much all of these changes already here, but I would like some feedback if these are things you would be interested in changing in the library. It's a big change, but I think the API would be much better with them. Anyway, let me know what you think!

Common message set (common.xml) is missing messages

Dear all,

it seems that the message definition file (common.xml) that is used to generate the code in this crate is pretty old, and misses quite a few messages. In my case I stumbled across this because of the LOGGING_DATA, LOGGING_DATA_ACKED and LOGGING_ACK messages (both are Mavlink 2 messages).

It would be great if this crate could be updated to the most recent version!

Thanks
Michael

MavFrame serialize into a vector with wrong fields order

True fields order for Mavlink Serialization:

  • magic (start)
  • len
  • ... (V2 fields)
  • sequence
  • system_id
  • component_id
  • message_id
  • payload
  • checksum

Now (MavFrame::ser method):

  • system_id
  • component_id
  • sequence
  • message_id
  • payload

In addition, MavFrame::ser and MavFrame::deser methods are not used in the MavConnection implementors as expected.

Update Mavlink submodule

The mavlink submodule should be updated, there is a few things in the newer versions which does not work with the parsing.
I started on it in #132, but never finished it.

Can this library serve as vehicle?

Skimming the docs, I only read about possibilities of connecting to a given network resource (hostname/ip + port). Can this library also be used to bind a TCP server locally, so that other non vehicle nodes (like GCS) can connect to to it (so that one may use this library on a vehicle)?

Question: Defining the sending port for UDPOUT

Hi, I'm new to Rust so sorry if this is a newbie question but I can't seem to work it out :)

Following the example I have created the following connections:
`let mut listening_address =
mavlink::connect::mavlink::common::MavMessage("udpin:127.0.0.1:14550").unwrap();

let mut send_address =
    mavlink::connect::<mavlink::common::MavMessage>("udpout:127.0.0.1:60036").unwrap();`

So listening_address listens to MAVLink packets coming from the SITL, and the send_address is the reverse allowing for commands to be sent to the drone.

But each time I create the send_address, there is a different src port being used for the send_address when I inspect in Wireshark.
Ideally, I would like to both listen for telemetry, and send commands from 127.0.0.1:14550, and it is my understanding that this is how applications such as QGroundControl also operate.

Is this possible with rust-mavlink?

Kind Regards

Getting ready for an official release

This is a tracking issue to make rust-mavlink an officially supported Mavlink implementation.

What needs to happen?

  • Split messages into one file per message (similar to what mavgen does)
  • Add quickcheck tests for each message
  • change enums to uints
  • Add fuzz testing
  • (optional) Build actual enums on top of message enums
  • Mavlink 2 support, including signing
  • Quote update
  • Somehow ensure max vector length for messages like v2_extension and statustext
  • Support for other dialects

MavMessage::parse panics on invalid message

quote!{
pub fn parse(version: MavlinkVersion, id: #id_width, payload: &[u8]) -> Option<MavMessage> {
match id {
#(#ids => Some(MavMessage::#enums(#structs::deser(version, payload).unwrap())),)*
_ => None,
}
}
}

MavMessage::parse is set up to unwrap() the value that is provided by serde.

Why can't it just return None instead of unwrapping? This way, invalid data will not lead to a panic.

feature ardupilotmega fail to build

error[E0432]: unresolved imports `crate::icarous`, `crate::uavionix`
 --> /home/patrick/git/blue/rust-mavlink/target/debug/build/mavlink-0dcff0587dd9cbda/out/ardupilotmega.rs:2:24
  |
2 | use crate::{common::*, icarous::*, uavionix::*};
  |                        ^^^^^^^     ^^^^^^^^ maybe a missing crate `uavionix`?
  |                        |
  |                        maybe a missing crate `icarous`?

error[E0433]: failed to resolve: maybe a missing crate `uavionix`?
    --> /home/patrick/git/blue/rust-mavlink/target/debug/build/mavlink-0dcff0587dd9cbda/out/ardupilotmega.rs:3531:21
     |
3531 |     uavionix(crate::uavionix::MavMessage),
     |                     ^^^^^^^^ maybe a missing crate `uavionix`?

error[E0433]: failed to resolve: maybe a missing crate `icarous`?
    --> /home/patrick/git/blue/rust-mavlink/target/debug/build/mavlink-0dcff0587dd9cbda/out/ardupilotmega.rs:3532:20
     |
3532 |     icarous(crate::icarous::MavMessage),
     |                    ^^^^^^^ maybe a missing crate `icarous`?

error[E0433]: failed to resolve: maybe a missing crate `uavionix`?
    --> /home/patrick/git/blue/rust-mavlink/target/debug/build/mavlink-0dcff0587dd9cbda/out/ardupilotmega.rs:3644:41
     |
3644 |                 if let Ok(msg) = crate::uavionix::MavMessage::parse(version, id, payload) {
     |                                         ^^^^^^^^ maybe a missing crate `uavionix`?

error[E0433]: failed to resolve: maybe a missing crate `icarous`?
    --> /home/patrick/git/blue/rust-mavlink/target/debug/build/mavlink-0dcff0587dd9cbda/out/ardupilotmega.rs:3647:41
     |
3647 |                 if let Ok(msg) = crate::icarous::MavMessage::parse(version, id, payload) {
     |                                         ^^^^^^^ maybe a missing crate `icarous`?

error[E0433]: failed to resolve: maybe a missing crate `uavionix`?
    --> /home/patrick/git/blue/rust-mavlink/target/debug/build/mavlink-0dcff0587dd9cbda/out/ardupilotmega.rs:3788:30
     |
3788 |                 match crate::uavionix::MavMessage::message_id_from_name(name) {
     |                              ^^^^^^^^ maybe a missing crate `uavionix`?

error[E0433]: failed to resolve: maybe a missing crate `icarous`?
    --> /home/patrick/git/blue/rust-mavlink/target/debug/build/mavlink-0dcff0587dd9cbda/out/ardupilotmega.rs:3792:30
     |
3792 |                 match crate::icarous::MavMessage::message_id_from_name(name) {
     |                              ^^^^^^^ maybe a missing crate `icarous`?

error[E0433]: failed to resolve: maybe a missing crate `uavionix`?
    --> /home/patrick/git/blue/rust-mavlink/target/debug/build/mavlink-0dcff0587dd9cbda/out/ardupilotmega.rs:4041:30
     |
4041 |                 match crate::uavionix::MavMessage::extra_crc(id) {
     |                              ^^^^^^^^ maybe a missing crate `uavionix`?

error[E0433]: failed to resolve: maybe a missing crate `icarous`?
    --> /home/patrick/git/blue/rust-mavlink/target/debug/build/mavlink-0dcff0587dd9cbda/out/ardupilotmega.rs:4045:30
     |
4045 |                 match crate::icarous::MavMessage::extra_crc(id) {
     |                              ^^^^^^^ maybe a missing crate `icarous`?

error: aborting due to 9 previous errors

Some errors have detailed explanations: E0432, E0433.
For more information about an error, try `rustc --explain E0432`.
error: could not compile `mavlink`.

To learn more, run the command again with --verbose.
 โœ˜ ๎‚ฐ ~/git/blue/rust-mavlink ๎‚ฐ ๎‚  master ๎‚ฐ 

Add support for mavlink 2

This repo was built before mavlink 2 was widely adopted. Unfortunately it is now incompatible with things like the px4_sitl version of mavlink.

cargo token need to be updated

@podhrmic can you update the token in our travis configuration ? Right now it's not impossible to do new releases:

error: api errors (status 401 Unauthorized): The given API token does not match the format used by crates.io. Tokens generated before 2020-07-14 were generated with an insecure random number generator, and have been revoked. You can generate a new token at https://crates.io/me. For more information please see https://blog.rust-lang.org/2020/07/14/crates-io-security-advisory.html. We apologize for any inconvenience.

Release 0.7 requires recompilation on every build

Dear all,

I just noticed that the recently published version 0.7 is rebuild by Cargo on every run, even though nothing has been modified.

To reproduce, create a new project and add mavlink to it:

$ cargo new --bin mavlink-test
$ cd mavlink-test
$ cargo add mavlink
$ cargo build

Then, just run the project twice without modifying anything in between:

$ cargo run && cargo run
   Compiling mavlink v0.7.0
   Compiling mavlink-test v0.1.0 (/Users/michaelp/Desktop/mavlink-test)
    Finished dev [unoptimized + debuginfo] target(s) in 17.18s
     Running `target/debug/mavlink-test`
Hello, world!
   Compiling mavlink v0.7.0
   Compiling mavlink-test v0.1.0 (/Users/michaelp/Desktop/mavlink-test)
    Finished dev [unoptimized + debuginfo] target(s) in 17.44s
     Running `target/debug/mavlink-test`
Hello, world!

Notice that both the mavlink crate as well as the application itself were compiled again.

For comparision, this is the output with version 0.6:

$ cargo run && cargo run
   Compiling mavlink-test v0.1.0 (/Users/michaelp/Desktop/mavlink-test)
    Finished dev [unoptimized + debuginfo] target(s) in 0.25s
     Running `target/debug/mavlink-test`
Hello, world!
    Finished dev [unoptimized + debuginfo] target(s) in 0.05s
     Running `target/debug/mavlink-test`
Hello, world

I'm using this crate in a fairly large application where compile times are measured in minutes, so having to rebuild even though nothing has changed is pretty annoying as you can probably imagine :)

Thanks,
Michael

Commands are not being properly parsed when the command type originates from `ardupilotmega.xml` (and others)

Hi! I have been trying to receive a command that is defined in ardupilotmega.xml without any success. I found out that this doesn't currently work because the generated mavlink::common::COMMAND_LONG struct has a member pub command: mavlink::common::MavCmd, however, that enum does not contain commands from any other file than common.xml.

This results in mavlink::common::COMMAND_LONG_DATA::deser() failing here:

_struct.command = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
    enum_type: "MavCmd".to_string(),
    value: tmp as u32,
})?;

Any thoughts as to how this could be solved?

Rust enums don't support combining, can't set multiple bitflags

Some of the bitflag data in the project is stored with enums, which causes issues with flags that are not mutually exclusive. Rust doesn't support combining enumerated values, and thus prevents the use of multiple flags, even though the flags are cast into u16 in serialisation.

The specific case I ran into is mavlink::common::GimbalDeviceFlags, where I'd like to lock each axis. This requires setting three flags, which can be done with bitwise-OR in C++, but is currently impossible with the Rust implementation.

Unused import warning

With 0.8 I get the following warning:

$ cargo build
...
warning: unused import: `crate :: { }`
 --> /tmp/rust-mavlink/target/package/mavlink-0.8.0/target/debug/build/mavlink-2d6a5ed84e19de61/out/common.rs:2:174
  |
...

It is not critical, but it would be nice to not have the warning.

Idiomatic way of accessing parsed message fields?

Hello,

I'm working on using some of the data from a prototype Aqualink ASV, and am curious if I'm missing the idiomatic way of directly parsing and accessing a data structure read from a Mavlink message.

I'm using something like the following to collect the messages:

let mut msgs: Vec<mavlink::common::MavMessage> = Vec::new();
loop {
    match vehicle.recv() {
            Ok((_header, msg)) => {
                println!("msg: {:?}\n",msg);
                msgs.push(msg);
            }
            Err(e) => {
                println!("e: {:?}",e);
                match e {
                    MessageReadError => {
                        //no messages currently available to receive -- wait a while
                        thread::sleep(Duration::from_millis(10));
                        continue;
                    }
                    _ => {
                        println!("recv error: {:?}", e);
                        break;
                    }
                }
            }
        }

        // Parse the last message in the queue
        let last_msg = &msgs.last().cloned().expect("Couldn't get the last message");
        let id = mavlink::common::MavMessage::message_id(last_msg);
        let payload = mavlink::common::MavMessage::ser(last_msg);

        let data = mavlink::common::MavMessage::parse(
            mavlink::MavlinkVersion::V2,
            last_msg.message_id(),
            &last_msg.ser(),
        ).expect("Couldn't parse data");

    // For example
    match id {
             30 => {
                 let attitude: Attitude = parse_attitude_message(last_msg).expect("Couldn't parse attitude message");
                 println!("Attitude: {:#?}", data);
             }
            _ => continue

}

The problem is, I'm taking the data and parsing it into my custom Attitude structure, by doing something like this:

#[derive(Debug, Clone, Copy)]
pub struct Attitude {
    pub roll: f32,
    pub pitch: f32,
    pub yaw: f32,
    pub rollspeed: f32,
    pub pitchspeed: f32,
    pub yawspeed: f32,
}

pub fn parse_attitude_message_30(msg: &mavlink::common::MavMessage) -> Result<Attitude, Box<dyn Error>> {
    let data = mavlink::common::MavMessage::parse(
        mavlink::MavlinkVersion::V2,
        msg.message_id(),
        &msg.ser(),
    )?;
    
    // It seems like there should be a function somewhere that extends this match statement out and returns 
    // the information in a mavlink::common::INFO_DATA struct right back. 
    let attitude = match data {
        mavlink::common::MavMessage::ATTITUDE(mavlink::common::ATTITUDE_DATA {
            time_boot_ms: _,
            roll,
            pitch,
            yaw,
            rollspeed,
            pitchspeed,
            yawspeed,
        }) => Attitude::new(
            roll,
            pitch,
            yaw * 180.0 / PI, // yaw is now going to be in degrees instead of radians
            rollspeed,          // However, the "speed" variables should stil be in rad/s
            pitchspeed,
            yawspeed * 180.0 / PI, //
        ),
        _ => panic!("Error while parsing message") // If it's not an Attitude message, then we need to break off
    };
    Ok(attitude)

}

Honestly, this seems a little silly; I know that there's a mavlink::common::ATTITUDE_DATA data structure with named fields somewhere, but I'm having an issue with directly instantiating it so I can directly access the data using something like

let attitude: mavlink::common::ATTITUDE_DATA = {/* something */};
println!("The roll value is {}", attitude.roll); 

Of course, this isn't too much of an issue with a single struct, but if I want to access multiple fields at once (say, for example, I want Attitude and GPS (through the mavlink::common::MavMessage::GLOBAL_POSITION_INT, I now need to write another ~50 LoC of boilerplate to have access to those values.

So, I guess my question is: am I missing something? I've spent a fair amount of time reading through the docs, and I know there's a parse() function that keeps showing up, but I'm having trouble figuring out how do combine all of these things in a better-looking way that still gets me what I'm looking for.

TCP receive blocks on OSX: MavConnection::recv never returns messages

Testing this library with a TCP connection, send seems to work but receive does not.
The problem seems to be that the socket read has no timeout by default, so the read waits forever.

Setting the timeout:

sock_clone.set_read_timeout(Some(Duration::from_millis(100))).unwrap();

and then loop-ignoring the resulting io::ErrorKind::WouldBlock seems to unstick the socket. I've got a WIP fork for this -- if this repo is still maintained, I can submit a PR for that when it's ready.

Unreadable dialects file.

image

This is part of the generated dialects of common.rs, it's hard to read. I used to use gomavlib, and the files generated are much more readable.

Another problem is that, whenever I navigate to the generated file, my NVIM editor just got stuck.

Serde derive macro is not found

I'm using mavlink with the default set of features and I get an error message for serde derive macro:

error: cannot find derive macro `Deserialize` in this scope
    --> /mnt/Disk/Projects/Personal/realsense/target/debug/build/mavlink-5f7d13b37869c4dd/out/common.rs:1144:49
     |
1144 | #[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
     |                                                 ^^^^^^^^^^^
     |
note: `Deserialize` is imported here, but it is only a trait, without a derive macro
    --> /mnt/Disk/Projects/Personal/realsense/target/debug/build/mavlink-5f7d13b37869c4dd/out/common.rs:23:13
     |
23   | use serde::{Deserialize, Serialize};

Heartbeat fields have an inconsistent order

As I understand the specification for the heatbeat message structure , custom_mode should come after base_mode and before system_status. However, when I look at the Rust code in common.rs, I have the following with the custom_mode bytes being inserted first:

pub fn ser(&self) -> Vec<u8> {
    let mut _tmp = Vec::new();
    _tmp.put_u32_le(self.custom_mode);
    _tmp.put_u8(self.mavtype as u8);
    _tmp.put_u8(self.autopilot as u8);
    _tmp.put_u8(self.base_mode.bits());
    _tmp.put_u8(self.system_status as u8);
    _tmp.put_u8(self.mavlink_version);
    _tmp
}

I guess one of the two are incorrect?

Add mavlink extension support in runtime

Right now we have a feature called emit-extensions that generate it it compile time.
But we have mavlink V1 or mavlink V2 as a runtime option and that should the way that we handle the extensions also.
It would be nice to have all extensions over a Option and serialize deserialize it based in the mavlink version running.

Don't support signing?

Just confirming for the mavlink docs tat this library doesn't support signing - right?

Are there any more docs than provided on the readme?
For context, I'm trying to characterize the things provided by each project

  • ie level of docs (where this one for C might be full
  • level of testing - ie what is tested, unit test, round trip tests, test that send receive from C library etc.

test failure - "test process_files::all"

the test process_files::all test is failing

cargo test --features all-dialects

Processing file: /tmp/testlogs/ArduSub-test.tlog
recv error: Error { kind: UnexpectedEof, message: "failed to fill whole buffer" }
Number of parsed messages: 0
thread 'process_files::all' panicked at 'Unable to hit the necessary amount of matches', tests/process_log_files.rs:71:9

seeing this locally, as well as in CI

Add new dialects from Mavlink upstream

The upstream version was updated in #164, but it did not add new dialects to the feature set.

The new dialets as of time writing this are storm32, AVSSUAS, all, cubepilot and development.

And the dialect autoquad was removed.

Support async contexts and make the crate more transport-agnostic

Hi there, I needed to decode MAVLink messages in an async application based on the Tokio executor, so I went ahead and implemented a decoder using tokio_util's Decoder trait and this library here: codec.rs. With this trait in place, I am able to decode messages asynchronously with just a few lines of code:

async fn example() {
    let mut mavlink = match TcpStream::connect((MAVLINK_IP, MAVLINK_PORT)).await {
        Ok(stream) => {
            FramedRead::new(stream, codec::MavMessageDecoder::<mavlink::common::MavMessage>::new())
        },
        Err(error) => {
            log::error!("Failed to connect");
            return;
        }
    };
    while let Some(message) = mavlink.next().await {
        match message {
            Ok(message) => log::info!("{:?}", message),
            Err(error) => log::error!("{}", error),
        }
    }
}

This exercise has revealed a couple design flaws in this library. One particular code smell that I picked up on was that I had to duplicate a lot of code in this library to achieve what I was doing. Referring back to codec.rs, I don't think lines 39 to 85 belong in my code and this functionality should be provided by the library.

I am still relatively new to Rust, but I have seen enough of the ecosystem to put forward the following proposals for the library:

  1. This crate should do one thing and do it well, provide types and traits for MAVLink messages and a means for converting them from/to u8 buffers or perhaps from/to the Buf, BufMut traits from the bytes crate. In particular, something like:
impl<B: bytes::Buf, M: mavlink::Message> std::convert::TryFrom<B> for M {
    type Error = mavlink::error::MessageReadError;

    fn try_from(buffer: B) -> std::result::Result<Self, Self::Error> {
        todo!()
    }
}
  1. The concepts, types, and details of transports such as TCP, UDP, or UART and the various libraries that implement these transports should not leak into crate. Referring to issue #16, I disagree that this library should have any methods like recv regardless of whether they are synchronous or asynchronous. For sure, any use case will involve one of these transports, but that code and its dependencies belong in the examples.

What I propose above are indeed breaking changes, however, it would make the library simpler, more flexible (i.e., regarding async vs. sync) and agnostic to the underlying transport. I believe this would also make no_std support easier (i.e. less functionality hidden behind feature gates).

add MSRV

this project doesn't seem to define an MSRV.

This should be added to CI.

benefits-

  • bumping the MSRV should be considered a patch change pre-1.0, and a minor change post 1.0
  • clippy can be configured with the MSRV to stop it suggesting changes which the MSRV doesn't support

the current MSRV for this project looks to be 1.56.1

Discussion: Improving the API

Hi, I would like to start a discussion about improving the MAVLink API. I frequently come across situations which are (at least with my knowledge) not easy to solve using this library.

Subscribing to a specific message

Often I want to receive a certain message somewhere in the code. This is a key feature in order to not have this one huge match statement where each and every message is processed. For this, it would be very nice to be able to subscribe to a message. I imagine an API like this:

impl MavConnectionHandler {
  subscribe(&self, message: MavMessage)->std::sync::mpsc::Receiver<MavMessage>
  subscribe_once(&self, message: MavMessage)->std::sync::mpsc::Receiver<MavMessage>
  // call frequently to do the housework
  spin(&self);
}

Obviously this would require that someone is calling spin regularly. Another less no_std friendly approach would be

impl MavConnectionHandler {
   /// spawns the MavConnectionHandler which takes care of handling subscriptions
  new<M>(conn: Box<dyn MavConnection<M> + Sync + Send>)->(JoinHandle<()>, Arc<dyn MavConnectionHandler>)
  subscribe(&self, message: MavMessage)->std::sync::mpsc::Receiver<MavMessage>
  subscribe_once(&self, message: MavMessage)->std::sync::mpsc::Receiver<MavMessage>
}

This however bears a big problem. AFAIK there is no way to talk about the type of a mavlink message without creating an instance of it. This brings us to my next pain point:

Allow a message type to be specified, without an Instance of the message

Well there is the message id, but that is by no means type safe (and IMO nothing we should rely on in an API). And yes, there is std::mem::discriminant, however that does require one to construct a value. If I want to name the type of MavMessage, the best option so far seems to be this:

let message_type = discriminant(&MavMessage::PARAM_VALUE(Default::default()));

Allow conversion of a MavMessage to one specific ..._DATA struct

I'm currently in the making of a nicer async API which operates on top of the MavConnection trait. AFAIK it is not possible to convert a MavMessage into on specific data structure. This is not an issue if one doesn't know what message the next recv() will yield. However, in my implementation I do know that. Consider the following example (which continues the last snippet):

/// currently. The thing which bothers me the most is that there is 
/// no way of avoiding yet another level of indentation.
if let MavMessage::PARAM_VALUE(data) = wrappe_conn.request(&message_type).await {
    
}

/// maybe in the future? ^^
/// Notice that the request method can do the unwrapping internally, 
/// as we already know that we will only receive the correct messages
let data = wrapped_conn.request(&message_type).await;

If I understand correctly, the issue is simple: There is no way of extracting data out of an enum instance without mentioning the variant which contains said data. Maybe its possible to add a method like this to MavMessage:

/// Tries to convert an instance of the `MavMessage` enum into one of the `_DATA` structs
impl MavMessage {
    into_inner(self)->Option<T>
}

Maybe it's also possible to exploit Any for the polymorphism needed in a generic receive function. A rough draft could be like this: For sure runtime reflections do work for this kind of stuff, but that would be a huge break in the API which will likely not pay off UX wise.

pub enum MavMessageType {
    HEARTBEAT,
    SYS_STATUS,
    SYSTEM_TIME,
    //...
}

impl MavMessage {
   type(&self)->MavMessageType;
   as_message<T>(&self)->T{
        self.downcast_ref::<T>().clone()
   }
   // serialize, deserialize, ...
}

Summary

I'm sure there is more room for improvement, but these are the points which have bitten me the most. My proposals are in no way ready and probably will even fail compilation, they solely are meant to be early drafts. Speaking of drafts, out of the need for my use cases I already implemented an async API wrapper for MavConnection in the last couple of days. I would be very happy if it eventually find's it's way back in the this crate, behind a feature gate which is disabled per default maybe? Currently you can only have a look into it here. It isn't feature complete, but it already works!
What do you think?

Is there a general desire to further refine the API?

Edit:
Some of my statements turned out to be questionable, thus I corrected them. Furthermore I added some more information and examples.
Edit 2:
I added some more information and again refine the examples.

New 0.9.0 version

I'm planning to deploy this week the 0.9.0 version with some new features including the new embedded support.
I'll just finish a couple of tests with the stm32f303 before doing it.
@podhrmic @kevinmehall let me know if you guys are ok with it

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.