From a3eb3600d001d7dfba8bd70a321d137949ba5d5d Mon Sep 17 00:00:00 2001 From: Tim Ryan <tim@3drobotics.com> Date: Tue, 15 Mar 2016 02:51:10 -0700 Subject: [PATCH] Fixes race conditions. --- Cargo.toml | 2 +- README.md | 2 +- src/bin/mavlink-dump.rs | 18 ++++++++++-------- src/connection.rs | 12 ++++-------- 4 files changed, 16 insertions(+), 18 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index 8270118..ebe04c5 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,6 +1,6 @@ [package] name = "mavlink" -version = "0.2.0" +version = "0.3.1" authors = ["Tim Ryan <tim@3dr.com>"] build = "build/main.rs" description = "Parses the MAVLink data interchange format for UAVs." diff --git a/README.md b/README.md index 5804f6a..5ae8fac 100644 --- a/README.md +++ b/README.md @@ -3,7 +3,7 @@ Add to your Cargo.toml: ``` -mavlink = "0.1.0" +mavlink = "0.3" ``` ## License diff --git a/src/bin/mavlink-dump.rs b/src/bin/mavlink-dump.rs index a71963f..20aba2a 100644 --- a/src/bin/mavlink-dump.rs +++ b/src/bin/mavlink-dump.rs @@ -14,13 +14,7 @@ fn main() { } let vlock = Arc::new(RwLock::new(mavlink::connect(&args[1]).unwrap())); - - { - let mut vehicle = vlock.write().unwrap(); - vehicle.send(mavlink::heartbeat_message()); - vehicle.send(mavlink::request_parameters()); - vehicle.send(mavlink::request_stream()); - } + let vehicle_recv = vlock.read().unwrap().wait_recv(); thread::spawn({ let vlock = vlock.clone(); @@ -35,8 +29,16 @@ fn main() { } }); + let mut first = true; loop { - vlock.read().unwrap().wait_recv().sleep(); + vehicle_recv.sleep(); + + if first { + let mut vehicle = vlock.write().unwrap(); + vehicle.send(mavlink::request_parameters()); + vehicle.send(mavlink::request_stream()); + first = false; + } if let Ok(msg) = vlock.write().unwrap().recv() { println!("{:?}", msg); diff --git a/src/connection.rs b/src/connection.rs index f041110..6c4b2bc 100644 --- a/src/connection.rs +++ b/src/connection.rs @@ -347,15 +347,16 @@ pub struct VehicleConnection { } pub struct VehicleAwait { - value: u64, pair: Arc<(Mutex<u64>, Condvar)>, } impl VehicleAwait { - pub fn sleep(self) { + pub fn sleep(&self) { + // TODO vehilce buffer? let &(ref lock, ref cvar) = &*self.pair; let mut started = lock.lock().unwrap(); - while *started == self.value { + let original = *started; + while *started == original { started = cvar.wait(started).unwrap(); } } @@ -389,12 +390,7 @@ impl VehicleConnection { } pub fn wait_recv(&self) -> VehicleAwait { - let count = { - let &(ref lock, _) = &*self.pair; - *lock.lock().unwrap() - }; VehicleAwait { - value: count, pair: self.pair.clone() } } -- GitLab