Skip to content

Commit

Permalink
fix: 🐛 make bare exceptions more narrow (#422)
Browse files Browse the repository at this point in the history
- fixes pre-commit pipeline
  • Loading branch information
jaron-l authored Aug 18, 2022
1 parent 8c2547c commit 9e08ee3
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -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
Expand Down

0 comments on commit 9e08ee3

Please sign in to comment.