We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent e786d1f commit 47baa59Copy full SHA for 47baa59
rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_trajectory_controller.py
@@ -238,8 +238,11 @@ def _update_jtc_list(self):
238
# for _all_ their joints
239
running_jtc = self._running_jtc_info()
240
if running_jtc and not self._robot_joint_limits:
241
+ self._robot_joint_limits = {}
242
for jtc_info in running_jtc:
- self._robot_joint_limits = get_joint_limits(self._node, _jtc_joint_names(jtc_info))
243
+ self._robot_joint_limits.update(
244
+ get_joint_limits(self._node, _jtc_joint_names(jtc_info))
245
+ )
246
valid_jtc = []
247
if self._robot_joint_limits:
248
0 commit comments