Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added arguments to test launch #785

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 26 additions & 2 deletions ur_robot_driver/test/dashboard_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
import rclpy
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription
from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.substitutions import FindPackagePrefix, FindPackageShare
Expand Down Expand Up @@ -69,7 +70,25 @@ def generate_test_description():
)
)

declared_arguments.append(
DeclareLaunchArgument(
"robot_ip",
default_value="192.168.56.101",
description="IP address of used UR robot.",
)
)

declared_arguments.append(
DeclareLaunchArgument(
"launch_ursim",
default_value="true",
description="Launches the ursim when running the test if yes",
)
)

ur_type = LaunchConfiguration("ur_type")
robot_ip = LaunchConfiguration("robot_ip")
launch_ursim = LaunchConfiguration("launch_ursim")

dashboard_client = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
Expand All @@ -82,9 +101,10 @@ def generate_test_description():
)
),
launch_arguments={
"robot_ip": "192.168.56.101",
"robot_ip": robot_ip,
}.items(),
)

ursim = ExecuteProcess(
cmd=[
PathJoinSubstitution(
Expand All @@ -101,6 +121,7 @@ def generate_test_description():
],
name="start_ursim",
output="screen",
condition=IfCondition(launch_ursim),
)

return LaunchDescription(declared_arguments + [ReadyToTest(), dashboard_client, ursim])
Expand Down Expand Up @@ -159,7 +180,10 @@ def test_switch_on(self):
# Wait until the robot is booted completely
end_time = time.time() + 10
mode = RobotMode.DISCONNECTED
while mode != RobotMode.POWER_OFF 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
83 changes: 80 additions & 3 deletions ur_robot_driver/test/robot_driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
IncludeLaunchDescription,
RegisterEventHandler,
)
from launch.conditions import IfCondition, UnlessCondition
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
Expand All @@ -57,6 +58,7 @@
from ur_dashboard_msgs.srv import GetRobotMode
from ur_msgs.msg import IOStates
from ur_msgs.srv import SetIO
from controller_manager_msgs.srv import ListControllers

TIMEOUT_WAIT_SERVICE = 10
TIMEOUT_WAIT_SERVICE_INITIAL = 60
Expand Down Expand Up @@ -90,7 +92,25 @@ def generate_test_description(tf_prefix):
)
)

declared_arguments.append(
DeclareLaunchArgument(
"robot_ip",
default_value="192.168.56.101",
description="IP address of used UR robot.",
)
)

declared_arguments.append(
DeclareLaunchArgument(
"launch_ursim",
default_value="true",
description="Launches the ursim when running the test if True",
)
)

ur_type = LaunchConfiguration("ur_type")
robot_ip = LaunchConfiguration("robot_ip")
launch_ursim = LaunchConfiguration("launch_ursim")

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

ursim = ExecuteProcess(
cmd=[
PathJoinSubstitution(
Expand All @@ -126,22 +148,48 @@ def generate_test_description(tf_prefix):
],
name="start_ursim",
output="screen",
condition=IfCondition(launch_ursim),
)

wait_dashboard_server = ExecuteProcess(
cmd=[
PathJoinSubstitution(
[FindPackagePrefix("ur_robot_driver"), "bin", "wait_dashboard_server.sh"]
)
),
],
name="wait_dashboard_server",
output="screen",
condition=IfCondition(launch_ursim),
)

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

robot_driver_no_wait = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution(
[FindPackageShare("ur_robot_driver"), "launch", "ur_control.launch.py"]
)
),
launch_arguments={
"robot_ip": robot_ip,
"ur_type": ur_type,
"launch_rviz": "false",
"controller_spawner_timeout": str(TIMEOUT_WAIT_SERVICE_INITIAL),
"initial_joint_controller": "scaled_joint_trajectory_controller",
"headless_mode": "true",
"launch_dashboard_client": "false",
"start_joint_controller": "false",
"tf_prefix": tf_prefix,
}.items(),
condition=UnlessCondition(launch_ursim),
urmahp marked this conversation as resolved.
Show resolved Hide resolved
)

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


Expand Down Expand Up @@ -184,6 +232,7 @@ def init_robot(self):
"/dashboard_client/get_robot_mode": GetRobotMode,
"/controller_manager/switch_controller": SwitchController,
"/io_and_status_controller/resend_robot_program": Trigger,
"/controller_manager/list_controllers": ListControllers,
}
self.service_clients.update(
{
Expand Down Expand Up @@ -282,6 +331,9 @@ def io_msg_cb(msg):

def test_trajectory(self, tf_prefix):
"""Test robot movement."""
# Wait for controller to be active
self.waitForController("scaled_joint_trajectory_controller")

# Construct test trajectory
test_trajectory = [
(Duration(sec=6, nanosec=0), [0.0 for j in ROBOT_JOINTS]),
Expand Down Expand Up @@ -320,6 +372,9 @@ def test_illegal_trajectory(self, tf_prefix):

This is more of a validation test that the testing suite does the right thing
"""
# Wait for controller to be active
self.waitForController("scaled_joint_trajectory_controller")

# Construct test trajectory, the second point wrongly starts before the first
test_trajectory = [
(Duration(sec=6, nanosec=0), [0.0 for j in ROBOT_JOINTS]),
Expand Down Expand Up @@ -347,6 +402,9 @@ def test_illegal_trajectory(self, tf_prefix):

def test_trajectory_scaled(self, tf_prefix):
"""Test robot movement."""
# Wait for controller to be active
self.waitForController("scaled_joint_trajectory_controller")

# Construct test trajectory
test_trajectory = [
(Duration(sec=6, nanosec=0), [0.0 for j in ROBOT_JOINTS]),
Expand Down Expand Up @@ -442,6 +500,25 @@ def get_result(self, action_name, goal_response, timeout):
else:
raise Exception(f"Exception while calling action: {future_res.exception()}")

def waitForController(
self, controller_name, controller_status="active", timeout=TIMEOUT_WAIT_SERVICE
):
controller_running = False
end_time = time.time() + timeout
while controller_running is False and time.time() < end_time:
time.sleep(1)
response = self.call_service(
"/controller_manager/list_controllers", ListControllers.Request()
)
for controller in response.controller:
if controller.name == controller_name:
controller_running = controller.state == controller_status

if controller_running is False:
raise Exception(
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
49 changes: 46 additions & 3 deletions ur_robot_driver/test/urscript_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
IncludeLaunchDescription,
RegisterEventHandler,
)
from launch.conditions import IfCondition, UnlessCondition
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
Expand Down Expand Up @@ -79,7 +80,25 @@ def generate_test_description():
)
)

declared_arguments.append(
DeclareLaunchArgument(
"robot_ip",
default_value="192.168.56.101",
description="IP address of used UR robot.",
)
)

declared_arguments.append(
DeclareLaunchArgument(
"launch_ursim",
default_value="true",
description="Launches the ursim when running the test if True",
)
)

ur_type = LaunchConfiguration("ur_type")
robot_ip = LaunchConfiguration("robot_ip")
launch_ursim = LaunchConfiguration("launch_ursim")

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

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

wait_dashboard_server = ExecuteProcess(
cmd=[
PathJoinSubstitution(
[FindPackagePrefix("ur_robot_driver"), "bin", "wait_dashboard_server.sh"]
)
),
],
name="wait_dashboard_server",
output="screen",
condition=IfCondition(launch_ursim),
)

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

robot_driver_no_wait = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution(
[FindPackageShare("ur_robot_driver"), "launch", "ur_control.launch.py"]
)
),
launch_arguments={
"robot_ip": robot_ip,
"ur_type": ur_type,
"launch_rviz": "false",
"controller_spawner_timeout": str(TIMEOUT_WAIT_SERVICE_INITIAL),
"initial_joint_controller": "scaled_joint_trajectory_controller",
"headless_mode": "true",
"launch_dashboard_client": "false",
"start_joint_controller": "false",
}.items(),
condition=UnlessCondition(launch_ursim),
)

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


Expand Down