diff --git a/src/teaching/pose_tf_listener.cpp b/src/teaching/pose_tf_listener.cpp
index 35e5e1d5609c49a8c39c5aa5c0f144bb79d2d132..c871681912d01c9167ec155f16e3f7f4acda1e17 100644
--- a/src/teaching/pose_tf_listener.cpp
+++ b/src/teaching/pose_tf_listener.cpp
@@ -17,10 +17,7 @@ void collect(ros::NodeHandle node_handle, geometry_msgs::TransformStamped t) {
     srv.request.pose.position.y = t.transform.translation.y;
     srv.request.pose.position.z = t.transform.translation.z;
 
-    srv.request.pose.orientation.x = t.transform.rotation.x;
-    srv.request.pose.orientation.y = t.transform.rotation.y;
-    srv.request.pose.orientation.z = t.transform.rotation.z;
-    srv.request.pose.orientation.w = t.transform.rotation.w;
+    srv.request.pose.orientation = t.transform.rotation;
 
     if (!client.call(srv)) {
         ROS_ERROR("Failed to call pose_storage_service.");