Skip to content

Commit

Permalink
Merge pull request #406 from compas-dev/robot_library
Browse files Browse the repository at this point in the history
Add RobotLibrary
  • Loading branch information
yck011522 authored Apr 12, 2024
2 parents 59235e9 + ff75aa9 commit d088aee
Show file tree
Hide file tree
Showing 98 changed files with 358,825 additions and 0 deletions.
2 changes: 2 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
### Added

* Add parameter to control which link the tool is connected to in Grasshopper.
* Introduced `compas_fab.robots.RobotLibrary` class with 4 built-in robots.
* Added a script to extract URDF, SRDF and meshes from a Docker MoveIt instance.

### Changed

Expand Down
53 changes: 53 additions & 0 deletions docs/examples/02_description_models/03_robot_instances.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
********************************************************************************
RobotModel Packages
********************************************************************************

.. rst-class:: lead

``COMPAS FAB`` provides several ready-to-use robot packages that can be used for
demonstrating the capabilities of the package. These packages can be accessed from the
:class:`compas_fab.robots.RobotLibrary`. The robot packages are loaded from local data
files. They contain
the `robot.model`, `robot.semantics` and meshes associated with the robot links.


The following packages are available:


.. list-table:: Robot Packages
:widths: 25 25 50 25
:header-rows: 1

* - Model
- Brand
- Description
- Location
* - UR5
- Universal Robots
- 6 DOF offset-wrist robot
- :class:`~compas_fab.robots.RobotLibrary.ur5`
* - UR10e
- Universal Robots
- 6 DOF offset-wrist robot
- :class:`~compas_fab.robots.RobotLibrary.ur10e`
* - IRB 4600-40/2.55
- ABB
- 6 DOF spherical-wrist robot
- :class:`~compas_fab.robots.RobotLibrary.abb_irb4600_40_255`
* - RFL
- ETH Arch_Tec_Lab
- Multi-​robotic system with 2 gantry and 4 robotic arms
- :class:`~compas_fab.robots.RobotLibrary.rfl`


Description of the RFL Robotic Setup (`Robotic Fabrication Laboratory <https://ita.arch.ethz.ch/archteclab/rfl.html>`_)


Origin of the packages
======================

The robot packages originates from ROS MoveIt Robot Packages located in
`gramaziokohler/ros_docker <https://github.com/gramaziokohler/ros_docker/>`_.
The docker files are *composed up* and extracted over ROS to a local folder structure
that is compatible with the COMPAS Fab package. The convertion script can be found in the
source code repository folder `scripts/extact_robot_package_from_ros.py`.
77 changes: 77 additions & 0 deletions scripts/extract_robot_package_from_ros.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
# This script extracts the URDF from a MoveIt! instance running in docker

# The purpose of this script is to extract the URDF and SRDF from a running MoveIt! instance.
# Many of the industrial robots have a MoveIt! configuration that can be found
# in the ROS package of the robot. However, there are some cases where XARCO files
# are used to define the robot, and the URDF and SRDF are not available.

# This script uses the compas_fab library to extract the URDF and SRDF from a running
# MoveIt! instance. In addition, the meshes are also downloaded and saved in a local
# directory. The extracted files can then be used to create a RobotModel instance
# without the need of a MoveIt! instance nor a ROS installation. This is useful for
# applications where the robot model is used with the PyBullet backend, or when the
# robot model is used for visualization (e.g. in Rhino), or when performing forward
# kinematics calculations that do not require any backends.

# The out name and path of the URDF and SRDF files are governed by the RosFileServerLoader
# class.
# The extract *package* root folder is "\robot_packages\{robot_name}" where {robot_name} is the name of the robot.
# The extracted URDF is located in "\robot_packages\{robot_name}\urdf\robot_description.urdf"
# The extracted SRDF is located in "\robot_packages\{robot_name}\robot_description_semantic.srdf"
# The extracted meshes are stored in paths relative to the package root and are defined in the URDF file.

import itertools
import os

from compas.datastructures import Mesh

from compas_fab.backends.ros.client import RosFileServerLoader
from compas_fab.backends import RosClient

HERE = os.path.dirname(__file__)


with RosClient() as client:
# Standard way to load a robot from a MoveIt! instance.
robot = client.load_robot()
robot.info()
print(robot.name)

# The RosFileServerLoader is used with a modified local_cache_directory argument
local_cache_directory = os.path.join(HERE, "robot_packages")
print("Saved to directory:", os.path.join(local_cache_directory, robot.name))
loader = RosFileServerLoader(client, True, local_cache_directory)

# The loader will retrieve URDF and SRDF from the ros server
urdf_string = loader.load_urdf("/robot_description")
srdf_string = loader.load_srdf("/robot_description_semantic")

# The meshes will be loaded from ROS to the local cache directory
mesh_precision = 12
robot.model.load_geometry(loader, precision=mesh_precision)

# Convert DAE meshes files to OBJ and update the URDF file
# The new OBJ files will be stored next to the original DAE files appended with ".obj" extension
for link in robot.model.links:
for element in itertools.chain(link.collision, link.visual):
shape = element.geometry.shape
if "filename" in dir(shape):
# Convert dae to stl
if shape.filename.endswith(".dae"):
filename_in_package = shape.filename.split("package://")[1]
local_path_to_stl = os.path.join(local_cache_directory, robot.name, filename_in_package + ".obj")
# Check if the STL file already exists (e.g. RFL have multiple links with the same mesh file)
if not os.path.exists(local_path_to_stl):
meshes = loader.load_meshes(shape.filename, precision=mesh_precision)
# Join all meshes into one for OBJ conversion (Note: Do not weld the vertices)
combined_mesh = Mesh()
for mesh in meshes:
combined_mesh.join(mesh, precision=mesh_precision)
combined_mesh.to_obj(local_path_to_stl, precision=mesh_precision)
print("> DAE Converted to OBJ file and stored in : ", local_path_to_stl)
# Change the filename in the URDF
shape.filename = shape.filename + ".obj"

robot.model.to_urdf_file(loader._urdf_filename, prettify=True)

print("Extraction Complete.")
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="abb_irb4600_40_255">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="manipulator">
<chain base_link="base_link" tip_link="tool0"/>
</group>
<group name="manipulator_lma">
<chain base_link="base_link" tip_link="tool0"/>
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="home" group="manipulator">
<joint name="joint_1" value="0"/>
<joint name="joint_2" value="0"/>
<joint name="joint_3" value="0"/>
<joint name="joint_4" value="0"/>
<joint name="joint_5" value="0"/>
<joint name="joint_6" value="0"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="flange" parent_link="tool0" group="manipulator"/>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link"/>
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="base_link"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="base_link" link2="link_1" reason="Adjacent"/>
<disable_collisions link1="base_link" link2="link_3" reason="Never"/>
<disable_collisions link1="link_1" link2="link_2" reason="Adjacent"/>
<disable_collisions link1="link_1" link2="link_3" reason="Never"/>
<disable_collisions link1="link_2" link2="link_3" reason="Adjacent"/>
<disable_collisions link1="link_2" link2="link_4" reason="Never"/>
<disable_collisions link1="link_2" link2="link_5" reason="Never"/>
<disable_collisions link1="link_2" link2="link_6" reason="Never"/>
<disable_collisions link1="link_3" link2="link_4" reason="Adjacent"/>
<disable_collisions link1="link_3" link2="link_5" reason="Never"/>
<disable_collisions link1="link_3" link2="link_6" reason="Never"/>
<disable_collisions link1="link_4" link2="link_5" reason="Adjacent"/>
<disable_collisions link1="link_4" link2="link_6" reason="Default"/>
<disable_collisions link1="link_5" link2="link_6" reason="Adjacent"/>
</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,205 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="abb_irb4600_40_255">
<link name="base_link">
<visual>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/visual/base_link.stl"/>
</geometry>
<material name="Material">
<color rgba="0.772549 0.7803922 0.7686275 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/collision/base_link.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<mass value="120.0"/>
<inertia ixx="-4.98" ixy="-0.0" ixz="2.7" iyy="-5.952" iyz="-0.0" izz="0.828"/>
</inertial>
</link>
<link name="link_1">
<visual>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/visual/link_1.stl"/>
</geometry>
<material name="Material">
<color rgba="0.772549 0.7803922 0.7686275 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/collision/link_1.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.18 0.0 0.5" rpy="0.0 0.0 0.0"/>
<mass value="120.0"/>
<inertia ixx="-4.98" ixy="-0.0" ixz="2.7" iyy="-5.952" iyz="-0.0" izz="0.828"/>
</inertial>
</link>
<link name="link_2">
<visual>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/visual/link_2.stl"/>
</geometry>
<material name="Material">
<color rgba="0.772549 0.7803922 0.7686275 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/collision/link_2.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.94 0.08 -0.34" rpy="0.0 0.0 0.0"/>
<mass value="120.0"/>
<inertia ixx="-2.96" ixy="2.256" ixz="-9.588" iyy="-18.72601" iyz="-0.816" izz="-14.95"/>
</inertial>
</link>
<link name="link_3">
<visual>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/visual/link_3.stl"/>
</geometry>
<material name="Material">
<color rgba="0.772549 0.7803922 0.7686275 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/collision/link_3.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.07 -0.266 0.088" rpy="0.0 0.0 0.0"/>
<mass value="120.0"/>
<inertia ixx="1.345" ixy="-0.5586" ixz="0.1848" iyy="4.65068" iyz="-0.70224" izz="2.76032"/>
</inertial>
</link>
<link name="link_4">
<visual>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/visual/link_4.stl"/>
</geometry>
<material name="Material">
<color rgba="0.772549 0.7803922 0.7686275 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/collision/link_4.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.0 0.0 1.0" rpy="0.0 0.0 0.0"/>
<mass value="40.0"/>
<inertia ixx="-8.0" ixy="-0.0" ixz="-0.0" iyy="-8.0" iyz="-0.0" izz="0.482"/>
</inertial>
</link>
<link name="link_5">
<visual>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/visual/link_5.stl"/>
</geometry>
<material name="Material">
<color rgba="0.772549 0.7803922 0.7686275 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/collision/link_5.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.14 0.0 0.0" rpy="0.0 0.0 0.0"/>
<mass value="10.0"/>
<inertia ixx="0.04" ixy="-0.0" ixz="-0.0" iyy="-0.009" iyz="-0.0" izz="-0.004"/>
</inertial>
</link>
<link name="link_6">
<visual>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/visual/link_6.stl"/>
</geometry>
<material name="Material">
<color rgba="0.1882353 0.1960784 0.2039216 1.0"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://abb_irb4600_40_255/meshes/collision/link_6.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0.081 -0.091 0.332" rpy="0.0 0.0 0.0"/>
<mass value="5.0"/>
<inertia ixx="-0.29652" ixy="-0.03686" ixz="0.09396" iyy="-0.28792" iyz="-0.10556" izz="-0.04621"/>
</inertial>
</link>
<link name="tool0"/>
<link name="base"/>
<joint name="joint_1" type="revolute">
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0.0 0.0 1.0"/>
<dynamics damping="0.2" friction="0.0"/>
<limit lower="-3.14159" upper="3.14159" effort="100000.0" velocity="2.618"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
<joint name="joint_2" type="revolute">
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0.0 1.0 0.0"/>
<dynamics damping="0.2" friction="0.0"/>
<limit lower="-1.5708" upper="2.61799" effort="100000.0" velocity="2.618"/>
<origin xyz="0.175 0.0 0.495" rpy="0.0 -0.0 0.0"/>
</joint>
<joint name="joint_3" type="revolute">
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0.0 1.0 0.0"/>
<dynamics damping="0.2" friction="0.0"/>
<limit lower="-3.14159" upper="1.309" effort="100000.0" velocity="2.618"/>
<origin xyz="0.0 0.0 1.095" rpy="0.0 -0.0 0.0"/>
</joint>
<joint name="joint_4" type="revolute">
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="1.0 0.0 0.0"/>
<dynamics damping="0.2" friction="0.0"/>
<limit lower="-6.98132" upper="6.98132" effort="10000.0" velocity="6.2832"/>
<origin xyz="0.331 0.0 0.175" rpy="0.0 -0.0 0.0"/>
</joint>
<joint name="joint_5" type="revolute">
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0.0 1.0 0.0"/>
<dynamics damping="0.2" friction="0.0"/>
<limit lower="-2.18166" upper="2.0944" effort="100000.0" velocity="6.2832"/>
<origin xyz="0.939 0.0 0.0" rpy="0.0 -0.0 0.0"/>
</joint>
<joint name="joint_6" type="revolute">
<parent link="link_5"/>
<child link="link_6"/>
<axis xyz="0.0 0.0 1.0"/>
<dynamics damping="0.2" friction="0.0"/>
<limit lower="-6.98132" upper="6.98132" effort="100000.0" velocity="7.854"/>
<origin xyz="0.135 0.0 0.0" rpy="0.0 1.57076 0.0"/>
</joint>
<joint name="joint_6-tool0" type="fixed">
<parent link="link_6"/>
<child link="tool0"/>
<axis xyz="1.0 0.0 0.0"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
<joint name="base_link-base" type="fixed">
<parent link="base_link"/>
<child link="base"/>
<axis xyz="1.0 0.0 0.0"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>
</robot>
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Loading

0 comments on commit d088aee

Please sign in to comment.