Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
@@ -12,8 +12,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0.043794"/>
|
<origin rpy="0 0 0" xyz="0 0 0.043794"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
|
<mesh filename="chassis.stl" scale="1 1 1"/>
|
||||||
<mesh filename="chassis.stl" scale="1 1 1"/>
|
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="yellow">
|
<material name="yellow">
|
||||||
<color rgba="0.95 0.75 0.05 1"/>
|
<color rgba="0.95 0.75 0.05 1"/>
|
||||||
@@ -22,28 +21,24 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="-1.57 0 0" xyz="0 0 0.043794"/>
|
<origin rpy="-1.57 0 0" xyz="0 0 0.043794"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
|
<mesh filename="chassis_vhacd_mod.obj" scale="1 1 1"/>
|
||||||
<mesh filename="chassis_vhacd_mod.obj" scale="1 1 1"/>
|
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
<link name="FR_hip_motor">
|
||||||
|
<contact>
|
||||||
|
|
||||||
<link name="FR_hip_motor">
|
|
||||||
<contact>
|
|
||||||
<lateral_friction value="1"/>
|
<lateral_friction value="1"/>
|
||||||
</contact>
|
</contact>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="0.02 0 0"/>
|
<origin rpy="0 0 0" xyz="0.02 0 0"/>
|
||||||
<mass value="1.095"/>
|
<mass value="1.095"/>
|
||||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
|
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="green"/>
|
<material name="green"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -51,19 +46,19 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="FR_hip_motor_2_chassis_joint" type="continuous">
|
<joint name="FR_hip_motor_2_chassis_joint" type="continuous">
|
||||||
<axis xyz="0 0 -1"/>
|
<axis xyz="0 0 -1"/>
|
||||||
<parent link="chassis"/>
|
<parent link="chassis"/>
|
||||||
<child link="FR_hip_motor"/>
|
<child link="FR_hip_motor"/>
|
||||||
<origin rpy="0 0 0" xyz="-0.0817145 0 0.242889"/>
|
<origin rpy="0 0 0" xyz="-0.0817145 0 0.242889"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="FR_upper_leg">
|
<link name="FR_upper_leg">
|
||||||
<contact>
|
<contact>
|
||||||
@@ -77,7 +72,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/>
|
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue"/>
|
<material name="blue"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -85,20 +80,20 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
|
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="FR_upper_leg_2_hip_motor_joint" type="continuous">
|
<joint name="FR_upper_leg_2_hip_motor_joint" type="continuous">
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="1 0 0"/>
|
||||||
<parent link="FR_hip_motor"/>
|
<parent link="FR_hip_motor"/>
|
||||||
<child link="FR_upper_leg"/>
|
<child link="FR_upper_leg"/>
|
||||||
<origin rpy="0 0 0" xyz="-0.053565 0 0"/>
|
<origin rpy="0 0 0" xyz="-0.053565 0 0"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="FR_lower_leg">
|
<link name="FR_lower_leg">
|
||||||
<contact>
|
<contact>
|
||||||
@@ -112,7 +107,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
|
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="red"/>
|
<material name="red"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -120,24 +115,22 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
|
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="FR_lower_leg_2_upper_leg_joint" type="continuous">
|
<joint name="FR_lower_leg_2_upper_leg_joint" type="continuous">
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="1 0 0"/>
|
||||||
<parent link="FR_upper_leg"/>
|
<parent link="FR_upper_leg"/>
|
||||||
<child link="FR_lower_leg"/>
|
<child link="FR_lower_leg"/>
|
||||||
|
|
||||||
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
|
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
<link name="FL_hip_motor">
|
<link name="FL_hip_motor">
|
||||||
<contact>
|
<contact>
|
||||||
<lateral_friction value="1"/>
|
<lateral_friction value="1"/>
|
||||||
</contact>
|
</contact>
|
||||||
@@ -149,7 +142,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="green">
|
<material name="green">
|
||||||
<color rgba="0.23 0.73 0.33 1"/>
|
<color rgba="0.23 0.73 0.33 1"/>
|
||||||
@@ -159,20 +152,20 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="FL_hip_motor_2_chassis_joint" type="continuous">
|
<joint name="FL_hip_motor_2_chassis_joint" type="continuous">
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
<parent link="chassis"/>
|
<parent link="chassis"/>
|
||||||
<child link="FL_hip_motor"/>
|
<child link="FL_hip_motor"/>
|
||||||
<origin rpy="0 0 0" xyz="0.0817145 0 0.242889"/>
|
<origin rpy="0 0 0" xyz="0.0817145 0 0.242889"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="FL_upper_leg">
|
<link name="FL_upper_leg">
|
||||||
<contact>
|
<contact>
|
||||||
@@ -187,7 +180,7 @@
|
|||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
|
|
||||||
<mesh filename="upper_leg.stl" scale="1 1 1"/>
|
<mesh filename="upper_leg.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="blue">
|
||||||
<color rgba="0.28 0.52 0.93 1"/>
|
<color rgba="0.28 0.52 0.93 1"/>
|
||||||
@@ -197,7 +190,7 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
|
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
@@ -205,13 +198,13 @@
|
|||||||
|
|
||||||
|
|
||||||
<joint name="FL_upper_leg_2_hip_motor_joint" type="continuous">
|
<joint name="FL_upper_leg_2_hip_motor_joint" type="continuous">
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="1 0 0"/>
|
||||||
<parent link="FL_hip_motor"/>
|
<parent link="FL_hip_motor"/>
|
||||||
<child link="FL_upper_leg"/>
|
<child link="FL_upper_leg"/>
|
||||||
<origin rpy="0 0 0" xyz="0.055855 0 0"/>
|
<origin rpy="0 0 0" xyz="0.055855 0 0"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
<link name="FL_lower_leg">
|
<link name="FL_lower_leg">
|
||||||
@@ -226,7 +219,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="red">
|
<material name="red">
|
||||||
<color rgba="0.85 0.19 0.21 1"/>
|
<color rgba="0.85 0.19 0.21 1"/>
|
||||||
@@ -236,27 +229,27 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="FL_lower_leg_2_upper_leg_joint" type="continuous">
|
<joint name="FL_lower_leg_2_upper_leg_joint" type="continuous">
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="1 0 0"/>
|
||||||
<parent link="FL_upper_leg"/>
|
<parent link="FL_upper_leg"/>
|
||||||
<child link="FL_lower_leg"/>
|
<child link="FL_lower_leg"/>
|
||||||
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
|
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
<link name="RR_hip_motor">
|
<link name="RR_hip_motor">
|
||||||
<contact>
|
<contact>
|
||||||
<lateral_friction value="1"/>
|
<lateral_friction value="1"/>
|
||||||
</contact>
|
</contact>
|
||||||
@@ -266,10 +259,10 @@
|
|||||||
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
|
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="green"/>
|
<material name="green"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -277,20 +270,20 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
<mesh filename="hip_motor_mirror.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="RR_hip_motor_2_chassis_joint" type="continuous">
|
<joint name="RR_hip_motor_2_chassis_joint" type="continuous">
|
||||||
<axis xyz="0 0 -1"/>
|
<axis xyz="0 0 -1"/>
|
||||||
<parent link="chassis"/>
|
<parent link="chassis"/>
|
||||||
<child link="RR_hip_motor"/>
|
<child link="RR_hip_motor"/>
|
||||||
<origin rpy="0 0 0" xyz="-0.0817145 0 -0.194401"/>
|
<origin rpy="0 0 0" xyz="-0.0817145 0 -0.194401"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="RR_upper_leg">
|
<link name="RR_upper_leg">
|
||||||
<contact>
|
<contact>
|
||||||
@@ -304,7 +297,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/>
|
<mesh filename="upper_leg_mirror.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue"/>
|
<material name="blue"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -312,20 +305,20 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
|
<mesh filename="upper_leg_right_vhacd.obj" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="RR_upper_leg_2_hip_motor_joint" type="continuous">
|
<joint name="RR_upper_leg_2_hip_motor_joint" type="continuous">
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="1 0 0"/>
|
||||||
<parent link="RR_hip_motor"/>
|
<parent link="RR_hip_motor"/>
|
||||||
<child link="RR_upper_leg"/>
|
<child link="RR_upper_leg"/>
|
||||||
<origin rpy="0 0 0" xyz="-0.053565 0 0"/>
|
<origin rpy="0 0 0" xyz="-0.053565 0 0"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="RR_lower_leg">
|
<link name="RR_lower_leg">
|
||||||
<contact>
|
<contact>
|
||||||
@@ -339,7 +332,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="red"/>
|
<material name="red"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -347,23 +340,23 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="RR_lower_leg_2_upper_leg_joint" type="continuous">
|
<joint name="RR_lower_leg_2_upper_leg_joint" type="continuous">
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="1 0 0"/>
|
||||||
<parent link="RR_upper_leg"/>
|
<parent link="RR_upper_leg"/>
|
||||||
<child link="RR_lower_leg"/>
|
<child link="RR_lower_leg"/>
|
||||||
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
|
<origin rpy="0 0 0" xyz="0.02069 -0.20833 -0.1422"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
<link name="RL_hip_motor">
|
<link name="RL_hip_motor">
|
||||||
<contact>
|
<contact>
|
||||||
<lateral_friction value="1"/>
|
<lateral_friction value="1"/>
|
||||||
</contact>
|
</contact>
|
||||||
@@ -375,7 +368,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="green"/>
|
<material name="green"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -383,21 +376,21 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
<mesh filename="hip_motor.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="RL_hip_motor_2_chassis_joint" type="continuous">
|
<joint name="RL_hip_motor_2_chassis_joint" type="continuous">
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
<parent link="chassis"/>
|
<parent link="chassis"/>
|
||||||
<child link="RL_hip_motor"/>
|
<child link="RL_hip_motor"/>
|
||||||
|
|
||||||
<origin rpy="0 0 0" xyz="0.0817145 0 -0.194401"/>
|
<origin rpy="0 0 0" xyz="0.0817145 0 -0.194401"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="RL_upper_leg">
|
<link name="RL_upper_leg">
|
||||||
<contact>
|
<contact>
|
||||||
@@ -411,7 +404,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="upper_leg.stl" scale="1 1 1"/>
|
<mesh filename="upper_leg.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue"/>
|
<material name="blue"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -419,7 +412,7 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
|
<mesh filename="upper_leg_left_vhacd.obj" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
@@ -427,13 +420,13 @@
|
|||||||
|
|
||||||
|
|
||||||
<joint name="RL_upper_leg_2_hip_motor_joint" type="continuous">
|
<joint name="RL_upper_leg_2_hip_motor_joint" type="continuous">
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="1 0 0"/>
|
||||||
<parent link="RL_hip_motor"/>
|
<parent link="RL_hip_motor"/>
|
||||||
<child link="RL_upper_leg"/>
|
<child link="RL_upper_leg"/>
|
||||||
<origin rpy="0 0 0" xyz="0.055855 0 0"/>
|
<origin rpy="0 0 0" xyz="0.055855 0 0"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
|
||||||
<link name="RL_lower_leg">
|
<link name="RL_lower_leg">
|
||||||
@@ -448,7 +441,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="red"/>
|
<material name="red"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -456,20 +449,20 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
<mesh filename="lower_leg_3.stl" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<joint name="RL_lower_leg_2_upper_leg_joint" type="continuous">
|
<joint name="RL_lower_leg_2_upper_leg_joint" type="continuous">
|
||||||
<axis xyz="1 0 0"/>
|
<axis xyz="1 0 0"/>
|
||||||
<parent link="RL_upper_leg"/>
|
<parent link="RL_upper_leg"/>
|
||||||
<child link="RL_lower_leg"/>
|
<child link="RL_lower_leg"/>
|
||||||
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
|
<origin rpy="0 0 0" xyz="-0.02069 -0.20833 -0.1422"/>
|
||||||
<limit effort="100" velocity="100"/>
|
<limit effort="100" velocity="100"/>
|
||||||
<joint_properties damping=".0" friction=".0"/>
|
<joint_properties damping=".0" friction=".0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="toeRL">
|
<link name="toeRL">
|
||||||
<contact>
|
<contact>
|
||||||
@@ -504,7 +497,7 @@
|
|||||||
<dynamics damping="0.0" friction="0.0"/>
|
<dynamics damping="0.0" friction="0.0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="toeRR">
|
<link name="toeRR">
|
||||||
<contact>
|
<contact>
|
||||||
<friction_anchor/>
|
<friction_anchor/>
|
||||||
<stiffness value="30000.0"/>
|
<stiffness value="30000.0"/>
|
||||||
@@ -537,7 +530,7 @@
|
|||||||
<dynamics damping="0.0" friction="0.0"/>
|
<dynamics damping="0.0" friction="0.0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="toeFL">
|
<link name="toeFL">
|
||||||
<contact>
|
<contact>
|
||||||
<friction_anchor/>
|
<friction_anchor/>
|
||||||
<stiffness value="30000.0"/>
|
<stiffness value="30000.0"/>
|
||||||
@@ -570,7 +563,7 @@
|
|||||||
<dynamics damping="0.0" friction="0.0"/>
|
<dynamics damping="0.0" friction="0.0"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link name="toeFR">
|
<link name="toeFR">
|
||||||
<contact>
|
<contact>
|
||||||
<friction_anchor/>
|
<friction_anchor/>
|
||||||
<stiffness value="30000.0"/>
|
<stiffness value="30000.0"/>
|
||||||
|
|||||||
Reference in New Issue
Block a user