Skip to content

Commit

Permalink
Merge pull request #10 from Witty-Wizard/main
Browse files Browse the repository at this point in the history
[Added]: World Link for the arm to be fixed
  • Loading branch information
Witty-Wizard authored Aug 26, 2024
2 parents 6b6c6fd + 671f8c7 commit 733b3b9
Show file tree
Hide file tree
Showing 11 changed files with 138 additions and 101 deletions.
8 changes: 5 additions & 3 deletions workspace/src/ur_description/urdf/inc/ur5_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,8 @@
model will be used, which will almost certainly not correspond to any
real robot.
-->
<xacro:macro name="ur5_robot" params="
<xacro:macro name="ur5_robot"
params="
prefix
joint_limits_parameters_file:='$(find ur_description)/config/ur5/joint_limits.yaml'
kinematics_parameters_file:='$(find ur_description)/config/ur5/default_kinematics.yaml'
Expand All @@ -31,7 +32,7 @@
safety_pos_margin:=0.15
safety_k_position:=20"
>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.xacro"/>
<xacro:include filename="$(find ur_description)/urdf/inc/ur_macro.xacro" />
<xacro:ur_robot
prefix="${prefix}"
joint_limits_parameters_file="${joint_limits_parameters_file}"
Expand All @@ -43,5 +44,6 @@
safety_pos_margin="${safety_pos_margin}"
safety_k_position="${safety_k_position}"
/>

</xacro:macro>
</robot>
</robot>
195 changes: 115 additions & 80 deletions workspace/src/ur_description/urdf/inc/ur_macro.xacro

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Default initial positions for ur10_robot's ros2_control fake system

initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
elbow_joint: 1.7
shoulder_lift_joint: -2.4
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Default initial positions for ur10e_robot's ros2_control fake system

initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
elbow_joint: 1.7
shoulder_lift_joint: -2.4
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Default initial positions for ur16e_robot's ros2_control fake system

initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
elbow_joint: 1.7
shoulder_lift_joint: -2.4
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Default initial positions for ur20_robot's ros2_control fake system

initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
elbow_joint: 1.7
shoulder_lift_joint: -2.4
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Default initial positions for ur30_robot's ros2_control fake system

initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
elbow_joint: 1.7
shoulder_lift_joint: -2.4
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Default initial positions for ur3_robot's ros2_control fake system

initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
elbow_joint: 1.7
shoulder_lift_joint: -2.4
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Default initial positions for ur3e_robot's ros2_control fake system

initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
elbow_joint: 1.7
shoulder_lift_joint: -2.4
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Default initial positions for ur5_robot's ros2_control fake system

initial_positions:
elbow_joint: 0
shoulder_lift_joint: -0.3
elbow_joint: 1.7
shoulder_lift_joint: -2.4
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Default initial positions for ur5e_robot's ros2_control fake system

initial_positions:
elbow_joint: 0
shoulder_lift_joint: 0
elbow_joint: 1.7
shoulder_lift_joint: -2.4
shoulder_pan_joint: 0
wrist_1_joint: 0
wrist_2_joint: 0
Expand Down

0 comments on commit 733b3b9

Please sign in to comment.