|
8 | 8 | use_tool_communication:=false
|
9 | 9 | script_filename output_recipe_filename
|
10 | 10 | input_recipe_filename tf_prefix
|
11 |
| - hash_kinematics robot_ip"> |
| 11 | + hash_kinematics robot_ip |
| 12 | + tool_voltage:=24 tool_parity:=0 tool_baud_rate:=115200 tool_stop_bits:=1 |
| 13 | + tool_rx_idle_chars:=1.5 tool_tx_idle_chars:=3.5 tool_device_name:=/tmp/ttyUR tool_tcp_port:=54321"> |
12 | 14 |
|
13 | 15 | <ros2_control name="${name}" type="system">
|
14 | 16 | <hardware>
|
|
32 | 34 | <param name="servoj_lookahead_time">0.03</param>
|
33 | 35 | <param name="use_tool_communication">${use_tool_communication}</param>
|
34 | 36 | <param name="kinematics/hash">${hash_kinematics}</param>
|
35 |
| - <param name="tool_voltage">0</param> |
36 |
| - <param name="tool_parity">0</param> |
37 |
| - <param name="tool_baud_rate">115200</param> |
38 |
| - <param name="tool_stop_bits">1</param> |
39 |
| - <param name="tool_rx_idle_chars">1.5</param> |
40 |
| - <param name="tool_tx_idle_chars">3.5</param> |
41 |
| - <param name="tool_device_name">/tmp/ttyUR</param> |
42 |
| - <param name="tool_tcp_port">54321</param> |
| 37 | + <param name="tool_voltage">${tool_voltage}</param> |
| 38 | + <param name="tool_parity">${tool_parity}</param> |
| 39 | + <param name="tool_baud_rate">${tool_baud_rate}</param> |
| 40 | + <param name="tool_stop_bits">${tool_stop_bits}</param> |
| 41 | + <param name="tool_rx_idle_chars">${tool_rx_idle_chars}</param> |
| 42 | + <param name="tool_tx_idle_chars">${tool_tx_idle_chars}</param> |
| 43 | + <param name="tool_device_name">${tool_device_name}</param> |
| 44 | + <param name="tool_tcp_port">${tool_tcp_port}</param> |
43 | 45 | </xacro:unless>
|
44 | 46 | </hardware>
|
45 | 47 | <joint name="${prefix}shoulder_pan_joint">
|
|
0 commit comments