Exemplo n.º 1
0
    def add_attached_collision_mesh(self,
                                    id_name,
                                    mesh,
                                    group=None,
                                    touch_links=[],
                                    scale=False):
        """Attaches a collision mesh to the robot's end-effector.

        Parameters
        ----------
            id_name (str): The identifier of the object.
            mesh (:class:`Mesh`): A triangulated COMPAS mesh.
            group (str, optional): The planning group on which's end-effector
                the object should be attached. Defaults to the robot's main
                planning group.
            touch_links(str list): The list of link names that the attached mesh
                is allowed to touch by default. The end-effector link name is
                already considered.
        """
        if not group:
            group = self.main_group_name  # ensure semantics
        ee_link_name = self.get_end_effector_link_name(group)

        if scale:
            S = Scale([1. / self.scale_factor] * 3)
            mesh = mesh_transformed(mesh, S)

        if ee_link_name not in touch_links:
            touch_links.append(ee_link_name)

        self.client.attached_collision_mesh(id_name, ee_link_name, mesh, 0,
                                            touch_links)
Exemplo n.º 2
0
    def add_collision_mesh_to_planning_scene(self, id_name, mesh, scale=False):
        """Adds a collision mesh to the robot's planning scene.

        Parameters
        ----------
            id_name (str): The identifier of the collision mesh.
            mesh (:class:`Mesh`): A triangulated COMPAS mesh.

        Examples
        --------
        """
        self.ensure_client()
        root_link_name = self.model.root.name

        if scale:
            S = Scale([1. / self.scale_factor] * 3)
            mesh = mesh_transformed(mesh, S)

        self.client.collision_mesh(id_name, root_link_name, mesh, 0)
Exemplo n.º 3
0
    def create_collision_mesh_attached_to_end_effector(self,
                                                       id_name,
                                                       mesh,
                                                       group=None,
                                                       scale=False):
        """Creates a collision object that is added to the end effector's tcp.
        """
        if not group:
            group = self.main_group_name  # ensure semantics
        ee_link_name = self.get_end_effector_link_name(group)

        if scale:
            S = Scale([1. / self.scale_factor] * 3)
            mesh = mesh_transformed(mesh, S)

        last_link_with_geometry = self.get_links_with_geometry(group)[-1]
        touch_links = [last_link_with_geometry.name]

        return self.client.build_attached_collision_mesh(
            ee_link_name, id_name, mesh, operation=0, touch_links=touch_links)
Exemplo n.º 4
0
    import compas

    from compas.datastructures import Mesh, mesh_transformed
    from compas.utilities import download_file_from_remote
    from compas_viewers.multimeshviewer import MultiMeshViewer

    source_glb = 'https://raw.githubusercontent.com/KhronosGroup/glTF-Sample-Models/master/2.0/BoxInterleaved/glTF-Binary/BoxInterleaved.glb'
    filepath_glb = os.path.join(compas.APPDATA, 'data', 'gltfs', 'khronos',
                                'BoxInterleaved.glb')

    download_file_from_remote(source_glb, filepath_glb, overwrite=False)

    gltf = GLTF(filepath_glb)
    gltf.read()

    default_scene = gltf.content.default_or_first_scene

    transformed_meshes = []

    for vertex_name, gltf_node in default_scene.nodes.items():
        if gltf_node.mesh_data is None:
            continue
        t = gltf_node.transform
        m = Mesh.from_vertices_and_faces(gltf_node.vertices, gltf_node.faces)
        transformed_mesh = mesh_transformed(m, t)
        transformed_meshes.append(transformed_mesh)

    viewer = MultiMeshViewer()
    viewer.meshes = transformed_meshes
    viewer.show()
                    attr['is_planned'], True)]
    sequence = [k for k in sequence if k not in exclude_keys] # keep order
    print("sequence", sequence)

    # Iterate over the sequence
    for key in sequence:

        start_configuration = picking_configuration

        # Read the placing frame from brick, zaxis down
        o, uvw = assembly_block_placing_frame(assembly, key)
        placing_frame = Frame(o, uvw[1], uvw[0])

        # create attached collision object
        brick = assembly.blocks[key]
        brick_tcp = mesh_transformed(brick, Transformation.from_frame_to_frame(placing_frame, Frame.worldXY()))
        aco = robot.create_collision_mesh_attached_to_end_effector('brick', brick_tcp, group)

        saveframe_place = Frame(placing_frame.point + save_vector, placing_frame.xaxis, placing_frame.yaxis)
        paths = [traj1]

        # Calculate kinematic path between saveframe_pick and saveframe_place
        try:
            response = robot.motion_plan_goal_frame(frame_WCF=saveframe_place,
                                                    start_configuration=start_configuration,
                                                    tolerance_position=0.005,
                                                    tolerance_angle=math.radians(1),
                                                    group=group,
                                                    path_constraints=None,
                                                    planner_id='RRT',
                                                    num_planning_attempts=20,