|
| 1 | +"""Helper functions for controlling UR10 robot arm across different simulation backends.""" |
| 2 | + |
| 3 | +import time |
| 4 | +from rclpy.node import Node |
| 5 | + |
| 6 | + |
| 7 | +def move_ur10_joints(node: Node, loop_iteration: int, sim_backend: str): |
| 8 | + """Publish joint positions for UR10 for the given iteration. |
| 9 | + |
| 10 | + Args: |
| 11 | + node: ROS2 node |
| 12 | + loop_iteration: Iteration number (0-2) to determine joint positions |
| 13 | + sim_backend: Simulation backend ("isaacsim", "o3de", or "gazebo") |
| 14 | + """ |
| 15 | + joint_positions_by_iteration = [ |
| 16 | + [0.0, -1.5708, 1.5708, -1.5708, -1.5708, 0.0], |
| 17 | + [0.7854, -1.0472, 0.7854, -0.7854, -1.5708, 0.5236], |
| 18 | + [-0.5236, -2.0944, 2.0944, -2.0944, -1.5708, -0.7854], |
| 19 | + ] |
| 20 | + joint_names = [ |
| 21 | + "shoulder_pan_joint", |
| 22 | + "shoulder_lift_joint", |
| 23 | + "elbow_joint", |
| 24 | + "wrist_1_joint", |
| 25 | + "wrist_2_joint", |
| 26 | + "wrist_3_joint", |
| 27 | + ] |
| 28 | + positions = joint_positions_by_iteration[loop_iteration] |
| 29 | + |
| 30 | + if sim_backend == "isaacsim": |
| 31 | + move_ur10_joints_topic(node, joint_names, positions) |
| 32 | + elif sim_backend == "o3de": |
| 33 | + move_ur10_joints_action(node, joint_names, positions) |
| 34 | + elif sim_backend == "gazebo": |
| 35 | + move_ur10_joint_array_topic(node, positions) |
| 36 | + else: |
| 37 | + print(f"Unknown simulation backend: {sim_backend}") |
| 38 | + |
| 39 | + |
| 40 | +def move_ur10_joints_topic(node: Node, joint_names: list, positions: list): |
| 41 | + """Move UR10 joints using JointState topic publisher. |
| 42 | + |
| 43 | + Used for Isaac Sim backend. |
| 44 | + |
| 45 | + Args: |
| 46 | + node: ROS2 node |
| 47 | + joint_names: List of joint names |
| 48 | + positions: List of joint positions (radians) |
| 49 | + """ |
| 50 | + from sensor_msgs.msg import JointState |
| 51 | + from std_msgs.msg import Header |
| 52 | + |
| 53 | + ur10_joint_pub = node.create_publisher(JointState, "/joint_commands", 10) |
| 54 | + joint_cmd = JointState() |
| 55 | + joint_cmd.header = Header() |
| 56 | + joint_cmd.header.stamp = node.get_clock().now().to_msg() |
| 57 | + joint_cmd.name = joint_names |
| 58 | + joint_cmd.position = positions |
| 59 | + |
| 60 | + for _ in range(10): |
| 61 | + ur10_joint_pub.publish(joint_cmd) |
| 62 | + time.sleep(0.2) |
| 63 | + |
| 64 | + |
| 65 | +def move_ur10_joint_array_topic(node: Node, positions: list): |
| 66 | + """Move UR10 joints using Float64MultiArray publisher. |
| 67 | + |
| 68 | + Used for Gazebo backend. |
| 69 | + |
| 70 | + Args: |
| 71 | + node: ROS2 node |
| 72 | + positions: List of joint positions (radians) |
| 73 | + """ |
| 74 | + from std_msgs.msg import Float64MultiArray |
| 75 | + |
| 76 | + ur10_joint_pub = node.create_publisher(Float64MultiArray, "/joint_commands", 10) |
| 77 | + joint_cmd = Float64MultiArray() |
| 78 | + joint_cmd.data = positions |
| 79 | + |
| 80 | + for _ in range(10): |
| 81 | + ur10_joint_pub.publish(joint_cmd) |
| 82 | + time.sleep(0.2) |
| 83 | + |
| 84 | + |
| 85 | +def move_ur10_joints_action(node: Node, joint_names: list, positions: list): |
| 86 | + """Move UR10 joints using FollowJointTrajectory action. |
| 87 | + |
| 88 | + Used for O3DE backend. |
| 89 | + |
| 90 | + Args: |
| 91 | + node: ROS2 node |
| 92 | + joint_names: List of joint names |
| 93 | + positions: List of joint positions (radians) |
| 94 | + """ |
| 95 | + import rclpy |
| 96 | + from rclpy.action import ActionClient |
| 97 | + from control_msgs.action import FollowJointTrajectory |
| 98 | + from control_msgs.msg import JointTolerance |
| 99 | + from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint |
| 100 | + from builtin_interfaces.msg import Duration |
| 101 | + |
| 102 | + action_client = ActionClient( |
| 103 | + node, |
| 104 | + FollowJointTrajectory, |
| 105 | + "/joint_trajectory_controller/follow_joint_trajectory" |
| 106 | + ) |
| 107 | + |
| 108 | + while not action_client.wait_for_server(timeout_sec=1.0): |
| 109 | + print("Waiting for action server...") |
| 110 | + |
| 111 | + # Build trajectory |
| 112 | + trajectory = JointTrajectory() |
| 113 | + trajectory.joint_names = joint_names |
| 114 | + |
| 115 | + point = JointTrajectoryPoint() |
| 116 | + point.positions = positions |
| 117 | + point.velocities = [0.0] * len(joint_names) |
| 118 | + point.effort = [0.0] * len(joint_names) |
| 119 | + point.time_from_start = Duration(sec=1, nanosec=0) |
| 120 | + trajectory.points.append(point) |
| 121 | + |
| 122 | + # Build goal with tolerances |
| 123 | + goal_tolerance = [JointTolerance(position=0.01) for _ in range(2)] |
| 124 | + goal_msg = FollowJointTrajectory.Goal() |
| 125 | + goal_msg.trajectory = trajectory |
| 126 | + goal_msg.goal_tolerance = goal_tolerance |
| 127 | + |
| 128 | + # Send goal and wait for result |
| 129 | + future = action_client.send_goal_async(goal_msg) |
| 130 | + rclpy.spin_until_future_complete(node, future) |
| 131 | + |
| 132 | + goal_handle = future.result() |
| 133 | + if not goal_handle.accepted: |
| 134 | + print("Goal rejected") |
| 135 | + return |
| 136 | + |
| 137 | + result_future = goal_handle.get_result_async() |
| 138 | + rclpy.spin_until_future_complete(node, result_future) |
0 commit comments