From 3be3fe95c3eb2a6a7e07bde2b96a9b8acc558d9a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Mon, 26 Aug 2024 14:52:27 +0200 Subject: [PATCH] Fix bug for displaying all controllers (#1259) --- .../joint_trajectory_controller.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) 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 4cc6c901af..5b27c2c832 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 @@ -238,8 +238,11 @@ def _update_jtc_list(self): # for _all_ their joints running_jtc = self._running_jtc_info() if running_jtc and not self._robot_joint_limits: + self._robot_joint_limits = {} for jtc_info in running_jtc: - self._robot_joint_limits = get_joint_limits(self._node, _jtc_joint_names(jtc_info)) + self._robot_joint_limits.update( + get_joint_limits(self._node, _jtc_joint_names(jtc_info)) + ) valid_jtc = [] if self._robot_joint_limits: for jtc_info in running_jtc: