Skip to content

Commit 25d72b6

Browse files
committed
minor refactoring
1 parent 8fb5875 commit 25d72b6

File tree

10 files changed

+77
-105
lines changed

10 files changed

+77
-105
lines changed

Cargo.toml

+5
Original file line numberDiff line numberDiff line change
@@ -8,3 +8,8 @@ num-traits = { version = "0.2", default-features = false }
88
num-derive = "0.3.2"
99
bitflags = "1.2.1"
1010
byteorder = { version = "1.3.4", default-features = false }
11+
12+
[workspace.lints.clippy]
13+
all = "deny"
14+
pedantic = "warn"
15+
nursery = "warn"

mavlink-bindgen/src/lib.rs

+3-4
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ fn _generate(
3939
) -> Result<GeneratedBindings, BindGenError> {
4040
let mut bindings = vec![];
4141

42-
for entry_maybe in read_dir(&definitions_dir).map_err(|source| {
42+
for entry_maybe in read_dir(definitions_dir).map_err(|source| {
4343
BindGenError::CouldNotReadDefinitionsDirectory {
4444
source,
4545
path: definitions_dir.to_path_buf(),
@@ -55,8 +55,7 @@ fn _generate(
5555
let definition_file = PathBuf::from(entry.file_name());
5656
let module_name = util::to_module_name(&definition_file);
5757

58-
let mut definition_rs = PathBuf::from(&module_name);
59-
definition_rs.set_extension("rs");
58+
let definition_rs = PathBuf::from(&module_name).with_extension("rs");
6059

6160
let dest_path = destination_dir.join(definition_rs);
6261
let mut outf = BufWriter::new(File::create(&dest_path).map_err(|source| {
@@ -67,7 +66,7 @@ fn _generate(
6766
})?);
6867

6968
// generate code
70-
parser::generate(&definitions_dir, &definition_file, &mut outf)?;
69+
parser::generate(definitions_dir, &definition_file, &mut outf)?;
7170

7271
bindings.push(GeneratedBinding {
7372
module_name,

mavlink-bindgen/src/parser.rs

+3-9
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,6 @@ use std::fs::File;
77
use std::io::{BufReader, Write};
88
use std::path::{Path, PathBuf};
99
use std::str::FromStr;
10-
use std::u32;
1110

1211
use quick_xml::{events::Event, Reader};
1312

@@ -330,7 +329,7 @@ impl MavEnum {
330329
value = quote!(#cnt);
331330
} else {
332331
let tmp_value = enum_entry.value.unwrap();
333-
cnt = cnt.max(tmp_value as u32);
332+
cnt = cnt.max(tmp_value);
334333
let tmp = TokenStream::from_str(&tmp_value.to_string()).unwrap();
335334
value = quote!(#tmp);
336335
};
@@ -774,10 +773,11 @@ impl MavField {
774773
}
775774
}
776775

777-
#[derive(Debug, PartialEq, Clone)]
776+
#[derive(Debug, PartialEq, Clone, Default)]
778777
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
779778
pub enum MavType {
780779
UInt8MavlinkVersion,
780+
#[default]
781781
UInt8,
782782
UInt16,
783783
UInt32,
@@ -792,12 +792,6 @@ pub enum MavType {
792792
Array(Box<MavType>, usize),
793793
}
794794

795-
impl Default for MavType {
796-
fn default() -> Self {
797-
Self::UInt8
798-
}
799-
}
800-
801795
impl MavType {
802796
fn parse_type(s: &str) -> Option<Self> {
803797
use self::MavType::*;

mavlink-core/src/connection/direct_serial.rs

+1-1
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ impl<M: Message> MavConnection<M> for SerialConnection {
9191
self.protocol_version = version;
9292
}
9393

94-
fn get_protocol_version(&self) -> MavlinkVersion {
94+
fn protocol_version(&self) -> MavlinkVersion {
9595
self.protocol_version
9696
}
9797
}

mavlink-core/src/connection/file.rs

+1-1
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ impl<M: Message> MavConnection<M> for FileConnection {
5252
self.protocol_version = version;
5353
}
5454

55-
fn get_protocol_version(&self) -> MavlinkVersion {
55+
fn protocol_version(&self) -> MavlinkVersion {
5656
self.protocol_version
5757
}
5858
}

mavlink-core/src/connection/mod.rs

+2-2
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ pub trait MavConnection<M: Message> {
2424
fn send(&self, header: &MavHeader, data: &M) -> Result<usize, crate::error::MessageWriteError>;
2525

2626
fn set_protocol_version(&mut self, version: MavlinkVersion);
27-
fn get_protocol_version(&self) -> MavlinkVersion;
27+
fn protocol_version(&self) -> MavlinkVersion;
2828

2929
/// Write whole frame
3030
fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, crate::error::MessageWriteError> {
@@ -34,7 +34,7 @@ pub trait MavConnection<M: Message> {
3434
/// Read whole frame
3535
fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
3636
let (header, msg) = self.recv()?;
37-
let protocol_version = self.get_protocol_version();
37+
let protocol_version = self.protocol_version();
3838
Ok(MavFrame {
3939
header,
4040
msg,

mavlink-core/src/connection/tcp.rs

+1-1
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@ impl<M: Message> MavConnection<M> for TcpConnection {
108108
self.protocol_version = version;
109109
}
110110

111-
fn get_protocol_version(&self) -> MavlinkVersion {
111+
fn protocol_version(&self) -> MavlinkVersion {
112112
self.protocol_version
113113
}
114114
}

mavlink-core/src/connection/udp.rs

+1-1
Original file line numberDiff line numberDiff line change
@@ -156,7 +156,7 @@ impl<M: Message> MavConnection<M> for UdpConnection {
156156
self.protocol_version = version;
157157
}
158158

159-
fn get_protocol_version(&self) -> MavlinkVersion {
159+
fn protocol_version(&self) -> MavlinkVersion {
160160
self.protocol_version
161161
}
162162
}

mavlink-core/src/lib.rs

+57-80
Original file line numberDiff line numberDiff line change
@@ -221,14 +221,11 @@ impl<M: Message> MavFrame<M> {
221221
MavlinkVersion::V1 => buf.get_u8().into(),
222222
};
223223

224-
match M::parse(version, msg_id, buf.remaining_bytes()) {
225-
Ok(msg) => Ok(Self {
226-
header,
227-
msg,
228-
protocol_version: version,
229-
}),
230-
Err(err) => Err(err),
231-
}
224+
M::parse(version, msg_id, buf.remaining_bytes()).map(|msg| Self {
225+
header,
226+
msg,
227+
protocol_version: version,
228+
})
232229
}
233230

234231
/// Return the frame header
@@ -474,22 +471,18 @@ pub fn read_v1_msg<M: Message, R: Read>(
474471
) -> Result<(MavHeader, M), error::MessageReadError> {
475472
let message = read_v1_raw_message::<M, _>(r)?;
476473

477-
M::parse(
478-
MavlinkVersion::V1,
479-
u32::from(message.message_id()),
480-
message.payload(),
481-
)
482-
.map(|msg| {
483-
(
484-
MavHeader {
485-
sequence: message.sequence(),
486-
system_id: message.system_id(),
487-
component_id: message.component_id(),
488-
},
489-
msg,
490-
)
491-
})
492-
.map_err(|err| err.into())
474+
Ok((
475+
MavHeader {
476+
sequence: message.sequence(),
477+
system_id: message.system_id(),
478+
component_id: message.component_id(),
479+
},
480+
M::parse(
481+
MavlinkVersion::V1,
482+
u32::from(message.message_id()),
483+
message.payload(),
484+
)?,
485+
))
493486
}
494487

495488
/// Async read a MAVLink v1 message from a Read stream.
@@ -502,22 +495,18 @@ pub async fn read_v1_msg_async<M: Message>(
502495
) -> Result<(MavHeader, M), error::MessageReadError> {
503496
let message = read_v1_raw_message_async::<M>(r).await?;
504497

505-
M::parse(
506-
MavlinkVersion::V1,
507-
u32::from(message.message_id()),
508-
message.payload(),
509-
)
510-
.map(|msg| {
511-
(
512-
MavHeader {
513-
sequence: message.sequence(),
514-
system_id: message.system_id(),
515-
component_id: message.component_id(),
516-
},
517-
msg,
518-
)
519-
})
520-
.map_err(|err| err.into())
498+
Ok((
499+
MavHeader {
500+
sequence: message.sequence(),
501+
system_id: message.system_id(),
502+
component_id: message.component_id(),
503+
},
504+
M::parse(
505+
MavlinkVersion::V1,
506+
u32::from(message.message_id()),
507+
message.payload(),
508+
)?,
509+
))
521510
}
522511

523512
const MAVLINK_IFLAG_SIGNED: u8 = 0x01;
@@ -818,18 +807,14 @@ pub fn read_v2_msg<M: Message, R: Read>(
818807
) -> Result<(MavHeader, M), error::MessageReadError> {
819808
let message = read_v2_raw_message::<M, _>(read)?;
820809

821-
M::parse(MavlinkVersion::V2, message.message_id(), message.payload())
822-
.map(|msg| {
823-
(
824-
MavHeader {
825-
sequence: message.sequence(),
826-
system_id: message.system_id(),
827-
component_id: message.component_id(),
828-
},
829-
msg,
830-
)
831-
})
832-
.map_err(|err| err.into())
810+
Ok((
811+
MavHeader {
812+
sequence: message.sequence(),
813+
system_id: message.system_id(),
814+
component_id: message.component_id(),
815+
},
816+
M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
817+
))
833818
}
834819

835820
/// Async read a MAVLink v2 message from a Read stream.
@@ -839,18 +824,14 @@ pub async fn read_v2_msg_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
839824
) -> Result<(MavHeader, M), error::MessageReadError> {
840825
let message = read_v2_raw_message_async::<M, _>(read).await?;
841826

842-
M::parse(MavlinkVersion::V2, message.message_id(), message.payload())
843-
.map(|msg| {
844-
(
845-
MavHeader {
846-
sequence: message.sequence(),
847-
system_id: message.system_id(),
848-
component_id: message.component_id(),
849-
},
850-
msg,
851-
)
852-
})
853-
.map_err(|err| err.into())
827+
Ok((
828+
MavHeader {
829+
sequence: message.sequence(),
830+
system_id: message.system_id(),
831+
component_id: message.component_id(),
832+
},
833+
M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
834+
))
854835
}
855836

856837
/// Async read a MAVLink v2 message from a Read stream.
@@ -863,22 +844,18 @@ pub async fn read_v2_msg_async<M: Message, R: embedded_io_async::Read>(
863844
) -> Result<(MavHeader, M), error::MessageReadError> {
864845
let message = read_v2_raw_message_async::<M>(r).await?;
865846

866-
M::parse(
867-
MavlinkVersion::V2,
868-
u32::from(message.message_id()),
869-
message.payload(),
870-
)
871-
.map(|msg| {
872-
(
873-
MavHeader {
874-
sequence: message.sequence(),
875-
system_id: message.system_id(),
876-
component_id: message.component_id(),
877-
},
878-
msg,
879-
)
880-
})
881-
.map_err(|err| err.into())
847+
Ok((
848+
MavHeader {
849+
sequence: message.sequence(),
850+
system_id: message.system_id(),
851+
component_id: message.component_id(),
852+
},
853+
M::parse(
854+
MavlinkVersion::V2,
855+
u32::from(message.message_id()),
856+
message.payload(),
857+
)?,
858+
))
882859
}
883860

884861
/// Write a message using the given mavlink version

mavlink/examples/embedded-async-read/src/main.rs

+3-6
Original file line numberDiff line numberDiff line change
@@ -82,12 +82,9 @@ pub async fn rx_task(rx: usart::UartRx<'static, Async>) {
8282
.unwrap();
8383
rprintln!("Read raw message: msg_id={}", raw.message_id());
8484

85-
match raw.message_id() {
86-
HEARTBEAT_DATA::ID => {
87-
let heartbeat = HEARTBEAT_DATA::deser(MavlinkVersion::V2, raw.payload()).unwrap();
88-
rprintln!("heartbeat: {:?}", heartbeat);
89-
}
90-
_ => {}
85+
if raw.message_id() == HEARTBEAT_DATA::ID {
86+
let heartbeat = HEARTBEAT_DATA::deser(MavlinkVersion::V2, raw.payload()).unwrap();
87+
rprintln!("heartbeat: {:?}", heartbeat);
9188
}
9289
}
9390
}

0 commit comments

Comments
 (0)