|
61 | 61 | <child link="${prefix}link1"/> |
62 | 62 | <axis xyz="0 0 1"/> |
63 | 63 | <limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/> |
| 64 | + <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/> |
64 | 65 | </joint> |
65 | 66 | <xacro:link name="link2"> |
66 | 67 | <self_collision_geometries> |
|
91 | 92 | <child link="${prefix}link2"/> |
92 | 93 | <axis xyz="0 0 1"/> |
93 | 94 | <limit effort="87" lower="-1.7628" upper="1.7628" velocity="2.1750"/> |
| 95 | + <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/> |
94 | 96 | </joint> |
95 | 97 | <xacro:link name="link3"> |
96 | 98 | <self_collision_geometries> |
|
121 | 123 | <child link="${prefix}link3"/> |
122 | 124 | <axis xyz="0 0 1"/> |
123 | 125 | <limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/> |
| 126 | + <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/> |
124 | 127 | </joint> |
125 | 128 | <xacro:link name="link4"> |
126 | 129 | <self_collision_geometries> |
|
151 | 154 | <child link="${prefix}link4"/> |
152 | 155 | <axis xyz="0 0 1"/> |
153 | 156 | <limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750"/> |
| 157 | + <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/> |
154 | 158 | </joint> |
155 | 159 | <xacro:link name="link5"> |
156 | 160 | <self_collision_geometries> |
|
199 | 203 | <child link="${prefix}link5"/> |
200 | 204 | <axis xyz="0 0 1"/> |
201 | 205 | <limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/> |
| 206 | + <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/> |
202 | 207 | </joint> |
203 | 208 | <xacro:link name="link6"> |
204 | 209 | <self_collision_geometries> |
|
229 | 234 | <child link="${prefix}link6"/> |
230 | 235 | <axis xyz="0 0 1"/> |
231 | 236 | <limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.6100"/> |
| 237 | + <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/> |
232 | 238 | </joint> |
233 | 239 | <xacro:link name="link7"> |
234 | 240 | <self_collision_geometries> |
|
259 | 265 | <child link="${prefix}link7"/> |
260 | 266 | <axis xyz="0 0 1"/> |
261 | 267 | <limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/> |
| 268 | + <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/> |
262 | 269 | </joint> |
263 | 270 | <link name="${prefix}link8"> |
264 | 271 | <collision> |
|
0 commit comments