Skip to content

Commit 43a9403

Browse files
Update to latest version of mavlink
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
1 parent 860b0fd commit 43a9403

File tree

4 files changed

+33
-70
lines changed

4 files changed

+33
-70
lines changed

Cargo.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ include_dir = "0.7"
3333
lazy_static = "1.4.0"
3434
log = "0.4"
3535
env_logger = "0.8"
36-
mavlink = { version = "0.10.11", features = [ "ardupilotmega", "emit-extensions"] }
36+
mavlink = { version = "0.16.1", features = [ "ardupilotmega", "emit-extensions"] }
3737
paperclip = { version = "0.8", features = ["actix3", "v3", "paperclip-actix", "swagger-ui"] }
3838
regex = "1"
3939
serde = "1.0.115"

src/endpoints.rs

Lines changed: 3 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -120,19 +120,14 @@ pub async fn helper_mavlink(
120120
let message_name = query.into_inner().name;
121121

122122
let result = match mavlink::ardupilotmega::MavMessage::message_id_from_name(&message_name) {
123-
Ok(id) => mavlink::Message::default_message_from_id(id),
124-
Err(error) => Err(error),
123+
Some(id) => mavlink::ardupilotmega::MavMessage::default_message_from_id(id)
124+
.ok_or("Invalid message name."),
125+
None => Err("Invalid message name."),
125126
};
126127

127128
match result {
128129
Ok(result) => {
129130
let msg = match result {
130-
mavlink::ardupilotmega::MavMessage::common(msg) => {
131-
parse_query(&data::MAVLinkMessage {
132-
header: mavlink::MavHeader::default(),
133-
message: msg,
134-
})
135-
}
136131
msg => parse_query(&data::MAVLinkMessage {
137132
header: mavlink::MavHeader::default(),
138133
message: msg,
@@ -176,27 +171,6 @@ pub async fn mavlink_post(
176171
},
177172
Err(err) => {
178173
debug!("Failed to parse ardupilotmega message: {err:?}");
179-
}
180-
}
181-
182-
match json5::from_str::<data::MAVLinkMessage<mavlink::common::MavMessage>>(&json_string) {
183-
Ok(content) => {
184-
let content_ardupilotmega = mavlink::ardupilotmega::MavMessage::common(content.message);
185-
match data
186-
.lock()
187-
.unwrap()
188-
.send(&content.header, &content_ardupilotmega)
189-
{
190-
Ok(_result) => {
191-
data::update((content.header, content_ardupilotmega));
192-
return HttpResponse::Ok().await;
193-
}
194-
Err(err) => {
195-
return not_found_response(format!("Failed to send message: {err:?}")).await;
196-
}
197-
}
198-
}
199-
Err(err) => {
200174
let error_message =
201175
format!("Failed to parse message, not a valid MAVLinkMessage: {err:?}");
202176
debug!("{error_message}");

src/main.rs

Lines changed: 0 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -70,19 +70,6 @@ fn ws_callback(
7070
data::update((content.header, content.message));
7171
}
7272

73-
format!("{result:?}")
74-
} else if let Ok(content @ MAVLinkMessage::<mavlink::common::MavMessage> { .. }) =
75-
serde_json::from_str(value)
76-
{
77-
let content_ardupilotmega = mavlink::ardupilotmega::MavMessage::common(content.message);
78-
let result = inner_vehicle
79-
.lock()
80-
.unwrap()
81-
.send(&content.header, &content_ardupilotmega);
82-
if result.is_ok() {
83-
data::update((content.header, content_ardupilotmega));
84-
}
85-
8673
format!("{result:?}")
8774
} else {
8875
String::from("Could not convert input message.")

src/mavlink_vehicle.rs

Lines changed: 29 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,10 @@ impl<M: mavlink::Message> MAVLinkVehicle<M> {
1818
// Convert from mavlink error to io error
1919
match result {
2020
Err(mavlink::error::MessageWriteError::Io(error)) => Err(error),
21+
Err(mavlink::error::MessageWriteError::MAVLink2Only) => Err(std::io::Error::new(
22+
std::io::ErrorKind::Other,
23+
"MAVLink2Only",
24+
)),
2125
Ok(something) => Ok(something),
2226
}
2327
}
@@ -33,7 +37,7 @@ pub struct MAVLinkVehicleHandle<M: mavlink::Message> {
3337
pub thread_rx_channel: std::sync::mpsc::Receiver<(mavlink::MavHeader, M)>,
3438
}
3539

36-
impl<M: mavlink::Message> MAVLinkVehicle<M> {
40+
impl<M: mavlink::Message + Send + Sync> MAVLinkVehicle<M> {
3741
fn new(
3842
mavlink_connection_string: &str,
3943
version: mavlink::MavlinkVersion,
@@ -55,20 +59,23 @@ impl<M: mavlink::Message> MAVLinkVehicle<M> {
5559
}
5660
}
5761

58-
impl<
59-
M: 'static + mavlink::Message + std::fmt::Debug + From<mavlink::common::MavMessage> + Send,
60-
> MAVLinkVehicleHandle<M>
61-
{
62+
impl MAVLinkVehicleHandle<mavlink::ardupilotmega::MavMessage> {
6263
pub fn new(
6364
connection_string: &str,
6465
version: mavlink::MavlinkVersion,
6566
system_id: u8,
6667
component_id: u8,
6768
send_initial_heartbeats: bool,
6869
) -> Self {
69-
let mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<M>>> = Arc::new(Mutex::new(
70-
MAVLinkVehicle::<M>::new(connection_string, version, system_id, component_id),
71-
));
70+
let mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<mavlink::ardupilotmega::MavMessage>>> =
71+
Arc::new(Mutex::new(MAVLinkVehicle::<
72+
mavlink::ardupilotmega::MavMessage,
73+
>::new(
74+
connection_string,
75+
version,
76+
system_id,
77+
component_id,
78+
)));
7279

7380
// PX4 requires a initial heartbeat to be sent to wake up the connection, otherwise it will
7481
// not send any messages
@@ -88,7 +95,8 @@ impl<
8895
let heartbeat_mavlink_vehicle = mavlink_vehicle.clone();
8996
let receive_message_mavlink_vehicle = mavlink_vehicle.clone();
9097

91-
let (tx_channel, rx_channel) = mpsc::channel::<(mavlink::MavHeader, M)>();
98+
let (tx_channel, rx_channel) =
99+
mpsc::channel::<(mavlink::MavHeader, mavlink::ardupilotmega::MavMessage)>();
92100

93101
Self {
94102
mavlink_vehicle,
@@ -101,11 +109,9 @@ impl<
101109
}
102110
}
103111

104-
fn receive_message_loop<
105-
M: mavlink::Message + std::fmt::Debug + From<mavlink::common::MavMessage>,
106-
>(
107-
mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<M>>>,
108-
channel: std::sync::mpsc::Sender<(mavlink::MavHeader, M)>,
112+
fn receive_message_loop(
113+
mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<mavlink::ardupilotmega::MavMessage>>>,
114+
channel: std::sync::mpsc::Sender<(mavlink::MavHeader, mavlink::ardupilotmega::MavMessage)>,
109115
) {
110116
let mavlink_vehicle = mavlink_vehicle.as_ref().lock().unwrap();
111117

@@ -132,34 +138,30 @@ fn receive_message_loop<
132138
}
133139
}
134140

135-
fn send_heartbeat<M: mavlink::Message + From<mavlink::common::MavMessage>>(
136-
mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<M>>>,
137-
) {
141+
fn send_heartbeat(mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<mavlink::ardupilotmega::MavMessage>>>) {
138142
let mavlink_vehicle = mavlink_vehicle.as_ref().lock().unwrap();
139143
let vehicle = mavlink_vehicle.vehicle.clone();
140144
let mut header = mavlink_vehicle.header.lock().unwrap();
141-
if let Err(error) = vehicle.as_ref().send(&header, &heartbeat_message().into()) {
145+
if let Err(error) = vehicle.as_ref().send(&header, &heartbeat_message()) {
142146
error!("Failed to send heartbeat: {:?}", error);
143147
}
144148
header.sequence = header.sequence.wrapping_add(1);
145149
}
146150

147-
fn heartbeat_loop<M: mavlink::Message + From<mavlink::common::MavMessage>>(
148-
mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<M>>>,
149-
) {
151+
fn heartbeat_loop(mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<mavlink::ardupilotmega::MavMessage>>>) {
150152
loop {
151153
std::thread::sleep(std::time::Duration::from_secs(1));
152154
send_heartbeat(mavlink_vehicle.clone());
153155
}
154156
}
155157

156-
pub fn heartbeat_message() -> mavlink::common::MavMessage {
157-
mavlink::common::MavMessage::HEARTBEAT(mavlink::common::HEARTBEAT_DATA {
158+
pub fn heartbeat_message() -> mavlink::ardupilotmega::MavMessage {
159+
mavlink::ardupilotmega::MavMessage::HEARTBEAT(mavlink::ardupilotmega::HEARTBEAT_DATA {
158160
custom_mode: 0,
159-
mavtype: mavlink::common::MavType::MAV_TYPE_ONBOARD_CONTROLLER,
160-
autopilot: mavlink::common::MavAutopilot::MAV_AUTOPILOT_INVALID,
161-
base_mode: mavlink::common::MavModeFlag::default(),
162-
system_status: mavlink::common::MavState::MAV_STATE_STANDBY,
161+
mavtype: mavlink::ardupilotmega::MavType::MAV_TYPE_ONBOARD_CONTROLLER,
162+
autopilot: mavlink::ardupilotmega::MavAutopilot::MAV_AUTOPILOT_INVALID,
163+
base_mode: mavlink::ardupilotmega::MavModeFlag::default(),
164+
system_status: mavlink::ardupilotmega::MavState::MAV_STATE_STANDBY,
163165
mavlink_version: 0x3,
164166
})
165167
}

0 commit comments

Comments
 (0)