from __future__ import absolute_import from __future__ import division from __future__ import print_function import math import sys from compas.robots import Joint from compas_fab.backends.interfaces import InverseKinematics from compas_fab.backends.pybullet.conversions import pose_from_frame from compas_fab.backends.pybullet.exceptions import InverseKinematicsError from compas_fab.utilities import LazyLoader pybullet = LazyLoader('pybullet', globals(), 'pybullet') __all__ = [ 'PyBulletInverseKinematics', ] 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):
from __future__ import absolute_import from __future__ import division from __future__ import print_function from compas_fab.backends.interfaces import AddAttachedCollisionMesh from compas_fab.backends.vrep.helpers import DEFAULT_OP_MODE from compas_fab.backends.vrep.helpers import VrepError from compas_fab.backends.vrep.helpers import assert_robot from compas_fab.utilities import LazyLoader __all__ = [ 'VrepAddAttachedCollisionMesh', ] vrep = LazyLoader('vrep', globals(), 'compas_fab.backends.vrep.remote_api.vrep') class VrepAddAttachedCollisionMesh(AddAttachedCollisionMesh): """Callable to add a building member to the 3D scene and attach it to the robot. """ def __init__(self, client): self.client = client def add_attached_collision_mesh(self, attached_collision_mesh, options=None): """Adds a building member to the 3D scene and attaches it to the robot. Args: attached_collision_mesh (:class:`compas.datastructures.Mesh`): Mesh