Skip to content
Closed
Show file tree
Hide file tree
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
2 changes: 1 addition & 1 deletion Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ include_dir = "0.7"
lazy_static = "1.4.0"
log = "0.4"
env_logger = "0.8"
mavlink = { git = "https://github.com/mavlink/rust-mavlink", rev = "0.10.2", features = [ "ardupilotmega", "emit-extensions"] }
mavlink = { version = "0.11.2", features = [ "ardupilotmega", "emit-extensions"] }
paperclip = { git = "https://github.com/patrickelectric/paperclip", branch = "patrick-swagger", features = ["actix", "swagger-ui"] }
regex = "1"
serde = "1.0.115"
Expand Down
50 changes: 12 additions & 38 deletions src/endpoints.rs
Original file line number Diff line number Diff line change
Expand Up @@ -119,27 +119,20 @@ pub async fn helper_mavlink(
) -> actix_web::Result<HttpResponse> {
let message_name = query.into_inner().name;

let result = match mavlink::ardupilotmega::MavMessage::message_id_from_name(&message_name) {
Ok(id) => mavlink::Message::default_message_from_id(id),
Err(error) => Err(error),
};
let result: Result<mavlink::ardupilotmega::MavMessage, &str> =
match mavlink::ardupilotmega::MavMessage::message_id_from_name(&message_name) {
Ok(id) => mavlink::Message::default_message_from_id(id),
Err(error) => Err(error),
};

match result {
Ok(result) => {
let msg = match result {
mavlink::ardupilotmega::MavMessage::common(msg) => {
parse_query(&data::MAVLinkMessage {
header: mavlink::MavHeader::default(),
message: msg,
})
}
msg => parse_query(&data::MAVLinkMessage {
header: mavlink::MavHeader::default(),
message: msg,
}),
};

ok_response(msg).await
Ok(msg) => {
let result = parse_query(&data::MAVLinkMessage {
header: mavlink::MavHeader::default(),
message: msg,
});

ok_response(result).await
}
Err(content) => not_found_response(parse_query(&content)).await,
}
Expand Down Expand Up @@ -177,25 +170,6 @@ pub async fn mavlink_post(
}
}

if let Ok(content) =
json5::from_str::<data::MAVLinkMessage<mavlink::common::MavMessage>>(&json_string)
{
let content_ardupilotmega = mavlink::ardupilotmega::MavMessage::common(content.message);
match data
.lock()
.unwrap()
.send(&content.header, &content_ardupilotmega)
{
Ok(_result) => {
data::update((content.header, content_ardupilotmega));
return HttpResponse::Ok().await;
}
Err(err) => {
return not_found_response(format!("Failed to send message: {err:?}")).await;
}
}
}

not_found_response(String::from(
"Failed to parse message, not a valid MAVLinkMessage.",
))
Expand Down
26 changes: 5 additions & 21 deletions src/main.rs
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ fn main() -> std::io::Result<()> {
};

let (system_id, component_id) = cli::mavlink_system_and_component_id();
let vehicle = mavlink_vehicle::MAVLinkVehicleHandle::<mavlink::ardupilotmega::MavMessage>::new(
let vehicle = mavlink_vehicle::MAVLinkVehicleHandle::new(
cli::mavlink_connection_string(),
mavlink_version,
system_id,
Expand Down Expand Up @@ -54,10 +54,7 @@ fn main() -> std::io::Result<()> {
}
}

fn ws_callback(
inner_vehicle: Arc<Mutex<mavlink_vehicle::MAVLinkVehicle<mavlink::ardupilotmega::MavMessage>>>,
value: &str,
) -> String {
fn ws_callback(inner_vehicle: Arc<Mutex<mavlink_vehicle::MAVLinkVehicle>>, value: &str) -> String {
if let Ok(content @ MAVLinkMessage::<mavlink::ardupilotmega::MavMessage> { .. }) =
serde_json::from_str(value)
{
Expand All @@ -69,21 +66,8 @@ fn ws_callback(
data::update((content.header, content.message));
}

format!("{result:?}")
} else if let Ok(content @ MAVLinkMessage::<mavlink::common::MavMessage> { .. }) =
serde_json::from_str(value)
{
let content_ardupilotmega = mavlink::ardupilotmega::MavMessage::common(content.message);
let result = inner_vehicle
.lock()
.unwrap()
.send(&content.header, &content_ardupilotmega);
if result.is_ok() {
data::update((content.header, content_ardupilotmega));
}

format!("{result:?}")
} else {
String::from("Could not convert input message.")
return format!("{:?}", result);
}

return "Could not convert input message.".into();
}
64 changes: 31 additions & 33 deletions src/mavlink_vehicle.rs
Original file line number Diff line number Diff line change
Expand Up @@ -2,18 +2,22 @@ use std::sync::{mpsc, Arc, Mutex};

use log::*;

pub type MAVLinkVehicleArcMutex = Arc<Mutex<MAVLinkVehicle<mavlink::ardupilotmega::MavMessage>>>;
pub type MAVLinkVehicleArcMutex = Arc<Mutex<MAVLinkVehicle>>;

#[derive(Clone)]
pub struct MAVLinkVehicle<M: mavlink::Message> {
pub struct MAVLinkVehicle {
//TODO: Check if Arc<Box can be only Arc or Box
vehicle: Arc<Box<dyn mavlink::MavConnection<M> + Sync + Send>>,
vehicle: Arc<Box<dyn mavlink::MavConnection<mavlink::ardupilotmega::MavMessage> + Sync + Send>>,
header: Arc<Mutex<mavlink::MavHeader>>,
}

impl<M: mavlink::Message> MAVLinkVehicle<M> {
pub fn send(&self, header: &mavlink::MavHeader, message: &M) -> std::io::Result<usize> {
let result = self.vehicle.send(header, message);
impl MAVLinkVehicle {
pub fn send(
&self,
header: &mavlink::MavHeader,
message: &mavlink::ardupilotmega::MavMessage,
) -> std::io::Result<usize> {
let result = self.vehicle.send(&header, &message);

// Convert from mavlink error to io error
match result {
Expand All @@ -23,17 +27,17 @@ impl<M: mavlink::Message> MAVLinkVehicle<M> {
}
}

#[allow(dead_code)]
pub struct MAVLinkVehicleHandle<M: mavlink::Message> {
pub struct MAVLinkVehicleHandle {
//TODO: Check if we can use vehicle here directly
pub mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<M>>>,
pub mavlink_vehicle: Arc<Mutex<MAVLinkVehicle>>,
heartbeat_thread: std::thread::JoinHandle<()>,
receive_message_thread: std::thread::JoinHandle<()>,
//TODO: Add a channel for errors
pub thread_rx_channel: std::sync::mpsc::Receiver<(mavlink::MavHeader, M)>,
pub thread_rx_channel:
std::sync::mpsc::Receiver<(mavlink::MavHeader, mavlink::ardupilotmega::MavMessage)>,
}

impl<M: mavlink::Message> MAVLinkVehicle<M> {
impl MAVLinkVehicle {
fn new(
mavlink_connection_string: &str,
version: mavlink::MavlinkVersion,
Expand All @@ -55,24 +59,22 @@ impl<M: mavlink::Message> MAVLinkVehicle<M> {
}
}

impl<
M: 'static + mavlink::Message + std::fmt::Debug + From<mavlink::common::MavMessage> + Send,
> MAVLinkVehicleHandle<M>
{
impl MAVLinkVehicleHandle {
pub fn new(
connection_string: &str,
version: mavlink::MavlinkVersion,
system_id: u8,
component_id: u8,
) -> Self {
let mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<M>>> = Arc::new(Mutex::new(
MAVLinkVehicle::<M>::new(connection_string, version, system_id, component_id),
let mavlink_vehicle: Arc<Mutex<MAVLinkVehicle>> = Arc::new(Mutex::new(
MAVLinkVehicle::new(connection_string.clone(), version, system_id, component_id),
));

let heartbeat_mavlink_vehicle = mavlink_vehicle.clone();
let receive_message_mavlink_vehicle = mavlink_vehicle.clone();

let (tx_channel, rx_channel) = mpsc::channel::<(mavlink::MavHeader, M)>();
let (tx_channel, rx_channel) =
mpsc::channel::<(mavlink::MavHeader, mavlink::ardupilotmega::MavMessage)>();

Self {
mavlink_vehicle,
Expand All @@ -85,11 +87,9 @@ impl<
}
}

fn receive_message_loop<
M: mavlink::Message + std::fmt::Debug + From<mavlink::common::MavMessage>,
>(
mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<M>>>,
channel: std::sync::mpsc::Sender<(mavlink::MavHeader, M)>,
fn receive_message_loop(
mavlink_vehicle: Arc<Mutex<MAVLinkVehicle>>,
channel: std::sync::mpsc::Sender<(mavlink::MavHeader, mavlink::ardupilotmega::MavMessage)>,
) {
let mavlink_vehicle = mavlink_vehicle.as_ref().lock().unwrap();

Expand All @@ -116,28 +116,26 @@ fn receive_message_loop<
}
}

fn heartbeat_loop<M: mavlink::Message + From<mavlink::common::MavMessage>>(
mavlink_vehicle: Arc<Mutex<MAVLinkVehicle<M>>>,
) {
fn heartbeat_loop(mavlink_vehicle: Arc<Mutex<MAVLinkVehicle>>) {
loop {
std::thread::sleep(std::time::Duration::from_secs(1));
let mavlink_vehicle = mavlink_vehicle.as_ref().lock().unwrap();
let vehicle = mavlink_vehicle.vehicle.clone();
let mut header = mavlink_vehicle.header.lock().unwrap();
if let Err(error) = vehicle.as_ref().send(&header, &heartbeat_message().into()) {
if let Err(error) = vehicle.as_ref().send(&header, &heartbeat_message()) {
error!("Failed to send heartbeat: {:?}", error);
}
header.sequence = header.sequence.wrapping_add(1);
}
}

pub fn heartbeat_message() -> mavlink::common::MavMessage {
mavlink::common::MavMessage::HEARTBEAT(mavlink::common::HEARTBEAT_DATA {
pub fn heartbeat_message() -> mavlink::ardupilotmega::MavMessage {
mavlink::ardupilotmega::MavMessage::HEARTBEAT(mavlink::ardupilotmega::HEARTBEAT_DATA {
custom_mode: 0,
mavtype: mavlink::common::MavType::MAV_TYPE_ONBOARD_CONTROLLER,
autopilot: mavlink::common::MavAutopilot::MAV_AUTOPILOT_INVALID,
base_mode: mavlink::common::MavModeFlag::default(),
system_status: mavlink::common::MavState::MAV_STATE_STANDBY,
mavtype: mavlink::ardupilotmega::MavType::MAV_TYPE_ONBOARD_CONTROLLER,
autopilot: mavlink::ardupilotmega::MavAutopilot::MAV_AUTOPILOT_INVALID,
base_mode: mavlink::ardupilotmega::MavModeFlag::default(),
system_status: mavlink::ardupilotmega::MavState::MAV_STATE_STANDBY,
mavlink_version: 0x3,
})
}
18 changes: 9 additions & 9 deletions src/vehicle_handler.rs
Original file line number Diff line number Diff line change
Expand Up @@ -119,22 +119,22 @@ impl InnerVehicle {
}

pub fn heartbeat_message() -> mavlink::ardupilotmega::MavMessage {
mavlink::ardupilotmega::MavMessage::common({
mavlink::common::MavMessage::HEARTBEAT(mavlink::common::HEARTBEAT_DATA {
mavlink::ardupilotmega::MavMessage::ardupilotmega({
mavlink::ardupilotmega::MavMessage::HEARTBEAT(mavlink::ardupilotmega::HEARTBEAT_DATA {
custom_mode: 0,
mavtype: mavlink::common::MavType::MAV_TYPE_QUADROTOR, // TODO: Move this to something else
autopilot: mavlink::common::MavAutopilot::MAV_AUTOPILOT_ARDUPILOTMEGA,
base_mode: mavlink::common::MavModeFlag::empty(),
system_status: mavlink::common::MavState::MAV_STATE_STANDBY,
mavtype: mavlink::ardupilotmega::MavType::MAV_TYPE_QUADROTOR, // TODO: Move this to something else
autopilot: mavlink::ardupilotmega::MavAutopilot::MAV_AUTOPILOT_ARDUPILOTMEGA,
base_mode: mavlink::ardupilotmega::MavModeFlag::empty(),
system_status: mavlink::ardupilotmega::MavState::MAV_STATE_STANDBY,
mavlink_version: 0x3,
})
})
}

pub fn request_stream() -> mavlink::ardupilotmega::MavMessage {
mavlink::ardupilotmega::MavMessage::common({
mavlink::common::MavMessage::REQUEST_DATA_STREAM(
mavlink::common::REQUEST_DATA_STREAM_DATA {
mavlink::ardupilotmega::MavMessage::ardupilotmega({
mavlink::ardupilotmega::MavMessage::REQUEST_DATA_STREAM(
mavlink::ardupilotmega::REQUEST_DATA_STREAM_DATA {
target_system: 0,
target_component: 0,
req_stream_id: 0,
Expand Down