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(), )), } }