Skip to content

Commit

Permalink
WIP Migration to RobotCell
Browse files Browse the repository at this point in the history
  • Loading branch information
yck011522 committed Oct 19, 2024
1 parent f1ce5df commit c652a39
Show file tree
Hide file tree
Showing 63 changed files with 478 additions and 2,164 deletions.
5 changes: 4 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,10 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
* Changed GH Component `ConstraintsFromTargetConfiguration` to `ConfigurationTarget`.

### Removed

* Removed `attached_collision_meshes` attribute from `JointTrajectory` class.
* Removed `Robot.merge_group_with_full_configuration` as it can be covered by `Configuration.merged`.
* Removed function `Robot.get_group_names_from_link_name` as it is too oddly specific.
* Removed `Robot.get_position_by_joint_name` as Configuration class can now be directly accessed by joint name.
* Removed `Tool` class from `compas_fab.robots` module.
* Removed Backend Feature `AddCollisionMesh`, `AppendCollisionMesh`, `AddAttachedCollisionMesh`, `RemoveCollisionMesh` and `RemoveAttachedCollisionMesh`.
* Removed `inverse_kinematics`, `forward_kinematics`, `plan_cartesian_motion`, and `plan_motion` methods from ClientInterface, access them using the planner instead.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
from compas_robots.resources import GithubPackageMeshLoader
from compas_fab.robots import RobotLibrary
from compas_fab.robots import RobotCellLibrary

# Load robot from RobotLibrary
# RobotLibrary also contains .ur5(), .ur10e(), abb_irb120_3_58(), abb_irb4600_40_255(), .rfl(), .panda()
robot = RobotLibrary.ur5()
model = robot.model
robot_cell, robot_cell_state = RobotCellLibrary.ur5()
robot_model = robot_cell.robot_model
robot_semantics = robot_cell.robot_semantics

# Also load geometry
print(model)
print(robot_model)
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
from compas_fab.backends import RosClient

with RosClient() as ros:
robot = ros.load_robot(load_geometry=True, precision=12)
robot_cell = ros.load_robot_cell(load_geometry=True, precision=12)

print(robot.model)
print(robot_cell.robot_model)
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,6 @@
with RosClient() as ros:
# Load complete model from ROS and set a local cache location
local_directory = os.path.join(os.path.expanduser("~"), "robot_description", "robot_name")
robot = ros.load_robot(load_geometry=True, local_cache_directory=local_directory, precision=12)
robot_cell = ros.load_robot_cell(load_geometry=True, local_cache_directory=local_directory, precision=12)

print(robot.model)
robot_cell.print_info()
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@

with RosClient() as ros:
# Load complete model from ROS
robot = ros.load_robot(load_geometry=True, precision=12)
robot_cell = ros.load_robot_cell(load_geometry=True, precision=12)

# Visualize robot
scene = Scene()
scene_object = scene.add(robot.model)
scene_object = scene.add(robot_cell)
scene.draw()
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
# This example file demonstrates how to print the chain of links and joints in a robot model.

from compas_fab.robots import RobotLibrary
from compas_fab.robots import RobotCellLibrary
from compas_robots.model import Joint

# RobotLibrary also contains .ur5(), .ur10e(), abb_irb120_3_58(), abb_irb4600_40_255(), .rfl(), .panda()
robot = RobotLibrary.panda(load_geometry=False)
robot_cell, robot_cell_state = RobotCellLibrary.panda(load_geometry=False)

model = robot.model
model = robot_cell.robot_model
print("Robot Model Chain:")

# ----------------------------------------------
Expand Down Expand Up @@ -38,12 +38,12 @@ def print_joint(joint, level=1):

def print_planning_group_chain(group):
print("Planning Group: {}".format(group))
base_link = robot.get_base_link_name(group)
base_link = robot_cell.get_base_link_name(group)
print("Base Link: {}".format(base_link))
tip_link = robot.get_end_effector_link_name(group)
tip_link = robot_cell.get_end_effector_link_name(group)
print("Tip Link: {}".format(tip_link))
print("--------------------")
group_object = robot.semantics.groups[group]
group_object = robot_cell.robot_semantics.groups[group]
joints_in_group = group_object["joints"]
links_in_group = group_object["links"]

Expand Down Expand Up @@ -84,5 +84,5 @@ def print_joint(joint, level=1):
print("")


for group in robot.semantics.groups:
for group in robot_cell.robot_semantics.groups:
print_planning_group_chain(group)
8 changes: 4 additions & 4 deletions docs/examples/02_description_models/files/05_robot_viewer.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# This example does not work with IronPython
from compas_fab.robots import RobotLibrary
from compas_fab.robots import RobotCellLibrary
from compas_robots.viewer.scene.robotmodelobject import RobotModelObject
from compas_robots.model import Joint
from compas_viewer.components import Slider
Expand All @@ -12,8 +12,8 @@

# Load robot from RobotLibrary
# RobotLibrary also contains .ur5(), .ur10e(), abb_irb120_3_58(), abb_irb4600_40_255(), .rfl(), .panda()
robot = RobotLibrary.ur5()
model = robot.model
robot_cell, robot_cell_state = RobotCellLibrary.ur5()
model = robot_cell.robot_model

start_configuration = model.zero_configuration()
robot_object: RobotModelObject = viewer.scene.add(model, show_lines=False, configuration=start_configuration) # type: ignore
Expand All @@ -30,7 +30,7 @@ def rotate(slider: Slider, value: float):


# Create one slider for each joint
for joint in robot.get_configurable_joints():
for joint in robot_cell.get_configurable_joints():
starting_val = start_configuration[joint.name]
print(joint.name, Joint.SUPPORTED_TYPES[joint.type], joint.limit.lower, joint.limit.upper, starting_val)
# Units are in radians or meters
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,23 +7,21 @@
from compas_fab.robots import ToolLibrary

with RosClient() as client:
robot = client.load_robot()
robot_cell = client.load_robot_cell()
planner = MoveItPlanner(client)

# =========
# Example 1
# =========

# Create a robot cell using the robot from the client
robot_cell = RobotCell(robot)
# Add a kinematic gripper tool to the robot cell
gripper = ToolLibrary.kinematic_gripper()
robot_cell.tool_models[gripper.name] = gripper
# Attach the gripper to the robot
robot_cell_state = RobotCellState.from_robot_cell(robot_cell)
robot_cell_state.set_tool_attached_to_group(
gripper.name,
robot.main_group_name,
robot_cell.main_group_name,
attachment_frame=Frame([0.0, 0.0, 0.0], [0.0, 0.0, 1.0], [1.0, 0.0, 0.0]),
touch_links=["wrist_3_link"], # This is the link that the tool is attached to
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,14 @@
from compas_fab.robots import RigidBody

with RosClient() as client:
robot = client.load_robot()
robot_cell = client.load_robot_cell()
planner = MoveItPlanner(client)

# =========
# Example 1
# =========

# Create a robot cell with the robot from the client
robot_cell = RobotCell(robot)
# Add a floor as rigid body to the robot cell, this will be static.
floor_mesh = Mesh.from_stl(compas_fab.get("planning_scene/floor.stl"))
robot_cell.rigid_body_models["floor"] = RigidBody.from_mesh(floor_mesh)
Expand All @@ -34,7 +33,7 @@
# In order to see the tool attached it is necessary to update the robot_cell_state
robot_cell_state = RobotCellState.from_robot_cell(robot_cell)
# Modify the tool state to attach the cone to the robot
robot_cell_state.tool_states["cone"].attached_to_group = robot.main_group_name
robot_cell_state.tool_states["cone"].attached_to_group = robot_cell.main_group_name
robot_cell_state.tool_states["cone"].attachment_frame = Frame([0.0, 0.0, 0.0], [0.0, 0.0, 1.0], [1.0, 0.0, 0.0])
# Specify the link of the robot that the tool is allowed to collide with
robot_cell_state.tool_states["cone"].touch_links = ["wrist_3_link"]
Expand All @@ -54,7 +53,7 @@
# Demonstrate that it is possible to have multiple tools in the robot cell

# Create a robot cell with the robot from the client
robot_cell = RobotCell(robot)
robot_cell = client.load_robot_cell()
# Add a two tools (gripper and cone) to the robot cell
gripper = ToolLibrary.static_gripper_small()
robot_cell.tool_models[gripper.name] = gripper
Expand All @@ -65,14 +64,14 @@
# It will also ensure that only one tool is attached to the specified group by removing others
robot_cell_state.set_tool_attached_to_group(
gripper.name,
robot.main_group_name,
robot_cell.main_group_name,
attachment_frame=Frame([0.0, 0.0, 0.0], [0.0, 0.0, 1.0], [1.0, 0.0, 0.0]),
touch_links=["wrist_3_link"],
)
# Specify the location of the detached cone tool
robot_cell_state.tool_states[cone_tool.name].frame = Frame([1.0, 1.0, 0.0], [0.0, 0.0, 1.0], [1.0, 0.0, 0.0])
# Move the robot to a different configuration
robot_cell_state.robot_configuration = robot.zero_configuration()
robot_cell_state.robot_configuration = robot_cell.zero_configuration()
robot_cell_state.robot_configuration._joint_values[1] = -0.5
robot_cell_state.robot_configuration._joint_values[2] = 0.5
result = planner.set_robot_cell(robot_cell, robot_cell_state)
Expand Down
6 changes: 2 additions & 4 deletions docs/examples/03_backends_ros/files/01_ros_set_robot_cell.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,13 @@
from compas_fab.robots import RigidBody

with RosClient() as client:
robot = client.load_robot()
robot_cell = client.load_robot_cell()
planner = MoveItPlanner(client)

# =========
# Example 1
# =========

# Create a robot cell with a floor geometry
robot_cell = RobotCell(robot)
floor_mesh = Mesh.from_stl(compas_fab.get("planning_scene/floor.stl"))
robot_cell.rigid_body_models["floor"] = RigidBody.from_mesh(floor_mesh)

Expand All @@ -30,7 +28,7 @@
# =========

# Create another robot cell with a cone geometry
robot_cell = RobotCell(robot)
robot_cell = client.load_robot_cell()
cone = Mesh.from_stl(compas_fab.get("planning_scene/cone.stl")).scaled(5)
robot_cell.rigid_body_models["cone"] = RigidBody.from_mesh(cone)

Expand Down
2 changes: 1 addition & 1 deletion docs/examples/03_backends_ros/files/01_ros_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
from compas_fab.robots import RobotCellState

with RosClient() as client:
robot = client.load_robot()
robot_cell = client.load_robot_cell()
planner = MoveItPlanner(client)

# =========
Expand Down
6 changes: 3 additions & 3 deletions docs/examples/03_backends_ros/files/02_robot_model.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
from compas_fab.backends import RosClient

with RosClient() as client:
robot = client.load_robot()
robot.info()
robot_cell = client.load_robot_cell()
robot_cell.print_info()

assert robot.name == 'ur5_robot'
assert robot_cell.robot_model.name == "ur5_robot"
4 changes: 2 additions & 2 deletions docs/examples/03_backends_ros/files/03_forward_kinematics.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
from compas_fab.backends import RosClient

with RosClient() as client:
robot = client.load_robot()
print(robot.name)
robot_cell = client.load_robot_cell()
print(robot_cell.robot_model.name)
assert robot.name == "ur5_robot"

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
@@ -1,10 +1,10 @@
from compas_robots import Configuration
from compas_fab.robots import RobotLibrary
from compas_fab.robots import RobotCellLibrary

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

frame_WCF = robot.forward_kinematics(configuration)
frame_WCF = robot_cell.robot_model.forward_kinematics(configuration)

print("Frame in the world coordinate system")
print(str(frame_WCF.point))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
from compas_fab.robots import TargetMode

with RosClient() as client:
robot = client.load_robot()
robot_cell = client.load_robot_cell()
assert robot.name == "ur5_robot"
planner = MoveItPlanner(client)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
from compas_fab.robots import TargetMode

with RosClient() as client:
robot = client.load_robot()
robot_cell = client.load_robot_cell()
assert robot.name == "ur5_robot"
planner = MoveItPlanner(client)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,11 @@
from compas_fab.robots import RobotCellState

with RosClient() as client:
robot = client.load_robot()
planner = MoveItPlanner(client)
robot_cell = RobotCell(robot)
robot_cell = client.load_robot_cell()
robot_cell_state = RobotCellState.from_robot_cell(robot_cell)

assert robot.name == "ur5_robot"
assert robot_cell.robot_model.name == "ur5_robot"

frames = []
frames.append(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 @@ -21,15 +21,13 @@
target_frames.append(Frame([0.0, -0.4, 0.45], [1, 0, 0], [0, 1, 0]))

with RosClient() as client:
robot = client.load_robot()
robot_cell = client.load_robot_cell()
planner = MoveItPlanner(client)

# =====================================
# Step 1: Creation of Robot Cell
# =====================================

# Create a robot cell using the robot from the client
robot_cell = RobotCell(robot)
# Add a rigid body for the floor
floor_mesh = Mesh.from_stl(compas_fab.get("planning_scene/floor.stl"))
robot_cell.rigid_body_models["floor"] = RigidBody.from_mesh(floor_mesh)
Expand All @@ -55,7 +53,7 @@
robot_cell_state = RobotCellState.from_robot_cell(robot_cell)
robot_cell_state.set_tool_attached_to_group(
gripper.name,
robot.main_group_name,
robot_cell.main_group_name,
attachment_frame=Frame([0.0, 0.0, 0.0], [0.0, 0.0, 1.0], [1.0, 0.0, 0.0]),
touch_links=["wrist_3_link"], # This is the link that the tool is attached to
)
Expand Down
8 changes: 4 additions & 4 deletions docs/examples/03_backends_ros/files/04_plan_motion.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,17 +8,17 @@
from compas_fab.backends import MoveItPlanner

with RosClient() as client:
robot = client.load_robot()
robot_cell = client.load_robot_cell()
planner = MoveItPlanner(client)
assert robot.name == "ur5_robot"
assert robot_cell.robot_model.name == "ur5_robot"

frame = Frame([0.4, 0.3, 0.4], [0, 1, 0], [0, 0, 1])
tolerance_position = 0.001
tolerance_orientation = math.radians(1)

start_configuration = robot.zero_configuration()
start_configuration = robot_cell.zero_configuration()
start_configuration.joint_values = (-3.530, 3.830, -0.580, -3.330, 4.760, 0.000)
group = robot.main_group_name
group = robot_cell.main_group_name

# create target from frame
target = FrameTarget(
Expand Down
8 changes: 2 additions & 6 deletions docs/examples/03_backends_ros/files/gh_robot_visualisation.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,6 @@
Whether or not to show the robot's collision meshes.
show_frames: bool
Whether or not to show the robot's joint frames.
show_base_frame: bool
Whether or not to show the robot's base frame.
show_end_effector_frame: bool
Whether or not to show the robot's end-effector frame.
Output:
Expand All @@ -22,6 +20,7 @@
base_frame_WCF: The robot's base frame.
ee_frame_WCF: The robot's end-effector frame.
"""

from __future__ import print_function

if robot and full_configuration:
Expand All @@ -40,9 +39,6 @@
axes = robot.transformed_axes(full_configuration, group)
frames = robot.transformed_frames(full_configuration, group)

if show_base_frame:
base_frame_WCF = robot.get_base_frame(group, full_configuration)

if show_end_effector_frame:
ee_frame_WCF = robot.get_end_effector_frame(group, full_configuration)
ee_frame_WCF = robot.model.forward_kinematics(full_configuration)
print("End-effector", ee_frame_WCF)
Loading

0 comments on commit c652a39

Please sign in to comment.