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..9e9c071002 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 @@ -457,12 +457,9 @@ def _joint_widgets(self): # TODO: Cache instead of compute every time? def _jtc_joint_names(jtc_info): - # NOTE: We assume that there is at least one hardware interface that - # claims resources (there should be), and the resource list is fetched - # from the first available interface joint_names = [] - for interface in jtc_info.claimed_interfaces: + for interface in jtc_info.required_state_interfaces: name = interface.split("/")[-2] if name not in joint_names: joint_names.append(name)