From b44f2a740c148b1e3f6cd48186ef248fabe36daa Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Tue, 9 Sep 2025 15:51:56 +0000 Subject: [PATCH] Add support for UR8 Long --- README.md | 2 +- .../config/ur8long_controllers.yaml | 166 ++++++++++++++++++ ur_robot_driver/launch/ur8long_bringup.launch | 30 ++++ 3 files changed, 197 insertions(+), 1 deletion(-) create mode 100644 ur_robot_driver/config/ur8long_controllers.yaml create mode 100644 ur_robot_driver/launch/ur8long_bringup.launch diff --git a/README.md b/README.md index d20c88848..f028fb40d 100644 --- a/README.md +++ b/README.md @@ -209,7 +209,7 @@ To actually start the robot driver use one of the existing launch files $ roslaunch ur_robot_driver _bringup.launch robot_ip:=192.168.56.101 -where **** is one of *ur3, ur5, ur10, ur3e, ur5e, ur7e, ur10e, ur12e, ur16e, ur15, ur20, ur30*. Note that in this example we +where **** is one of *ur3, ur5, ur10, ur3e, ur5e, ur7e, ur10e, ur12e, ur16e, ur8long, ur15, ur20, ur30*. Note that in this example we load the calibration parameters for the robot "ur10_example". If you calibrated your robot before, pass that calibration to the launch file: diff --git a/ur_robot_driver/config/ur8long_controllers.yaml b/ur_robot_driver/config/ur8long_controllers.yaml new file mode 100644 index 000000000..6033cbd9e --- /dev/null +++ b/ur_robot_driver/config/ur8long_controllers.yaml @@ -0,0 +1,166 @@ +# Settings for ros_control control loop +hardware_control_loop: + loop_hz: &loop_hz 500 + +# Settings for ros_control hardware interface +ur_hardware_interface: + joints: &robot_joints + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint + +# Publish all joint states ---------------------------------- +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: *loop_hz + +# Publish wrench ---------------------------------- +force_torque_sensor_controller: + type: force_torque_sensor_controller/ForceTorqueSensorController + publish_rate: *loop_hz + +# Publish speed_scaling factor +speed_scaling_state_controller: + type: scaled_controllers/SpeedScalingStateController + publish_rate: *loop_hz + +# Joint Trajectory Controller - position based ------------------------------- +# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller +scaled_pos_joint_traj_controller: + type: position_controllers/ScaledJointTrajectoryController + joints: *robot_joints + constraints: + goal_time: 0.6 + stopped_velocity_tolerance: 0.05 + shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} + shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} + elbow_joint: {trajectory: 0.2, goal: 0.1} + wrist_1_joint: {trajectory: 0.2, goal: 0.1} + wrist_2_joint: {trajectory: 0.2, goal: 0.1} + wrist_3_joint: {trajectory: 0.2, goal: 0.1} + stop_trajectory_duration: 0.5 + state_publish_rate: *loop_hz + action_monitor_rate: 20 + +pos_joint_traj_controller: + type: position_controllers/JointTrajectoryController + joints: *robot_joints + constraints: + goal_time: 0.6 + stopped_velocity_tolerance: 0.05 + shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} + shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} + elbow_joint: {trajectory: 0.2, goal: 0.1} + wrist_1_joint: {trajectory: 0.2, goal: 0.1} + wrist_2_joint: {trajectory: 0.2, goal: 0.1} + wrist_3_joint: {trajectory: 0.2, goal: 0.1} + stop_trajectory_duration: 0.5 + state_publish_rate: *loop_hz + action_monitor_rate: 20 + +scaled_vel_joint_traj_controller: + type: velocity_controllers/ScaledJointTrajectoryController + joints: *robot_joints + constraints: + goal_time: 0.6 + stopped_velocity_tolerance: 0.05 + shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} + shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} + elbow_joint: {trajectory: 0.1, goal: 0.1} + wrist_1_joint: {trajectory: 0.1, goal: 0.1} + wrist_2_joint: {trajectory: 0.1, goal: 0.1} + wrist_3_joint: {trajectory: 0.1, goal: 0.1} + gains: + #!!These values have not been optimized!! + shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + # Use a feedforward term to reduce the size of PID gains + velocity_ff: + shoulder_pan_joint: 1.0 + shoulder_lift_joint: 1.0 + elbow_joint: 1.0 + wrist_1_joint: 1.0 + wrist_2_joint: 1.0 + wrist_3_joint: 1.0 + stop_trajectory_duration: 0.5 + state_publish_rate: *loop_hz + action_monitor_rate: 20 + +vel_joint_traj_controller: + type: velocity_controllers/JointTrajectoryController + joints: *robot_joints + constraints: + goal_time: 0.6 + stopped_velocity_tolerance: 0.05 + shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} + shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} + elbow_joint: {trajectory: 0.1, goal: 0.1} + wrist_1_joint: {trajectory: 0.1, goal: 0.1} + wrist_2_joint: {trajectory: 0.1, goal: 0.1} + wrist_3_joint: {trajectory: 0.1, goal: 0.1} + gains: + #!!These values have not been optimized!! + shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + # Use a feedforward term to reduce the size of PID gains + velocity_ff: + shoulder_pan_joint: 1.0 + shoulder_lift_joint: 1.0 + elbow_joint: 1.0 + wrist_1_joint: 1.0 + wrist_2_joint: 1.0 + wrist_3_joint: 1.0 + stop_trajectory_duration: 0.5 + state_publish_rate: *loop_hz + action_monitor_rate: 20 + +# Pass an array of joint velocities directly to the joints +joint_group_vel_controller: + type: velocity_controllers/JointGroupVelocityController + joints: *robot_joints + +forward_joint_traj_controller: + type: "pass_through_controllers/JointTrajectoryController" + joints: *robot_joints + +forward_cartesian_traj_controller: + type: "pass_through_controllers/CartesianTrajectoryController" + joints: *robot_joints + +twist_controller: + type: "ros_controllers_cartesian/TwistController" + frame_id: "tool0_controller" + publish_rate: *loop_hz + joints: *robot_joints + +pose_based_cartesian_traj_controller: + type: pose_controllers/CartesianTrajectoryController + + # UR driver convention + base: base + tip: tool0_controller + joints: *robot_joints + +joint_based_cartesian_traj_controller: + type: position_controllers/CartesianTrajectoryController + + # UR driver convention + base: base + tip: tool0 + joints: *robot_joints + +robot_status_controller: + type: industrial_robot_status_controller/IndustrialRobotStatusController + handle_name: industrial_robot_status_handle + publish_rate: 10 diff --git a/ur_robot_driver/launch/ur8long_bringup.launch b/ur_robot_driver/launch/ur8long_bringup.launch new file mode 100644 index 000000000..b4f7169c5 --- /dev/null +++ b/ur_robot_driver/launch/ur8long_bringup.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +