Skip to content

Commit

Permalink
add pivot to domino
Browse files Browse the repository at this point in the history
  • Loading branch information
yichao-liang committed Jan 10, 2025
1 parent 1b3dff0 commit abac238
Show file tree
Hide file tree
Showing 4 changed files with 291 additions and 32 deletions.
68 changes: 68 additions & 0 deletions predicators/envs/assets/urdf/domino_pivot.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
<?xml version="1.0"?>
<robot name="horizontal_flap">
<!-- Vertical bar (base) -->
<link name="vertical_bar">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.005" length="0.2"/>
</geometry>
<material name="gray">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.005" length="0.2"/>
</geometry>
</collision>
<inertial>
<mass value="0.0005"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia
ixx="0.0001" ixy="0" ixz="0"
iyy="0.0001" iyz="0"
izz="0.0001"/>
</inertial>
</link>


<!-- Horizontal flap -->
<link name="horizontal_flap">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.2 0.08 0.003"/>
</geometry>
<material name="box_color_horizontal_flap">
<color rgba="1 1 0.5 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.2 0.08 0.003"/>
</geometry>
</collision>
<inertial>
<mass value="0.0005"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia
ixx="0.0001" ixy="0" ixz="0"
iyy="0.0001" iyz="0"
izz="0.0001"/>
</inertial>
</link>

<joint name="flap_hinge_joint" type="continuous">
<parent link="vertical_bar"/>
<child link="horizontal_flap"/>
<origin xyz="0 0 0.16" rpy="1.5707963267948966 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.0001" friction="0.0001"/>
<limit lower="-3.141592653589793" upper="3.141592653589793"/>
</joint>


</robot>
34 changes: 17 additions & 17 deletions predicators/envs/assets/urdf/domino_target.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,9 @@
<mass value="1.0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia
ixx="0.01" ixy="0.0" ixz="0.0"
iyy="0.01" iyz="0.0"
izz="0.01"/>
ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001"/>
</inertial>
</link>

Expand Down Expand Up @@ -120,12 +120,12 @@
</geometry>
</collision>
<inertial>
<mass value="0.005"/>
<mass value="0.001"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia
ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001"/>
ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001"/>
</inertial>
</link>

Expand All @@ -142,22 +142,22 @@
<!-- Short flap 1 -->
<link name="short_flap1">
<visual>
<origin xyz="0 0 -0.09" rpy="0 0 0"/>
<origin xyz="0 0 -0.075" rpy="0 0 0"/>
<geometry>
<box size="0.06 0.003 0.18"/>
<box size="0.06 0.003 0.15"/>
</geometry>
<material name="box_color_short_flap1">
<color rgba="1.0 0.5 0.5 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -0.09" rpy="0 0 0"/>
<origin xyz="0 0 -0.075" rpy="0 0 0"/>
<geometry>
<box size="0.06 0.003 0.18"/>
<box size="0.06 0.003 0.15"/>
</geometry>
</collision>
<inertial>
<mass value="0.005"/>
<mass value="0.001"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia
ixx="0.0005" ixy="0.0" ixz="0.0"
Expand All @@ -179,22 +179,22 @@
<!-- Short flap 2 -->
<link name="short_flap2">
<visual>
<origin xyz="0 0 -0.09" rpy="0 0 0"/>
<origin xyz="0 0 -0.075" rpy="0 0 0"/>
<geometry>
<box size="0.06 0.003 0.18"/>
<box size="0.06 0.003 0.15"/>
</geometry>
<material name="box_color_short_flap2">
<color rgba="1.0 0.5 0.5 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -0.09" rpy="0 0 0"/>
<origin xyz="0 0 -0.075" rpy="0 0 0"/>
<geometry>
<box size="0.06 0.003 0.18"/>
<box size="0.06 0.003 0.15"/>
</geometry>
</collision>
<inertial>
<mass value="0.005"/>
<mass value="0.001"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia
ixx="0.0005" ixy="0.0" ixz="0.0"
Expand Down
68 changes: 68 additions & 0 deletions predicators/envs/domino_pivot.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
<?xml version="1.0"?>
<robot name="horizontal_flap">
<!-- Vertical bar (base) -->
<link name="vertical_bar">
<visual>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.005" length="0.2"/>
</geometry>
<material name="gray">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.005" length="0.2"/>
</geometry>
</collision>
<inertial>
<mass value="0.001"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia
ixx="0.001" ixy="0" ixz="0"
iyy="0.001" iyz="0"
izz="0.001"/>
</inertial>
</link>


<!-- Horizontal flap -->
<link name="horizontal_flap">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.2 0.08 0.003"/>
</geometry>
<material name="box_color_horizontal_flap">
<color rgba="1 1 0.5 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.2 0.08 0.003"/>
</geometry>
</collision>
<inertial>
<mass value="0.001"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia
ixx="0.002" ixy="0" ixz="0"
iyy="0.002" iyz="0"
izz="0.002"/>
</inertial>
</link>

<joint name="flap_hinge_joint" type="continuous">
<parent link="vertical_bar"/>
<child link="horizontal_flap"/>
<origin xyz="0 0 0.16" rpy="1.5707963267948966 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.001" friction="0.001"/>
<limit lower="-3.141592653589793" upper="3.141592653589793"/>
</joint>


</robot>
Loading

0 comments on commit abac238

Please sign in to comment.