Skip to content

Commit

Permalink
Add limits to the continuous joints (#387) (#411)
Browse files Browse the repository at this point in the history
(cherry picked from commit d0db83f)

Co-authored-by: Christoph Fröhlich <christophfroehlich@users.noreply.github.com>
  • Loading branch information
mergify[bot] and christophfroehlich authored Dec 24, 2023
1 parent 37e30b7 commit 2a7fbea
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@
<origin xyz="0 -${base_width/2} ${z_offset}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.2"/>
<limit effort="100" velocity="1.0"/>
</joint>

<!-- left wheel Link -->
Expand Down Expand Up @@ -84,6 +85,7 @@
<origin xyz="0 ${base_width/2} ${z_offset}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.2"/>
<limit effort="100" velocity="1.0"/>
</joint>

<!-- right wheel Link -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@
<origin xyz="0 ${width} ${height1 - axel_offset}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.7"/>
<limit effort="100" velocity="1.0"/>
</joint>

<!-- Middle Link -->
Expand Down Expand Up @@ -85,6 +86,7 @@
<origin xyz="0 ${width} ${height2 - axel_offset*2}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.7"/>
<limit effort="100" velocity="1.0"/>
</joint>

<!-- Top Link -->
Expand Down

0 comments on commit 2a7fbea

Please sign in to comment.