Skip to content

Commit

Permalink
ackermann: remove rotation limits for wheel motors
Browse files Browse the repository at this point in the history
  • Loading branch information
chfriedrich98 committed Nov 26, 2024
1 parent 6cfc59c commit a6c7ef4
Showing 1 changed file with 0 additions and 20 deletions.
20 changes: 0 additions & 20 deletions models/rover_ackermann/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -333,11 +333,6 @@
<pose relative_to="servo_1">0 0 0 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>

</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
Expand All @@ -351,11 +346,6 @@
<pose relative_to="servo_0 ">0 0 0 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>

</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
Expand All @@ -369,11 +359,6 @@
<pose relative_to="base_link">-0.192 -.1 0 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>

</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
Expand All @@ -387,11 +372,6 @@
<pose relative_to="base_link">-0.192 .1 0 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>

</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
Expand Down

0 comments on commit a6c7ef4

Please sign in to comment.