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

Add use_external_cable parameter to URDF #155

Merged
merged 3 commits into from
Jul 28, 2023
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
98 changes: 71 additions & 27 deletions kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

<!-- Propagate last link name information because it is the gripper's parent link -->
<xacro:property name="last_arm_link" value="end_effector_link"/>
<xacro:property name="PI" value="3.1415926535897931"/>

<xacro:macro name="load_arm" params="
parent
Expand All @@ -24,6 +25,7 @@
sim_gazebo:=false
sim_ignition:=false
sim_isaac:=false
use_external_cable:=false
initial_positions:=${dict(joint_1=0.0,joint_2=0.0,joint_3=0.0,joint_4=0.0,joint_5=0.0,joint_6=0.0)}" >

<!-- ros2 control include -->
Expand Down Expand Up @@ -95,19 +97,39 @@
</geometry>
</collision>
</link>
<joint
name="${prefix}joint_1"
type="continuous">
<origin
xyz="0 0 0.15643"
rpy="-3.1416 0.0 0.0" />
<parent link="${prefix}base_link" />
<child link="${prefix}shoulder_link" />
<axis xyz="0 0 1" />
<limit
effort="39"
velocity="1.3963" />
</joint>
<xacro:if value="${use_external_cable}">
<joint
name="${prefix}joint_1"
type="revolute">
<origin
xyz="0 0 0.15643"
rpy="-3.1416 0.0 0.0" />
<parent link="${prefix}base_link" />
<child link="${prefix}shoulder_link" />
<axis xyz="0 0 1" />
<limit
lower="${-2*PI}"
upper="${2*PI}"
effort="39"
velocity="1.3963" />
</joint>
</xacro:if>
<xacro:unless value="${use_external_cable}">
<joint
name="${prefix}joint_1"
type="continuous">
<origin
xyz="0 0 0.15643"
rpy="-3.1416 0.0 0.0" />
<parent link="${prefix}base_link" />
<child link="${prefix}shoulder_link" />
<axis xyz="0 0 1" />
<limit
effort="39"
velocity="1.3963" />
</joint>
</xacro:unless>

<link name="${prefix}bicep_link">
<inertial>
<origin
Expand Down Expand Up @@ -200,13 +222,24 @@
</geometry>
</collision>
</link>
<joint name="${prefix}joint_4" type="continuous">
<origin xyz="0 0.20843 -0.006375" rpy="1.5708 0.0 0.0" />
<parent link="${prefix}forearm_link" />
<child link="${prefix}spherical_wrist_1_link" />
<axis xyz="0 0 1" />
<limit effort="9" velocity="1.2218" />
</joint>
<xacro:if value="${use_external_cable}">
<joint name="${prefix}joint_4" type="revolute">
<origin xyz="0 0.20843 -0.006375" rpy="1.5708 0.0 0.0" />
<parent link="${prefix}forearm_link" />
<child link="${prefix}spherical_wrist_1_link" />
<axis xyz="0 0 1" />
<limit lower="${-2*PI}" upper="${2*PI}" effort="9" velocity="1.2218" />
</joint>
</xacro:if>
<xacro:unless value="${use_external_cable}">
<joint name="${prefix}joint_4" type="continuous">
<origin xyz="0 0.20843 -0.006375" rpy="1.5708 0.0 0.0" />
<parent link="${prefix}forearm_link" />
<child link="${prefix}spherical_wrist_1_link" />
<axis xyz="0 0 1" />
<limit effort="9" velocity="1.2218" />
</joint>
</xacro:unless>
<link name="${prefix}spherical_wrist_2_link">
<inertial>
<origin xyz="-1E-06 0.046429 -0.008704" rpy="0 0 0" />
Expand Down Expand Up @@ -284,13 +317,24 @@
</collision>
</link>
</xacro:unless>
<joint name="${prefix}joint_6" type="continuous">
<origin xyz="0 0.10593 -0.00017505" rpy="1.5708 0.0 0.0" />
<parent link="${prefix}spherical_wrist_2_link" />
<child link="${prefix}bracelet_link" />
<axis xyz="0 0 1" />
<limit effort="9" velocity="1.2218" />
</joint>
<xacro:if value="${use_external_cable}">
<joint name="${prefix}joint_6" type="revolute">
<origin xyz="0 0.10593 -0.00017505" rpy="1.5708 0.0 0.0" />
<parent link="${prefix}spherical_wrist_2_link" />
<child link="${prefix}bracelet_link" />
<axis xyz="0 0 1" />
<limit lower="${-2*PI}" upper="${2*PI}" effort="9" velocity="1.2218" />
</joint>
</xacro:if>
<xacro:unless value="${use_external_cable}">
<joint name="${prefix}joint_6" type="continuous">
<origin xyz="0 0.10593 -0.00017505" rpy="1.5708 0.0 0.0" />
<parent link="${prefix}spherical_wrist_2_link" />
<child link="${prefix}bracelet_link" />
<axis xyz="0 0 1" />
<limit effort="9" velocity="1.2218" />
</joint>
</xacro:unless>
<link name="${prefix}end_effector_link" />
<joint
name="${prefix}end_effector"
Expand Down
191 changes: 136 additions & 55 deletions kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
sim_gazebo:=false
sim_ignition:=false
sim_isaac:=false
use_external_cable:=false
initial_positions:=${dict(joint_1=0.0,joint_2=0.0,joint_3=0.0,joint_4=0.0,joint_5=0.0,joint_6=0.0,joint_7=0.0)}" >

<!-- ros2 control include -->
Expand Down Expand Up @@ -102,20 +103,40 @@
</geometry>
</collision>
</link>
<joint
<xacro:if value="${use_external_cable}">
<joint
name="${prefix}joint_1"
type="continuous">
<origin xyz="0 0 0.15643" rpy="3.1416 2.7629E-18 -4.9305E-36" />
<parent
link="${prefix}base_link" />
<child
link="${prefix}shoulder_link" />
<axis
xyz="0 0 1" />
<limit
effort="39"
velocity="1.3963" />
</joint>
type="revolute">
<origin xyz="0 0 0.15643" rpy="3.1416 2.7629E-18 -4.9305E-36" />
<parent
link="${prefix}base_link" />
<child
link="${prefix}shoulder_link" />
<axis
xyz="0 0 1" />
<limit
lower="${-2*PI}"
upper="${2*PI}"
effort="39"
velocity="1.3963" />
</joint>
</xacro:if>
<xacro:unless value="${use_external_cable}">
<joint
name="${prefix}joint_1"
type="continuous">
<origin xyz="0 0 0.15643" rpy="3.1416 2.7629E-18 -4.9305E-36" />
<parent
link="${prefix}base_link" />
<child
link="${prefix}shoulder_link" />
<axis
xyz="0 0 1" />
<limit
effort="39"
velocity="1.3963" />
</joint>
</xacro:unless>
<link name="${prefix}half_arm_1_link">
<inertial>
<origin xyz="-4.4E-05 -0.09958 -0.013278" rpy="0 0 0" />
Expand Down Expand Up @@ -172,20 +193,40 @@
</geometry>
</collision>
</link>
<joint
name="${prefix}joint_3"
type="continuous">
<origin xyz="0 -0.21038 -0.006375" rpy="-1.5708 1.2326E-32 -2.9122E-16" />
<parent
link="${prefix}half_arm_1_link" />
<child
link="${prefix}half_arm_2_link" />
<axis
xyz="0 0 1" />
<limit
effort="39"
velocity="1.3963" />
</joint>
<xacro:if value="${use_external_cable}">
<joint
name="${prefix}joint_3"
type="revolute">
<origin xyz="0 -0.21038 -0.006375" rpy="-1.5708 1.2326E-32 -2.9122E-16" />
<parent
link="${prefix}half_arm_1_link" />
<child
link="${prefix}half_arm_2_link" />
<axis
xyz="0 0 1" />
<limit
lower="${-2*PI}"
upper="${2*PI}"
effort="39"
velocity="1.3963" />
</joint>
</xacro:if>
<xacro:unless value="${use_external_cable}">
<joint
name="${prefix}joint_3"
type="continuous">
<origin xyz="0 -0.21038 -0.006375" rpy="-1.5708 1.2326E-32 -2.9122E-16" />
<parent
link="${prefix}half_arm_1_link" />
<child
link="${prefix}half_arm_2_link" />
<axis
xyz="0 0 1" />
<limit
effort="39"
velocity="1.3963" />
</joint>
</xacro:unless>
<link name="${prefix}forearm_link">
<inertial>
<origin xyz="-1.8E-05 -0.075478 -0.015006" rpy="0 0 0" />
Expand Down Expand Up @@ -242,20 +283,40 @@
</geometry>
</collision>
</link>
<joint
name="${prefix}joint_5"
type="continuous">
<origin xyz="0 -0.20843 -0.006375" rpy="-1.5708 2.2204E-16 -6.373E-17" />
<parent
link="${prefix}forearm_link" />
<child
link="${prefix}spherical_wrist_1_link" />
<axis
xyz="0 0 1" />
<limit
effort="9"
velocity="1.2218" />
</joint>
<xacro:if value="${use_external_cable}">
<joint
name="${prefix}joint_5"
type="revolute">
<origin xyz="0 -0.20843 -0.006375" rpy="-1.5708 2.2204E-16 -6.373E-17" />
<parent
link="${prefix}forearm_link" />
<child
link="${prefix}spherical_wrist_1_link" />
<axis
xyz="0 0 1" />
<limit
lower="${-2*PI}"
upper="${2*PI}"
effort="9"
velocity="1.2218" />
</joint>
</xacro:if>
<xacro:unless value="${use_external_cable}">
<joint
name="${prefix}joint_5"
type="continuous">
<origin xyz="0 -0.20843 -0.006375" rpy="-1.5708 2.2204E-16 -6.373E-17" />
<parent
link="${prefix}forearm_link" />
<child
link="${prefix}spherical_wrist_1_link" />
<axis
xyz="0 0 1" />
<limit
effort="9"
velocity="1.2218" />
</joint>
</xacro:unless>
<link name="${prefix}spherical_wrist_2_link">
<inertial>
<origin xyz="1E-06 -0.045483 -0.00965" rpy="0 0 0" />
Expand Down Expand Up @@ -338,20 +399,40 @@
</collision>
</link>
</xacro:unless>
<joint
name="${prefix}joint_7"
type="continuous">
<origin xyz="0 -0.10593 -0.00017505" rpy="-1.5708 -5.5511E-17 9.6396E-17" />
<parent
link="${prefix}spherical_wrist_2_link" />
<child
link="${prefix}bracelet_link" />
<axis
xyz="0 0 1" />
<limit
effort="9"
velocity="1.2218" />
</joint>
<xacro:if value="${use_external_cable}">
<joint
name="${prefix}joint_7"
type="revolute">
<origin xyz="0 -0.10593 -0.00017505" rpy="-1.5708 -5.5511E-17 9.6396E-17" />
<parent
link="${prefix}spherical_wrist_2_link" />
<child
link="${prefix}bracelet_link" />
<axis
xyz="0 0 1" />
<limit
lower="${-2*PI}"
upper="${2*PI}"
effort="9"
velocity="1.2218" />
</joint>
</xacro:if>
<xacro:unless value="${use_external_cable}">
<joint
name="${prefix}joint_7"
type="continuous">
<origin xyz="0 -0.10593 -0.00017505" rpy="-1.5708 -5.5511E-17 9.6396E-17" />
<parent
link="${prefix}spherical_wrist_2_link" />
<child
link="${prefix}bracelet_link" />
<axis
xyz="0 0 1" />
<limit
effort="9"
velocity="1.2218" />
</joint>
</xacro:unless>
<link name="${prefix}end_effector_link" />
<joint
name="${prefix}end_effector"
Expand Down
4 changes: 3 additions & 1 deletion kortex_description/robots/gen3.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<xacro:arg name="use_fake_hardware" default="false" />
<xacro:arg name="fake_sensor_commands" default="false" />
<xacro:arg name="use_internal_bus_gripper_comm" default="false" />
<xacro:arg name="use_external_cable" default="false" />

<xacro:include filename="$(find kortex_description)/robots/kortex_robot.xacro" />
<link name="world" />
Expand All @@ -49,7 +50,8 @@
fake_sensor_commands="$(arg fake_sensor_commands)"
sim_gazebo="$(arg sim_gazebo)"
sim_ignition="$(arg sim_ignition)"
sim_isaac="$(arg sim_isaac)" >
sim_isaac="$(arg sim_isaac)"
use_external_cable="$(arg use_external_cable)" >
<origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
</xacro:load_robot>

Expand Down
4 changes: 3 additions & 1 deletion kortex_description/robots/kortex_robot.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
sim_gazebo:=false
sim_ignition:=false
sim_isaac:=false
use_external_cable:=false
gripper_max_velocity:=100.0
gripper_max_force:=100.0">

Expand Down Expand Up @@ -51,7 +52,8 @@
sim_isaac="${sim_isaac}"
gripper_joint_name="${gripper_joint_name}"
gripper_max_velocity="${gripper_max_velocity}"
gripper_max_force="${gripper_max_force}">
gripper_max_force="${gripper_max_force}"
use_external_cable="${use_external_cable}">
<xacro:insert_block name="origin" />
</xacro:load_arm>

Expand Down
Loading
Loading