Skip to content

Commit

Permalink
Fix: Isolate Universal Robots driver and client library dependencies (#…
Browse files Browse the repository at this point in the history
  • Loading branch information
luis-camero authored Feb 7, 2025
1 parent 0f122b7 commit 4134d15
Showing 1 changed file with 49 additions and 40 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -59,14 +59,33 @@
<xacro:property name="_safety_limits" value="false" lazy_eval="false"/>
<xacro:property name="_safety_pos_margin" value="0.15" lazy_eval="false"/>
<xacro:property name="_safety_k_position" value="20" lazy_eval="false"/>
<!-- Default Description Parameters Overwrites -->
<xacro:if value="${initial_positions != ''}"> <xacro:property name="_initial_positions" value="${initial_positions}" lazy_eval="false"/> </xacro:if>
<!-- if initial positions file is passed, overwrite initial positions parameter -->
<xacro:if value="${initial_positions_file != ''}"> <xacro:property name="_initial_positions" value="${xacro.load_yaml(initial_positions_file)}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${joint_limits_parameters_file != ''}"> <xacro:property name="_joint_limits_parameters_file" value="${joint_limits_parameters_file}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${kinematics_parameters_file != ''}"> <xacro:property name="_kinematics_parameters_file" value="${kinematics_parameters_file}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${physical_parameters_file != ''}"> <xacro:property name="_physical_parameters_file" value="${physical_parameters_file}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${visual_parameters_file != ''}"> <xacro:property name="$_visual_parameters_file" value="${visual_parameters_file}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${safety_limits != ''}"> <xacro:property name="_safety_limits" value="${safety_limits}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${safety_pos_margin != ''}"> <xacro:property name="_safety_pos_margin" value="${safety_pos_margin}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${safety_k_position != ''}"> <xacro:property name="_safety_k_position" value="${safety_k_position}" lazy_eval="false"/> </xacro:if>

<!-- Default Simulation Parameters -->
<xacro:property name="_use_fake_hardware" value="false" />
<xacro:property name="_fake_sensor_commands" value="false" />
<xacro:property name="_sim_gazebo" value="false" />
<xacro:property name="_sim_ignition" value="$(arg is_sim)" />
<!-- Default Simulation Parameters Overwrites -->
<xacro:if value="${use_fake_hardware != ''}"> <xacro:property name="_use_fake_hardware" value="${use_fake_hardware}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${fake_sensor_commands != ''}"> <xacro:property name="_fake_sensor_commands" value="${fake_sensor_commands}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${sim_gazebo != ''}"> <xacro:property name="_sim_gazebo" value="${sim_gazebo}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${sim_ignition != ''}"> <xacro:property name="_sim_ignition" value="${sim_ignition}" lazy_eval="false"/> </xacro:if>

<!-- Default ros2_control Parameters -->
<xacro:property name="_generate_ros2_control_tag" value="$(arg use_manipulation_controllers)" lazy_eval="false"/>
<xacro:property name="_headless_mode" value="false" lazy_eval="false"/>
<xacro:property name="_robot_ip" value="192.168.131.40" lazy_eval="false"/>
<xacro:property name="_script_filename" value="$(find ur_client_library)/resources/external_control.urscript" lazy_eval="false"/>
<xacro:property name="_output_recipe_filename" value="$(find ur_robot_driver)/resources/rtde_output_recipe.txt" lazy_eval="false"/>
<xacro:property name="_input_recipe_filename" value="$(find ur_robot_driver)/resources/rtde_input_recipe.txt" lazy_eval="false"/>
<xacro:property name="_reverse_ip" value="0.0.0.0" lazy_eval="false"/>
<xacro:property name="_script_command_port" value="50004" lazy_eval="false"/>
<xacro:property name="_reverse_port" value="50001" lazy_eval="false"/>
Expand All @@ -75,42 +94,10 @@
<xacro:property name="_transmission_hw_interface" value="hardware_interface/PositionJointInterface" lazy_eval="false"/>
<xacro:property name="_non_blocking_read" value="true" lazy_eval="false"/>
<xacro:property name="_keep_alive_count" value="2.0" lazy_eval="false"/>

<!-- Default Tool Communication Parameters -->
<xacro:property name="_use_tool_communication" value="false" lazy_eval="false"/>
<xacro:property name="_tool_voltage" value="0" lazy_eval="false"/>
<xacro:property name="_tool_parity" value="0" lazy_eval="false"/>
<xacro:property name="_tool_baud_rate" value="115200" lazy_eval="false"/>
<xacro:property name="_tool_stop_bits" value="1" lazy_eval="false"/>
<xacro:property name="_tool_rx_idle_chars" value="1.5" lazy_eval="false"/>
<xacro:property name="_tool_tx_idle_chars" value="3.5" lazy_eval="false"/>
<xacro:property name="_tool_device_name" value="/tmp/ttyUR" lazy_eval="false"/>
<xacro:property name="_tool_tcp_port" value="54321" lazy_eval="false"/>

<!-- Default Simulation Parameters -->
<xacro:property name="_use_fake_hardware" value="false" />
<xacro:property name="_fake_sensor_commands" value="false" />
<xacro:property name="_sim_gazebo" value="false" />
<xacro:property name="_sim_ignition" value="$(arg is_sim)" />

<!-- Parameter Overwrites -->
<xacro:if value="${initial_positions != ''}"> <xacro:property name="_initial_positions" value="${initial_positions}" lazy_eval="false"/> </xacro:if>
<!-- if initial positions file is passed, overwrite initial positions parameter -->
<xacro:if value="${initial_positions_file != ''}"> <xacro:property name="_initial_positions" value="${xacro.load_yaml(initial_positions_file)}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${joint_limits_parameters_file != ''}"> <xacro:property name="_joint_limits_parameters_file" value="${joint_limits_parameters_file}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${kinematics_parameters_file != ''}"> <xacro:property name="_kinematics_parameters_file" value="${kinematics_parameters_file}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${physical_parameters_file != ''}"> <xacro:property name="_physical_parameters_file" value="${physical_parameters_file}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${visual_parameters_file != ''}"> <xacro:property name="$_visual_parameters_file" value="${visual_parameters_file}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${safety_limits != ''}"> <xacro:property name="_safety_limits" value="${safety_limits}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${safety_pos_margin != ''}"> <xacro:property name="_safety_pos_margin" value="${safety_pos_margin}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${safety_k_position != ''}"> <xacro:property name="_safety_k_position" value="${safety_k_position}" lazy_eval="false"/> </xacro:if>

<!-- Default ros2_control Parameters Overwrites -->
<xacro:if value="${generate_ros2_control_tag != ''}"> <xacro:property name="_generate_ros2_control_tag" value="${generate_ros2_control_tag}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${headless_mode != ''}"> <xacro:property name="_headless_mode" value="${headless_mode}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${robot_ip != ''}"> <xacro:property name="_robot_ip" value="${robot_ip}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${script_filename != ''}"> <xacro:property name="_script_filename" value="${script_filename}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${output_recipe_filename != ''}"> <xacro:property name="_output_recipe_filename" value="${output_recipe_filename}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${input_recipe_filename != ''}"> <xacro:property name="_input_recipe_filename" value="${input_recipe_filename}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${reverse_ip != ''}"> <xacro:property name="_reverse_ip" value="${reverse_ip}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${script_command_port != ''}"> <xacro:property name="_script_command_port" value="${script_command_port}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${reverse_port != ''}"> <xacro:property name="_reverse_port" value="${reverse_port}" lazy_eval="false"/> </xacro:if>
Expand All @@ -119,7 +106,33 @@
<xacro:if value="${transmission_hw_interface != ''}"> <xacro:property name="_transmission_hw_interface" value="${transmission_hw_interface}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${non_blocking_read != ''}"> <xacro:property name="_non_blocking_read" value="${non_blocking_read}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${keep_alive_count != ''}"> <xacro:property name="_keep_alive_count" value="${keep_alive_count}" lazy_eval="false"/> </xacro:if>
<!-- Driver Dependent Parameters -->
<xacro:if value="${_generate_ros2_control_tag and not _use_fake_hardware and not _sim_ignition}">
<xacro:property name="_script_filename" value="$(find ur_client_library)/resources/external_control.urscript" lazy_eval="false"/>
<xacro:property name="_output_recipe_filename" value="$(find ur_robot_driver)/resources/rtde_output_recipe.txt" lazy_eval="false"/>
<xacro:property name="_input_recipe_filename" value="$(find ur_robot_driver)/resources/rtde_input_recipe.txt" lazy_eval="false"/>
</xacro:if>
<xacro:unless value="${_generate_ros2_control_tag and not _use_fake_hardware and not _sim_ignition}">
<xacro:property name="_script_filename" value="" lazy_eval="false"/>
<xacro:property name="_output_recipe_filename" value="" lazy_eval="false"/>
<xacro:property name="_input_recipe_filename" value="" lazy_eval="false"/>
</xacro:unless>
<!-- Driver Dependent Parameters Overwrites -->
<xacro:if value="${script_filename != ''}"> <xacro:property name="_script_filename" value="${script_filename}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${output_recipe_filename != ''}"> <xacro:property name="_output_recipe_filename" value="${output_recipe_filename}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${input_recipe_filename != ''}"> <xacro:property name="_input_recipe_filename" value="${input_recipe_filename}" lazy_eval="false"/> </xacro:if>

<!-- Default Tool Communication Parameters -->
<xacro:property name="_use_tool_communication" value="false" lazy_eval="false"/>
<xacro:property name="_tool_voltage" value="0" lazy_eval="false"/>
<xacro:property name="_tool_parity" value="0" lazy_eval="false"/>
<xacro:property name="_tool_baud_rate" value="115200" lazy_eval="false"/>
<xacro:property name="_tool_stop_bits" value="1" lazy_eval="false"/>
<xacro:property name="_tool_rx_idle_chars" value="1.5" lazy_eval="false"/>
<xacro:property name="_tool_tx_idle_chars" value="3.5" lazy_eval="false"/>
<xacro:property name="_tool_device_name" value="/tmp/ttyUR" lazy_eval="false"/>
<xacro:property name="_tool_tcp_port" value="54321" lazy_eval="false"/>
<!-- Tool Communication Parameter Overwrites -->
<xacro:if value="${use_tool_communication != ''}"> <xacro:property name="_use_tool_communication" value="${use_tool_communication}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${tool_voltage != ''}"> <xacro:property name="_tool_voltage" value="${tool_voltage}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${tool_parity != ''}"> <xacro:property name="_tool_parity" value="${tool_parity}" lazy_eval="false"/> </xacro:if>
Expand All @@ -130,10 +143,6 @@
<xacro:if value="${tool_device_name != ''}"> <xacro:property name="_tool_device_name" value="${tool_device_name}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${tool_tcp_port != ''}"> <xacro:property name="_tool_tcp_port" value="${tool_tcp_port}" lazy_eval="false"/> </xacro:if>

<xacro:if value="${use_fake_hardware != ''}"> <xacro:property name="_use_fake_hardware" value="${use_fake_hardware}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${fake_sensor_commands != ''}"> <xacro:property name="_fake_sensor_commands" value="${fake_sensor_commands}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${sim_gazebo != ''}"> <xacro:property name="_sim_gazebo" value="${sim_gazebo}" lazy_eval="false"/> </xacro:if>
<xacro:if value="${sim_ignition != ''}"> <xacro:property name="_sim_ignition" value="${sim_ignition}" lazy_eval="false"/> </xacro:if>

<!-- Universal_Robots_ROS2_Description -->
<xacro:ur_robot
Expand Down

0 comments on commit 4134d15

Please sign in to comment.