Skip to content

Commit d0db83f

Browse files
Add limits to the continuous joints (ros-controls#387)
1 parent 9492e47 commit d0db83f

File tree

2 files changed

+4
-0
lines changed

2 files changed

+4
-0
lines changed

ros2_control_demo_description/diffbot/urdf/diffbot_description.urdf.xacro

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@
4949
<origin xyz="0 -${base_width/2} ${z_offset}" rpy="0 0 0"/>
5050
<axis xyz="0 1 0"/>
5151
<dynamics damping="0.2"/>
52+
<limit effort="100" velocity="1.0"/>
5253
</joint>
5354

5455
<!-- left wheel Link -->
@@ -84,6 +85,7 @@
8485
<origin xyz="0 ${base_width/2} ${z_offset}" rpy="0 0 0"/>
8586
<axis xyz="0 1 0"/>
8687
<dynamics damping="0.2"/>
88+
<limit effort="100" velocity="1.0"/>
8789
</joint>
8890

8991
<!-- right wheel Link -->

ros2_control_demo_description/rrbot/urdf/rrbot_description.urdf.xacro

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,7 @@
5050
<origin xyz="0 ${width} ${height1 - axel_offset}" rpy="0 0 0"/>
5151
<axis xyz="0 1 0"/>
5252
<dynamics damping="0.7"/>
53+
<limit effort="100" velocity="1.0"/>
5354
</joint>
5455

5556
<!-- Middle Link -->
@@ -85,6 +86,7 @@
8586
<origin xyz="0 ${width} ${height2 - axel_offset*2}" rpy="0 0 0"/>
8687
<axis xyz="0 1 0"/>
8788
<dynamics damping="0.7"/>
89+
<limit effort="100" velocity="1.0"/>
8890
</joint>
8991

9092
<!-- Top Link -->

0 commit comments

Comments
 (0)