Skip to content

Commit 6a6c4a2

Browse files
committed
New examples branch
1 parent d4947aa commit 6a6c4a2

File tree

5 files changed

+482
-17
lines changed

5 files changed

+482
-17
lines changed

ur_robot_driver/CMakeLists.txt

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -161,8 +161,10 @@ install(PROGRAMS
161161
scripts/wait_for_robot_description
162162
scripts/example_move.py
163163
scripts/start_ursim.sh
164-
examples/examples.py
165164
examples/force_mode.py
165+
examples/robot_class.py
166+
examples/passthrough.py
167+
examples/scaled_joint.py
166168
DESTINATION lib/${PROJECT_NAME}
167169
)
168170

ur_robot_driver/examples/force_mode.py

Lines changed: 8 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -48,20 +48,15 @@
4848

4949
from ur_msgs.srv import SetForceMode
5050

51-
from examples import Robot
51+
from robot_class import Robot
5252

5353
if __name__ == "__main__":
5454
rclpy.init()
5555
node = Node("robot_driver_test")
5656
robot = Robot(node)
5757

58-
# Add force mode service to service interfaces and re-init robot
59-
robot.service_interfaces.update({"/force_mode_controller/start_force_mode": SetForceMode})
60-
robot.service_interfaces.update({"/force_mode_controller/stop_force_mode": Trigger})
61-
robot.init_robot()
62-
time.sleep(0.5)
6358
# Press play on the robot
64-
robot.call_service("/dashboard_client/play", Trigger.Request())
59+
robot.play()
6560

6661
time.sleep(0.5)
6762
# Start controllers
@@ -75,11 +70,9 @@
7570
)
7671

7772
# Move robot in to position
78-
robot.send_trajectory(
73+
robot.passthrough_trajectory(
7974
waypts=[[-1.5707, -1.5707, -1.5707, -1.5707, 1.5707, 0]],
80-
time_vec=[Duration(sec=5, nanosec=0)],
81-
action_client=robot.passthrough_trajectory_action_client,
82-
)
75+
time_vec=[Duration(sec=5, nanosec=0)])
8376

8477
# Finished moving
8578
# Create task frame for force mode
@@ -130,13 +123,12 @@
130123

131124
# Send request to controller
132125
node.get_logger().info(f"Starting force mode with {req}")
133-
robot.call_service("/force_mode_controller/start_force_mode", req)
134-
robot.send_trajectory(
126+
robot.start_force_mode(req)
127+
robot.passthrough_trajectory(
135128
waypts=[[1.5707, -1.5707, -1.5707, -1.5707, 1.5707, 0]],
136-
time_vec=[Duration(sec=5, nanosec=0)],
137-
action_client=robot.passthrough_trajectory_action_client,
129+
time_vec=[Duration(sec=5, nanosec=0)]
138130
)
139131

140132
time.sleep(3)
141133
node.get_logger().info("Deactivating force mode controller.")
142-
robot.call_service("/force_mode_controller/stop_force_mode", Trigger.Request())
134+
robot.stop_force_mode()
Lines changed: 95 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,95 @@
1+
#!/usr/bin/env python3
2+
# Copyright 2024, Universal Robots
3+
#
4+
# Redistribution and use in source and binary forms, with or without
5+
# modification, are permitted provided that the following conditions are met:
6+
#
7+
# * Redistributions of source code must retain the above copyright
8+
# notice, this list of conditions and the following disclaimer.
9+
#
10+
# * Redistributions in binary form must reproduce the above copyright
11+
# notice, this list of conditions and the following disclaimer in the
12+
# documentation and/or other materials provided with the distribution.
13+
#
14+
# * Neither the name of the {copyright_holder} nor the names of its
15+
# contributors may be used to endorse or promote products derived from
16+
# this software without specific prior written permission.
17+
#
18+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22+
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
# POSSIBILITY OF SUCH DAMAGE.
29+
30+
import rclpy
31+
from builtin_interfaces.msg import Duration
32+
from rclpy.node import Node
33+
from robot_class import Robot
34+
35+
36+
if __name__ == "__main__":
37+
rclpy.init()
38+
node = Node("robot_driver_test")
39+
robot = Robot(node)
40+
41+
# The following list are arbitrary joint positions, change according to your own needs
42+
waypts = [
43+
[-1, -2.5998, -1.004, -2.676, -0.992, -1.5406],
44+
[-0.5, -2.0, -0.5, -2.0, -0.4, -1.0],
45+
[0, -1.5, 0, 0, 0, -0.5],
46+
[-0.5, -2.0, -0.5, -2.0, -0.4, -1.0],
47+
[-1, -2.5998, -1.004, -2.676, -0.992, -1.5406],
48+
]
49+
# Velocities and accelerations can be omitted
50+
vels = [
51+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
52+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
53+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
54+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
55+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
56+
]
57+
accels = [
58+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
59+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
60+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
61+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
62+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
63+
]
64+
bad_vels = [
65+
[0.1, 0.1, 0.1, 0.1, 0.1],
66+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
67+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
68+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
69+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
70+
]
71+
bad_accels = [
72+
[0.1, 0.1, 0.1, 0.1, 0.1],
73+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
74+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
75+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
76+
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1],
77+
]
78+
time_vec = [
79+
Duration(sec=2, nanosec=0),
80+
Duration(sec=6, nanosec=0),
81+
Duration(sec=10, nanosec=0),
82+
Duration(sec=14, nanosec=0),
83+
Duration(sec=18, nanosec=0),
84+
]
85+
86+
# Execute trajectory on robot, make sure that the robot is booted and the control script is running
87+
robot.play()
88+
# Trajectory using positions, velocities and accelerations
89+
robot.passthrough_trajectory(waypts, time_vec, vels, accels)
90+
# Trajectory using only positions
91+
robot.passthrough_trajectory(waypts, time_vec)
92+
93+
robot.passthrough_trajectory(waypts, time_vec, bad_vels, accels)
94+
95+
robot.passthrough_trajectory(waypts, time_vec, vels, bad_accels)

0 commit comments

Comments
 (0)