Skip to content

Commit 7d63ba5

Browse files
committed
Formatting
1 parent 02938bb commit 7d63ba5

File tree

3 files changed

+27
-19
lines changed

3 files changed

+27
-19
lines changed

ur_robot_driver/test/dashboard_client.py

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ def generate_test_description():
8282
DeclareLaunchArgument(
8383
"launch_ursim",
8484
default_value="true",
85-
description="Launches the ursim when running the test if yes"
85+
description="Launches the ursim when running the test if yes",
8686
)
8787
)
8888

@@ -122,7 +122,7 @@ def generate_test_description():
122122
],
123123
name="start_ursim",
124124
output="screen",
125-
condition=IfCondition(launch_ursim)
125+
condition=IfCondition(launch_ursim),
126126
)
127127

128128
return LaunchDescription(declared_arguments + [ReadyToTest(), dashboard_client, ursim])
@@ -181,7 +181,10 @@ def test_switch_on(self):
181181
# Wait until the robot is booted completely
182182
end_time = time.time() + 10
183183
mode = RobotMode.DISCONNECTED
184-
while mode not in (RobotMode.POWER_OFF, RobotMode.IDLE, RobotMode.RUNNING) and time.time() < end_time:
184+
while (
185+
mode not in (RobotMode.POWER_OFF, RobotMode.IDLE, RobotMode.RUNNING)
186+
and time.time() < end_time
187+
):
185188
time.sleep(0.1)
186189
result = self.call_dashboard_service("get_robot_mode", GetRobotMode.Request())
187190
self.assertTrue(result.success)

ur_robot_driver/test/robot_driver.py

Lines changed: 13 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -104,7 +104,7 @@ def generate_test_description(tf_prefix):
104104
DeclareLaunchArgument(
105105
"launch_ursim",
106106
default_value="true",
107-
description="Launches the ursim when running the test if True"
107+
description="Launches the ursim when running the test if True",
108108
)
109109
)
110110

@@ -129,7 +129,7 @@ def generate_test_description(tf_prefix):
129129
"start_joint_controller": "false",
130130
"tf_prefix": tf_prefix,
131131
}.items(),
132-
condition=IfCondition(launch_ursim)
132+
condition=IfCondition(launch_ursim),
133133
)
134134

135135
ursim = ExecuteProcess(
@@ -148,7 +148,7 @@ def generate_test_description(tf_prefix):
148148
],
149149
name="start_ursim",
150150
output="screen",
151-
condition=IfCondition(launch_ursim)
151+
condition=IfCondition(launch_ursim),
152152
)
153153

154154
wait_dashboard_server = ExecuteProcess(
@@ -159,12 +159,12 @@ def generate_test_description(tf_prefix):
159159
],
160160
name="wait_dashboard_server",
161161
output="screen",
162-
condition=IfCondition(launch_ursim)
162+
condition=IfCondition(launch_ursim),
163163
)
164164

165165
driver_starter = RegisterEventHandler(
166166
OnProcessExit(target_action=wait_dashboard_server, on_exit=robot_driver),
167-
condition=IfCondition(launch_ursim)
167+
condition=IfCondition(launch_ursim),
168168
)
169169

170170
robot_driver_no_wait = IncludeLaunchDescription(
@@ -184,11 +184,12 @@ def generate_test_description(tf_prefix):
184184
"start_joint_controller": "false",
185185
"tf_prefix": tf_prefix,
186186
}.items(),
187-
condition=UnlessCondition(launch_ursim)
187+
condition=UnlessCondition(launch_ursim),
188188
)
189189

190190
return LaunchDescription(
191-
declared_arguments + [ReadyToTest(), wait_dashboard_server, ursim, driver_starter, robot_driver_no_wait]
191+
declared_arguments
192+
+ [ReadyToTest(), wait_dashboard_server, ursim, driver_starter, robot_driver_no_wait]
192193
)
193194

194195
class RobotDriverTest(unittest.TestCase):
@@ -499,7 +500,9 @@ def get_result(self, action_name, goal_response, timeout):
499500
raise Exception(f"Exception while calling action: {future_res.exception()}")
500501

501502

502-
def waitForController(self, controller_name, controller_status="active", timeout=TIMEOUT_WAIT_SERVICE):
503+
def waitForController(
504+
self, controller_name, controller_status="active", timeout=TIMEOUT_WAIT_SERVICE
505+
):
503506
controller_running = False
504507
end_time = time.time() + timeout
505508
while controller_running == False and time.time() < end_time:
@@ -513,7 +516,8 @@ def waitForController(self, controller_name, controller_status="active", timeout
513516

514517
if controller_running == False:
515518
raise Exception(
516-
f"Controller {controller_name} did not reach controller state {controller_status} within timeout of {timeout}")
519+
f"Controller {controller_name} did not reach controller state {controller_status} within timeout of {timeout}"
520+
)
517521

518522
def waitForService(node, srv_name, srv_type, timeout=TIMEOUT_WAIT_SERVICE):
519523
client = node.create_client(srv_type, srv_name)

ur_robot_driver/test/urscript_interface.py

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ def generate_test_description():
9292
DeclareLaunchArgument(
9393
"launch_ursim",
9494
default_value="true",
95-
description="Launches the ursim when running the test if True"
95+
description="Launches the ursim when running the test if True",
9696
)
9797
)
9898

@@ -116,7 +116,7 @@ def generate_test_description():
116116
"launch_dashboard_client": "false",
117117
"start_joint_controller": "false",
118118
}.items(),
119-
condition=IfCondition(launch_ursim)
119+
condition=IfCondition(launch_ursim),
120120
)
121121

122122
ursim = ExecuteProcess(
@@ -135,7 +135,7 @@ def generate_test_description():
135135
],
136136
name="start_ursim",
137137
output="screen",
138-
condition=IfCondition(launch_ursim)
138+
condition=IfCondition(launch_ursim),
139139
)
140140

141141
wait_dashboard_server = ExecuteProcess(
@@ -146,13 +146,13 @@ def generate_test_description():
146146
],
147147
name="wait_dashboard_server",
148148
output="screen",
149-
condition=IfCondition(launch_ursim)
149+
condition=IfCondition(launch_ursim),
150150
)
151151

152152
driver_starter = RegisterEventHandler(
153153
OnProcessExit(target_action=wait_dashboard_server, on_exit=robot_driver),
154-
condition=IfCondition(launch_ursim)
155-
)
154+
condition=IfCondition(launch_ursim),
155+
)
156156

157157
robot_driver_no_wait = IncludeLaunchDescription(
158158
PythonLaunchDescriptionSource(
@@ -174,7 +174,8 @@ def generate_test_description():
174174
)
175175

176176
return LaunchDescription(
177-
declared_arguments + [ReadyToTest(), wait_dashboard_server, ursim, driver_starter, robot_driver_no_wait]
177+
declared_arguments
178+
+ [ReadyToTest(), wait_dashboard_server, ursim, driver_starter, robot_driver_no_wait]
178179
)
179180

180181
class URScriptInterfaceTest(unittest.TestCase):

0 commit comments

Comments
 (0)