Skip to content

Commit 6cdccfc

Browse files
committed
Propagate tool parameters.
1 parent 051f472 commit 6cdccfc

File tree

3 files changed

+29
-10
lines changed

3 files changed

+29
-10
lines changed

urdf/ur.ros2_control.xacro

Lines changed: 11 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,9 @@
88
use_tool_communication:=false
99
script_filename output_recipe_filename
1010
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">
1214

1315
<ros2_control name="${name}" type="system">
1416
<hardware>
@@ -32,14 +34,14 @@
3234
<param name="servoj_lookahead_time">0.03</param>
3335
<param name="use_tool_communication">${use_tool_communication}</param>
3436
<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>
4345
</xacro:unless>
4446
</hardware>
4547
<joint name="${prefix}shoulder_pan_joint">

urdf/ur.urdf.xacro

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,16 @@
1919
<xacro:arg name="use_fake_hardware" default="false" />
2020
<xacro:arg name="fake_sensor_commands" default="false" />
2121
<xacro:arg name="headless_mode" default="false" />
22+
<!-- tool communication related parameters-->
2223
<xacro:arg name="use_tool_communication" default="false" />
24+
<xacro:arg name="tool_voltage" default="24" />
25+
<xacro:arg name="tool_parity" default="0" />
26+
<xacro:arg name="tool_baud_rate" default="115200" />
27+
<xacro:arg name="tool_stop_bits" default="1" />
28+
<xacro:arg name="tool_rx_idle_chars" default="1.5" />
29+
<xacro:arg name="tool_tx_idle_chars" default="3.5" />
30+
<xacro:arg name="tool_device_name" default="/tmp/ttyUR" />
31+
<xacro:arg name="tool_tcp_port" default="54321" />
2332

2433
<!-- initial position for fake hardware -->
2534
<xacro:arg name="initial_positions_file" default="$(find ur_description)/config/initial_positions.yaml"/>

urdf/ur_macro.xacro

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,15 @@
7070
fake_sensor_commands:=false
7171
headless_mode:=false
7272
initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}
73-
use_tool_communication:=false">
73+
use_tool_communication:=false
74+
tool_voltage:=24
75+
tool_parity:=0
76+
tool_baud_rate:=115200
77+
tool_stop_bits:=1
78+
tool_rx_idle_chars:=1.5
79+
tool_tx_idle_chars:=3.5
80+
tool_device_name:=/tmp/ttyUR
81+
tool_tcp_port:=54321" >
7482

7583
<!-- Load configuration data from the provided .yaml files -->
7684
<xacro:read_model_data

0 commit comments

Comments
 (0)