Skip to content

Commit

Permalink
fixes malformed pose brackets
Browse files Browse the repository at this point in the history
Signed-off-by: frederik <[email protected]>
  • Loading branch information
frede791 authored and dagar committed Feb 15, 2024
1 parent f1c461f commit 2228336
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions models/r1_rover/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@
</axis>
</joint>
<link name='lb_wheel_link'>
pose>-0.15 0.16317 0.0215 0 -0 0</pose>
<pose>-0.15 0.16317 0.0215 0 -0 0</pose>
<inertial>
<pose>0 0 0 1.57079632679 0 0</pose>
<mass>0.414</mass>
Expand Down Expand Up @@ -319,7 +319,7 @@
</inertia>
</inertial>
<collision name='rf_wheel_link_collision'>
pose>0 0 0 1.57079632679 0 0</pose>
<pose>0 0 0 1.57079632679 0 0</pose>
<geometry>
<cylinder>
<radius>0.0686</radius>
Expand Down

0 comments on commit 2228336

Please sign in to comment.