From 772bf996a13fee4b9dbec8eb41032906ea131f9c Mon Sep 17 00:00:00 2001 From: Jaron <13423952+jaron-l@users.noreply.github.com> Date: Thu, 18 Aug 2022 13:14:15 -0500 Subject: [PATCH] fix: :bug: make bare exceptions more narrow (#422) - fixes pre-commit pipeline --- .../rqt_joint_trajectory_controller/joint_limits_urdf.py | 6 +++--- .../joint_trajectory_controller.py | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_limits_urdf.py b/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_limits_urdf.py index d7517b1847..7914a76b17 100644 --- a/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_limits_urdf.py +++ b/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/joint_limits_urdf.py @@ -66,7 +66,7 @@ def get_joint_limits(node, key="robot_description", use_smallest_joint_limits=Tr name = child.getAttribute("name") try: limit = child.getElementsByTagName("limit")[0] - except: + except IndexError: continue if jtype == "continuous": minval = -pi @@ -75,11 +75,11 @@ def get_joint_limits(node, key="robot_description", use_smallest_joint_limits=Tr try: minval = float(limit.getAttribute("lower")) maxval = float(limit.getAttribute("upper")) - except: + except ValueError: continue try: maxvel = float(limit.getAttribute("velocity")) - except: + except ValueError: continue safety_tags = child.getElementsByTagName("safety_controller") if use_small and len(safety_tags) == 1: 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 ab55d6eb78..7e8ec4948e 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 @@ -321,7 +321,7 @@ def _load_jtc(self): par = partial(self._update_single_cmd_cb, name=name) joint_widget.valueChanged.connect(par) - except: + except Exception: # TODO: Can we do better than swallow the exception? from sys import exc_info @@ -350,7 +350,7 @@ def _unload_jtc(self): # Stop updating the joint positions try: self.jointStateChanged.disconnect(self._on_joint_state_change) - except: + except Exception: pass # Reset ROS interfaces