|
12 | 12 | use_tool_communication:=false
|
13 | 13 | script_filename output_recipe_filename
|
14 | 14 | input_recipe_filename tf_prefix
|
15 |
| - hash_kinematics robot_ip"> |
| 15 | + hash_kinematics robot_ip |
| 16 | + tool_voltage:=24 tool_parity:=0 tool_baud_rate:=115200 tool_stop_bits:=1 |
| 17 | + tool_rx_idle_chars:=1.5 tool_tx_idle_chars:=3.5 tool_device_name:=/tmp/ttyUR tool_tcp_port:=54321"> |
16 | 18 |
|
17 | 19 | <ros2_control name="${name}" type="system">
|
18 | 20 | <hardware>
|
|
42 | 44 | <param name="servoj_lookahead_time">0.03</param>
|
43 | 45 | <param name="use_tool_communication">${use_tool_communication}</param>
|
44 | 46 | <param name="kinematics/hash">${hash_kinematics}</param>
|
45 |
| - <param name="tool_voltage">0</param> |
46 |
| - <param name="tool_parity">0</param> |
47 |
| - <param name="tool_baud_rate">115200</param> |
48 |
| - <param name="tool_stop_bits">1</param> |
49 |
| - <param name="tool_rx_idle_chars">1.5</param> |
50 |
| - <param name="tool_tx_idle_chars">3.5</param> |
51 |
| - <param name="tool_device_name">/tmp/ttyUR</param> |
52 |
| - <param name="tool_tcp_port">54321</param> |
| 47 | + <param name="tool_voltage">${tool_voltage}</param> |
| 48 | + <param name="tool_parity">${tool_parity}</param> |
| 49 | + <param name="tool_baud_rate">${tool_baud_rate}</param> |
| 50 | + <param name="tool_stop_bits">${tool_stop_bits}</param> |
| 51 | + <param name="tool_rx_idle_chars">${tool_rx_idle_chars}</param> |
| 52 | + <param name="tool_tx_idle_chars">${tool_tx_idle_chars}</param> |
| 53 | + <param name="tool_device_name">${tool_device_name}</param> |
| 54 | + <param name="tool_tcp_port">${tool_tcp_port}</param> |
53 | 55 | </xacro:unless>
|
54 | 56 | </hardware>
|
55 | 57 | <joint name="${prefix}shoulder_pan_joint">
|
|
0 commit comments