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

Reduce UR descriptions duplication #223

Merged
merged 15 commits into from
Feb 29, 2024
110 changes: 110 additions & 0 deletions src/picknik_ur_base_config/description/environment.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!-- wrist_3_link/forearm_link have a radius 0f 0.0375m. Actual offset from surface is (radius - attached_link's radius). -->
<!-- UR Drivers check for a 2.5cm distance between tool_flange/wrist_3 and forearm links. -->
pac48 marked this conversation as resolved.
Show resolved Hide resolved
<xacro:macro name="environment" params="parent">
<!-- Import environment macros -->
<xacro:include filename="$(find picknik_accessories)/descriptions/geometry/collision_and_visual/cube_collision_and_visual.urdf.xacro" />
<xacro:include filename="$(find picknik_accessories)/descriptions/geometry/visual/cube_visual.urdf.xacro" />
<xacro:include filename="$(find picknik_accessories)/descriptions/sensors/realsense_d435.urdf.xacro" />

<!-- Environment -->
<link name="environment">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://picknik_accessories/descriptions/furniture/generic_table/wood_block.dae" scale="0.25 0.25 0.1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://picknik_accessories/descriptions/furniture/generic_table/wood_block.dae" scale="0.25 0.25 0.1"/>
</geometry>
</collision>
</link>

<joint name="table_joint" type="fixed">
<parent link="base" />
<child link="environment" />
<origin rpy="0 0 0" xyz="0 0 -0.05" />
</joint>

<link name="box_1">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.1 0.1 0.1 0.9" />
</xacro:cube_visual>
</link>

<joint name="box1_on_table" type="fixed">
<parent link="environment" />
<child link="box_1" />
<origin rpy="0 0 0" xyz="0.65 -0.35 0.1" />
</joint>

<link name="box_2">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.5 0.5 0.5 0.9" />
</xacro:cube_visual>
</link>

<joint name="box2_on_table" type="fixed">
<parent link="environment" />
<child link="box_2" />
<origin rpy="0 0 0" xyz="0.65 0.35 0.1" />
</joint>

<link name="box_3">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.8 0.3 0.1 0.9" />
</xacro:cube_visual>
</link>

<joint name="box3_on_table" type="fixed">
<parent link="environment" />
<child link="box_3" />
<origin rpy="0 0 0" xyz="0.65 0 0.1" />
</joint>

<link name="box_4">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.8 0.3 0.1 0.9" />
</xacro:cube_visual>
</link>

<joint name="box4_on_table" type="fixed">
<parent link="environment" />
<child link="box_4" />
<origin rpy="0 0 0" xyz="-0.65 0.25 0.1" />
</joint>

<link name="box_5">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.1 0.3 0.8 0.9" />
</xacro:cube_visual>
</link>

<joint name="box5_on_table" type="fixed">
<parent link="environment" />
<child link="box_5" />
<origin rpy="0 0 0" xyz="-0.65 -0.25 0.1" />
</joint>

<!-- External Camera -->
<link name="external_camera_link" />
<joint name="external_camera_joint" type="fixed">
<parent link="${parent}" />
<child link="external_camera_link" />
<origin xyz="-0.3 0.3 1.0" rpy="0.0 0.4 0" />
</joint>

<xacro:realsense_d435 parent="external_camera_link" name="scene_camera" visible="false">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:realsense_d435>
</xacro:macro>
sea-bass marked this conversation as resolved.
Show resolved Hide resolved
</robot>
40 changes: 0 additions & 40 deletions src/picknik_ur_base_config/description/gripper_and_camera.xacro

This file was deleted.

215 changes: 25 additions & 190 deletions src/picknik_ur_base_config/description/picknik_ur.xacro
Original file line number Diff line number Diff line change
@@ -1,200 +1,35 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="$(arg name)">
<!-- parameters -->
<xacro:arg name="use_fake_hardware" default="false" />
<xacro:arg name="external_camera" default="false" />
<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="" />

<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" />
<xacro:arg name="tool_voltage" default="0" />
<xacro:arg name="tool_device_name" default="/dev/ttyUSB0" />

<xacro:if value="$(arg has_tool_changer)">
<xacro:property name="camera_adapter_parent" value="tool_changer_tool0" />
</xacro:if>
<xacro:unless value="$(arg has_tool_changer)">
<xacro:property name="camera_adapter_parent" value="tool0" />
</xacro:unless>

<!-- Import macros for main hardware components -->
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro" />
<xacro:include filename="$(find robotiq_description)/urdf/ur_to_robotiq_adapter.urdf.xacro" />
<xacro:include filename="$(find robotiq_description)/urdf/robotiq_2f_85_macro.urdf.xacro" />
<xacro:include filename="$(find picknik_accessories)/descriptions/brackets/mtc_ur_tool_changer/mtc_ur_tool_changer.urdf.xacro" />
<xacro:include filename="$(find picknik_accessories)/descriptions/brackets/ur_realsense_camera_adapter/picknik_ur_camera_adapter.urdf.xacro" />
<xacro:include filename="$(find picknik_accessories)/descriptions/sensors/realsense_d415.urdf.xacro" />
<xacro:include filename="$(find picknik_accessories)/descriptions/sensors/realsense_d435.urdf.xacro" />
<xacro:include filename="$(find picknik_ur_base_config)/description/pinch_links.xacro" />

<!-- Initial positions for simulations (Mock Hardware and Gazebo) -->
<xacro:arg name="use_fake_hardware" default="false"/>
<xacro:arg name="external_camera" default="false"/>
<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=""/>
<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"/>
<xacro:arg name="tool_voltage" default="0"/>
<xacro:arg name="tool_device_name" default="/dev/ttyUSB0"/>
<xacro:arg name="initial_positions_file" default="$(find picknik_ur_base_config)/config/initial_positions.yaml"/>
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>

<!-- Import environment macros -->
<xacro:include filename="$(find picknik_accessories)/descriptions/geometry/collision_and_visual/cube_collision_and_visual.urdf.xacro" />
<xacro:include filename="$(find picknik_accessories)/descriptions/geometry/visual/cube_visual.urdf.xacro" />

<link name="world" />
<!-- arm -->
<xacro:ur_robot
name="$(arg name)"
tf_prefix=""
parent="world"
joint_limits_parameters_file="$(arg joint_limits_parameters_file)"
kinematics_parameters_file="$(arg kinematics_parameters_file)"
physical_parameters_file="$(arg physical_parameters_file)"
visual_parameters_file="$(arg 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)"
use_tool_communication="$(arg use_tool_communication)"
tool_voltage="$(arg tool_voltage)"
tool_device_name="$(arg tool_device_name)"
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" rpy="0 0 0" />
</xacro:ur_robot>

<xacro:if value="$(arg has_tool_changer)">
<!-- tool changer-->
<xacro:mtc_ur_tool_changer prefix="" connected_to="tool0" rotation="0" />
</xacro:if>

<!-- pinch geometry for moveit motion planning. see https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/issues/611 -->
<xacro:if value="$(arg use_pinch_links)">
<xacro:forearm_pinch_link/>
<xacro:wrist_3_pinch_link/>
</xacro:if>

<!-- wrist camera adapter and camera-->
<xacro:ur_realsense_camera_adapter prefix="" connected_to="${camera_adapter_parent}" rotation="0" />

<xacro:realsense_d415 parent="d415_mount_link" name="wrist_mounted_camera">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:realsense_d415>

<!-- Gripper and UR adapter-->
<xacro:ur_to_robotiq prefix="" connected_to="realsense_camera_adapter_tool0" rotation="0" />

<xacro:robotiq_gripper name="RobotiqGripperHardwareInterface" prefix=""
parent="gripper_mount_link" use_fake_hardware="$(arg use_fake_hardware)" com_port="$(arg tool_device_name)">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:robotiq_gripper>

<!-- This link aligns the axes of the grasp frame to our required convention for motion planning tasks. -->
<link name="grasp_link" />
<joint name="grasp_link_joint" type="fixed">
<parent link="robotiq_85_base_link" />
<child link="grasp_link" />
<origin xyz="0.0 0.0 0.134" rpy="0.0 0.0 ${pi}" />
</joint>

<!-- Environment -->
<link name="environment">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://picknik_accessories/descriptions/furniture/generic_table/wood_block.dae" scale="0.25 0.25 0.1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://picknik_accessories/descriptions/furniture/generic_table/wood_block.dae" scale="0.25 0.25 0.1"/>
</geometry>
</collision>
</link>

<joint name="table_joint" type="fixed">
<parent link="base" />
<child link="environment" />
<origin rpy="0 0 0" xyz="0 0 -0.05" />
</joint>

<link name="box_1">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.1 0.1 0.1 0.9" />
</xacro:cube_visual>
</link>

<joint name="box1_on_table" type="fixed">
<parent link="environment" />
<child link="box_1" />
<origin rpy="0 0 0" xyz="0.65 -0.35 0.1" />
</joint>

<link name="box_2">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.5 0.5 0.5 0.9" />
</xacro:cube_visual>
</link>

<joint name="box2_on_table" type="fixed">
<parent link="environment" />
<child link="box_2" />
<origin rpy="0 0 0" xyz="0.65 0.35 0.1" />
</joint>

<link name="box_3">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.8 0.3 0.1 0.9" />
</xacro:cube_visual>
</link>

<joint name="box3_on_table" type="fixed">
<parent link="environment" />
<child link="box_3" />
<origin rpy="0 0 0" xyz="0.65 0 0.1" />
</joint>

<link name="box_4">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.8 0.3 0.1 0.9" />
</xacro:cube_visual>
</link>
<xacro:arg name="environment_xacro" default="$(find picknik_ur_base_config)/description/environment.xacro"/>

<joint name="box4_on_table" type="fixed">
<parent link="environment" />
<child link="box_4" />
<origin rpy="0 0 0" xyz="-0.65 0.25 0.1" />
</joint>
<!-- Import UR and environment macros -->
<xacro:include filename="$(find picknik_ur_base_config)/description/picknik_ur_macro.xacro"/>
<xacro:include filename="$(find picknik_ur_base_config)/description/picknik_ur_attachments_macro.xacro"/>
<xacro:include filename="$(arg environment_xacro)"/>

<link name="box_5">
<xacro:cube_visual length="0.05" width="0.05" height="0.05">
<origin xyz="0 0 0" rpy="0 0 0" />
<color rgba="0.1 0.3 0.8 0.9" />
</xacro:cube_visual>
</link>
<!-- 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)" />

<joint name="box5_on_table" type="fixed">
<parent link="environment" />
<child link="box_5" />
<origin rpy="0 0 0" xyz="-0.65 -0.25 0.1" />
</joint>
<!-- Gripper and UR adapter and realsense camera -->
<xacro:picknik_ur_attachments parent="tool0" child="grasp_link" has_tool_changer="$(arg has_tool_changer)"/>

<!-- External Camera -->
<link name="external_camera_link" />
<joint name="external_camera_joint" type="fixed">
<parent link="world" />
<child link="external_camera_link" />
<origin xyz="-0.3 0.3 1.0" rpy="0.0 0.4 0" />
</joint>
<!-- Environment: contains scene geometry and external sensors, e.g. cameras -->
<xacro:environment parent="world"/>

<xacro:realsense_d435 parent="external_camera_link" name="scene_camera" visible="false">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:realsense_d435>
</robot>
Loading
Loading