Skip to content

Commit

Permalink
wip
Browse files Browse the repository at this point in the history
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
  • Loading branch information
patrickelectric committed Feb 23, 2025
1 parent b816a88 commit 7a715e2
Show file tree
Hide file tree
Showing 3 changed files with 92 additions and 4 deletions.
44 changes: 40 additions & 4 deletions src/lib/drivers/rest/control.rs
Original file line number Diff line number Diff line change
@@ -1,17 +1,34 @@
use anyhow::Result;
use lazy_static::lazy_static;
use mavlink;
use serde::Serialize;

use std::collections::HashMap;
use std::sync::{Arc, Mutex};

#[derive(Debug)]
#[derive(Clone, Debug, Default, Serialize)]
pub struct Attitude {
pub roll: f32,
pub pitch: f32,
pub yaw: f32,
}

#[derive(Clone, Debug, Default, Serialize)]
pub struct Position {
pub latitude: f64,
pub longitude: f64,
pub altitude: f32,
}

#[derive(Clone, Debug, Default, Serialize)]
pub struct Vehicle {
vehicle_id: u8,
armed: bool,
attitude: Attitude,
position: Position,
}

#[derive(Debug, Default)]
#[derive(Clone, Debug, Default, Serialize)]
pub struct Vehicles {
vehicles: HashMap<u8, Vehicle>,
}
Expand All @@ -38,7 +55,7 @@ impl Vehicle {
}

// Let's only take care of the vehicle and not the components
if header.component_id != 1 {
if header.component_id != mavlink::ardupilotmega::MavComponent::MAV_COMP_ID_AUTOPILOT1 as u8 {
return;
}

Expand All @@ -50,6 +67,20 @@ impl Vehicle {

println!("Vehicle {self:#?}");
}
mavlink::ardupilotmega::MavMessage::ATTITUDE(attitude) => {
self.attitude = Attitude {
roll: attitude.roll,
pitch: attitude.pitch,
yaw: attitude.yaw,
};
}
mavlink::ardupilotmega::MavMessage::GLOBAL_POSITION_INT(global_position) => {
self.position = Position {
latitude: global_position.lat as f64 / 1e7, //degE7
longitude: global_position.lon as f64 / 1e7, //degE7
altitude: global_position.alt as f32 / 1e3, //mm
};
}
_ => {}
}
}
Expand Down Expand Up @@ -100,7 +131,12 @@ pub fn update((header, message): (mavlink::MavHeader, mavlink::ardupilotmega::Ma
.entry(header.system_id)
.or_insert(Vehicle {
vehicle_id: header.system_id,
armed: false,
..Default::default()
});
vehicle.update(header, message);
}

pub fn vehicles() -> Vec<Vehicle> {
let mut vehicles = DATA.vehicles.lock().unwrap();
vehicles.vehicles.values().cloned().collect()
}
50 changes: 50 additions & 0 deletions src/lib/drivers/rest/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,49 @@ impl Rest {
Ok(())
}

#[instrument(level = "debug", skip_all)]
async fn controller_receive_task(
context: &SendReceiveContext,
ws_receiver: &mut broadcast::Receiver<String>,
) -> Result<()> {
while let Ok(message) = ws_receiver.recv().await {
let Ok(content) =
json5::from_str::<MAVLinkJSON<mavlink::ardupilotmega::MavMessage>>(&message)
else {
warn!("Failed to parse message, not a valid MAVLinkMessage: {message:?}");
continue;
};

let bus_message = Arc::new(Protocol::from_mavlink_raw(
content.header.inner,
&content.message,
"Ws",
));

trace!("Received message: {bus_message:?}");

context.stats.write().await.stats.update_input(&bus_message);

for future in context.on_message_input.call_all(bus_message.clone()) {
if let Err(error) = future.await {
debug!("Dropping message: on_message_input callback returned error: {error:?}");
continue;
}
}

if let Err(error) = context.hub_sender.send(bus_message) {
error!("Failed to send message to hub: {error:?}");
continue;
}

trace!("Message sent to hub");
}

debug!("Driver receiver task stopped!");

Ok(())
}

#[instrument(level = "debug", skip_all)]
async fn send_task(context: &SendReceiveContext) -> Result<()> {
let mut hub_receiver = context.hub_sender.subscribe();
Expand Down Expand Up @@ -201,6 +244,13 @@ impl Driver for Rest {
error!("Error in rest receive task: {e:?}");
}
}
/*
result = Rest::controller_receive_task(&context) => {
if let Err(e) = result {
error!("Error in controller receive task: {e:?}");
}
}
*/
}
}
}
Expand Down
2 changes: 2 additions & 0 deletions src/lib/web/routes/v1/rest/mod.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
pub mod mavlink;
pub mod vehicles;
pub mod websocket;

use axum::{routing::get, Router};
Expand All @@ -18,4 +19,5 @@ pub fn router() -> Router {
"/mavlink/message_id_from_name/{*name}",
get(mavlink::message_id_from_name),
)
.route("/vehicles", get(vehicles::vehicles))
}

0 comments on commit 7a715e2

Please sign in to comment.