|
1 | 1 | <?xml version="1.0"?> |
2 | | -<robot name="simple_biped"> |
| 2 | +<robot name="biped_with_knees"> |
3 | 3 |
|
4 | | - <!-- Torso/Hip Link --> |
| 4 | + <!-- Torso --> |
5 | 5 | <link name="torso"> |
6 | 6 | <visual> |
7 | 7 | <geometry> |
|
23 | 23 | </inertial> |
24 | 24 | </link> |
25 | 25 |
|
26 | | - <!-- Left Leg --> |
27 | | - <link name="left_leg"> |
| 26 | + <!-- Upper and lower legs (left) --> |
| 27 | + <link name="left_upper_leg"> |
28 | 28 | <visual> |
29 | 29 | <geometry> |
30 | | - <cylinder length="0.5" radius="0.05"/> |
| 30 | + <cylinder length="0.3" radius="0.05"/> |
31 | 31 | </geometry> |
32 | | - <origin xyz="0 0 -0.25" rpy="0 0 0"/> |
| 32 | + <origin xyz="0 0 -0.15" rpy="0 0 0"/> |
33 | 33 | <material name="blue"> |
34 | 34 | <color rgba="0 0 1 1"/> |
35 | 35 | </material> |
36 | 36 | </visual> |
37 | 37 | <collision> |
38 | 38 | <geometry> |
39 | | - <cylinder length="0.5" radius="0.05"/> |
| 39 | + <cylinder length="0.3" radius="0.05"/> |
40 | 40 | </geometry> |
41 | | - <origin xyz="0 0 -0.25" rpy="0 0 0"/> |
| 41 | + <origin xyz="0 0 -0.15" rpy="0 0 0"/> |
42 | 42 | </collision> |
43 | 43 | <inertial> |
44 | | - <mass value="2.0"/> |
45 | | - <inertia ixx="0.02" ixy="0" ixz="0" iyy="0.02" iyz="0" izz="0.01"/> |
| 44 | + <mass value="1.5"/> |
| 45 | + <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/> |
46 | 46 | </inertial> |
47 | 47 | </link> |
48 | 48 |
|
49 | | - <!-- Right Leg --> |
50 | | - <link name="right_leg"> |
| 49 | + <link name="left_lower_leg"> |
51 | 50 | <visual> |
52 | 51 | <geometry> |
53 | | - <cylinder length="0.5" radius="0.05"/> |
| 52 | + <cylinder length="0.3" radius="0.04"/> |
54 | 53 | </geometry> |
55 | | - <origin xyz="0 0 -0.25" rpy="0 0 0"/> |
| 54 | + <origin xyz="0 0 -0.15" rpy="0 0 0"/> |
| 55 | + <material name="cyan"> |
| 56 | + <color rgba="0 1 1 1"/> |
| 57 | + </material> |
| 58 | + </visual> |
| 59 | + <collision> |
| 60 | + <geometry> |
| 61 | + <cylinder length="0.3" radius="0.04"/> |
| 62 | + </geometry> |
| 63 | + <origin xyz="0 0 -0.15" rpy="0 0 0"/> |
| 64 | + </collision> |
| 65 | + <inertial> |
| 66 | + <mass value="1.0"/> |
| 67 | + <inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/> |
| 68 | + </inertial> |
| 69 | + </link> |
| 70 | + |
| 71 | + <!-- Upper and lower legs (right) --> |
| 72 | + <link name="right_upper_leg"> |
| 73 | + <visual> |
| 74 | + <geometry> |
| 75 | + <cylinder length="0.3" radius="0.05"/> |
| 76 | + </geometry> |
| 77 | + <origin xyz="0 0 -0.15" rpy="0 0 0"/> |
56 | 78 | <material name="red"> |
57 | 79 | <color rgba="1 0 0 1"/> |
58 | 80 | </material> |
59 | 81 | </visual> |
60 | 82 | <collision> |
61 | 83 | <geometry> |
62 | | - <cylinder length="0.5" radius="0.05"/> |
| 84 | + <cylinder length="0.3" radius="0.05"/> |
| 85 | + </geometry> |
| 86 | + <origin xyz="0 0 -0.15" rpy="0 0 0"/> |
| 87 | + </collision> |
| 88 | + <inertial> |
| 89 | + <mass value="1.5"/> |
| 90 | + <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/> |
| 91 | + </inertial> |
| 92 | + </link> |
| 93 | + |
| 94 | + <link name="right_lower_leg"> |
| 95 | + <visual> |
| 96 | + <geometry> |
| 97 | + <cylinder length="0.3" radius="0.04"/> |
| 98 | + </geometry> |
| 99 | + <origin xyz="0 0 -0.15" rpy="0 0 0"/> |
| 100 | + <material name="pink"> |
| 101 | + <color rgba="1 0 1 1"/> |
| 102 | + </material> |
| 103 | + </visual> |
| 104 | + <collision> |
| 105 | + <geometry> |
| 106 | + <cylinder length="0.3" radius="0.04"/> |
63 | 107 | </geometry> |
64 | | - <origin xyz="0 0 -0.25" rpy="0 0 0"/> |
| 108 | + <origin xyz="0 0 -0.15" rpy="0 0 0"/> |
65 | 109 | </collision> |
66 | 110 | <inertial> |
67 | | - <mass value="2.0"/> |
68 | | - <inertia ixx="0.02" ixy="0" ixz="0" iyy="0.02" iyz="0" izz="0.01"/> |
| 111 | + <mass value="1.0"/> |
| 112 | + <inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/> |
69 | 113 | </inertial> |
70 | 114 | </link> |
71 | 115 |
|
72 | | - <!-- Left Hip Joint --> |
| 116 | + <!-- Joints --> |
| 117 | + <!-- Left hip --> |
73 | 118 | <joint name="left_hip_joint" type="revolute"> |
74 | 119 | <parent link="torso"/> |
75 | | - <child link="left_leg"/> |
| 120 | + <child link="left_upper_leg"/> |
76 | 121 | <origin xyz="0.1 0 -0.15" rpy="0 0 0"/> |
77 | 122 | <axis xyz="1 0 0"/> |
78 | 123 | <limit effort="20" lower="-1.57" upper="1.57" velocity="2.0"/> |
79 | 124 | </joint> |
80 | 125 |
|
81 | | - <!-- Right Hip Joint --> |
| 126 | + <!-- Left knee --> |
| 127 | + <joint name="left_knee_joint" type="revolute"> |
| 128 | + <parent link="left_upper_leg"/> |
| 129 | + <child link="left_lower_leg"/> |
| 130 | + <origin xyz="0 0 -0.3" rpy="0 0 0"/> |
| 131 | + <axis xyz="1 0 0"/> |
| 132 | + <limit effort="20" lower="0" upper="2.0" velocity="2.0"/> |
| 133 | + </joint> |
| 134 | + |
| 135 | + <!-- Right hip --> |
82 | 136 | <joint name="right_hip_joint" type="revolute"> |
83 | 137 | <parent link="torso"/> |
84 | | - <child link="right_leg"/> |
| 138 | + <child link="right_upper_leg"/> |
85 | 139 | <origin xyz="-0.1 0 -0.15" rpy="0 0 0"/> |
86 | 140 | <axis xyz="1 0 0"/> |
87 | 141 | <limit effort="20" lower="-1.57" upper="1.57" velocity="2.0"/> |
88 | 142 | </joint> |
89 | 143 |
|
| 144 | + <!-- Right knee --> |
| 145 | + <joint name="right_knee_joint" type="revolute"> |
| 146 | + <parent link="right_upper_leg"/> |
| 147 | + <child link="right_lower_leg"/> |
| 148 | + <origin xyz="0 0 -0.3" rpy="0 0 0"/> |
| 149 | + <axis xyz="1 0 0"/> |
| 150 | + <limit effort="20" lower="0" upper="2.0" velocity="2.0"/> |
| 151 | + </joint> |
| 152 | + |
90 | 153 | </robot> |
0 commit comments