diff --git a/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_trajectory_controller.py b/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_trajectory_controller.py index 162977cdfe..66b60418ad 100644 --- a/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_trajectory_controller.py +++ b/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_trajectory_controller.py @@ -335,7 +335,7 @@ def _load_jtc(self): # Setup ROS interfaces jtc_ns = _resolve_controller_ns(self._cm_ns, self._jtc_name) - state_topic = jtc_ns + "/controller_state" + state_topic = jtc_ns + "/state" cmd_topic = jtc_ns + "/joint_trajectory" self._state_sub = self._node.create_subscription( JointTrajectoryControllerState, state_topic, self._state_cb, 1 @@ -410,7 +410,7 @@ def _state_cb(self, msg): current_pos = {} for i in range(len(msg.joint_names)): joint_name = msg.joint_names[i] - joint_pos = msg.feedback.positions[i] + joint_pos = msg.actual.positions[i] current_pos[joint_name] = joint_pos self.jointStateChanged.emit(current_pos)