Skip to content

Commit

Permalink
Formatting
Browse files Browse the repository at this point in the history
  • Loading branch information
urmahp committed Aug 28, 2023
1 parent 02938bb commit 7d63ba5
Show file tree
Hide file tree
Showing 3 changed files with 27 additions and 19 deletions.
9 changes: 6 additions & 3 deletions ur_robot_driver/test/dashboard_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ def generate_test_description():
DeclareLaunchArgument(
"launch_ursim",
default_value="true",
description="Launches the ursim when running the test if yes"
description="Launches the ursim when running the test if yes",
)
)

Expand Down Expand Up @@ -122,7 +122,7 @@ def generate_test_description():
],
name="start_ursim",
output="screen",
condition=IfCondition(launch_ursim)
condition=IfCondition(launch_ursim),
)

return LaunchDescription(declared_arguments + [ReadyToTest(), dashboard_client, ursim])
Expand Down Expand Up @@ -181,7 +181,10 @@ def test_switch_on(self):
# Wait until the robot is booted completely
end_time = time.time() + 10
mode = RobotMode.DISCONNECTED
while mode not in (RobotMode.POWER_OFF, RobotMode.IDLE, RobotMode.RUNNING) and time.time() < end_time:
while (
mode not in (RobotMode.POWER_OFF, RobotMode.IDLE, RobotMode.RUNNING)
and time.time() < end_time
):
time.sleep(0.1)
result = self.call_dashboard_service("get_robot_mode", GetRobotMode.Request())
self.assertTrue(result.success)
Expand Down
22 changes: 13 additions & 9 deletions ur_robot_driver/test/robot_driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ def generate_test_description(tf_prefix):
DeclareLaunchArgument(
"launch_ursim",
default_value="true",
description="Launches the ursim when running the test if True"
description="Launches the ursim when running the test if True",
)
)

Expand All @@ -129,7 +129,7 @@ def generate_test_description(tf_prefix):
"start_joint_controller": "false",
"tf_prefix": tf_prefix,
}.items(),
condition=IfCondition(launch_ursim)
condition=IfCondition(launch_ursim),
)

ursim = ExecuteProcess(
Expand All @@ -148,7 +148,7 @@ def generate_test_description(tf_prefix):
],
name="start_ursim",
output="screen",
condition=IfCondition(launch_ursim)
condition=IfCondition(launch_ursim),
)

wait_dashboard_server = ExecuteProcess(
Expand All @@ -159,12 +159,12 @@ def generate_test_description(tf_prefix):
],
name="wait_dashboard_server",
output="screen",
condition=IfCondition(launch_ursim)
condition=IfCondition(launch_ursim),
)

driver_starter = RegisterEventHandler(
OnProcessExit(target_action=wait_dashboard_server, on_exit=robot_driver),
condition=IfCondition(launch_ursim)
condition=IfCondition(launch_ursim),
)

robot_driver_no_wait = IncludeLaunchDescription(
Expand All @@ -184,11 +184,12 @@ def generate_test_description(tf_prefix):
"start_joint_controller": "false",
"tf_prefix": tf_prefix,
}.items(),
condition=UnlessCondition(launch_ursim)
condition=UnlessCondition(launch_ursim),
)

return LaunchDescription(
declared_arguments + [ReadyToTest(), wait_dashboard_server, ursim, driver_starter, robot_driver_no_wait]
declared_arguments
+ [ReadyToTest(), wait_dashboard_server, ursim, driver_starter, robot_driver_no_wait]
)

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


def waitForController(self, controller_name, controller_status="active", timeout=TIMEOUT_WAIT_SERVICE):
def waitForController(
self, controller_name, controller_status="active", timeout=TIMEOUT_WAIT_SERVICE
):
controller_running = False
end_time = time.time() + timeout
while controller_running == False and time.time() < end_time:
Expand All @@ -513,7 +516,8 @@ def waitForController(self, controller_name, controller_status="active", timeout

if controller_running == False:
raise Exception(
f"Controller {controller_name} did not reach controller state {controller_status} within timeout of {timeout}")
f"Controller {controller_name} did not reach controller state {controller_status} within timeout of {timeout}"
)

def waitForService(node, srv_name, srv_type, timeout=TIMEOUT_WAIT_SERVICE):
client = node.create_client(srv_type, srv_name)
Expand Down
15 changes: 8 additions & 7 deletions ur_robot_driver/test/urscript_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ def generate_test_description():
DeclareLaunchArgument(
"launch_ursim",
default_value="true",
description="Launches the ursim when running the test if True"
description="Launches the ursim when running the test if True",
)
)

Expand All @@ -116,7 +116,7 @@ def generate_test_description():
"launch_dashboard_client": "false",
"start_joint_controller": "false",
}.items(),
condition=IfCondition(launch_ursim)
condition=IfCondition(launch_ursim),
)

ursim = ExecuteProcess(
Expand All @@ -135,7 +135,7 @@ def generate_test_description():
],
name="start_ursim",
output="screen",
condition=IfCondition(launch_ursim)
condition=IfCondition(launch_ursim),
)

wait_dashboard_server = ExecuteProcess(
Expand All @@ -146,13 +146,13 @@ def generate_test_description():
],
name="wait_dashboard_server",
output="screen",
condition=IfCondition(launch_ursim)
condition=IfCondition(launch_ursim),
)

driver_starter = RegisterEventHandler(
OnProcessExit(target_action=wait_dashboard_server, on_exit=robot_driver),
condition=IfCondition(launch_ursim)
)
condition=IfCondition(launch_ursim),
)

robot_driver_no_wait = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
Expand All @@ -174,7 +174,8 @@ def generate_test_description():
)

return LaunchDescription(
declared_arguments + [ReadyToTest(), wait_dashboard_server, ursim, driver_starter, robot_driver_no_wait]
declared_arguments
+ [ReadyToTest(), wait_dashboard_server, ursim, driver_starter, robot_driver_no_wait]
)

class URScriptInterfaceTest(unittest.TestCase):
Expand Down

0 comments on commit 7d63ba5

Please sign in to comment.