Skip to content

Commit e484f6d

Browse files
livanov93Felix Exner
authored andcommitted
Propagate tool parameters.
1 parent 12e7b18 commit e484f6d

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
@@ -12,7 +12,9 @@
1212
use_tool_communication:=false
1313
script_filename output_recipe_filename
1414
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">
1618

1719
<ros2_control name="${name}" type="system">
1820
<hardware>
@@ -42,14 +44,14 @@
4244
<param name="servoj_lookahead_time">0.03</param>
4345
<param name="use_tool_communication">${use_tool_communication}</param>
4446
<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>
5355
</xacro:unless>
5456
</hardware>
5557
<joint name="${prefix}shoulder_pan_joint">

urdf/ur.urdf.xacro

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,16 @@
1717
<xacro:arg name="safety_k_position" default="20"/>
1818
<!-- ros2_control related parameters -->
1919
<xacro:arg name="headless_mode" default="false" />
20+
<!-- tool communication related parameters-->
2021
<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" />
2130

2231
<!-- Simulation parameters -->
2332
<xacro:arg name="use_fake_hardware" default="false" />

urdf/ur_macro.xacro

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,15 @@
7272
sim_ignition:=false
7373
headless_mode:=false
7474
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)}
75-
use_tool_communication:=false">
75+
use_tool_communication:=false
76+
tool_voltage:=24
77+
tool_parity:=0
78+
tool_baud_rate:=115200
79+
tool_stop_bits:=1
80+
tool_rx_idle_chars:=1.5
81+
tool_tx_idle_chars:=3.5
82+
tool_device_name:=/tmp/ttyUR
83+
tool_tcp_port:=54321" >
7684

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

0 commit comments

Comments
 (0)