Skip to content

Commit 3c349d5

Browse files
author
bailaC
authored
Correcting Example 3 (#40)
1 parent 701577a commit 3c349d5

File tree

1 file changed

+26
-28
lines changed

1 file changed

+26
-28
lines changed

design_drafts/components_architecture_and_urdf_examples.md

Lines changed: 26 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -153,34 +153,32 @@ Note:
153153
<ros2_control name="RRBotSystemWithSensor" type="system">
154154
<hardware>
155155
<plugin>ros2_control_demo_hardware/RRBotSystemWithSensorHardware</plugin>
156-
<param name="example_param_write_for_sec">2</param>
157-
<param name="example_param_read_for_sec">2</param>
158-
</hardware>
159-
<joint name="joint1">
160-
<command_interface name="position">
161-
<param name="min">-1</param>
162-
<param name="max">1</param>
163-
</command_interface>
164-
<state_interface name="position"/>
165-
</joint>
166-
<joint name="joint2">
167-
<command_interface name="position">
168-
<param name="min">-1</param>
169-
<param name="max">1</param>
170-
</command_interface>
171-
<state_interface name="position"/>
172-
</joint>
173-
<sensor name="tcp_fts_sensor">
174-
<state_interface name="fx"/>
175-
<state_interface name="fy"/>
176-
<state_interface name="fz"/>
177-
<state_interface name="tx"/>
178-
<state_interface name="ty"/>
179-
<state_interface name="tz"/>
180-
<param name="frame_id">kuka_tcp</param>
181-
<param name="lower_limits">-100</param>
182-
<param name="upper_limits">100</param>
183-
</sensor>
156+
<param name="example_param_hw_start_duration_sec">2.0</param>
157+
<param name="example_param_hw_stop_duration_sec">3.0</param>
158+
<param name="example_param_hw_slowdown">2.0</param>
159+
<param name="example_param_max_sensor_change">5.0</param>
160+
</hardware>
161+
<joint name="joint1">
162+
<command_interface name="position">
163+
<param name="min">-1</param>
164+
<param name="max">1</param>
165+
</command_interface>
166+
<state_interface name="position"/>
167+
</joint>
168+
<joint name="joint2">
169+
<command_interface name="position">
170+
<param name="min">-1</param>
171+
<param name="max">1</param>
172+
</command_interface>
173+
<state_interface name="position"/>
174+
</joint>
175+
<sensor name="tcp_fts_sensor">
176+
<state_interface name="fx"/>
177+
<state_interface name="tz"/>
178+
<param name="frame_id">rrbot_tcp</param>
179+
<param name="fx_range">100</param>
180+
<param name="tz_range">15</param>
181+
</sensor>
184182
</ros2_control>
185183
```
186184

0 commit comments

Comments
 (0)