diff --git a/src/main.rs b/src/main.rs index 2c824f6..4524003 100644 --- a/src/main.rs +++ b/src/main.rs @@ -36,7 +36,7 @@ fn main() -> Result<(), RclrsError> { let ros_services = Arc::new(ROSServices::new(opc_ua_client_copy_services)); let _enable_impedance_control = ros_node_copy_service - .create_service::("enable_impedance_control", { + .create_service::("~/enable_impedance_control", { let rsc = Arc::clone(&ros_services); move |request_header, request| rsc.enable_impedance_control(request_header, request) }); diff --git a/src/register_subscriptions.rs b/src/register_subscriptions.rs index 6263965..b297b61 100644 --- a/src/register_subscriptions.rs +++ b/src/register_subscriptions.rs @@ -27,10 +27,10 @@ pub fn register_opcua_subscriptions(ros_node: Arc, opc_ua_client: Arc>> = Arc::new(Mutex::new( - RosPublisher::new(&ros_node, "tcp_twist").unwrap(), + RosPublisher::new(&ros_node, "~/tcp_twist").unwrap(), )); let tcp_wrench_publisher: Arc>> = Arc::new(Mutex::new( - RosPublisher::new(&ros_node, "tcp_wrench").unwrap(), + RosPublisher::new(&ros_node, "~/tcp_wrench").unwrap(), )); opc_ua_client diff --git a/src/ros_publisher.rs b/src/ros_publisher.rs index 955638c..a61e331 100644 --- a/src/ros_publisher.rs +++ b/src/ros_publisher.rs @@ -40,7 +40,7 @@ impl JointStatesBuffer { current_velocities: Arc::new(Mutex::new(vec![0.0; 6])), current_efforts: Arc::new(Mutex::new(vec![0.0; 6])), publisher: Arc::new(Mutex::new( - RosPublisher::new(&ros_node, "joint_states").unwrap(), + RosPublisher::new(&ros_node, "~/joint_states").unwrap(), )), } } @@ -116,7 +116,7 @@ impl TCPPoseBuffer { current_pose: Arc::new(Mutex::new(vec![0.0; 6])), current_quaternions: Arc::new(Mutex::new(vec![0.0; 4])), publisher: Arc::new(Mutex::new( - RosPublisher::new(&ros_node, "tcp_pose").unwrap(), + RosPublisher::new(&ros_node, "~/tcp_pose").unwrap(), )), } } diff --git a/tests/test_bridge.rs b/tests/test_bridge.rs index c87e5a1..569d396 100644 --- a/tests/test_bridge.rs +++ b/tests/test_bridge.rs @@ -72,7 +72,7 @@ async fn e2e_opc_ua_var_to_ros_topic() { // Spawn ROS Subscriber against a sample topic let subscription = Arc::new( - helpers::ros_subscriber::Subscriber::new("joint_states_subscriber", "joint_states") + helpers::ros_subscriber::Subscriber::new("joint_states_subscriber", "/voraus_bridge_node/joint_states") .unwrap(), ); let clone = Arc::clone(&subscription.node); @@ -122,7 +122,7 @@ async fn e2e_ros_service_to_opc_ua_call() { let mut bridge_process = ManagedRosBridge::new().expect("Failed to start subprocess"); let service_caller = Arc::new( - helpers::ros_service_caller::ServiceCaller::new("enable_impedance_control").unwrap(), + helpers::ros_service_caller::ServiceCaller::new("/voraus_bridge_node/enable_impedance_control").unwrap(), ); // TODO: Figure out why this takes almost 10 s [RR-836]