|
17 | 17 | <xacro:arg name="safety_k_position" default="20"/>
|
18 | 18 | <!-- ros2_control related parameters -->
|
19 | 19 | <xacro:arg name="headless_mode" default="false" />
|
| 20 | + <!-- tool communication related parameters--> |
20 | 21 | <xacro:arg name="use_tool_communication" default="false" />
|
| 22 | + <xacro:arg name="tool_voltage" default="24" /> |
| 23 | + <xacro:arg name="tool_parity" default="0" /> |
| 24 | + <xacro:arg name="tool_baud_rate" default="115200" /> |
| 25 | + <xacro:arg name="tool_stop_bits" default="1" /> |
| 26 | + <xacro:arg name="tool_rx_idle_chars" default="1.5" /> |
| 27 | + <xacro:arg name="tool_tx_idle_chars" default="3.5" /> |
| 28 | + <xacro:arg name="tool_device_name" default="/tmp/ttyUR" /> |
| 29 | + <xacro:arg name="tool_tcp_port" default="54321" /> |
21 | 30 |
|
22 | 31 | <!-- Simulation parameters -->
|
23 | 32 | <xacro:arg name="use_fake_hardware" default="false" />
|
|
54 | 63 | sim_ignition="$(arg sim_ignition)"
|
55 | 64 | headless_mode="$(arg headless_mode)"
|
56 | 65 | initial_positions="${load_yaml(initial_positions_file)}"
|
57 |
| - use_tool_communication="$(arg use_tool_communication)" > |
| 66 | + use_tool_communication="$(arg use_tool_communication)" |
| 67 | + tool_voltage="$(arg tool_voltage)" |
| 68 | + tool_parity="$(arg tool_parity)" |
| 69 | + tool_baud_rate="$(arg tool_baud_rate)" |
| 70 | + tool_stop_bits="$(arg tool_stop_bits)" |
| 71 | + tool_rx_idle_chars="$(arg tool_rx_idle_chars)" |
| 72 | + tool_tx_idle_chars="$(arg tool_tx_idle_chars)" |
| 73 | + tool_device_name="$(arg tool_device_name)" |
| 74 | + tool_tcp_port="$(arg tool_tcp_port)" > |
58 | 75 | <origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
|
59 | 76 | </xacro:ur_robot>
|
60 | 77 |
|
|
0 commit comments