Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove Planner call magic, using multi-inherence instead. #433

Merged
merged 14 commits into from
Jun 14, 2024
Merged
Show file tree
Hide file tree
Changes from 12 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
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0

### Changed

* Backend planners use multi-inherence instead of `__call__` to include the backend functions. This allows for better generated documentation.
* `Robot.plan_cartesian_motion()` now accepts `Waypoints` as target. Implementation for `FrameWaypoints` is supported with same functionality as before. Simply wrap `Frame` objects using `FrameWaypoints(frames)`.
* Changed `BoundingVolume`, `Constraint`, `JointConstraint`, `OrientationConstraint`, `PositionConstraint` to inherit from `compas.data.Data` class.
* Change the signature of `plan_motion()` to use `target` (`Target` class) instead of `goal_constraints`. Only one target is accepted. Users who wish to compose their own constraint sets can still use `ConstraintSetTarget`.
Expand Down
12 changes: 12 additions & 0 deletions docs/developer/backends.rst
Original file line number Diff line number Diff line change
Expand Up @@ -82,3 +82,15 @@ Backend interfaces
==================

.. automodule:: compas_fab.backends.interfaces

Implemented backend features
============================

The following backend features are implemented for the ROS backend:

.. automodule:: compas_fab.backends.ros.backend_features

The following backend features are implemented for the PyBullet backend:

.. automodule:: compas_fab.backends.pybullet.backend_features

17 changes: 10 additions & 7 deletions src/compas_fab/backends/interfaces/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
:toctree: generated/
:nosignatures:
BackendFeature
ForwardKinematics
InverseKinematics
PlanMotion
Expand All @@ -46,6 +47,7 @@
from .backend_features import AddAttachedCollisionMesh
from .backend_features import AddCollisionMesh
from .backend_features import AppendCollisionMesh
from .backend_features import BackendFeature
from .backend_features import ForwardKinematics
from .backend_features import GetPlanningScene
from .backend_features import InverseKinematics
Expand All @@ -58,17 +60,18 @@
from .client import PlannerInterface

__all__ = [
"AddAttachedCollisionMesh",
"AddCollisionMesh",
"AppendCollisionMesh",
"BackendFeature",
"ClientInterface",
"ForwardKinematics",
"GetPlanningScene",
"InverseKinematics",
"PlanMotion",
"PlanCartesianMotion",
"GetPlanningScene",
"AddCollisionMesh",
"AppendCollisionMesh",
"PlanMotion",
"PlannerInterface",
"RemoveCollisionMesh",
"AddAttachedCollisionMesh",
"RemoveAttachedCollisionMesh",
"ResetPlanningScene",
"ClientInterface",
"PlannerInterface",
]
205 changes: 83 additions & 122 deletions src/compas_fab/backends/interfaces/backend_features.py

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion src/compas_fab/backends/interfaces/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ class PlannerInterface(object):
"""

def __init__(self, client):
super(PlannerInterface, self).__init__()
# super(PlannerInterface, self).__init__()
self.client = client

# ==========================================================================
Expand Down
25 changes: 23 additions & 2 deletions src/compas_fab/backends/pybullet/backend_features/__init__.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,26 @@
"""
PyBullet backend features
=========================
.. autosummary::
:toctree: generated/
:nosignatures:
PyBulletAddAttachedCollisionMesh
PyBulletAddCollisionMesh
PyBulletAppendCollisionMesh
PyBulletForwardKinematics
PyBulletInverseKinematics
PyBulletRemoveAttachedCollisionMesh
PyBulletRemoveCollisionMesh
"""

from __future__ import absolute_import


from compas_fab.backends.pybullet.backend_features.pybullet_add_attached_collision_mesh import (
PyBulletAddAttachedCollisionMesh,
)
Expand All @@ -17,8 +38,8 @@
"PyBulletAddAttachedCollisionMesh",
"PyBulletAddCollisionMesh",
"PyBulletAppendCollisionMesh",
"PyBulletRemoveCollisionMesh",
"PyBulletRemoveAttachedCollisionMesh",
"PyBulletForwardKinematics",
"PyBulletInverseKinematics",
"PyBulletRemoveAttachedCollisionMesh",
"PyBulletRemoveCollisionMesh",
]
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,6 @@
class PyBulletAddAttachedCollisionMesh(AddAttachedCollisionMesh):
"""Callable to add a collision mesh and attach it to the robot."""

def __init__(self, client):
self.client = client

def add_attached_collision_mesh(self, attached_collision_mesh, options=None):
"""Add a collision mesh and attach it to the robot.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,6 @@
class PyBulletAddCollisionMesh(AddCollisionMesh):
"""Callable to add a collision mesh to the planning scene."""

def __init__(self, client):
self.client = client

def add_collision_mesh(self, collision_mesh, options=None):
"""Add a collision mesh to the planning scene.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,6 @@
class PyBulletAppendCollisionMesh(AppendCollisionMesh):
"""Callable to append a collision mesh to the planning scene."""

def __init__(self, client):
self.client = client

def append_collision_mesh(self, collision_mesh, options=None):
"""Append a collision mesh to the planning scene.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,6 @@
class PyBulletForwardKinematics(ForwardKinematics):
"""Callable to calculate the robot's forward kinematic."""

def __init__(self, client):
self.client = client

def forward_kinematics(self, robot, configuration, group=None, options=None):
"""Calculate the robot's forward kinematic.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,6 @@
class PyBulletInverseKinematics(InverseKinematics):
"""Callable to calculate the robot's inverse kinematics for a given frame."""

def __init__(self, client):
self.client = client

def inverse_kinematics(self, robot, frame_WCF, start_configuration=None, group=None, options=None):
"""Calculate the robot's inverse kinematic for a given frame.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,6 @@
class PyBulletRemoveAttachedCollisionMesh(RemoveAttachedCollisionMesh):
"""Callable to remove an attached collision mesh from the robot."""

def __init__(self, client):
self.client = client

def remove_attached_collision_mesh(self, id, options=None):
"""Remove an attached collision mesh from the robot.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,6 @@
class PyBulletRemoveCollisionMesh(RemoveCollisionMesh):
"""Callable to remove a collision mesh from the planning scene."""

def __init__(self, client):
self.client = client

def remove_collision_mesh(self, id, options=None):
"""Remove a collision mesh from the planning scene.
Expand Down
15 changes: 11 additions & 4 deletions src/compas_fab/backends/pybullet/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -827,8 +827,15 @@ def _get_geometry_args(path, concavity=False, scale=1.0):


class AnalyticalPyBulletClient(PyBulletClient):
def inverse_kinematics(self, *args, **kwargs):
return AnalyticalInverseKinematics(self)(*args, **kwargs)
"""Combination of PyBullet as the client for Collision Detection and Analytical Inverse Kinematics."""

def plan_cartesian_motion(self, *args, **kwargs):
return AnalyticalPlanCartesianMotion(self)(*args, **kwargs)
def __init__(self, connection_type="gui", verbose=False):
super(self, AnalyticalPyBulletClient).__init__(self, connection_type=connection_type, verbose=verbose)
gonzalocasas marked this conversation as resolved.
Show resolved Hide resolved

def inverse_kinematics(self, robot, frame_WCF, start_configuration=None, group=None, options=None):
planner = AnalyticalInverseKinematics(self)
return planner.inverse_kinematics(robot, frame_WCF, start_configuration, group, options)

def plan_cartesian_motion(self, robot, waypoints, start_configuration=None, group=None, options=None):
planner = AnalyticalPlanCartesianMotion(self)
return planner.plan_cartesian_motion(robot, waypoints, start_configuration, group, options)
43 changes: 12 additions & 31 deletions src/compas_fab/backends/pybullet/planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from __future__ import print_function

from compas_fab.backends.interfaces.client import PlannerInterface
from compas_fab.backends.interfaces.client import forward_docstring

from compas_fab.backends.pybullet.backend_features.pybullet_add_attached_collision_mesh import (
PyBulletAddAttachedCollisionMesh,
)
Expand All @@ -21,36 +21,17 @@
]


class PyBulletPlanner(PlannerInterface):
class PyBulletPlanner(
PyBulletAddAttachedCollisionMesh,
PyBulletAddCollisionMesh,
PyBulletAppendCollisionMesh,
PyBulletRemoveCollisionMesh,
PyBulletRemoveAttachedCollisionMesh,
PyBulletForwardKinematics,
PyBulletInverseKinematics,
PlannerInterface,
):
"""Implement the planner backend interface for PyBullet."""

def __init__(self, client):
super(PyBulletPlanner, self).__init__(client)

@forward_docstring(PyBulletAddAttachedCollisionMesh)
def add_attached_collision_mesh(self, *args, **kwargs):
return PyBulletAddAttachedCollisionMesh(self.client)(*args, **kwargs)

@forward_docstring(PyBulletAddCollisionMesh)
def add_collision_mesh(self, *args, **kwargs):
return PyBulletAddCollisionMesh(self.client)(*args, **kwargs)

@forward_docstring(PyBulletAppendCollisionMesh)
def append_collision_mesh(self, *args, **kwargs):
return PyBulletAppendCollisionMesh(self.client)(*args, **kwargs)

@forward_docstring(PyBulletRemoveCollisionMesh)
def remove_collision_mesh(self, *args, **kwargs):
return PyBulletRemoveCollisionMesh(self.client)(*args, **kwargs)

@forward_docstring(PyBulletRemoveAttachedCollisionMesh)
def remove_attached_collision_mesh(self, *args, **kwargs):
return PyBulletRemoveAttachedCollisionMesh(self.client)(*args, **kwargs)

@forward_docstring(PyBulletForwardKinematics)
def forward_kinematics(self, *args, **kwargs):
return PyBulletForwardKinematics(self.client)(*args, **kwargs)

@forward_docstring(PyBulletInverseKinematics)
def inverse_kinematics(self, *args, **kwargs):
return PyBulletInverseKinematics(self.client)(*args, **kwargs)
self.client = client
22 changes: 22 additions & 0 deletions src/compas_fab/backends/ros/backend_features/__init__.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,25 @@
"""
ROS backend features
====================
.. autosummary::
:toctree: generated/
:nosignatures:
MoveItAddAttachedCollisionMesh
MoveItAddCollisionMesh
MoveItAppendCollisionMesh
MoveItForwardKinematics
MoveItInverseKinematics
MoveItPlanCartesianMotion
MoveItPlanMotion
MoveItPlanningScene
MoveItRemoveAttachedCollisionMesh
MoveItRemoveCollisionMesh
MoveItResetPlanningScene
"""

from __future__ import absolute_import

from compas_fab.backends.ros.backend_features.move_it_add_attached_collision_mesh import MoveItAddAttachedCollisionMesh
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,6 @@ class MoveItAddAttachedCollisionMesh(AddAttachedCollisionMesh):
ApplyPlanningSceneResponse,
)

def __init__(self, ros_client):
self.ros_client = ros_client

def add_attached_collision_mesh(self, attached_collision_mesh, options=None):
"""Add a collision mesh and attach it to the robot.
Expand All @@ -56,5 +53,5 @@ def add_attached_collision_mesh_async(self, callback, errback, attached_collisio
aco.object.operation = CollisionObject.ADD
robot_state = RobotState(attached_collision_objects=[aco], is_diff=True)
scene = PlanningScene(robot_state=robot_state, is_diff=True)
request = scene.to_request(self.ros_client.ros_distro)
self.APPLY_PLANNING_SCENE(self.ros_client, request, callback, errback)
request = scene.to_request(self.client.ros_distro)
self.APPLY_PLANNING_SCENE(self.client, request, callback, errback)
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,6 @@ class MoveItAddCollisionMesh(AddCollisionMesh):
ApplyPlanningSceneResponse,
)

def __init__(self, ros_client):
self.ros_client = ros_client

def add_collision_mesh(self, collision_mesh, options=None):
"""Add a collision mesh to the planning scene.
Expand All @@ -55,5 +52,5 @@ def add_collision_mesh_async(self, callback, errback, collision_mesh):
co.operation = CollisionObject.ADD
world = PlanningSceneWorld(collision_objects=[co])
scene = PlanningScene(world=world, is_diff=True)
request = scene.to_request(self.ros_client.ros_distro)
self.APPLY_PLANNING_SCENE(self.ros_client, request, callback, errback)
request = scene.to_request(self.client.ros_distro)
self.APPLY_PLANNING_SCENE(self.client, request, callback, errback)
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,6 @@ class MoveItAppendCollisionMesh(AppendCollisionMesh):
ApplyPlanningSceneResponse,
)

def __init__(self, ros_client):
self.ros_client = ros_client

def append_collision_mesh(self, collision_mesh, options=None):
"""Append a collision mesh to the planning scene.
Expand All @@ -55,5 +52,5 @@ def append_collision_mesh_async(self, callback, errback, collision_mesh):
co.operation = CollisionObject.APPEND
world = PlanningSceneWorld(collision_objects=[co])
scene = PlanningScene(world=world, is_diff=True)
request = scene.to_request(self.ros_client.ros_distro)
self.APPLY_PLANNING_SCENE(self.ros_client, request, callback, errback)
request = scene.to_request(self.client.ros_distro)
self.APPLY_PLANNING_SCENE(self.client, request, callback, errback)
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,6 @@ class MoveItForwardKinematics(ForwardKinematics):
"/compute_fk", "GetPositionFK", GetPositionFKRequest, GetPositionFKResponse, validate_response
)

def __init__(self, ros_client):
self.ros_client = ros_client

def forward_kinematics(self, robot, configuration, group=None, options=None):
"""Calculate the robot's forward kinematic.
Expand Down Expand Up @@ -83,9 +80,9 @@ def forward_kinematics_async(self, callback, errback, configuration, options):
header = Header(frame_id=base_link)
joint_state = JointState(name=configuration.joint_names, position=configuration.joint_values, header=header)
robot_state = RobotState(joint_state, MultiDOFJointState(header=header))
robot_state.filter_fields_for_distro(self.ros_client.ros_distro)
robot_state.filter_fields_for_distro(self.client.ros_distro)

def convert_to_frame(response):
callback(response.pose_stamped[0].pose.frame)

self.GET_POSITION_FK(self.ros_client, (header, fk_link_names, robot_state), convert_to_frame, errback)
self.GET_POSITION_FK(self.client, (header, fk_link_names, robot_state), convert_to_frame, errback)
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,6 @@ class MoveItInverseKinematics(InverseKinematics):
"/compute_ik", "GetPositionIK", GetPositionIKRequest, GetPositionIKResponse, validate_response
)

def __init__(self, ros_client):
self.ros_client = ros_client

def inverse_kinematics(self, robot, frame_WCF, start_configuration=None, group=None, options=None):
"""Calculate the robot's inverse kinematic for a given frame.
Expand Down Expand Up @@ -115,7 +112,7 @@ def inverse_kinematics_async(
start_state.attached_collision_objects.append(aco)

# Filter needs to happen after all objects have been added
start_state.filter_fields_for_distro(self.ros_client.ros_distro)
start_state.filter_fields_for_distro(self.client.ros_distro)

constraints = convert_constraints_to_rosmsg(options.get("constraints"), header)

Expand All @@ -135,10 +132,10 @@ def inverse_kinematics_async(
# The field `attempts` was removed in Noetic (and higher)
# so it needs to be removed from the message otherwise it causes a serialization error
# https://github.com/ros-planning/moveit/pull/1288
if self.ros_client.ros_distro not in (RosDistro.KINETIC, RosDistro.MELODIC):
if self.client.ros_distro not in (RosDistro.KINETIC, RosDistro.MELODIC):
del ik_request.attempts

def convert_to_positions(response):
callback((response.solution.joint_state.position, response.solution.joint_state.name))

self.GET_POSITION_IK(self.ros_client, (ik_request,), convert_to_positions, errback)
self.GET_POSITION_IK(self.client, (ik_request,), convert_to_positions, errback)
Loading
Loading