Skip to content

Commit

Permalink
feat!: Prepend the node's namespace for ROS communication
Browse files Browse the repository at this point in the history
  • Loading branch information
philipp-caspers committed Oct 14, 2024
1 parent 8a6c163 commit 3deddf3
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 7 deletions.
2 changes: 1 addition & 1 deletion src/main.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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::<std_srvs::srv::Empty, _>("enable_impedance_control", {
.create_service::<std_srvs::srv::Empty, _>("~/enable_impedance_control", {
let rsc = Arc::clone(&ros_services);
move |request_header, request| rsc.enable_impedance_control(request_header, request)
});
Expand Down
4 changes: 2 additions & 2 deletions src/register_subscriptions.rs
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,10 @@ pub fn register_opcua_subscriptions(ros_node: Arc<Node>, opc_ua_client: Arc<Mute
let tcp_pose_buffer_copy_quaternion = Arc::clone(&tcp_pose_buffer);

let tcp_twist_publisher: Arc<Mutex<RosPublisher<TwistStamped>>> = Arc::new(Mutex::new(
RosPublisher::new(&ros_node, "tcp_twist").unwrap(),
RosPublisher::new(&ros_node, "~/tcp_twist").unwrap(),
));
let tcp_wrench_publisher: Arc<Mutex<RosPublisher<WrenchStamped>>> = Arc::new(Mutex::new(
RosPublisher::new(&ros_node, "tcp_wrench").unwrap(),
RosPublisher::new(&ros_node, "~/tcp_wrench").unwrap(),
));

opc_ua_client
Expand Down
4 changes: 2 additions & 2 deletions src/ros_publisher.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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(),
)),
}
}
Expand Down Expand Up @@ -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(),
)),
}
}
Expand Down
4 changes: 2 additions & 2 deletions tests/test_bridge.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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]
Expand Down

0 comments on commit 3deddf3

Please sign in to comment.