Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 11 additions & 9 deletions urdf/ur.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -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">

<ros2_control name="${name}" type="system">
<hardware>
Expand Down Expand Up @@ -42,14 +44,14 @@
<param name="servoj_lookahead_time">0.03</param>
<param name="use_tool_communication">${use_tool_communication}</param>
<param name="kinematics/hash">${hash_kinematics}</param>
<param name="tool_voltage">0</param>
<param name="tool_parity">0</param>
<param name="tool_baud_rate">115200</param>
<param name="tool_stop_bits">1</param>
<param name="tool_rx_idle_chars">1.5</param>
<param name="tool_tx_idle_chars">3.5</param>
<param name="tool_device_name">/tmp/ttyUR</param>
<param name="tool_tcp_port">54321</param>
<param name="tool_voltage">${tool_voltage}</param>
<param name="tool_parity">${tool_parity}</param>
<param name="tool_baud_rate">${tool_baud_rate}</param>
<param name="tool_stop_bits">${tool_stop_bits}</param>
<param name="tool_rx_idle_chars">${tool_rx_idle_chars}</param>
<param name="tool_tx_idle_chars">${tool_tx_idle_chars}</param>
<param name="tool_device_name">${tool_device_name}</param>
<param name="tool_tcp_port">${tool_tcp_port}</param>
</xacro:unless>
</hardware>
<joint name="${prefix}shoulder_pan_joint">
Expand Down
19 changes: 18 additions & 1 deletion urdf/ur.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,16 @@
<xacro:arg name="safety_k_position" default="20"/>
<!-- ros2_control related parameters -->
<xacro:arg name="headless_mode" default="false" />
<!-- tool communication related parameters-->
<xacro:arg name="use_tool_communication" default="false" />
<xacro:arg name="tool_voltage" default="24" />
<xacro:arg name="tool_parity" default="0" />
<xacro:arg name="tool_baud_rate" default="115200" />
<xacro:arg name="tool_stop_bits" default="1" />
<xacro:arg name="tool_rx_idle_chars" default="1.5" />
<xacro:arg name="tool_tx_idle_chars" default="3.5" />
<xacro:arg name="tool_device_name" default="/tmp/ttyUR" />
<xacro:arg name="tool_tcp_port" default="54321" />

<!-- Simulation parameters -->
<xacro:arg name="use_fake_hardware" default="false" />
Expand Down Expand Up @@ -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)" >
<origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
</xacro:ur_robot>

Expand Down
20 changes: 18 additions & 2 deletions urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -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" >

<!-- Load configuration data from the provided .yaml files -->
<xacro:read_model_data
Expand Down Expand Up @@ -105,7 +113,15 @@
tf_prefix=""
hash_kinematics="${kinematics_hash}"
robot_ip="$(arg robot_ip)"
use_tool_communication="${use_tool_communication}"/>
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}"/>

<!-- Add URDF transmission elements (for ros_control) -->
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
Expand Down