Skip to content

Commit

Permalink
test: Split integration tests into method and variables
Browse files Browse the repository at this point in the history
  • Loading branch information
philipp-caspers committed Dec 16, 2024
1 parent 3ca59f9 commit 36ded93
Show file tree
Hide file tree
Showing 3 changed files with 111 additions and 96 deletions.
97 changes: 1 addition & 96 deletions tests/test_bridge.rs
Original file line number Diff line number Diff line change
@@ -1,110 +1,15 @@
use std::{
env,
ffi::OsString,
iter::zip,
sync::{atomic::Ordering, mpsc, Arc},
time::Duration,
};

use common::{wait_for_function_to_pass, ManagedRosBridge};
use common::ManagedRosBridge;

pub mod common;
pub mod helpers;

#[test]
fn test_joint_states() {
let (assertion_tx, _assertion_rx) = mpsc::channel();
let (stop_opc_ua_server_tx, stop_opc_ua_server_rx) = mpsc::channel();
helpers::opc_ua_test_server::run_opc_ua_test_server(assertion_tx, stop_opc_ua_server_rx);

let mut _bridge_process = ManagedRosBridge::new(None).expect("Failed to start subprocess");

let subscription = Arc::new(
helpers::ros_subscriber::Subscriber::new(
"joint_states_subscriber",
"/voraus_bridge_node/joint_states",
)
.unwrap(),
);
let clone = Arc::clone(&subscription.node);
// TODO: Figure out why this takes almost 10 s [RR-836]
rclrs::spin_once(clone, Some(Duration::from_secs(25))).expect("Could not spin");

wait_for_function_to_pass(
|| {
rclrs::spin_once(subscription.node.clone(), Some(Duration::new(5, 0)))
.expect("Could not spin");
let joint_state = subscription.data.lock().unwrap().clone().unwrap();
let mut joint_state_flat = joint_state
.position
.into_iter()
.chain(joint_state.velocity.into_iter().chain(joint_state.effort));
joint_state_flat.all(|x| x != 0.0)
},
5000,
)
.unwrap();

let number_of_messages_received = subscription.num_messages.load(Ordering::SeqCst);
let first_value = subscription.data.lock().unwrap().clone().unwrap();
assert!(number_of_messages_received >= 2);
let joint_state_first_value_flat = first_value
.position
.into_iter()
.chain(first_value.velocity.into_iter().chain(first_value.effort));

wait_for_function_to_pass(
|| {
rclrs::spin_once(subscription.node.clone(), Some(Duration::new(5, 0)))
.expect("Could not spin");
let joint_state = subscription.data.lock().unwrap().clone().unwrap();
let joint_state_flat = joint_state
.position
.into_iter()
.chain(joint_state.velocity.into_iter().chain(joint_state.effort));
zip(joint_state_flat, joint_state_first_value_flat.clone())
.all(|(current, first)| current > first)
},
5000,
)
.unwrap();

stop_opc_ua_server_tx.send(()).unwrap();
}

#[test]
fn e2e_ros_service_to_opc_ua_call() {
let (assertion_tx, _assertion_rx) = mpsc::channel();
let (stop_opc_ua_server_tx, stop_opc_ua_server_rx) = mpsc::channel();
helpers::opc_ua_test_server::run_opc_ua_test_server(assertion_tx, stop_opc_ua_server_rx);

let mut bridge_process = ManagedRosBridge::new(None).expect("Failed to start subprocess");

let service_caller = Arc::new(
helpers::ros_service_caller::ServiceCaller::new(
"/voraus_bridge_node/impedance_control/enable",
)
.unwrap(),
);

// TODO: Figure out why this takes almost 10 s [RR-836]
service_caller.start();
assert!(*service_caller.number_of_calls.lock().unwrap() == 0);
service_caller.call();

wait_for_function_to_pass(
|| *service_caller.number_of_calls.lock().unwrap() == 1,
5000,
)
.unwrap();
bridge_process.terminate();
assert!(bridge_process
.get_std_err()
.unwrap()
.contains("ROS service called"));
stop_opc_ua_server_tx.send(()).unwrap();
}

#[test]
fn e2e_frame_id_prefix() {
let (assertion_tx, _assertion_rx) = mpsc::channel();
Expand Down
39 changes: 39 additions & 0 deletions tests/test_bridge_methods.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
use std::sync::{mpsc, Arc};

use common::{wait_for_function_to_pass, ManagedRosBridge};

pub mod common;
pub mod helpers;

#[test]
fn e2e_ros_service_to_opc_ua_call() {
let (assertion_tx, _assertion_rx) = mpsc::channel();
let (stop_opc_ua_server_tx, stop_opc_ua_server_rx) = mpsc::channel();
helpers::opc_ua_test_server::run_opc_ua_test_server(assertion_tx, stop_opc_ua_server_rx);

let mut bridge_process = ManagedRosBridge::new(None).expect("Failed to start subprocess");

let service_caller = Arc::new(
helpers::ros_service_caller::ServiceCaller::new(
"/voraus_bridge_node/impedance_control/enable",
)
.unwrap(),
);

// TODO: Figure out why this takes almost 10 s [RR-836]
service_caller.start();
assert!(*service_caller.number_of_calls.lock().unwrap() == 0);
service_caller.call();

wait_for_function_to_pass(
|| *service_caller.number_of_calls.lock().unwrap() == 1,
5000,
)
.unwrap();
bridge_process.terminate();
assert!(bridge_process
.get_std_err()
.unwrap()
.contains("ROS service called"));
stop_opc_ua_server_tx.send(()).unwrap();
}
71 changes: 71 additions & 0 deletions tests/test_bridge_variables.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
use std::{
iter::zip,
sync::{atomic::Ordering, mpsc, Arc},
time::Duration,
};

use common::{wait_for_function_to_pass, ManagedRosBridge};

pub mod common;
pub mod helpers;

#[test]
fn test_joint_states() {
let (assertion_tx, _assertion_rx) = mpsc::channel();
let (stop_opc_ua_server_tx, stop_opc_ua_server_rx) = mpsc::channel();
helpers::opc_ua_test_server::run_opc_ua_test_server(assertion_tx, stop_opc_ua_server_rx);

let mut _bridge_process = ManagedRosBridge::new(None).expect("Failed to start subprocess");

let subscription = Arc::new(
helpers::ros_subscriber::Subscriber::new(
"joint_states_subscriber",
"/voraus_bridge_node/joint_states",
)
.unwrap(),
);
let clone = Arc::clone(&subscription.node);
// TODO: Figure out why this takes almost 10 s [RR-836]
rclrs::spin_once(clone, Some(Duration::from_secs(25))).expect("Could not spin");

wait_for_function_to_pass(
|| {
rclrs::spin_once(subscription.node.clone(), Some(Duration::new(5, 0)))
.expect("Could not spin");
let joint_state = subscription.data.lock().unwrap().clone().unwrap();
let mut joint_state_flat = joint_state
.position
.into_iter()
.chain(joint_state.velocity.into_iter().chain(joint_state.effort));
joint_state_flat.all(|x| x != 0.0)
},
5000,
)
.unwrap();

let number_of_messages_received = subscription.num_messages.load(Ordering::SeqCst);
let first_value = subscription.data.lock().unwrap().clone().unwrap();
assert!(number_of_messages_received >= 2);
let joint_state_first_value_flat = first_value
.position
.into_iter()
.chain(first_value.velocity.into_iter().chain(first_value.effort));

wait_for_function_to_pass(
|| {
rclrs::spin_once(subscription.node.clone(), Some(Duration::new(5, 0)))
.expect("Could not spin");
let joint_state = subscription.data.lock().unwrap().clone().unwrap();
let joint_state_flat = joint_state
.position
.into_iter()
.chain(joint_state.velocity.into_iter().chain(joint_state.effort));
zip(joint_state_flat, joint_state_first_value_flat.clone())
.all(|(current, first)| current > first)
},
5000,
)
.unwrap();

stop_opc_ua_server_tx.send(()).unwrap();
}

0 comments on commit 36ded93

Please sign in to comment.