diff --git a/urdf/ur.ros2_control.xacro b/urdf/ur.ros2_control.xacro index 6a546ef..bac1b45 100644 --- a/urdf/ur.ros2_control.xacro +++ b/urdf/ur.ros2_control.xacro @@ -12,7 +12,9 @@ use_tool_communication:=false script_filename output_recipe_filename input_recipe_filename tf_prefix - hash_kinematics robot_ip"> + hash_kinematics robot_ip + tool_voltage:=24 tool_parity:=0 tool_baud_rate:=115200 tool_stop_bits:=1 + tool_rx_idle_chars:=1.5 tool_tx_idle_chars:=3.5 tool_device_name:=/tmp/ttyUR tool_tcp_port:=54321"> @@ -42,14 +44,14 @@ 0.03 ${use_tool_communication} ${hash_kinematics} - 0 - 0 - 115200 - 1 - 1.5 - 3.5 - /tmp/ttyUR - 54321 + ${tool_voltage} + ${tool_parity} + ${tool_baud_rate} + ${tool_stop_bits} + ${tool_rx_idle_chars} + ${tool_tx_idle_chars} + ${tool_device_name} + ${tool_tcp_port} diff --git a/urdf/ur.urdf.xacro b/urdf/ur.urdf.xacro index 0868b96..cf6d235 100644 --- a/urdf/ur.urdf.xacro +++ b/urdf/ur.urdf.xacro @@ -17,7 +17,16 @@ + + + + + + + + + @@ -54,7 +63,15 @@ sim_ignition="$(arg sim_ignition)" headless_mode="$(arg headless_mode)" initial_positions="${load_yaml(initial_positions_file)}" - use_tool_communication="$(arg use_tool_communication)" > + use_tool_communication="$(arg use_tool_communication)" + tool_voltage="$(arg tool_voltage)" + tool_parity="$(arg tool_parity)" + tool_baud_rate="$(arg tool_baud_rate)" + tool_stop_bits="$(arg tool_stop_bits)" + tool_rx_idle_chars="$(arg tool_rx_idle_chars)" + tool_tx_idle_chars="$(arg tool_tx_idle_chars)" + tool_device_name="$(arg tool_device_name)" + tool_tcp_port="$(arg tool_tcp_port)" > diff --git a/urdf/ur_macro.xacro b/urdf/ur_macro.xacro index 73c996c..34ca5f5 100644 --- a/urdf/ur_macro.xacro +++ b/urdf/ur_macro.xacro @@ -72,7 +72,15 @@ sim_ignition:=false headless_mode:=false 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)} - use_tool_communication:=false"> + use_tool_communication:=false + tool_voltage:=24 + tool_parity:=0 + tool_baud_rate:=115200 + tool_stop_bits:=1 + tool_rx_idle_chars:=1.5 + tool_tx_idle_chars:=3.5 + tool_device_name:=/tmp/ttyUR + tool_tcp_port:=54321" > + use_tool_communication="${use_tool_communication}" + tool_voltage="${tool_voltage}" + tool_parity="${tool_parity}" + tool_baud_rate="${tool_baud_rate}" + tool_stop_bits="${tool_stop_bits}" + tool_rx_idle_chars="${tool_rx_idle_chars}" + tool_tx_idle_chars="${tool_tx_idle_chars}" + tool_device_name="${tool_device_name}" + tool_tcp_port="${tool_tcp_port}"/>