Gripper removed and force sensors xmls added.
This commit is contained in:
parent
4ccda75410
commit
7ed925c48a
|
@ -120,6 +120,12 @@
|
||||||
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
|
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
|
||||||
<geom name="FR" class="foot"/>
|
<geom name="FR" class="foot"/>
|
||||||
<site name="FR_foot" pos="0 0 -0.213" size="0.02"/>
|
<site name="FR_foot" pos="0 0 -0.213" size="0.02"/>
|
||||||
|
<body name="FR_dummy" pos="-0.002 0 -0.213">
|
||||||
|
<!-- <inertial pos="0 0 0" mass="0.0001" diaginertia="0.0 0.0 0.0"/> -->
|
||||||
|
<inertial pos="0 0 0" mass="0.04" diaginertia="9.6e-06 9.6e-06 9.6e-06"/>
|
||||||
|
<geom size="0.022" rgba="0 1 0 1"/>
|
||||||
|
<site name="FR_force_site" size="0.022" pos="0 0 0" rgba="0 1 0 1"/>
|
||||||
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
|
@ -149,7 +155,12 @@
|
||||||
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
|
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
|
||||||
<geom name="FL" class="foot"/>
|
<geom name="FL" class="foot"/>
|
||||||
<site name="FL_foot" pos="0 0 -0.213" size="0.02"/>
|
<site name="FL_foot" pos="0 0 -0.213" size="0.02"/>
|
||||||
|
<body name="FL_dummy" pos="-0.002 0 -0.213">
|
||||||
|
<!-- <inertial pos="0 0 0" mass="0.0001" diaginertia="0.0 0.0 0.0"/> -->
|
||||||
|
<inertial pos="0 0 0" mass="0.04" diaginertia="9.6e-06 9.6e-06 9.6e-06"/>
|
||||||
|
<geom size="0.022" rgba="0 1 0 1"/>
|
||||||
|
<site name="FL_force_site" size="0.022" pos="0 0 0" rgba="0 1 0 1"/>
|
||||||
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
|
@ -179,6 +190,12 @@
|
||||||
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
|
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
|
||||||
<geom name="RR" class="foot"/>
|
<geom name="RR" class="foot"/>
|
||||||
<site name="RR_foot" pos="0 0 -0.213" size="0.02"/>
|
<site name="RR_foot" pos="0 0 -0.213" size="0.02"/>
|
||||||
|
<body name="RR_dummy" pos="-0.002 0 -0.213">
|
||||||
|
<!-- <inertial pos="0 0 0" mass="0.0001" diaginertia="0.0 0.0 0.0"/> -->
|
||||||
|
<inertial pos="0 0 0" mass="0.04" diaginertia="9.6e-06 9.6e-06 9.6e-06"/>
|
||||||
|
<geom size="0.022" rgba="0 1 0 1"/>
|
||||||
|
<site name="RR_force_site" size="0.022" pos="0 0 0" rgba="0 1 0 1"/>
|
||||||
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
|
@ -208,7 +225,12 @@
|
||||||
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
|
<geom pos="0 0 -0.213" mesh="foot" class="visual" material="black"/>
|
||||||
<geom name="RL" class="foot"/>
|
<geom name="RL" class="foot"/>
|
||||||
<site name="RL_foot" pos="0 0 -0.213" size="0.02"/>
|
<site name="RL_foot" pos="0 0 -0.213" size="0.02"/>
|
||||||
|
<body name="RL_dummy" pos="-0.002 0 -0.213">
|
||||||
|
<!-- <inertial pos="0 0 0" mass="0.0001" diaginertia="0.0 0.0 0.0"/> -->
|
||||||
|
<inertial pos="0 0 0" mass="0.04" diaginertia="9.6e-06 9.6e-06 9.6e-06"/>
|
||||||
|
<geom size="0.022" rgba="0 1 0 1"/>
|
||||||
|
<site name="RL_force_site" size="0.022" pos="0 0 0" rgba="0 1 0 1"/>
|
||||||
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
|
@ -239,6 +261,12 @@
|
||||||
<inertial pos="-0.0068528 -3.9973e-06 0.039705" quat="0.494949 0.495288 -0.504676 0.504992" mass="0.077892" diaginertia="4.8843e-05 3.8232e-05 1.7707e-05"/>
|
<inertial pos="-0.0068528 -3.9973e-06 0.039705" quat="0.494949 0.495288 -0.504676 0.504992" mass="0.077892" diaginertia="4.8843e-05 3.8232e-05 1.7707e-05"/>
|
||||||
<joint name="Joint6" pos="0 0 0" axis="0 0 -1" range="-2.35 2.35"/>
|
<joint name="Joint6" pos="0 0 0" axis="0 0 -1" range="-2.35 2.35"/>
|
||||||
<geom type="mesh" rgba="1 1 1 1" mesh="Link6"/>
|
<geom type="mesh" rgba="1 1 1 1" mesh="Link6"/>
|
||||||
|
<body name="EF_dummy" pos="0.0 0 0.0405">
|
||||||
|
<!-- <inertial pos="0 0 0" mass="0.0001" diaginertia="0.0 0.0 0.0"/> -->
|
||||||
|
<inertial pos="0 0 0" mass="0.04" diaginertia="9.6e-06 9.6e-06 9.6e-06"/>
|
||||||
|
<geom size="0.015" rgba="0 1 0 1"/>
|
||||||
|
<site name="EF_force_site" size="0.025" pos="0 0 0" rgba="0 1 0 1"/>
|
||||||
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
</body>
|
</body>
|
||||||
|
@ -283,8 +311,18 @@
|
||||||
<touch name="FL_foot_contact" site="RL_foot"/>
|
<touch name="FL_foot_contact" site="RL_foot"/>
|
||||||
<touch name="RR_foot_contact" site="RR_foot"/>
|
<touch name="RR_foot_contact" site="RR_foot"/>
|
||||||
<touch name="RL_foot_contact" site="RL_foot"/>
|
<touch name="RL_foot_contact" site="RL_foot"/>
|
||||||
|
<force name="FL_force" site="FL_force_site"/>
|
||||||
|
<force name="FR_force" site="FR_force_site"/>
|
||||||
|
<force name="RL_force" site="RL_force_site"/>
|
||||||
|
<force name="RR_force" site="RR_force_site"/>
|
||||||
|
<force name="EF_force" site="EF_force_site"/>
|
||||||
</sensor>
|
</sensor>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
<keyframe>
|
<keyframe>
|
||||||
<key name="home" qpos="0 0 0.27 1 0 0 0 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0 0 0 0 0"
|
<key name="home" qpos="0 0 0.27 1 0 0 0 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0 0 0 0 0"
|
||||||
ctrl="0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0 0 0 0 0"/>
|
ctrl="0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0 0 0 0 0"/>
|
||||||
|
|
|
@ -985,7 +985,7 @@ Stephen Brawner (brawner@gmail.com)
|
||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="d1_assets/stl/Link6.STL" />
|
filename="d1_assets/stl/Link6-new.stl" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material
|
<material
|
||||||
name="">
|
name="">
|
||||||
|
@ -1013,136 +1013,20 @@ Stephen Brawner (brawner@gmail.com)
|
||||||
effort="0"
|
effort="0"
|
||||||
velocity="0" />
|
velocity="0" />
|
||||||
</joint>
|
</joint>
|
||||||
<link
|
|
||||||
name="Link7_1">
|
|
||||||
<inertial>
|
|
||||||
<origin
|
|
||||||
xyz="0.018927 0.006 0.012082"
|
|
||||||
rpy="0 0 0" />
|
|
||||||
<mass
|
|
||||||
value="0.015046" />
|
|
||||||
<inertia
|
|
||||||
ixx="1.2692E-06"
|
|
||||||
ixy="7.7441E-20"
|
|
||||||
ixz="-1.133E-07"
|
|
||||||
iyy="2.0229E-06"
|
|
||||||
iyz="1.2044E-20"
|
|
||||||
izz="2.6177E-06" />
|
|
||||||
</inertial>
|
|
||||||
<visual>
|
|
||||||
<origin
|
|
||||||
xyz="0 0 0"
|
|
||||||
rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<mesh
|
|
||||||
filename="d1_assets/stl/Link7_1.STL" />
|
|
||||||
</geometry>
|
|
||||||
<material
|
|
||||||
name="">
|
|
||||||
<color
|
|
||||||
rgba="1 1 1 1" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin
|
|
||||||
xyz="0 0 0"
|
|
||||||
rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<mesh
|
|
||||||
filename="d1_assets/stl/Link7_1.STL" />
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
</link>
|
|
||||||
<joint
|
|
||||||
name="Joint7_1"
|
|
||||||
type="prismatic">
|
|
||||||
<origin
|
|
||||||
xyz="-0.0056012 -0.029636 0.0706"
|
|
||||||
rpy="-1.5714 -1.5708 0" />
|
|
||||||
<parent
|
|
||||||
link="Link6" />
|
|
||||||
<child
|
|
||||||
link="Link7_1" />
|
|
||||||
<axis
|
|
||||||
xyz="0 0 -1" />
|
|
||||||
<limit
|
|
||||||
lower="0"
|
|
||||||
upper="0.03"
|
|
||||||
effort="0"
|
|
||||||
velocity="0" />
|
|
||||||
</joint>
|
|
||||||
<link
|
|
||||||
name="Link7_2">
|
|
||||||
<inertial>
|
|
||||||
<origin
|
|
||||||
xyz="0.018927 -0.006 0.012082"
|
|
||||||
rpy="0 0 0" />
|
|
||||||
<mass
|
|
||||||
value="0.015046" />
|
|
||||||
<inertia
|
|
||||||
ixx="1.2692E-06"
|
|
||||||
ixy="-7.8273E-20"
|
|
||||||
ixz="-1.133E-07"
|
|
||||||
iyy="2.0229E-06"
|
|
||||||
iyz="-1.2122E-20"
|
|
||||||
izz="2.6177E-06" />
|
|
||||||
</inertial>
|
|
||||||
<visual>
|
|
||||||
<origin
|
|
||||||
xyz="0 0 0"
|
|
||||||
rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<mesh
|
|
||||||
filename="d1_assets/stl/Link7_2.STL" />
|
|
||||||
</geometry>
|
|
||||||
<material
|
|
||||||
name="">
|
|
||||||
<color
|
|
||||||
rgba="1 1 1 1" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
|
||||||
<collision>
|
|
||||||
<origin
|
|
||||||
xyz="0 0 0"
|
|
||||||
rpy="0 0 0" />
|
|
||||||
<geometry>
|
|
||||||
<mesh
|
|
||||||
filename="d1_assets/stl/Link7_2.STL" />
|
|
||||||
</geometry>
|
|
||||||
</collision>
|
|
||||||
</link>
|
|
||||||
<joint
|
|
||||||
name="Joint7_2"
|
|
||||||
type="prismatic">
|
|
||||||
<origin
|
|
||||||
xyz="-0.0056388 0.02964 0.0706"
|
|
||||||
rpy="1.5702 -1.5708 0" />
|
|
||||||
<parent
|
|
||||||
link="Link6" />
|
|
||||||
<child
|
|
||||||
link="Link7_2" />
|
|
||||||
<axis
|
|
||||||
xyz="0 0 1" />
|
|
||||||
<limit
|
|
||||||
lower="-0.03"
|
|
||||||
upper="0"
|
|
||||||
effort="0"
|
|
||||||
velocity="0" />
|
|
||||||
</joint>
|
|
||||||
|
|
||||||
<link
|
<link
|
||||||
name="Link6_tip">
|
name="ef_tip">
|
||||||
</link>
|
</link>
|
||||||
<joint
|
<joint
|
||||||
name="tip_joint"
|
name="tip_joint"
|
||||||
type="fixed">
|
type="fixed">
|
||||||
<origin
|
<origin
|
||||||
xyz="0.0 0.0 0.0"
|
xyz="0.0 0.0 0.053"
|
||||||
rpy="0.0 0.0 0.0" />
|
rpy="0.0 0.0 0.0" />
|
||||||
<parent
|
<parent
|
||||||
link="Link6" />
|
link="Link6" />
|
||||||
<child
|
<child
|
||||||
link="Link6_tip" />
|
link="ef_tip" />
|
||||||
</joint>
|
</joint>
|
||||||
</robot>
|
</robot>
|
||||||
|
|
||||||
|
|
File diff suppressed because one or more lines are too long
Loading…
Reference in New Issue