Skip to content

Commit

Permalink
Merge pull request #407 from compas-dev/robot_library_remove_old_robots
Browse files Browse the repository at this point in the history
Robot library remove old robots
  • Loading branch information
yck011522 authored Apr 12, 2024
2 parents d088aee + 454e67e commit 08773ba
Show file tree
Hide file tree
Showing 56 changed files with 185 additions and 427,378 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/integration.yml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ jobs:
- name: Set up Python 3.8
uses: actions/setup-python@v2
with:
python-version: 3.8
python-version: '3.8'
- name: Set up docker containers
run: |
docker-compose -f "tests/integration_setup/docker-compose.yml" up -d --build
Expand Down
3 changes: 3 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -55,13 +55,16 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
* Add `attributes` to `Trajectory` class.
* Fixed `data` serialization API to comply with `COMPAS 2.0` private data API.
* Use the tool's `connected_to` link when showing end-effector frames in Grasshopper.
* Change default end-effector link name from `ee_link` to `tool0`.

### Removed

* Removed V-Rep backend.
* Removed outdated `PathPlan` class.
* Removed outdated rfl demo class.
* Remove deprecated aliases for artists (currently on `compas_robots`).
* Removed `compas_fab.robots.ur5` because it is now part of `compas_fab.robots.RobotLibrary`.
* Removed data files of ur5 and ur10e from `src/compas_fab/data/universal_robots` because they are now in of `src/compas_fab/data/robot_library`.

## [0.28.0] 2023-05-10

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,14 @@
import compas_fab

# Locate the URDF file inside compas fab installation
urdf = compas_fab.get("universal_robot/ur_description/urdf/ur10e.urdf")
urdf = compas_fab.get("robot_library/ur10e_robot/urdf/robot_description.urdf")

# Create robot model from URDF
model = RobotModel.from_urdf_file(urdf)

# Also load geometry
loader = LocalPackageMeshLoader(compas_fab.get("universal_robot"), "ur_description")
support_package_name = ""
loader = LocalPackageMeshLoader(compas_fab.get("robot_library/ur10e_robot"), support_package_name)
model.load_geometry(loader, precision=12)

print(model)
9 changes: 0 additions & 9 deletions docs/examples/03_backends_ros/02_robot_models.rst
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,3 @@ request the full model to be loaded from ROS.

.. literalinclude :: files/02_robot_model.py
:language: python
Load model from URDF
====================

Alternatively, the URDF model can be loaded from URDF files (stored locally
or remotely):

.. literalinclude :: files/02_robot_model_urdf.py
:language: python
12 changes: 0 additions & 12 deletions docs/examples/03_backends_ros/files/02_robot_model_urdf.py

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
from compas_robots import Configuration
from compas_fab.robots.ur5 import Robot
from compas_fab.robots import RobotLibrary

robot = Robot()
robot = RobotLibrary.ur5()
configuration = Configuration.from_revolute_values([-2.238, -1.153, -2.174, 0.185, 0.667, 0.0])

frame_WCF = robot.forward_kinematics(configuration)

print("Frame in the world coordinate system")
print(frame_WCF)
print(str(frame_WCF.point))

assert str(frame_WCF.point) == "Point(x=0.300, y=0.100, z=0.500)"
8 changes: 4 additions & 4 deletions docs/examples/03_backends_ros/files/robot-playground.ghx
Original file line number Diff line number Diff line change
Expand Up @@ -2844,7 +2844,7 @@ if robot:
from scriptcontext import sticky as st

import compas
from compas_fab.robots.ur5 import Robot
from compas_fab.robots import RobotLibrary
from compas_ghpython.artists import RobotModelArtist

compas.PRECISION = '12f'
Expand All @@ -2857,7 +2857,7 @@ if robot_key not in st:
st[robot_key] = None

if load:
robot = Robot(load_geometry=True)
robot = RobotLibrary.ur5(load_geometry=True)
robot.artist = RobotModelArtist(robot.model)
st[robot_key] = robot
robot.scale(scale_factor)
Expand Down Expand Up @@ -6410,7 +6410,7 @@ Add path constraints</item>
<item name="ScrollRatio" type_name="gh_double" type_code="6">0</item>
<item name="Source" index="0" type_name="gh_guid" type_code="9">63649309-f44e-4e3b-ad3a-514b976df80d</item>
<item name="SourceCount" type_name="gh_int32" type_code="3">1</item>
<item name="UserText" type_name="gh_string" type_code="10">ee_link</item>
<item name="UserText" type_name="gh_string" type_code="10">tool0</item>
</items>
<chunks count="2">
<chunk name="Attributes">
Expand Down Expand Up @@ -6680,7 +6680,7 @@ Add path constraints</item>
<item name="ScrollRatio" type_name="gh_double" type_code="6">0</item>
<item name="Source" index="0" type_name="gh_guid" type_code="9">96a2f2f6-5901-4527-abb3-829097bd2417</item>
<item name="SourceCount" type_name="gh_int32" type_code="3">1</item>
<item name="UserText" type_name="gh_string" type_code="10">ee_link</item>
<item name="UserText" type_name="gh_string" type_code="10">tool0</item>
<item name="WireDisplay" type_name="gh_int32" type_code="3">1</item>
</items>
<chunks count="2">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,13 @@


with PyBulletClient() as client:
urdf_filepath = compas_fab.get('universal_robot/ur_description/urdf/ur5.urdf')
loader = LocalPackageMeshLoader(compas_fab.get('universal_robot'), 'ur_description')
urdf_filepath = compas_fab.get('robot_library/ur5_robot/urdf/robot_description.urdf')
loader = LocalPackageMeshLoader(compas_fab.get('robot_library/ur5_robot'), '')
robot = client.load_robot(urdf_filepath, [loader])

mesh = Mesh.from_stl(compas_fab.get('planning_scene/cone.stl'))
cm = CollisionMesh(mesh, 'tip')
acm = AttachedCollisionMesh(cm, 'ee_link')
acm = AttachedCollisionMesh(cm, 'tool0')
client.add_attached_collision_mesh(acm, {'mass': 0.5, 'robot': robot})

time.sleep(1)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
from compas_fab.robots import CollisionMesh

with PyBulletClient() as client:
urdf_filepath = compas_fab.get('universal_robot/ur_description/urdf/ur5.urdf')
urdf_filepath = compas_fab.get('robot_library/ur5_robot/urdf/robot_description.urdf')
robot = client.load_robot(urdf_filepath)

mesh = Mesh.from_stl(compas_fab.get('planning_scene/floor.stl'))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from compas_fab.backends import PyBulletClient

with PyBulletClient() as client:
urdf_filename = compas_fab.get("universal_robot/ur_description/urdf/ur5.urdf")
urdf_filename = compas_fab.get("robot_library/ur5_robot/urdf/robot_description.urdf")
robot = client.load_robot(urdf_filename)

configuration = Configuration.from_revolute_values([-2.238, -1.153, -2.174, 0.185, 0.667, 0.0])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from compas_fab.backends import PyBulletClient

with PyBulletClient() as client:
urdf_filename = compas_fab.get('universal_robot/ur_description/urdf/ur5.urdf')
urdf_filename = compas_fab.get('robot_library/ur5_robot/urdf/robot_description.urdf')
robot = client.load_robot(urdf_filename)

frame_WCF = Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from compas_fab.backends import PyBulletClient

with PyBulletClient(connection_type='direct') as client:
urdf_filename = compas_fab.get('universal_robot/ur_description/urdf/ur5.urdf')
urdf_filename = compas_fab.get('robot_library/ur5_robot/urdf/robot_description.urdf')
robot = client.load_robot(urdf_filename)

frame_WCF = Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0])
Expand Down
9 changes: 5 additions & 4 deletions docs/examples/06_backends_kinematics/files/01_iter_ik.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
from compas.geometry import Frame
from compas_fab.robots.ur5 import Robot
from compas_fab.robots import RobotLibrary
from compas_fab.backends import AnalyticalInverseKinematics

ik = AnalyticalInverseKinematics()
robot = Robot()
robot = RobotLibrary.ur5()

frame_WCF = Frame((0.381, 0.093, 0.382), (0.371, -0.292, -0.882), (0.113, 0.956, -0.269))

for jp, jn in ik.inverse_kinematics(robot, frame_WCF, options={'solver': 'ur5'}): # knows that we need the IK for the UR5 robot
print(jp)
# The solver must be one of the supported PLANNER_BACKENDS
for joint_positions, joint_names in ik.inverse_kinematics(robot, frame_WCF, options={'solver': 'ur5'}):
print(joint_positions)
14 changes: 8 additions & 6 deletions src/compas_fab/backends/pybullet/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
from compas_fab.backends.kinematics import AnalyticalInverseKinematics
from compas_fab.backends.kinematics import AnalyticalPlanCartesianMotion
from compas_fab.robots import Robot
from compas_fab.robots import RobotLibrary
from compas_fab.robots import RobotSemantics
from compas_fab.utilities import LazyLoader

Expand Down Expand Up @@ -193,21 +194,22 @@ def load_ur5(self, load_geometry=False, concavity=False):
:class:`compas_fab.robots.Robot`
A robot instance.
"""
robot_model = RobotModel.ur5(load_geometry)
robot = Robot(robot_model, client=self)
robot = RobotLibrary.ur5(client=self, load_geometry=load_geometry)
robot.ensure_semantics()

robot.attributes["pybullet"] = {}
if load_geometry:
self.cache_robot(robot, concavity)
else:
robot.attributes["pybullet"]["cached_robot"] = robot.model
robot.attributes["pybullet"]["cached_robot_filepath"] = compas.get("ur_description/urdf/ur5.urdf")
robot.attributes["pybullet"]["cached_robot_filepath"] = compas_fab.get(
"robot_library/ur5_robot/urdf/robot_description.urdf"
)

urdf_fp = robot.attributes["pybullet"]["cached_robot_filepath"]

self._load_robot_to_pybullet(urdf_fp, robot)

srdf_filename = compas_fab.get("universal_robot/ur5_moveit_config/config/ur5.srdf")
self.load_semantics(robot, srdf_filename)
self.disabled_collisions = robot.semantics.disabled_collisions

return robot

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ def forward_kinematics(self, robot, configuration, group=None, options=None):
calculate the forward kinematics for. Defaults to the group's end
effector link.
Backwards compatibility note: if there's no ``link`` option, the
planner will try also ``ee_link`` as fallback before defaulting
planner will try also ``tool0`` as fallback before defaulting
to the end effector's link.
Returns
Expand All @@ -69,7 +69,7 @@ def forward_kinematics(self, robot, configuration, group=None, options=None):
options["base_link"] = options.get("base_link", robot.model.root.name)

# Use selected link or default to group's end effector
options["link"] = options.get("link", options.get("ee_link")) or robot.get_end_effector_link_name(group)
options["link"] = options.get("link", options.get("tool0")) or robot.get_end_effector_link_name(group)
if options["link"] not in robot.get_link_names(group):
raise ValueError("Link name {} does not exist in planning group".format(options["link"]))

Expand Down
7 changes: 2 additions & 5 deletions src/compas_fab/backends/ros/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -123,10 +123,8 @@ class RosClient(Ros, ClientInterface):
Examples
--------
>>> from compas_fab.backends import RosClient
>>> with RosClient() as client:
... print('Connected: %s' % client.is_connected)
... print('Connected:', client.is_connected)
Connected: True
Notes
Expand Down Expand Up @@ -185,12 +183,11 @@ def load_robot(
Examples
--------
>>> from compas_fab.backends import RosClient
>>> with RosClient() as client:
... robot = client.load_robot()
... print(robot.name)
ur5_robot
"""
robot_name = None

Expand Down
2 changes: 1 addition & 1 deletion src/compas_fab/backends/ros/messages/services.py
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ def __init__(
self.header = header or Header()
self.start_state = start_state or RobotState() # moveit_msgs/RobotState
self.group_name = group_name
self.link_name = link_name # ee_link
self.link_name = link_name # End Effector Link Name e.g. tool0, flange, etc.
self.waypoints = waypoints if waypoints else [] # geometry_msgs/Pose[]
self.max_step = float(max_step)
self.jump_threshold = float(jump_threshold)
Expand Down

This file was deleted.

This file was deleted.

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.
Loading

0 comments on commit 08773ba

Please sign in to comment.