Skip to content

Commit

Permalink
src: mavlink: Remove sleeps from mavlink recv and send loops
Browse files Browse the repository at this point in the history
These sleeps on the mavlink-related part are _not_ needed, and they only clog
the messages, making MCM lose messages, or snowball into an overloaded state.
  • Loading branch information
joaoantoniocardoso committed Mar 13, 2024
1 parent b547dda commit ee56ae7
Showing 1 changed file with 7 additions and 9 deletions.
16 changes: 7 additions & 9 deletions src/mavlink/manager.rs
Expand Up @@ -74,8 +74,6 @@ impl Manager {
fn receiver_loop(inner: Arc<RwLock<Connection>>) {
loop {
loop {
std::thread::sleep(std::time::Duration::from_millis(10));

let Ok(inner_guard) = inner.read() else {
break; // Break to trigger reconnection
};
Expand Down Expand Up @@ -133,19 +131,19 @@ impl Manager {

loop {
loop {
std::thread::sleep(std::time::Duration::from_millis(10));

// Receive answer from the cameras
let (header, message) = match receiver.try_recv() {
let (header, message) = match receiver.blocking_recv() {
Ok(Message::ToBeSent(message)) => message,
Err(broadcast::error::TryRecvError::Closed) => {
Ok(Message::Received(_)) => continue,
Err(broadcast::error::RecvError::Closed) => {
unreachable!(
"Closed channel: This should never happen, this channel is static!"
);
}
// Since we are sharing a singel channel to both send and receive, and we don't care
// when the channel is empty or lagged, we can safely ignore anything else here.
_ => continue,
Err(broadcast::error::RecvError::Lagged(samples)) => {
warn!("Channel is lagged behind by {samples} messages. Expect degraded performance on the mavlink responsiviness.");
continue;
}
};

let Ok(inner_guard) = inner.read() else {
Expand Down

0 comments on commit ee56ae7

Please sign in to comment.