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

ros2srrc_robots_UR10 #21

Merged
merged 1 commit into from
Mar 28, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
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
1 change: 1 addition & 0 deletions ros2srrc_robots/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ install(

ur3
ur5
ur10
ur10e
ur16e

Expand Down
32 changes: 32 additions & 0 deletions ros2srrc_robots/ur10/config/controller.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
controller_manager:
ros__parameters:

update_rate: 250 #Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

joint_trajectory_controller:
ros__parameters:
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity
state_publish_rate: 250.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
constraints:
stopped_velocity_tolerance: 0.0
goal_time: 0.0
27 changes: 27 additions & 0 deletions ros2srrc_robots/ur10/config/controller_moveit2.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
controller_names:
- joint_trajectory_controller
- scaled_joint_trajectory_controller

joint_trajectory_controller:
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint

scaled_joint_trajectory_controller:
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: false
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
83 changes: 83 additions & 0 deletions ros2srrc_robots/ur10/config/controller_ur.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
controller_manager:
ros__parameters:

update_rate: 500 #Hz

io_and_status_controller:
type: ur_controllers/GPIOController

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

speed_scaling_state_broadcaster:
type: ur_controllers/SpeedScalingStateBroadcaster

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

scaled_joint_trajectory_controller:
type: ur_controllers/ScaledJointTrajectoryController

io_and_status_controller:
ros__parameters:
tf_prefix: ""

speed_scaling_state_broadcaster:
ros__parameters:
state_publish_rate: 100.0
tf_prefix: ""

joint_trajectory_controller:
ros__parameters:
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
command_interfaces:
- position
state_interfaces:
- position
- velocity
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
constraints:
stopped_velocity_tolerance: 0.2
goal_time: 0.0
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 }

scaled_joint_trajectory_controller:
ros__parameters:
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
command_interfaces:
- position
state_interfaces:
- position
- velocity
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
constraints:
stopped_velocity_tolerance: 0.2
goal_time: 0.0
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 }
speed_scaling_interface_name: speed_scaling/speed_scaling_factor
38 changes: 38 additions & 0 deletions ros2srrc_robots/ur10/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
joint_limits:
shoulder_pan_joint:
has_velocity_limits: true
max_velocity: 1.5
has_acceleration_limits: true
max_acceleration: 5.0
shoulder_lift_joint:
has_velocity_limits: true
max_velocity: 1.5
has_acceleration_limits: true
max_acceleration: 5.0
elbow_joint:
has_velocity_limits: true
max_velocity: 1.5
has_acceleration_limits: true
max_acceleration: 5.0
wrist_1_joint:
has_velocity_limits: true
max_velocity: 2.0
has_acceleration_limits: true
max_acceleration: 5.0
wrist_2_joint:
has_velocity_limits: true
max_velocity: 2.0
has_acceleration_limits: true
max_acceleration: 5.0
wrist_3_joint:
has_velocity_limits: true
max_velocity: 2.0
has_acceleration_limits: true
max_acceleration: 5.0

# VALUES TAKEN FROM: https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/main/ur_moveit_config/config/joint_limits.yaml

# These limits are used by MoveIt and augment/override the definitions in ur_description:
# While the robot does not inherently have any limits on joint accelerations (only on torques),
# MoveIt needs them for time parametrization. They were chosen conservatively to work in most use
# cases. For specific applications, higher values might lead to better execution performance.
4 changes: 4 additions & 0 deletions ros2srrc_robots/ur10/config/joint_specifications.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# ROS 2 Sim-to-Real Robot Control -> ROBOT-JOINT SPECIFICATIONS (Universal Robots UR10)
Limits:
Max: [360.0, 360.0, 180.0, 360.0, 360.0, 360.0]
Min: [-360.0, -360.0, -180.0, -360.0, -360.0, -360.0]
5 changes: 5 additions & 0 deletions ros2srrc_robots/ur10/config/kinematics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
ur10_arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
9 changes: 9 additions & 0 deletions ros2srrc_robots/ur10/config/pilz_cartesian_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
cartesian_limits:
max_trans_vel: 0.25
max_trans_acc: 0.25
max_trans_dec: 0.25
max_rot_vel: 2.0

# These values have been reduced (to really conservative values)
# since the maximum speed in the actual robot controller has been
# reduced to its 30% for safety purposes.
Binary file added ros2srrc_robots/ur10/meshes/collision/base.stl
Binary file not shown.
Binary file added ros2srrc_robots/ur10/meshes/collision/forearm.stl
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file added ros2srrc_robots/ur10/meshes/collision/wrist1.stl
Binary file not shown.
Binary file added ros2srrc_robots/ur10/meshes/collision/wrist2.stl
Binary file not shown.
Binary file added ros2srrc_robots/ur10/meshes/collision/wrist3.stl
Binary file not shown.
160 changes: 160 additions & 0 deletions ros2srrc_robots/ur10/meshes/visual/base.dae

Large diffs are not rendered by default.

403 changes: 403 additions & 0 deletions ros2srrc_robots/ur10/meshes/visual/forearm.dae

Large diffs are not rendered by default.

251 changes: 251 additions & 0 deletions ros2srrc_robots/ur10/meshes/visual/shoulder.dae

Large diffs are not rendered by default.

357 changes: 357 additions & 0 deletions ros2srrc_robots/ur10/meshes/visual/upperarm.dae

Large diffs are not rendered by default.

251 changes: 251 additions & 0 deletions ros2srrc_robots/ur10/meshes/visual/wrist1.dae

Large diffs are not rendered by default.

247 changes: 247 additions & 0 deletions ros2srrc_robots/ur10/meshes/visual/wrist2.dae

Large diffs are not rendered by default.

219 changes: 219 additions & 0 deletions ros2srrc_robots/ur10/meshes/visual/wrist3.dae

Large diffs are not rendered by default.

Loading