mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 22:00:05 +00:00
add z-up version of Laikago, centered along the chassis center of mass
This commit is contained in:
parent
7c5796b67d
commit
2f6eb59e16
@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 0
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
File diff suppressed because it is too large
Load Diff
13
examples/pybullet/gym/pybullet_data/laikago/chassis_zup.mtl
Normal file
13
examples/pybullet/gym/pybullet_data/laikago/chassis_zup.mtl
Normal file
@ -0,0 +1,13 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None.003
|
||||
Ns 0.000000
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.800000 0.800000 0.800000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.000000
|
||||
d 1.000000
|
||||
illum 2
|
||||
map_Kd laikago_tex.jpg
|
24050
examples/pybullet/gym/pybullet_data/laikago/chassis_zup.obj
Normal file
24050
examples/pybullet/gym/pybullet_data/laikago/chassis_zup.obj
Normal file
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,598 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="plane">
|
||||
<link name="chassis">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="13.715"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz=" 0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="chassis_zup.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="chassis_vhacd_mod_zup.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="FR_hip_motor">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.02 0 0"/>
|
||||
<mass value="1.095"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="hip_motor_mirror.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="FR_hip_motor_2_chassis_joint" type="continuous">
|
||||
<axis xyz="0 0 -1"/>
|
||||
<parent link="chassis"/>
|
||||
<child link="FR_hip_motor"/>
|
||||
<origin rpy="1.57079 0 1.57079" xyz="0.199095 -0.0817145 -0.03"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
<link name="FR_upper_leg">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
|
||||
<mass value="1.527"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="upper_leg_mirror.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name="FR_upper_leg_2_hip_motor_joint" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="FR_hip_motor"/>
|
||||
<child link="FR_upper_leg"/>
|
||||
<origin rpy="0 0 0" xyz="-0.053565 0 0"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
<link name="FR_lower_leg">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
|
||||
<mass value="0.241"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="lower_leg3.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="FR_lower_leg_2_upper_leg_joint" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="FR_upper_leg"/>
|
||||
<child link="FR_lower_leg"/>
|
||||
|
||||
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<link name="FL_hip_motor">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-.02 0 0"/>
|
||||
<mass value="1.095"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="hip_motor.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name="FL_hip_motor_2_chassis_joint" type="continuous">
|
||||
<axis xyz="0 0 1"/>
|
||||
<parent link="chassis"/>
|
||||
<child link="FL_hip_motor"/>
|
||||
<origin rpy="1.57079 0 1.57079" xyz="0.199095 0.0817145 -0.03"/>
|
||||
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
<link name="FL_upper_leg">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
|
||||
<mass value="1.527"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
|
||||
<mesh filename="upper_leg_left.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
|
||||
<joint name="FL_upper_leg_2_hip_motor_joint" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="FL_hip_motor"/>
|
||||
<child link="FL_upper_leg"/>
|
||||
<origin rpy="0 0 0" xyz="0.055855 0 0"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<link name="FL_lower_leg">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
|
||||
<mass value="0.241"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="lower_leg3.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name="FL_lower_leg_2_upper_leg_joint" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="FL_upper_leg"/>
|
||||
<child link="FL_lower_leg"/>
|
||||
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
<link name="RR_hip_motor">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.02 0 0"/>
|
||||
<mass value="1.095"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="hip_motor_mirror.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name="RR_hip_motor_2_chassis_joint" type="continuous">
|
||||
<axis xyz="0 0 -1"/>
|
||||
<parent link="chassis"/>
|
||||
<child link="RR_hip_motor"/>
|
||||
<origin rpy="1.57079 0 1.57079" xyz="-0.238195 -0.0817145 -0.03"/>
|
||||
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
<link name="RR_upper_leg">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
|
||||
<mass value="1.527"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="upper_leg_mirror2.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name="RR_upper_leg_2_hip_motor_joint" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="RR_hip_motor"/>
|
||||
<child link="RR_upper_leg"/>
|
||||
<origin rpy="0 0 0" xyz="-0.053565 0 0"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
<link name="RR_lower_leg">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
|
||||
<mass value="0.241"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="lower_leg3.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name="RR_lower_leg_2_upper_leg_joint" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="RR_upper_leg"/>
|
||||
<child link="RR_lower_leg"/>
|
||||
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<link name="RL_hip_motor">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-.02 0 0"/>
|
||||
<mass value="1.095"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="hip_motor.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name="RL_hip_motor_2_chassis_joint" type="continuous">
|
||||
<axis xyz="0 0 1"/>
|
||||
<parent link="chassis"/>
|
||||
<child link="RL_hip_motor"/>
|
||||
|
||||
<origin rpy="1.57079 0 1.57079" xyz="-0.238195 0.0817145 -0.03"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
<link name="RL_upper_leg">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
|
||||
<mass value="1.527"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="upper_leg_left2.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
|
||||
<joint name="RL_upper_leg_2_hip_motor_joint" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="RL_hip_motor"/>
|
||||
<child link="RL_upper_leg"/>
|
||||
<origin rpy="0 0 0" xyz="0.055855 0 0"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<link name="RL_lower_leg">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
|
||||
<mass value="0.241"/>
|
||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="lower_leg3.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name="RL_lower_leg_2_upper_leg_joint" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<parent link="RL_upper_leg"/>
|
||||
<child link="RL_lower_leg"/>
|
||||
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
|
||||
<limit effort="100" velocity="100"/>
|
||||
<joint_properties damping=".0" friction=".0"/>
|
||||
</joint>
|
||||
|
||||
<link name="toeRL">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
<lateral_friction value="1.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.1"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="jtoeRL" type="fixed">
|
||||
<parent link="RL_lower_leg"/>
|
||||
<child link="toeRL"/>
|
||||
<origin xyz="0 -0.25 -0.022"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
|
||||
<link name="toeRR">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
<lateral_friction value="1.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.1"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="jtoeRR" type="fixed">
|
||||
<parent link="RR_lower_leg"/>
|
||||
<child link="toeRR"/>
|
||||
<origin xyz="0 -0.25 -0.022"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
|
||||
<link name="toeFL">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
<lateral_friction value="1.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.1"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="jtoeFL" type="fixed">
|
||||
<parent link="FL_lower_leg"/>
|
||||
<child link="toeFL"/>
|
||||
<origin xyz="0 -0.25 -0.022"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
|
||||
<link name="toeFR">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
<lateral_friction value="1.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.0"/>
|
||||
</geometry>
|
||||
<material name="white"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.03"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.1"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="jtoeFR" type="fixed">
|
||||
<parent link="FR_lower_leg"/>
|
||||
<child link="toeFR"/>
|
||||
<origin xyz="0 -0.25 -0.022"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
</robot>
|
||||
|
Loading…
Reference in New Issue
Block a user