Skip to content
This repository has been archived by the owner on Dec 13, 2024. It is now read-only.

added more arms #301

Draft
wants to merge 2 commits into
base: main
Choose a base branch
from
Draft
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
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,22 @@
<xacro:arg name="has_tool_changer" default="true"/>
<xacro:arg name="use_pinch_links" default="true"/>
<xacro:arg name="name" default=""/>
<xacro:arg name="joint_limits_parameters_file" default=""/>
<xacro:arg name="kinematics_parameters_file" default=""/>
<xacro:arg name="physical_parameters_file" default=""/>
<xacro:arg name="visual_parameters_file" default=""/>
<!-- ur3e -->
<xacro:arg name="ur3e_kinematics_parameters_file" default="$(find ur_description)/config/ur3e/default_kinematics.yaml"/>
<xacro:arg name="ur3e_physical_parameters_file" default="$(find ur_description)/config/ur3e/physical_parameters.yaml"/>
<xacro:arg name="ur3e_visual_parameters_file" default="$(find ur_description)/config/ur3e/visual_parameters.yaml"/>
<!-- ur5e -->
<xacro:arg name="ur5e_kinematics_parameters_file" default="$(find ur_description)/config/ur5e/default_kinematics.yaml"/>
<xacro:arg name="ur5e_physical_parameters_file" default="$(find ur_description)/config/ur5e/physical_parameters.yaml"/>
<xacro:arg name="ur5e_visual_parameters_file" default="$(find ur_description)/config/ur5e/visual_parameters.yaml"/>
<!-- ur10e -->
<xacro:arg name="ur10e_kinematics_parameters_file" default="$(find ur_description)/config/ur10e/default_kinematics.yaml"/>
<xacro:arg name="ur10e_physical_parameters_file" default="$(find ur_description)/config/ur10e/physical_parameters.yaml"/>
<xacro:arg name="ur10e_visual_parameters_file" default="$(find ur_description)/config/ur10e/visual_parameters.yaml"/>
<!-- ur16e -->
<xacro:arg name="ur16e_kinematics_parameters_file" default="$(find ur_description)/config/ur16e/default_kinematics.yaml"/>
<xacro:arg name="ur16e_physical_parameters_file" default="$(find ur_description)/config/ur16e/physical_parameters.yaml"/>
<xacro:arg name="ur16e_visual_parameters_file" default="$(find ur_description)/config/ur16e/visual_parameters.yaml"/>
<xacro:arg name="headless_mode" default="false"/>
<xacro:arg name="robot_ip" default="0.0.0.0"/>
<xacro:arg name="use_tool_communication" default="false"/>
Expand All @@ -23,13 +35,122 @@
<xacro:include filename="$(find picknik_ur_base_config)/description/picknik_ur_attachments_macro.xacro"/>
<xacro:include filename="$(arg environment_xacro)"/>

<!-- Robot: contains robot description from the world frame to the tool frame -->
<xacro:picknik_ur parent="world" child="tool0" initial_positions_file="$(arg initial_positions_file)">
<origin xyz="0 0 0" rpy="0 0 ${pi/2}" />
</xacro:picknik_ur>
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro" />
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>

<link name="world" />
<!-- FIRST ROBOT -->
<!-- arm -->
<xacro:ur_robot
name="ur3e"
Copy link
Contributor Author

@MikeWrock MikeWrock Jun 30, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@rwehner186 change this (and the other lined below) to a different UR type if you don't want one of each. See:
https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/blob/rolling/urdf/ur.urdf.xacro#L8

possible 'ur_type' values: ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e, ur20 

tf_prefix="first_"
parent="world"
joint_limits_parameters_file="$(arg joint_limits_parameters_file)"
kinematics_parameters_file="$(arg ur3e_kinematics_parameters_file)"
physical_parameters_file="$(arg ur3e_physical_parameters_file)"
visual_parameters_file="$(arg ur3e_visual_parameters_file)"
use_fake_hardware="$(arg use_fake_hardware)"
initial_positions="${xacro.load_yaml(initial_positions_file)}"
headless_mode="$(arg headless_mode)"
robot_ip="$(arg robot_ip)"
script_filename="$(find ur_robot_driver)/resources/ros_control.urscript"
output_recipe_filename="$(find ur_robot_driver)/resources/rtde_output_recipe.txt"
input_recipe_filename="$(find ur_robot_driver)/resources/rtde_input_recipe.txt">
<origin xyz="0.0 -0.6 0" rpy="0 0 0" />
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@rwehner186 change the numbers here to place the arms in different locations

</xacro:ur_robot>



<xacro:picknik_ur_attachments
prefix="first"
parent="first_tool0"
child="first_grasp_link"
has_tool_changer="$(arg has_tool_changer)"
/>

<!-- SECOND ROBOT -->
<!-- arm -->
<xacro:ur_robot
name="ur5e"
tf_prefix="second_"
parent="world"
joint_limits_parameters_file="$(arg joint_limits_parameters_file)"
kinematics_parameters_file="$(arg ur5e_kinematics_parameters_file)"
physical_parameters_file="$(arg ur5e_physical_parameters_file)"
visual_parameters_file="$(arg ur5e_visual_parameters_file)"
use_fake_hardware="$(arg use_fake_hardware)"
initial_positions="${xacro.load_yaml(initial_positions_file)}"
headless_mode="$(arg headless_mode)"
robot_ip="$(arg robot_ip)"
script_filename="$(find ur_robot_driver)/resources/ros_control.urscript"
output_recipe_filename="$(find ur_robot_driver)/resources/rtde_output_recipe.txt"
input_recipe_filename="$(find ur_robot_driver)/resources/rtde_input_recipe.txt">
<origin xyz="0 -0.2 0" rpy="0 0 0" />
</xacro:ur_robot>

<xacro:picknik_ur_attachments
prefix="second"
parent="second_tool0"
child="second_grasp_link"
has_tool_changer="$(arg has_tool_changer)"
/>

<!-- THIRD ROBOT -->
<!-- arm -->
<xacro:ur_robot
name="ur10e"
tf_prefix="third_"
parent="world"
joint_limits_parameters_file="$(arg joint_limits_parameters_file)"
kinematics_parameters_file="$(arg ur10e_kinematics_parameters_file)"
physical_parameters_file="$(arg ur10e_physical_parameters_file)"
visual_parameters_file="$(arg ur10e_visual_parameters_file)"
use_fake_hardware="$(arg use_fake_hardware)"
initial_positions="${xacro.load_yaml(initial_positions_file)}"
headless_mode="$(arg headless_mode)"
robot_ip="$(arg robot_ip)"
script_filename="$(find ur_robot_driver)/resources/ros_control.urscript"
output_recipe_filename="$(find ur_robot_driver)/resources/rtde_output_recipe.txt"
input_recipe_filename="$(find ur_robot_driver)/resources/rtde_input_recipe.txt">
<origin xyz="0 0.2 0" rpy="0 0 0" />
</xacro:ur_robot>

<xacro:picknik_ur_attachments
prefix="third"
parent="third_tool0"
child="third_grasp_link"
has_tool_changer="$(arg has_tool_changer)"
/>

<!-- FOURTH ROBOT -->
<!-- arm -->
<xacro:ur_robot
name="ur16e"
tf_prefix="fourth_"
parent="world"
joint_limits_parameters_file="$(arg joint_limits_parameters_file)"
kinematics_parameters_file="$(arg ur16e_kinematics_parameters_file)"
physical_parameters_file="$(arg ur16e_physical_parameters_file)"
visual_parameters_file="$(arg ur16e_visual_parameters_file)"
use_fake_hardware="$(arg use_fake_hardware)"
initial_positions="${xacro.load_yaml(initial_positions_file)}"
headless_mode="$(arg headless_mode)"
robot_ip="$(arg robot_ip)"
script_filename="$(find ur_robot_driver)/resources/ros_control.urscript"
output_recipe_filename="$(find ur_robot_driver)/resources/rtde_output_recipe.txt"
input_recipe_filename="$(find ur_robot_driver)/resources/rtde_input_recipe.txt">
<origin xyz="0 0.6 0" rpy="0 0 0" />
</xacro:ur_robot>

<xacro:picknik_ur_attachments
prefix="fourth"
parent="fourth_tool0"
child="fourth_grasp_link"
has_tool_changer="$(arg has_tool_changer)"
/>

<!-- Gripper and UR adapter and realsense camera -->
<xacro:picknik_ur_attachments parent="tool0" child="grasp_link" has_tool_changer="$(arg has_tool_changer)"/>
<xacro:picknik_ur_attachments parent="first_tool0" child="grasp_link" has_tool_changer="$(arg has_tool_changer)"/>

<!-- Environment: contains scene geometry and external sensors, e.g. cameras -->
<xacro:environment parent="world"/>
Expand Down
Loading