Skip to content

Commit eefe605

Browse files
destoglAndyZe
authored andcommitted
Using modern python
1 parent 65c8b1d commit eefe605

File tree

4 files changed

+7
-11
lines changed

4 files changed

+7
-11
lines changed

ur_bringup/launch/ur_moveit.launch.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -31,9 +31,9 @@ def load_yaml(package_name, file_path):
3131
absolute_file_path = os.path.join(package_path, file_path)
3232

3333
try:
34-
with open(absolute_file_path, "r") as file:
34+
with open(absolute_file_path) as file:
3535
return yaml.safe_load(file)
36-
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
36+
except OSError: # parent of IOError, OSError *and* WindowsError where available
3737
return None
3838

3939

ur_robot_driver/test/io_test.py

Lines changed: 3 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727

2828
class IOTest(unittest.TestCase):
2929
def __init__(self, *args):
30-
super(IOTest, self).__init__(*args)
30+
super().__init__(*args)
3131
rospy.init_node("io_test")
3232

3333
timeout = 10
@@ -53,9 +53,7 @@ def test_set_io(self):
5353

5454
while pin_state:
5555
if messages >= maximum_messages:
56-
self.fail(
57-
"Could not read desired state after {} messages.".format(maximum_messages)
58-
)
56+
self.fail(f"Could not read desired state after {maximum_messages} messages.")
5957
io_state = rospy.wait_for_message("/ur_hardware_interface/io_states", IOStates)
6058
pin_state = io_state.digital_out_states[pin].state
6159
messages += 1
@@ -67,9 +65,7 @@ def test_set_io(self):
6765

6866
while not pin_state:
6967
if messages >= maximum_messages:
70-
self.fail(
71-
"Could not read desired state after {} messages.".format(maximum_messages)
72-
)
68+
self.fail(f"Could not read desired state after {maximum_messages} messages.")
7369
io_state = rospy.wait_for_message("/ur_hardware_interface/io_states", IOStates)
7470
pin_state = io_state.digital_out_states[pin].state
7571
messages += 1

ur_robot_driver/test/switch_on_test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727

2828
class IOTest(unittest.TestCase):
2929
def __init__(self, *args):
30-
super(IOTest, self).__init__(*args)
30+
super().__init__(*args)
3131

3232
rospy.init_node("switch_on_robot")
3333
self.client = actionlib.SimpleActionClient("/ur_hardware_interface/set_mode", SetModeAction)

ur_robot_driver/test/trajectory_test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434

3535
class TrajectoryTest(unittest.TestCase):
3636
def __init__(self, *args):
37-
super(TrajectoryTest, self).__init__(*args)
37+
super().__init__(*args)
3838
rospy.init_node("trajectory_testing_client")
3939
self.client = actionlib.SimpleActionClient(
4040
"follow_joint_trajectory", FollowJointTrajectoryAction

0 commit comments

Comments
 (0)