Skip to content

Commit

Permalink
Removed robot driver duplication and added robot_ip to wait for dashb…
Browse files Browse the repository at this point in the history
…oard
  • Loading branch information
urmahp committed Aug 29, 2023
1 parent e7e47d5 commit 22d2cd4
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 51 deletions.
10 changes: 8 additions & 2 deletions ur_robot_driver/scripts/wait_dashboard_server.sh
Original file line number Diff line number Diff line change
@@ -1,11 +1,17 @@
#!/bin/bash

netcat -z 192.168.56.101 29999
ip="192.168.56.101"
if [[ ! -z "$1" ]]
then
ip=$1
fi

netcat -z $ip 29999
while [ $? -eq 1 ]
do
echo "Dashboard server not accepting connections..."
sleep 3
netcat -z 192.168.56.101 29999
netcat -z $ip 29999
done
echo "Dashboard server connections are possible."
sleep 5
28 changes: 3 additions & 25 deletions ur_robot_driver/test/robot_driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ def generate_test_description(tf_prefix):
)
),
launch_arguments={
"robot_ip": "192.168.56.101",
"robot_ip": robot_ip,
"ur_type": ur_type,
"launch_rviz": "false",
"controller_spawner_timeout": str(TIMEOUT_WAIT_SERVICE_INITIAL),
Expand All @@ -129,7 +129,6 @@ def generate_test_description(tf_prefix):
"start_joint_controller": "false",
"tf_prefix": tf_prefix,
}.items(),
condition=IfCondition(launch_ursim),
)

ursim = ExecuteProcess(
Expand All @@ -156,40 +155,19 @@ def generate_test_description(tf_prefix):
PathJoinSubstitution(
[FindPackagePrefix("ur_robot_driver"), "bin", "wait_dashboard_server.sh"]
),
robot_ip,
],
name="wait_dashboard_server",
output="screen",
condition=IfCondition(launch_ursim),
)

driver_starter = RegisterEventHandler(
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),
)

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


Expand Down
27 changes: 3 additions & 24 deletions ur_robot_driver/test/urscript_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ def generate_test_description():
)
),
launch_arguments={
"robot_ip": "192.168.56.101",
"robot_ip": robot_ip,
"ur_type": ur_type,
"launch_rviz": "false",
"controller_spawner_timeout": str(TIMEOUT_WAIT_SERVICE_INITIAL),
Expand All @@ -116,7 +116,6 @@ def generate_test_description():
"launch_dashboard_client": "false",
"start_joint_controller": "false",
}.items(),
condition=IfCondition(launch_ursim),
)

ursim = ExecuteProcess(
Expand All @@ -143,39 +142,19 @@ def generate_test_description():
PathJoinSubstitution(
[FindPackagePrefix("ur_robot_driver"), "bin", "wait_dashboard_server.sh"]
),
robot_ip,
],
name="wait_dashboard_server",
output="screen",
condition=IfCondition(launch_ursim),
)

driver_starter = RegisterEventHandler(
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, ursim, driver_starter, robot_driver_no_wait]
+ [ReadyToTest(), wait_dashboard_server, ursim, driver_starter]
)


Expand Down

0 comments on commit 22d2cd4

Please sign in to comment.