|
64 | 64 | <parent link="pelvis_link" /> |
65 | 65 | <child link="L_hip_yaw_link" /> |
66 | 66 | <axis xyz="0 0 1" /> |
67 | | - <limit lower="-0.55" upper="0.55" effort="50" velocity="10.472"/> |
| 67 | + <limit lower="-0.55" upper="0.55" effort="30" velocity="10.472"/> |
68 | 68 | </joint> |
69 | 69 | <link name="L_hip_roll_link"> |
70 | 70 | <inertial> |
|
93 | 93 | <parent link="L_hip_yaw_link" /> |
94 | 94 | <child link="L_hip_roll_link" /> |
95 | 95 | <axis xyz="1 0 0" /> |
96 | | - <limit lower="-0.2618" upper="0.524" effort="50" velocity="10.471975511965978"/> |
| 96 | + <limit lower="-0.2618" upper="0.524" effort="45" velocity="10.471975511965978"/> |
97 | 97 | </joint> |
98 | 98 | <link name="L_hip_pitch_link"> |
99 | 99 | <inertial> |
|
122 | 122 | <parent link="L_hip_roll_link" /> |
123 | 123 | <child link="L_hip_pitch_link" /> |
124 | 124 | <axis xyz="0 -1 0" /> |
125 | | - <limit lower="-0.5236" upper="2.13" effort="72" velocity="9.163"/> |
| 125 | + <limit lower="-0.5236" upper="2.13" effort="45" velocity="9.163"/> |
126 | 126 | </joint> |
127 | 127 | <link name="L_knee_pitch_link"> |
128 | 128 | <inertial> |
|
240 | 240 | <parent link="pelvis_link" /> |
241 | 241 | <child link="R_hip_yaw_link" /> |
242 | 242 | <axis xyz="0 0 -1" /> |
243 | | - <limit lower="-0.55" upper="0.55" effort="50" velocity="10.472"/> |
| 243 | + <limit lower="-0.55" upper="0.55" effort="30" velocity="10.472"/> |
244 | 244 | </joint> |
245 | 245 | <link name="R_hip_roll_link"> |
246 | 246 | <inertial> |
|
269 | 269 | <parent link="R_hip_yaw_link" /> |
270 | 270 | <child link="R_hip_roll_link" /> |
271 | 271 | <axis xyz="-1 0 0" /> |
272 | | - <limit lower="-0.2618" upper="0.524" effort="50" velocity="10.472"/> |
| 272 | + <limit lower="-0.2618" upper="0.524" effort="45" velocity="10.472"/> |
273 | 273 | </joint> |
274 | 274 | <link name="R_hip_pitch_link"> |
275 | 275 | <inertial> |
|
298 | 298 | <parent link="R_hip_roll_link" /> |
299 | 299 | <child link="R_hip_pitch_link" /> |
300 | 300 | <axis xyz="0 -1 0" /> |
301 | | - <limit lower="-0.5236" upper="2.13" effort="72" velocity="9.163"/> |
| 301 | + <limit lower="-0.5236" upper="2.13" effort="45" velocity="9.163"/> |
302 | 302 | </joint> |
303 | 303 | <link name="R_knee_pitch_link"> |
304 | 304 | <inertial> |
|
0 commit comments