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

Joint limits modifications #241

Merged
merged 1 commit into from
Oct 7, 2024
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
6 changes: 3 additions & 3 deletions kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@
<parent link="${prefix}shoulder_link" />
<child link="${prefix}bicep_link" />
<axis xyz="0 0 1" />
<limit lower="-2.41" upper="2.41" effort="39" velocity="1.3963" />
<limit lower="-2.24" upper="2.24" effort="39" velocity="1.3963" />
</joint>
<link name="${prefix}forearm_link">
<inertial>
Expand Down Expand Up @@ -208,7 +208,7 @@
<parent link="${prefix}bicep_link" />
<child link="${prefix}forearm_link" />
<axis xyz="0 0 1" />
<limit lower="-2.66" upper="2.66" effort="39" velocity="1.3963" />
<limit lower="-2.57" upper="2.57" effort="39" velocity="1.3963" />
</joint>
<link name="${prefix}spherical_wrist_1_link">
<inertial>
Expand Down Expand Up @@ -277,7 +277,7 @@
<parent link="${prefix}spherical_wrist_1_link" />
<child link="${prefix}spherical_wrist_2_link" />
<axis xyz="0 0 1" />
<limit lower="-2.23" upper="2.23" effort="9" velocity="1.2218" />
<limit lower="-2.09" upper="2.09" effort="9" velocity="1.2218" />
</joint>
<xacro:if value="${vision}">
<link name="${prefix}bracelet_link">
Expand Down
6 changes: 3 additions & 3 deletions kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@
link="${prefix}half_arm_1_link" />
<axis
xyz="0 0 1" />
<limit lower="-2.41" upper="2.41" effort="39" velocity="1.3963" />
<limit lower="-2.24" upper="2.24" effort="39" velocity="1.3963" />
</joint>
<link name="${prefix}half_arm_2_link">
<inertial>
Expand Down Expand Up @@ -263,7 +263,7 @@
link="${prefix}forearm_link" />
<axis
xyz="0 0 1" />
<limit lower="-2.66" upper="2.66" effort="39" velocity="1.3963" />
<limit lower="-2.57" upper="2.57" effort="39" velocity="1.3963" />
</joint>
<link name="${prefix}spherical_wrist_1_link">
<inertial>
Expand Down Expand Up @@ -353,7 +353,7 @@
link="${prefix}spherical_wrist_2_link" />
<axis
xyz="0 0 1" />
<limit lower="-2.23" upper="2.23" effort="9" velocity="1.2218" />
<limit lower="-2.09" upper="2.09" effort="9" velocity="1.2218" />
</joint>
<xacro:if value="${vision}">
<link name="${prefix}bracelet_link">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@
<parent link="${prefix}base_link" />
<child link="${prefix}shoulder_link" />
<axis xyz="0 0 1" />
<limit lower="-2.69" upper="2.69" effort="10" velocity="1.6" />
<limit lower="-2.68" upper="2.68" effort="10" velocity="1.6" />
</joint>
<link name="${prefix}arm_link">
<inertial>
Expand Down Expand Up @@ -159,7 +159,7 @@
<parent link="${prefix}shoulder_link" />
<child link="${prefix}arm_link" />
<axis xyz="0 0 1" />
<limit lower="-2.69" upper="2.69" effort="14" velocity="1.6" />
<limit lower="-2.61" upper="2.61" effort="14" velocity="1.6" />
</joint>
<link name="${prefix}forearm_link">
<inertial>
Expand Down Expand Up @@ -191,7 +191,7 @@
<parent link="${prefix}arm_link" />
<child link="${prefix}forearm_link" />
<axis xyz="0 0 1" />
<limit lower="-2.69" upper="2.69" effort="10" velocity="1.6" />
<limit lower="-2.61" upper="2.61" effort="10" velocity="1.6" />
</joint>
<link name="${prefix}lower_wrist_link">
<inertial>
Expand Down Expand Up @@ -223,7 +223,7 @@
<parent link="${prefix}forearm_link" />
<child link="${prefix}lower_wrist_link" />
<axis xyz="0 0 1" />
<limit lower="-2.59" upper="2.59" effort="7" velocity="1.6" />
<limit lower="-2.6" upper="2.6" effort="7" velocity="1.6" />
</joint>
<link name="${prefix}upper_wrist_link">
<inertial>
Expand Down Expand Up @@ -255,15 +255,15 @@
<parent link="${prefix}lower_wrist_link" />
<child link="${prefix}upper_wrist_link" />
<axis xyz="0 0 1" />
<limit lower="-2.57" upper="2.57" effort="7" velocity="1.6" />
<limit lower="-2.53" upper="2.53" effort="7" velocity="1.6" />
</joint>
<link name="${prefix}end_effector_link"/>
<joint name="${prefix}joint_6" type="revolute">
<origin xyz="-0.105 0 0.0285" rpy="0 -1.5708 0" />
<parent link="${prefix}upper_wrist_link" />
<child link="${prefix}end_effector_link" />
<axis xyz="0 0 1" />
<limit lower="-2.59" upper="2.59" effort="7" velocity="3.2" />
<limit lower="-2.6" upper="2.6" effort="7" velocity="3.2" />
</joint>
<link name="${prefix}dummy_link" />
<joint name="${prefix}end_effector" type="fixed">
Expand Down
Loading