Beispiel #1
0
def parse_collision_mesh_from_path(dir_path, filename, scale=1e-3):
    file_path = os.path.join(dir_path, filename)
    obj_name = filename.split('.')[0]
    if filename.endswith('.obj'):
        mesh = Mesh.from_obj(file_path)
    elif filename.endswith('.stl'):
        mesh = Mesh.from_stl(file_path)
    else:
        return None
    cm = CollisionMesh(mesh, obj_name)
    cm.scale(scale)
    return cm
Beispiel #2
0
 def to_collision_meshes(self):
     """Creates a list of collision meshes from a :class:`compas_fab.backends.CollisionObject`
     """
     collision_meshes = []
     for mesh, pose in zip(self.meshes, self.mesh_poses):
         pose = pose if isinstance(pose, Pose) else Pose(**pose)
         pose.position = pose.position if isinstance(pose.position, Point) else Point(**pose.position)
         pose.position.x = float(pose.position.x)
         pose.position.y = float(pose.position.y)
         pose.position.z = float(pose.position.z)
         pose.orientation = pose.orientation if isinstance(pose.orientation, Quaternion) else Quaternion(**pose.orientation)
         pose.orientation.x = float(pose.orientation.x)
         pose.orientation.y = float(pose.orientation.y)
         pose.orientation.z = float(pose.orientation.z)
         pose.orientation.w = float(pose.orientation.w)
         mesh = mesh if isinstance(mesh, Mesh) else Mesh(**mesh)
         mesh.triangles = [t if isinstance(t, MeshTriangle) else MeshTriangle(**t) for t in mesh.triangles]
         for triangle in mesh.triangles:
             triangle.vertex_indices = [int(x) for x in triangle.vertex_indices]
         mesh.vertices = [v if isinstance(v, Point) else Point(**v) for v in mesh.vertices]
         for vertex in mesh.vertices:
             vertex.x = float(vertex.x)
             vertex.y = float(vertex.y)
             vertex.z = float(vertex.z)
         root_name = getattr(self.header, 'frame_id', None) or self.header['frame_id']
         cm = CollisionMesh(mesh.mesh, self.id, pose.frame, root_name)
         collision_meshes.append(cm)
     return collision_meshes
Beispiel #3
0
 def RunScript(self, scene, M, name, add, remove):
     ok = False
     if scene and M and name:
         mesh = RhinoMesh.from_geometry(M).to_compas()
         collision_mesh = CollisionMesh(mesh, name)
         if add:
             scene.add_collision_mesh(collision_mesh)
             ok = True
         if remove:
             scene.remove_collision_mesh(name)
             ok = True
     return ok
Beispiel #4
0
 def RunScript(self, scene, mesh, identifier, link_name, touch_links, add, remove):
     attached_collision_mesh = None
     if scene and mesh and identifier and link_name:
         compas_mesh = RhinoMesh.from_geometry(mesh).to_compas()
         collision_mesh = CollisionMesh(compas_mesh, identifier)
         attached_collision_mesh = AttachedCollisionMesh(collision_mesh, link_name, touch_links)
         if add:
             scene.add_attached_collision_mesh(attached_collision_mesh)
         if remove:
             scene.remove_attached_collision_mesh(identifier)
             scene.remove_collision_mesh(identifier)
     return attached_collision_mesh
def move_and_placing_motion(element, start_configuration, tolerance_vector,
                            savelevel_vector, brick_acm):
    """Returns two trajectories to move and place an element.
    """

    # settings for plan_motion
    tolerance_position = 0.001
    tolerance_axes = [math.radians(1)] * 3

    target_frame = element.gripping_frame.copy()
    target_frame.point += tolerance_vector

    savelevel_target_frame = target_frame.copy()
    savelevel_target_frame.point += savelevel_vector

    # calulate a free-space motion to the savelevel_target_frame
    savelevel_target_frame_tool0 = robot.from_attached_tool_to_tool0(
        [savelevel_target_frame])[0]
    goal_constraints = robot.constraints_from_frame(
        savelevel_target_frame_tool0, tolerance_position, tolerance_axes)

    trajectory2 = robot.plan_motion(goal_constraints,
                                    start_configuration,
                                    planner_id='RRT',
                                    attached_collision_meshes=[brick_acm])

    # calculate a cartesian motion to the target_frame
    frames = [savelevel_target_frame, target_frame]

    start_configuration = trajectory2.points[
        -1]  # as start configuration take last trajectory's end configuration
    trajectory3 = robot.plan_cartesian_motion(
        robot.from_attached_tool_to_tool0(frames),
        start_configuration,
        max_step=0.01,
        attached_collision_meshes=[brick_acm])
    assert (trajectory3.fraction == 1.)

    # add the brick to the planning scene
    brick = CollisionMesh(element.mesh, 'brick_wall')
    scene.append_collision_mesh(brick)
    time.sleep(0.5)
    return trajectory2, trajectory3
import time

from compas.datastructures import Mesh
from compas.geometry import Box, Translation

from compas_fab.backends import RosClient
from compas_fab.robots import CollisionMesh
from compas_fab.robots import PlanningScene

with RosClient('localhost') as client:
    robot = client.load_robot()
    scene = PlanningScene(robot)

    brick = Box.from_width_height_depth(0.016, 0.012, 0.031)
    brick.transform(Translation.from_vector([0, 0, brick.zsize / 2.]))

    for i in range(5):
        mesh = Mesh.from_shape(brick)
        cm = CollisionMesh(mesh, 'brick_wall')
        cm.frame.point.y += 0.5
        cm.frame.point.z += brick.zsize * i

        scene.append_collision_mesh(cm)

    # sleep a bit before terminating the client
    time.sleep(1)
import time

from compas.datastructures import Mesh
from compas.geometry import Box

from compas_fab.backends import RosClient
from compas_fab.robots import CollisionMesh
from compas_fab.robots import PlanningScene

with RosClient() as client:
    robot = client.load_robot()
    scene = PlanningScene(robot)
    assert robot.name == 'ur5_robot'

    brick = Box.from_width_height_depth(0.11, 0.07, 0.25)

    for i in range(5):
        mesh = Mesh.from_vertices_and_faces(brick.vertices, brick.faces)
        cm = CollisionMesh(mesh, 'brick')
        cm.frame.point.y += 0.5
        cm.frame.point.z += brick.zsize * i

        scene.append_collision_mesh(cm)

    # sleep a bit before removing the bricks
    time.sleep(1)

    scene.remove_collision_mesh('brick')
def main():
    parser = argparse.ArgumentParser()
    # ur_picknplace_multiple_piece
    parser.add_argument('-p',
                        '--problem',
                        default='ur_picknplace_single_piece',
                        help='The name of the problem to solve')
    parser.add_argument('-rob',
                        '--robot',
                        default='ur3',
                        help='The type of UR robot to use.')
    parser.add_argument('-m',
                        '--plan_transit',
                        action='store_false',
                        help='Plans motions between each picking and placing')
    parser.add_argument('-v',
                        '--viewer',
                        action='store_true',
                        help='Enables the viewer during planning (slow!)')
    parser.add_argument('-s',
                        '--save_result',
                        action='store_true',
                        help='save planning results as a json file')
    parser.add_argument(
        '-scale',
        '--model_scale',
        default=0.001,
        help='model scale conversion to meter, default 0.001 (from millimeter)'
    )
    parser.add_argument('-vik',
                        '--view_ikfast',
                        action='store_true',
                        help='Visualize each ikfast solutions')
    parser.add_argument('-tres',
                        '--transit_res',
                        default=0.01,
                        help='joint resolution (rad)')
    parser.add_argument('-ros',
                        '--use_ros',
                        action='store_true',
                        help='use ros backend with moveit planners')
    parser.add_argument('-cart_ts',
                        '--cartesian_time_step',
                        default=0.1,
                        help='cartesian time step in trajectory simulation')
    parser.add_argument('-trans_ts',
                        '--transit_time_step',
                        default=0.01,
                        help='transition time step in trajectory simulation')
    parser.add_argument('-per_conf_step',
                        '--per_conf_step',
                        action='store_true',
                        help='stepping each configuration in simulation')
    args = parser.parse_args()
    print('Arguments:', args)

    VIZ = args.viewer
    VIZ_IKFAST = args.view_ikfast
    TRANSITION_JT_RESOLUTION = float(args.transit_res)
    plan_transition = args.plan_transit
    use_moveit_planner = args.use_ros

    # sim settings
    CART_TIME_STEP = args.cartesian_time_step
    TRANSITION_TIME_STEP = args.transit_time_step
    PER_CONF_STEP = args.per_conf_step

    # transition motion planner settings
    RRT_RESTARTS = 5
    RRT_ITERATIONS = 40

    # choreo pkg settings
    choreo_problem_instance_dir = compas_fab.get('choreo_instances')
    unit_geos, static_obstacles = load_assembly_package(
        choreo_problem_instance_dir, args.problem, scale=args.model_scale)

    result_save_path = os.path.join(
        choreo_problem_instance_dir, 'results',
        'choreo_result.json') if args.save_result else None

    # urdf, end effector settings
    if args.robot == 'ur3':
        # urdf_filename = compas_fab.get('universal_robot/ur_description/urdf/ur3.urdf')
        urdf_filename = compas_fab.get(
            'universal_robot/ur_description/urdf/ur3_collision_viz.urdf')
        srdf_filename = compas_fab.get(
            'universal_robot/ur3_moveit_config/config/ur3.srdf')
    else:
        urdf_filename = compas_fab.get(
            'universal_robot/ur_description/urdf/ur5.urdf')
        srdf_filename = compas_fab.get(
            'universal_robot/ur5_moveit_config/config/ur5.srdf')

    urdf_pkg_name = 'ur_description'

    ee_filename = compas_fab.get(
        'universal_robot/ur_description/meshes/' +
        'pychoreo_workshop_gripper/collision/victor_gripper_jaw03.obj')
    # ee_sep_filename = compas_fab.get('universal_robot/ur_description/meshes/' +
    #                             'pychoreo_workshop_gripper/collision/victor_gripper_jaw03_rough_sep.obj')
    # ee_decomp_file_dir = compas_fab.get('universal_robot/ur_description/meshes/' +
    #                                 'pychoreo_workshop_gripper/collision/decomp')
    # ee_decomp_file_prefix = 'victor_gripper_jaw03_decomp_'
    # decomp_parts_num = 36

    client = RosClient() if use_moveit_planner else None

    # geometry file is not loaded here
    model = RobotModel.from_urdf_file(urdf_filename)
    semantics = RobotSemantics.from_srdf_file(srdf_filename, model)
    robot = RobotClass(model, semantics=semantics, client=client)

    group = robot.main_group_name
    base_link_name = robot.get_base_link_name()
    ee_link_name = robot.get_end_effector_link_name()
    ik_joint_names = robot.get_configurable_joint_names()

    # parse end effector mesh
    # ee_meshes = [Mesh.from_obj(os.path.join(ee_decomp_file_dir, ee_decomp_file_prefix + str(i) + '.obj')) for i in range(decomp_parts_num)]
    ee_meshes = [Mesh.from_obj(ee_filename)]
    # ee_meshes = [Mesh.from_obj(ee_sep_filename)]

    # define TCP transformation
    tcp_tf = Translation([0.099, 0, 0])  # in meters
    ur5_start_conf = [0, -1.65715, 1.71108, -1.62348, 0, 0]

    if use_moveit_planner:
        # TODO: attach end effector to the robot in planning scene
        # https://github.com/compas-dev/compas_fab/issues/66
        scene = PlanningScene(robot)
        scene.remove_all_collision_objects()
        client.set_joint_positions(group, ik_joint_names, ur5_start_conf)
    else:
        scene = None

    # add static collision obstacles
    co_dict = {}
    for i, static_obs_mesh in enumerate(static_obstacles):
        # offset the table a bit...
        cm = CollisionMesh(static_obs_mesh,
                           'so_' + str(i),
                           frame=Frame.from_transformation(
                               Translation([0, 0, -0.02])))
        if use_moveit_planner:
            scene.add_collision_mesh(cm)
        else:
            co_dict[cm.id] = {}
            co_dict[cm.id]['meshes'] = [cm.mesh]
            co_dict[cm.id]['mesh_poses'] = [cm.frame]

    if use_moveit_planner:
        # See: https://github.com/compas-dev/compas_fab/issues/63#issuecomment-519525879
        time.sleep(1)
        co_dict = scene.get_collision_meshes_and_poses()

    # ======================================================
    # ======================================================
    # start pybullet environment & load pybullet robot
    connect(use_gui=VIZ)
    pb_robot = create_pb_robot_from_ros_urdf(urdf_filename,
                                             urdf_pkg_name,
                                             planning_scene=scene,
                                             ee_link_name=ee_link_name)
    ee_attachs = attach_end_effector_geometry(ee_meshes, pb_robot,
                                              ee_link_name)

    # update current joint conf and attach end effector
    pb_ik_joints = joints_from_names(pb_robot, ik_joint_names)
    pb_end_effector_link = link_from_name(pb_robot, ee_link_name)
    if not use_moveit_planner:
        set_joint_positions(pb_robot, pb_ik_joints, ur5_start_conf)
    for e_at in ee_attachs:
        e_at.assign()

    # draw TCP frame in pybullet
    if has_gui():
        TCP_pb_pose = get_TCP_pose(pb_robot,
                                   ee_link_name,
                                   tcp_tf,
                                   return_pb_pose=True)
        handles = draw_pose(TCP_pb_pose, length=0.04)
        # wait_for_user()

    # deliver ros collision meshes to pybullet
    static_obstacles_from_name = convert_meshes_and_poses_to_pybullet_bodies(
        co_dict)
    # for now...
    for so_key, so_val in static_obstacles_from_name.items():
        static_obstacles_from_name[so_key] = so_val[0]

    for unit_name, unit_geo in unit_geos.items():
        geo_bodies = []
        for sub_id, mesh in enumerate(unit_geo.mesh):
            geo_bodies.append(convert_mesh_to_pybullet_body(mesh))
        unit_geo.pybullet_bodies = geo_bodies

    # check collision between obstacles and element geometries
    assert not sanity_check_collisions(unit_geos, static_obstacles_from_name)

    # from random import shuffle
    seq_assignment = list(range(len(unit_geos)))
    # shuffle(seq_assignment)
    element_seq = {seq_id: e_id for seq_id, e_id in enumerate(seq_assignment)}

    # for key, val in element_seq.items():
    #     # element_seq[key] = 'e_' + str(val)
    #     element_seq[key] = val

    if has_gui():
        for e_id in element_seq.values():
            # for e_body in brick_from_index[e_id].body: set_pose(e_body, brick_from_index[e_id].goal_pose)
            handles.extend(
                draw_pose(unit_geos[e_id].initial_pb_pose, length=0.02))
            handles.extend(draw_pose(unit_geos[e_id].goal_pb_pose,
                                     length=0.02))
            for e_body in unit_geos[e_id].pybullet_bodies:
                set_pose(e_body, unit_geos[e_id].initial_pb_pose)
        print('pybullet env loaded.')
        # wait_for_user()
        for h in handles:
            remove_debug(h)

    saved_world = WorldSaver()

    ik_fn = ikfast_ur3.get_ik if args.robot == 'ur3' else ikfast_ur5.get_ik
    tot_traj, graph_sizes = \
    direct_ladder_graph_solve_picknplace(pb_robot, ik_joint_names, base_link_name, ee_link_name, ik_fn,
        unit_geos, element_seq, static_obstacles_from_name,
        tcp_transf=pb_pose_from_Transformation(tcp_tf),
        ee_attachs=ee_attachs,
        max_attempts=100, viz=VIZ_IKFAST, st_conf=ur5_start_conf)

    picknplace_cart_plans = divide_nested_list_chunks(tot_traj, graph_sizes)

    saved_world.restore()
    print('Cartesian planning finished.')

    # reset robot and parts for better visualization
    set_joint_positions(pb_robot, pb_ik_joints, ur5_start_conf)
    for ee in ee_attachs:
        ee.assign()
    for e_id in element_seq.values():
        for e_body in unit_geos[e_id].pybullet_bodies:
            set_pose(e_body, unit_geos[e_id].initial_pb_pose)

    # if has_gui():
    #     wait_for_user()

    def flatten_unit_geos_bodies(in_dict):
        out_list = []
        for ug in in_dict.values():
            out_list.extend(ug.pybullet_bodies)
        return out_list

    if plan_transition:
        print('Transition planning started.')

        for seq_id, unit_picknplace in enumerate(picknplace_cart_plans):
            print('----\ntransition seq#{}'.format(seq_id))
            e_id = element_seq[seq_id]

            if seq_id != 0:
                tr_start_conf = picknplace_cart_plans[seq_id -
                                                      1]['place_retreat'][-1]
            else:
                tr_start_conf = ur5_start_conf

            # obstacles=static_obstacles + cur_mo_list
            place2pick_st_conf = list(tr_start_conf)
            place2pick_goal_conf = list(
                picknplace_cart_plans[seq_id]['pick_approach'][0])
            # assert not client.is_joint_state_colliding(group, ik_joint_names, place2pick_st_conf)
            # assert not client.is_joint_state_colliding(group, ik_joint_names, place2pick_goal_conf)

            if use_moveit_planner:
                # TODO: add collision objects

                st_conf = Configuration.from_revolute_values(
                    place2pick_st_conf)
                goal_conf = Configuration.from_revolute_values(
                    place2pick_goal_conf)
                goal_constraints = robot.constraints_from_configuration(
                    goal_conf, [math.radians(1)] * 6, group)
                place2pick_jt_traj = robot.plan_motion(goal_constraints,
                                                       st_conf,
                                                       group,
                                                       planner_id='RRTConnect')
                place2pick_path = [
                    jt_pt['values']
                    for jt_pt in place2pick_jt_traj.to_data()['points']
                ]

            else:
                saved_world = WorldSaver()

                set_joint_positions(pb_robot, pb_ik_joints, place2pick_st_conf)
                for ee_a in ee_attachs:
                    ee_a.assign()

                place2pick_path = plan_joint_motion(
                    pb_robot,
                    pb_ik_joints,
                    place2pick_goal_conf,
                    attachments=ee_attachs,
                    obstacles=list(static_obstacles_from_name.values()) +
                    flatten_unit_geos_bodies(unit_geos),
                    self_collisions=True,
                    resolutions=[TRANSITION_JT_RESOLUTION] * len(pb_ik_joints),
                    restarts=RRT_RESTARTS,
                    iterations=RRT_ITERATIONS,
                )
                saved_world.restore()

                if not place2pick_path:
                    saved_world = WorldSaver()

                    print('****\nseq #{} cannot find place2pick transition'.
                          format(seq_id))
                    print('Diagnosis...')

                    cfn = get_collision_fn_diagnosis(pb_robot, pb_ik_joints, \
                        obstacles=list(static_obstacles_from_name.values()) + flatten_unit_geos_bodies(unit_geos),
                        attachments=ee_attachs, self_collisions=True)

                    print('start pose:')
                    cfn(place2pick_st_conf)

                    print('end pose:')
                    cfn(place2pick_goal_conf)

                    saved_world.restore()
                    print('Diagnosis over')

            pick2place_st_conf = picknplace_cart_plans[seq_id]['pick_retreat'][
                -1]
            pick2place_goal_conf = picknplace_cart_plans[seq_id][
                'place_approach'][0]

            if use_moveit_planner:
                st_conf = Configuration.from_revolute_values(
                    picknplace_cart_plans[seq_id]['pick_retreat'][-1])
                goal_conf = Configuration.from_revolute_values(
                    picknplace_cart_plans[seq_id]['place_approach'][0])
                goal_constraints = robot.constraints_from_configuration(
                    goal_conf, [math.radians(1)] * 6, group)
                pick2place_jt_traj = robot.plan_motion(goal_constraints,
                                                       st_conf,
                                                       group,
                                                       planner_id='RRTConnect')
                pick2place_path = [
                    jt_pt['values']
                    for jt_pt in pick2place_jt_traj.to_data()['points']
                ]
            else:
                saved_world = WorldSaver()

                # create attachement without needing to keep track of grasp...
                set_joint_positions(
                    pb_robot, pb_ik_joints,
                    picknplace_cart_plans[seq_id]['pick_retreat'][0])
                # attachs = [Attachment(robot, tool_link, invert(grasp.attach), e_body) for e_body in brick.body]
                element_attachs = [create_attachment(pb_robot, pb_end_effector_link, e_body) \
                    for e_body in unit_geos[e_id].pybullet_bodies]

                set_joint_positions(pb_robot, pb_ik_joints, pick2place_st_conf)
                for ee_a in ee_attachs:
                    ee_a.assign()
                for e_a in element_attachs:
                    e_a.assign()

                pick2place_path = plan_joint_motion(
                    pb_robot,
                    pb_ik_joints,
                    pick2place_goal_conf,
                    obstacles=list(static_obstacles_from_name.values()) +
                    flatten_unit_geos_bodies(unit_geos),
                    attachments=ee_attachs + element_attachs,
                    self_collisions=True,
                    resolutions=[TRANSITION_JT_RESOLUTION] * len(pb_ik_joints),
                    restarts=RRT_RESTARTS,
                    iterations=RRT_ITERATIONS,
                )

                saved_world.restore()

                if not pick2place_path:
                    saved_world = WorldSaver()

                    print('****\nseq #{} cannot find pick2place transition'.
                          format(seq_id))
                    print('Diagnosis...')

                    cfn = get_collision_fn_diagnosis(pb_robot, pb_ik_joints,
                        obstacles=list(static_obstacles_from_name.values()) + flatten_unit_geos_bodies(unit_geos), \
                        attachments=ee_attachs + element_attachs, self_collisions=True)

                    print('start pose:')
                    cfn(pick2place_st_conf)

                    print('end pose:')
                    cfn(pick2place_goal_conf)

                    saved_world.restore()

                    print('Diagnosis over')

            picknplace_cart_plans[seq_id]['place2pick'] = place2pick_path
            picknplace_cart_plans[seq_id]['pick2place'] = pick2place_path

            for e_body in unit_geos[e_id].pybullet_bodies:
                set_pose(e_body, unit_geos[e_id].goal_pb_pose)

            if seq_id == len(picknplace_cart_plans) - 1:
                saved_world = WorldSaver()

                set_joint_positions(
                    pb_robot, pb_ik_joints,
                    picknplace_cart_plans[seq_id]['place_retreat'][-1])
                for ee_a in ee_attachs:
                    ee_a.assign()

                return2idle_path = plan_joint_motion(
                    pb_robot,
                    pb_ik_joints,
                    ur5_start_conf,
                    obstacles=list(static_obstacles_from_name.values()) +
                    flatten_unit_geos_bodies(unit_geos),
                    attachments=ee_attachs,
                    self_collisions=True,
                    resolutions=[TRANSITION_JT_RESOLUTION] * len(pb_ik_joints),
                    restarts=RRT_RESTARTS,
                    iterations=RRT_ITERATIONS,
                )

                saved_world.restore()
                picknplace_cart_plans[seq_id]['return2idle'] = return2idle_path

        print('Transition planning finished.')

    # convert to ros JointTrajectory
    traj_json_data = []
    traj_time_count = 0.0
    for i, element_process in enumerate(picknplace_cart_plans):
        e_proc_data = {}
        for sub_proc_name, sub_process in element_process.items():
            sub_process_jt_traj_list = []
            for jt_sol in sub_process:
                sub_process_jt_traj_list.append(
                    JointTrajectoryPoint(values=jt_sol,
                                         types=[0] * 6,
                                         time_from_start=Duration(
                                             traj_time_count, 0)))
                traj_time_count += 1.0  # meaningless timestamp
            e_proc_data[sub_proc_name] = JointTrajectory(
                trajectory_points=sub_process_jt_traj_list,
                start_configuration=sub_process_jt_traj_list[0]).to_data()
        traj_json_data.append(e_proc_data)

    if result_save_path:
        with open(result_save_path, 'w+') as outfile:
            json.dump(traj_json_data, outfile, indent=4)
            print('planned trajectories saved to {}'.format(result_save_path))

    print('\n*************************\nplanning completed. Simulate?')
    if has_gui():
        wait_for_user()

    for e_id in element_seq.values():
        for e_body in unit_geos[e_id].pybullet_bodies:
            set_pose(e_body, unit_geos[e_id].initial_pb_pose)

    display_picknplace_trajectories(pb_robot, ik_joint_names, ee_link_name,
                                    unit_geos, traj_json_data, \
                                    ee_attachs=ee_attachs,
                                    cartesian_time_step=CART_TIME_STEP, transition_time_step=TRANSITION_TIME_STEP, step_sim=True, per_conf_step=PER_CONF_STEP)

    if use_moveit_planner: scene.remove_all_collision_objects()
Beispiel #9
0
with RosClient('localhost') as client:
    robot = client.load_robot()
    scene = PlanningScene(robot)

    scene.remove_collision_mesh('brick_wall')

    # attach tool
    robot.attach_tool(tool)
    # add tool to scene
    scene.add_attached_tool()

    # create an attached collision mesh to the robot's end effector.
    ee_link_name = robot.get_end_effector_link_name()
    brick_acm = AttachedCollisionMesh(
        CollisionMesh(element_tool0.mesh, 'brick'), ee_link_name)
    # add the collision mesh to the scene
    scene.add_attached_collision_mesh(brick_acm)

    # ==========================================================================
    # 1. Calculate a cartesian motion from the picking frame to the savelevel_picking_frame
    frames = [picking_frame, savelevel_picking_frame]

    start_configuration = picking_configuration
    trajectory1 = robot.plan_cartesian_motion(
        robot.from_attached_tool_to_tool0(frames),
        start_configuration,
        max_step=0.01,
        attached_collision_meshes=[brick_acm])
    assert (trajectory1.fraction == 1.)
def test_plan_motion(abb_irb4600_40_255_setup, itj_TC_g1_cms, itj_beam_cm,
                     column_obstacle_cm, base_plate_cm,
                     itj_tool_changer_grasp_transf, itj_gripper_grasp_transf,
                     itj_beam_grasp_transf, tool_type,
                     itj_tool_changer_urdf_path, itj_g1_urdf_path, viewer,
                     diagnosis):
    # modified from https://github.com/yijiangh/pybullet_planning/blob/dev/tests/test_collisions.py
    urdf_filename, semantics = abb_irb4600_40_255_setup

    move_group = 'bare_arm'
    ee_touched_link_names = ['link_6']

    with PyChoreoClient(viewer=viewer) as client:
        with LockRenderer():
            robot = client.load_robot(urdf_filename)
            robot.semantics = semantics
            client.disabled_collisions = robot.semantics.disabled_collisions

            if tool_type == 'static':
                for _, ee_cm in itj_TC_g1_cms.items():
                    client.add_collision_mesh(ee_cm)
            else:
                client.add_tool_from_urdf('TC', itj_tool_changer_urdf_path)
                client.add_tool_from_urdf('g1', itj_g1_urdf_path)

            # * add static obstacles
            client.add_collision_mesh(base_plate_cm)
            client.add_collision_mesh(column_obstacle_cm)

        ik_joint_names = robot.get_configurable_joint_names(group=move_group)
        ik_joint_types = robot.get_joint_types_by_names(ik_joint_names)
        flange_link_name = robot.get_end_effector_link_name(group=move_group)

        tool0_tf = Transformation.from_frame(
            client.get_link_frame_from_name(robot, flange_link_name))
        tool0_from_tool_changer_base = itj_tool_changer_grasp_transf
        tool0_from_gripper_base = itj_gripper_grasp_transf
        client.set_object_frame(
            '^{}'.format('TC'),
            Frame.from_transformation(tool0_tf * tool0_from_tool_changer_base))
        client.set_object_frame(
            '^{}'.format('g1'),
            Frame.from_transformation(tool0_tf * tool0_from_gripper_base))

        names = client._get_collision_object_names('^{}'.format('g1')) + \
            client._get_collision_object_names('^{}'.format('TC'))
        for ee_name in names:
            attach_options = {'robot': robot}
            if tool_type == 'actuated':
                attached_child_link_name = 'toolchanger_base' if 'TC' in ee_name else 'gripper_base'
                attach_options.update(
                    {'attached_child_link_name': attached_child_link_name})
            client.add_attached_collision_mesh(AttachedCollisionMesh(
                CollisionMesh(None, ee_name),
                flange_link_name,
                touch_links=ee_touched_link_names),
                                               options=attach_options)

        #* attach beam
        client.add_collision_mesh(itj_beam_cm)
        tool0_tf = Transformation.from_frame(
            client.get_link_frame_from_name(robot, flange_link_name))
        tool0_from_beam_base = itj_beam_grasp_transf
        client.set_object_frame(
            '^{}$'.format('itj_beam_b2'),
            Frame.from_transformation(tool0_tf * tool0_from_beam_base))
        client.add_attached_collision_mesh(AttachedCollisionMesh(
            CollisionMesh(None, 'itj_beam_b2'),
            flange_link_name,
            touch_links=[]),
                                           options={'robot': robot})
        wait_if_gui('beam attached.')

        vals = [
            -1.4660765716752369, -0.22689280275926285, 0.27925268031909273,
            0.17453292519943295, 0.22689280275926285, -0.22689280275926285
        ]
        start_conf = Configuration(values=vals,
                                   types=ik_joint_types,
                                   joint_names=ik_joint_names)
        # client.set_robot_configuration(robot, start_conf)
        # wait_if_gui()

        # vals = [0.05235987755982989, -0.087266462599716474, -0.05235987755982989, 1.7104226669544429, 0.13962634015954636, -0.43633231299858238]
        vals = [
            0.034906585039886591, 0.68067840827778847, 0.15707963267948966,
            -0.89011791851710809, -0.034906585039886591, -2.2514747350726849
        ]
        end_conf = Configuration(values=vals,
                                 types=ik_joint_types,
                                 joint_names=ik_joint_names)
        # client.set_robot_configuration(robot, end_conf)
        # wait_if_gui()

        plan_options = {'diagnosis': True, 'resolutions': 0.05}

        goal_constraints = robot.constraints_from_configuration(
            end_conf, [0.01], [0.01], group=move_group)

        st_time = time.time()
        trajectory = client.plan_motion(robot,
                                        goal_constraints,
                                        start_configuration=start_conf,
                                        group=move_group,
                                        options=plan_options)
        print('Solving time: {}'.format(elapsed_time(st_time)))

        if trajectory is None:
            cprint('Client motion planner CANNOT find a plan!', 'red')
            # assert False, 'Client motion planner CANNOT find a plan!'
            # TODO warning
        else:
            cprint('Client motion planning find a plan!', 'green')
            wait_if_gui('Start sim.')
            time_step = 0.03
            for traj_pt in trajectory.points:
                client.set_robot_configuration(robot, traj_pt)
                wait_for_duration(time_step)

        wait_if_gui("Finished.")
Beispiel #11
0
# load settings (shared by GH)
settings_file = os.path.join(DATA, "settings.json")
with open(settings_file, 'r') as f:
    data = json.load(f)

# define brick dimensions
width, length, height = data['brick_dimensions']

# define target frame
target_frame = Frame([-0.26, -0.28, height], [1, 0, 0], [0, 1, 0])

# Move brick to target frame
element = Element.from_data(data['brick'])
element.transform(
    Transformation.from_frame_to_frame(element.frame, target_frame))

with RosClient('localhost') as client:
    robot = client.load_robot()
    scene = PlanningScene(robot)

    # create a CollisionMesh from the element and add it to the scene
    brick = CollisionMesh(element.mesh, 'brick_wall')
    scene.append_collision_mesh(brick)

    time.sleep(2)

    # Remove elements from scene
    # scene.remove_collision_mesh(brick.id)
    # time.sleep(1)
def sequenced_picknplace_plan(
        assembly_json_path,
        robot_model='ur3',
        pick_from_same_rack=True,
        customized_sequence=[],
        from_seq_id=0,
        to_seq_id=None,
        num_cart_steps=10,
        enable_viewer=True,
        plan_transit=True,
        transit_res=0.01,
        view_ikfast=False,
        tcp_tf_list=[1e-3 * 80.525, 0, 0],
        robot_start_conf=[0, -1.65715, 1.71108, -1.62348, 0, 0],
        scale=1,
        result_save_path='',
        sim_traj=True,
        cart_ts=0.1,
        trans_ts=0.01,
        per_conf_step=False,
        step_sim=False):

    # parser.add_argument('-vik', '--view_ikfast', action='store_true', help='Visualize each ikfast solutions')
    # parser.add_argument('-per_conf_step', '--per_conf_step', action='store_true', help='stepping each configuration in simulation')

    # transition motion planner settings
    RRT_RESTARTS = 5
    RRT_ITERATIONS = 40

    # rescaling
    # TODO: this should be done when the Assembly object is made
    unit_geos, static_obstacles = load_assembly_package(assembly_json_path,
                                                        scale=scale)

    # urdf, end effector settings
    if robot_model == 'ur3':
        urdf_filename = compas_fab.get(
            'universal_robot/ur_description/urdf/ur3.urdf')
        # urdf_filename = compas_fab.get('universal_robot/ur_description/urdf/ur3_collision_viz.urdf')
        srdf_filename = compas_fab.get(
            'universal_robot/ur3_moveit_config/config/ur3.srdf')
    else:
        urdf_filename = compas_fab.get(
            'universal_robot/ur_description/urdf/ur5.urdf')
        srdf_filename = compas_fab.get(
            'universal_robot/ur5_moveit_config/config/ur5.srdf')

    urdf_pkg_name = 'ur_description'

    ee_filename = compas_fab.get(
        'universal_robot/ur_description/meshes/' +
        'dms_2019_gripper/collision/190907_Gripper_05.obj')

    # geometry file is not loaded here
    model = RobotModel.from_urdf_file(urdf_filename)
    semantics = RobotSemantics.from_srdf_file(srdf_filename, model)
    robot = RobotClass(model, semantics=semantics)

    base_link_name = robot.get_base_link_name()
    ee_link_name = robot.get_end_effector_link_name()
    ik_joint_names = robot.get_configurable_joint_names()
    disabled_link_names = semantics.get_disabled_collisions()

    # parse end effector mesh
    ee_meshes = [Mesh.from_obj(ee_filename)]
    tcp_tf = Translation(tcp_tf_list)

    # add static collision obstacles
    co_dict = {}
    for i, static_obs_mesh in enumerate(static_obstacles):
        cm = CollisionMesh(static_obs_mesh, 'so_' + str(i))
        co_dict[cm.id] = {}
        co_dict[cm.id]['meshes'] = [cm.mesh]
        co_dict[cm.id]['mesh_poses'] = [cm.frame]

    # ======================================================
    # ======================================================
    # start pybullet environment & load pybullet robot
    connect(use_gui=enable_viewer)

    camera_base_pt = (0, 0, 0)
    camera_pt = np.array(camera_base_pt) + np.array([1, 0, 0.5])
    set_camera_pose(tuple(camera_pt), camera_base_pt)

    pb_robot = create_pb_robot_from_ros_urdf(urdf_filename,
                                             urdf_pkg_name,
                                             ee_link_name=ee_link_name)
    ee_attachs = attach_end_effector_geometry(ee_meshes, pb_robot,
                                              ee_link_name)

    # update current joint conf and attach end effector
    pb_ik_joints = joints_from_names(pb_robot, ik_joint_names)
    pb_end_effector_link = link_from_name(pb_robot, ee_link_name)
    set_joint_positions(pb_robot, pb_ik_joints, robot_start_conf)
    for e_at in ee_attachs:
        e_at.assign()

    # draw TCP frame in pybullet
    handles = []
    if has_gui() and view_ikfast:
        TCP_pb_pose = get_TCP_pose(pb_robot,
                                   ee_link_name,
                                   tcp_tf,
                                   return_pb_pose=True)
        handles = draw_pose(TCP_pb_pose, length=0.04)
        # wait_for_user()

    # deliver ros collision meshes to pybullet
    so_lists_from_name = convert_meshes_and_poses_to_pybullet_bodies(co_dict)
    static_obstacles_from_name = {}
    for so_key, so_val in so_lists_from_name.items():
        for so_i, so_item in enumerate(so_val):
            static_obstacles_from_name[so_key + '_' + str(so_i)] = so_item

    for unit_name, unit_geo in unit_geos.items():
        geo_bodies = []
        for sub_id, mesh in enumerate(unit_geo.mesh):
            geo_bodies.append(convert_mesh_to_pybullet_body(mesh))
        unit_geo.pybullet_bodies = geo_bodies

    # check collision between obstacles and element geometries
    assert not sanity_check_collisions(unit_geos, static_obstacles_from_name)

    # from random import shuffle
    seq_assignment = customized_sequence or list(range(len(unit_geos)))
    element_seq = {seq_id: e_id for seq_id, e_id in enumerate(seq_assignment)}

    to_seq_id = to_seq_id or len(element_seq) - 1
    assert 0 <= from_seq_id and from_seq_id < len(element_seq)
    assert from_seq_id <= to_seq_id and to_seq_id < len(element_seq)

    if has_gui():
        for e_id in element_seq.values():
            handles.extend(
                draw_pose(unit_geos[e_id].initial_pb_pose, length=0.02))
            handles.extend(draw_pose(unit_geos[e_id].goal_pb_pose,
                                     length=0.02))
            for e_body in unit_geos[e_id].pybullet_bodies:
                set_pose(e_body, unit_geos[e_id].initial_pb_pose)
        print('pybullet env loaded.')
        # wait_for_user()
        for h in handles:
            remove_debug(h)

    saved_world = WorldSaver()

    ik_fn = ikfast_ur3.get_ik if robot_model == 'ur3' else ikfast_ur5.get_ik
    tot_traj, graph_sizes = \
    direct_ladder_graph_solve_picknplace(pb_robot, ik_joint_names, base_link_name, ee_link_name, ik_fn,
        unit_geos, element_seq, static_obstacles_from_name,
        from_seq_id=from_seq_id, to_seq_id=to_seq_id,
        pick_from_same_rack=pick_from_same_rack,
        tcp_transf=pb_pose_from_Transformation(tcp_tf),
        ee_attachs=ee_attachs, disabled_collision_link_names=disabled_link_names, viz=view_ikfast, st_conf=robot_start_conf,
        num_cart_steps=num_cart_steps)

    picknplace_cart_plans = divide_nested_list_chunks(tot_traj, graph_sizes)

    saved_world.restore()
    print('Cartesian planning finished.')

    # reset robot and parts for better visualization
    set_joint_positions(pb_robot, pb_ik_joints, robot_start_conf)
    for ee in ee_attachs:
        ee.assign()
    for e_id in element_seq.values():
        for e_body in unit_geos[e_id].pybullet_bodies:
            set_pose(e_body, unit_geos[e_id].initial_pb_pose)

    def flatten_unit_geos_bodies(in_dict):
        out_list = []
        for ug in in_dict.values():
            out_list.extend(ug.pybullet_bodies)
        return out_list

    if plan_transit:
        print('Transition planning started.')
        disabled_collision_links = [(link_from_name(pb_robot, pair[0]), link_from_name(pb_robot, pair[1])) \
                for pair in disabled_link_names]

        for seq_id in range(0, from_seq_id):
            e_id = element_seq[seq_id]
            for e_body in unit_geos[e_id].pybullet_bodies:
                set_pose(e_body, unit_geos[e_id].goal_pb_pose)

        for seq_id in range(from_seq_id, to_seq_id + 1):
            e_id = element_seq[seq_id]
            print('----\ntransition seq#{} element #{}'.format(seq_id, e_id))

            if seq_id != from_seq_id:
                tr_start_conf = picknplace_cart_plans[
                    seq_id - 1 - from_seq_id]['place_retreat'][-1]
            else:
                tr_start_conf = robot_start_conf

            place2pick_st_conf = list(tr_start_conf)
            assert picknplace_cart_plans[seq_id - from_seq_id][
                'pick_approach'], 'pick approach not found in sequence {} (element id: {})!'.format(
                    seq_id, e_id)
            place2pick_goal_conf = list(
                picknplace_cart_plans[seq_id -
                                      from_seq_id]['pick_approach'][0])

            saved_world = WorldSaver()

            set_joint_positions(pb_robot, pb_ik_joints, place2pick_st_conf)
            for ee_a in ee_attachs:
                ee_a.assign()

            built_obstacles = []
            ignored_pairs = []
            if pick_from_same_rack:
                built_obstacles =  flatten_unit_geos_bodies({element_seq[prev_seq_id] : \
                    unit_geos[element_seq[prev_seq_id]] for prev_seq_id in range(seq_id)})
                # if seq_id > 0:
                #     ignored_pairs = list(product([ee_attach.child for ee_attach in ee_attachs], unit_geos[element_seq[seq_id-1]].pybullet_bodies))
            else:
                built_obstacles = flatten_unit_geos_bodies(unit_geos)
            place2pick_obstacles = list(
                static_obstacles_from_name.values()) + built_obstacles

            place2pick_path = plan_joint_motion(
                pb_robot,
                pb_ik_joints,
                place2pick_goal_conf,
                attachments=ee_attachs,
                obstacles=place2pick_obstacles,
                disabled_collisions=disabled_collision_links,
                self_collisions=True,
                resolutions=[transit_res] * len(pb_ik_joints),
                restarts=RRT_RESTARTS,
                iterations=RRT_ITERATIONS,
                ignored_pairs=ignored_pairs)
            saved_world.restore()

            if not place2pick_path:
                saved_world = WorldSaver()

                print('****\nseq #{} cannot find place2pick transition'.format(
                    seq_id))
                print('Diagnosis...')

                cfn = get_collision_fn(pb_robot, pb_ik_joints, \
                    obstacles=place2pick_obstacles,
                    attachments=ee_attachs, self_collisions=True, diagnosis=True)

                print('start pose:')
                cfn(place2pick_st_conf)

                print('end pose:')
                cfn(place2pick_goal_conf)

                saved_world.restore()
                print('Diagnosis over')

            assert picknplace_cart_plans[seq_id - from_seq_id][
                'pick_retreat'], 'pick retreat not found! in sequence {} (element id: {})!'.format(
                    seq_id, e_id)
            assert picknplace_cart_plans[seq_id - from_seq_id][
                'place_approach'], 'place approach not found! in sequence {} (element id: {})!'.format(
                    seq_id, e_id)
            pick2place_st_conf = picknplace_cart_plans[
                seq_id - from_seq_id]['pick_retreat'][-1]
            pick2place_goal_conf = picknplace_cart_plans[
                seq_id - from_seq_id]['place_approach'][0]

            saved_world = WorldSaver()

            # create attachement without needing to keep track of grasp...
            set_joint_positions(
                pb_robot, pb_ik_joints,
                picknplace_cart_plans[seq_id - from_seq_id]['pick_retreat'][0])
            # attachs = [Attachment(robot, tool_link, invert(grasp.attach), e_body) for e_body in brick.body]
            element_attachs = [create_attachment(pb_robot, pb_end_effector_link, e_body) \
                for e_body in unit_geos[e_id].pybullet_bodies]

            set_joint_positions(pb_robot, pb_ik_joints, pick2place_st_conf)
            for ee_a in ee_attachs:
                ee_a.assign()
            for e_a in element_attachs:
                e_a.assign()

            built_obstacles = []
            if pick_from_same_rack:
                built_obstacles =  flatten_unit_geos_bodies({element_seq[prev_seq_id] : \
                    unit_geos[element_seq[prev_seq_id]] for prev_seq_id in range(seq_id)})
            else:
                built_obstacles = flatten_unit_geos_bodies(unit_geos)
            pick2place_obstacles = list(
                static_obstacles_from_name.values()) + built_obstacles

            pick2place_path = plan_joint_motion(
                pb_robot,
                pb_ik_joints,
                pick2place_goal_conf,
                disabled_collisions=disabled_collision_links,
                obstacles=pick2place_obstacles,
                attachments=ee_attachs + element_attachs,
                self_collisions=True,
                resolutions=[transit_res] * len(pb_ik_joints),
                restarts=RRT_RESTARTS,
                iterations=RRT_ITERATIONS,
            )

            saved_world.restore()

            if not pick2place_path:
                saved_world = WorldSaver()

                print('****\nseq #{} cannot find pick2place transition'.format(
                    seq_id))
                print('Diagnosis...')

                cfn = get_collision_fn(pb_robot, pb_ik_joints,
                    obstacles=pick2place_obstacles, \
                    attachments=ee_attachs + element_attachs, self_collisions=True, diagnosis=True)

                print('start pose:')
                cfn(pick2place_st_conf)

                print('end pose:')
                cfn(pick2place_goal_conf)

                saved_world.restore()

                print('Diagnosis over')

            picknplace_cart_plans[seq_id -
                                  from_seq_id]['place2pick'] = place2pick_path
            picknplace_cart_plans[seq_id -
                                  from_seq_id]['pick2place'] = pick2place_path

            for e_body in unit_geos[e_id].pybullet_bodies:
                set_pose(e_body, unit_geos[e_id].goal_pb_pose)

            if seq_id == to_seq_id:
                saved_world = WorldSaver()
                return2idle_st_conf = picknplace_cart_plans[
                    seq_id - from_seq_id]['place_retreat'][-1]
                return2idle_goal_conf = robot_start_conf

                set_joint_positions(pb_robot, pb_ik_joints,
                                    return2idle_st_conf)
                for ee_a in ee_attachs:
                    ee_a.assign()

                built_obstacles =  flatten_unit_geos_bodies({element_seq[prev_seq_id] : \
                    unit_geos[element_seq[prev_seq_id]] for prev_seq_id in range(seq_id+1)})
                return2idle_obstacles = list(
                    static_obstacles_from_name.values()) + built_obstacles
                return2idle_path = plan_joint_motion(
                    pb_robot,
                    pb_ik_joints,
                    return2idle_goal_conf,
                    disabled_collisions=disabled_collision_links,
                    obstacles=return2idle_obstacles,
                    attachments=ee_attachs,
                    self_collisions=True,
                    resolutions=[transit_res] * len(pb_ik_joints),
                    restarts=RRT_RESTARTS,
                    iterations=RRT_ITERATIONS,
                )

                if not return2idle_path:
                    saved_world = WorldSaver()

                    print('****\nseq #{} cannot find return2idle transition'.
                          format(seq_id))
                    print('Diagnosis...')

                    cfn = get_collision_fn(pb_robot, pb_ik_joints, \
                        obstacles=return2idle_obstacles,
                        attachments=ee_attachs, self_collisions=True, diagnosis=True)

                    print('start pose:')
                    cfn(return2idle_st_conf)

                    print('end pose:')
                    cfn(return2idle_goal_conf)

                    saved_world.restore()
                    print('Diagnosis over')

                saved_world.restore()
                picknplace_cart_plans[
                    seq_id - from_seq_id]['return2idle'] = return2idle_path

        print('Transition planning finished.')

    # convert to ros JointTrajectory
    traj_json_data = []
    traj_time_count = 0.0
    for i, element_process in enumerate(picknplace_cart_plans):
        e_proc_data = {}
        for sub_proc_name, sub_process in element_process.items():
            sub_process_jt_traj_list = []
            if not sub_process:
                continue
            for jt_sol in sub_process:
                sub_process_jt_traj_list.append(
                    JointTrajectoryPoint(values=jt_sol,
                                         types=[0] * 6,
                                         time_from_start=Duration(
                                             traj_time_count, 0)))
                traj_time_count += 1.0  # meaningless timestamp
            e_proc_data[sub_proc_name] = JointTrajectory(
                trajectory_points=sub_process_jt_traj_list,
                start_configuration=sub_process_jt_traj_list[0]).to_data()
        traj_json_data.append(e_proc_data)

    if result_save_path:
        if not os.path.exists(os.path.dirname(result_save_path)):
            os.mkdir(os.path.dirname(result_save_path))
        with open(result_save_path, 'w+') as outfile:
            json.dump(traj_json_data, outfile)
            print('planned trajectories saved to {}'.format(result_save_path))

    print('\n*************************\nplanning completed.')

    if sim_traj and has_gui():
        #     if has_gui():
        #         wait_for_user()

        for e_id in element_seq.values():
            for e_body in unit_geos[e_id].pybullet_bodies:
                set_pose(e_body, unit_geos[e_id].initial_pb_pose)

        display_picknplace_trajectories(pb_robot, ik_joint_names, ee_link_name,
                                        unit_geos, traj_json_data, \
                                        element_seq=element_seq,
                                        from_seq_id=from_seq_id, to_seq_id=to_seq_id,
                                        ee_attachs=ee_attachs,
                                        cartesian_time_step=cart_ts,
                                        transition_time_step=trans_ts, step_sim=step_sim, per_conf_step=per_conf_step)

    return traj_json_data
with RosClient('localhost') as client:
    robot = client.load_robot()
    scene = PlanningScene(robot)

    scene.remove_collision_mesh('brick_wall')
    time.sleep(0.5)

    # attach tool
    robot.attach_tool(tool)
    # add tool to scene
    scene.add_attached_tool()

    # create an attached collision mesh to the robot's end effector.
    ee_link_name = robot.get_end_effector_link_name()
    brick_acm = AttachedCollisionMesh(
        CollisionMesh(element_tool0.mesh, 'brick'), ee_link_name)
    # add the collision mesh to the scene
    scene.add_attached_collision_mesh(brick_acm)

    # compute 'pick' cartesian motion
    trajectory1 = calculate_picking_motion(start_configuration, picking_frame,
                                           tolerance_vector, savelevel_vector)
    assert (trajectory1.fraction == 1.)
    start_configuration = trajectory1.points[-1]

    for key in assembly.network.vertices():
        elem = assembly.element(key)
        trajectory2, trajectory3 = move_and_placing_motion(
            elem, start_configuration, tolerance_vector, savelevel_vector,
            brick_acm)
        assert (trajectory3.fraction == 1.)
def test_collision_checker(abb_irb4600_40_255_setup, itj_TC_g1_cms,
                           itj_beam_cm, column_obstacle_cm, base_plate_cm,
                           itj_tool_changer_grasp_transf,
                           itj_gripper_grasp_transf, itj_beam_grasp_transf,
                           tool_type, itj_tool_changer_urdf_path,
                           itj_g1_urdf_path, viewer, diagnosis):
    # modified from https://github.com/yijiangh/pybullet_planning/blob/dev/tests/test_collisions.py
    urdf_filename, semantics = abb_irb4600_40_255_setup

    move_group = 'bare_arm'
    ee_touched_link_names = ['link_6']

    with PyChoreoClient(viewer=viewer) as client:
        with LockRenderer():
            robot = client.load_robot(urdf_filename)
            robot.semantics = semantics
            client.disabled_collisions = robot.semantics.disabled_collisions

            if tool_type == 'static':
                for _, ee_cm in itj_TC_g1_cms.items():
                    client.add_collision_mesh(ee_cm)
            else:
                client.add_tool_from_urdf('TC', itj_tool_changer_urdf_path)
                client.add_tool_from_urdf('g1', itj_g1_urdf_path)

            # * add static obstacles
            client.add_collision_mesh(base_plate_cm)
            client.add_collision_mesh(column_obstacle_cm)

        ik_joint_names = robot.get_configurable_joint_names(group=move_group)
        ik_joint_types = robot.get_joint_types_by_names(ik_joint_names)
        flange_link_name = robot.get_end_effector_link_name(group=move_group)

        tool0_tf = Transformation.from_frame(
            client.get_link_frame_from_name(robot, flange_link_name))
        tool0_from_tool_changer_base = itj_tool_changer_grasp_transf
        tool0_from_gripper_base = itj_gripper_grasp_transf
        client.set_object_frame(
            '^{}'.format('TC'),
            Frame.from_transformation(tool0_tf * tool0_from_tool_changer_base))
        client.set_object_frame(
            '^{}'.format('g1'),
            Frame.from_transformation(tool0_tf * tool0_from_gripper_base))

        names = client._get_collision_object_names('^{}'.format('g1')) + \
            client._get_collision_object_names('^{}'.format('TC'))
        for ee_name in names:
            attach_options = {'robot': robot}
            if tool_type == 'actuated':
                attached_child_link_name = 'toolchanger_base' if 'TC' in ee_name else 'gripper_base'
                attach_options.update(
                    {'attached_child_link_name': attached_child_link_name})
            client.add_attached_collision_mesh(AttachedCollisionMesh(
                CollisionMesh(None, ee_name),
                flange_link_name,
                touch_links=ee_touched_link_names),
                                               options=attach_options)
        # client._print_object_summary()
        # wait_if_gui('EE attached.')

        if tool_type == 'actuated':
            # lower 0.0008 upper 0.01
            tool_bodies = client._get_bodies('^{}'.format('itj_PG500'))
            tool_conf = Configuration(
                values=[0.01, 0.01],
                types=[Joint.PRISMATIC, Joint.PRISMATIC],
                joint_names=['joint_gripper_jaw_l', 'joint_gripper_jaw_r'])
            for b in tool_bodies:
                client._set_body_configuration(b, tool_conf)
            wait_if_gui('Open')

            tool_conf = Configuration(
                values=[0.0008, 0.0008],
                types=[Joint.PRISMATIC, Joint.PRISMATIC],
                joint_names=['joint_gripper_jaw_l', 'joint_gripper_jaw_r'])
            for b in tool_bodies:
                client._set_body_configuration(b, tool_conf)
            wait_if_gui('Close')

        cprint('safe start conf', 'green')
        conf = Configuration(values=[0.] * 6,
                             types=ik_joint_types,
                             joint_names=ik_joint_names)
        assert not client.check_collisions(
            robot, conf, options={'diagnosis': diagnosis})

        cprint('joint over limit', 'cyan')
        conf = Configuration(values=[0., 0., 1.5, 0, 0, 0],
                             types=ik_joint_types,
                             joint_names=ik_joint_names)
        assert client.check_collisions(robot,
                                       conf,
                                       options={'diagnosis': diagnosis})

        cprint('attached gripper-obstacle collision - column', 'cyan')
        vals = [
            -0.33161255787892263, -0.43633231299858238, 0.43633231299858238,
            -1.0471975511965976, 0.087266462599716474, 0.0
        ]
        # conf = Configuration(values=vals, types=ik_joint_types, joint_names=ik_joint_names)
        # client.set_robot_configuration(robot, conf)
        # wait_if_gui()
        assert client.check_collisions(robot,
                                       conf,
                                       options={'diagnosis': diagnosis})

        #* attach beam
        client.add_collision_mesh(itj_beam_cm)
        tool0_tf = Transformation.from_frame(
            client.get_link_frame_from_name(robot, flange_link_name))
        tool0_from_beam_base = itj_beam_grasp_transf
        client.set_object_frame(
            '^{}$'.format('itj_beam_b2'),
            Frame.from_transformation(tool0_tf * tool0_from_beam_base))
        client.add_attached_collision_mesh(AttachedCollisionMesh(
            CollisionMesh(None, 'itj_beam_b2'),
            flange_link_name,
            touch_links=[]),
                                           options={'robot': robot})
        # wait_if_gui('beam attached.')

        cprint('attached beam-robot body self collision', 'cyan')
        vals = [
            0.73303828583761843, -0.59341194567807209, 0.54105206811824214,
            -0.17453292519943295, 1.064650843716541, 1.7278759594743862
        ]
        conf = Configuration(values=vals,
                             types=ik_joint_types,
                             joint_names=ik_joint_names)
        assert client.check_collisions(robot,
                                       conf,
                                       options={'diagnosis': diagnosis})

        cprint('attached beam-obstacle collision - column', 'cyan')
        vals = [
            0.087266462599716474, -0.19198621771937624, 0.20943951023931956,
            0.069813170079773182, 1.2740903539558606, 0.069813170079773182
        ]
        conf = Configuration(values=vals,
                             types=ik_joint_types,
                             joint_names=ik_joint_names)
        assert client.check_collisions(robot,
                                       conf,
                                       options={'diagnosis': diagnosis})

        cprint('attached beam-obstacle collision - ground', 'cyan')
        vals = [
            -0.017453292519943295, 0.6108652381980153, 0.20943951023931956,
            1.7627825445142729, 1.2740903539558606, 0.069813170079773182
        ]
        conf = Configuration(values=vals,
                             types=ik_joint_types,
                             joint_names=ik_joint_names)
        assert client.check_collisions(robot,
                                       conf,
                                       options={'diagnosis': diagnosis})

        cprint('robot link-obstacle collision - column', 'cyan')
        vals = [
            -0.41887902047863912, 0.20943951023931956, 0.20943951023931956,
            1.7627825445142729, 1.2740903539558606, 0.069813170079773182
        ]
        conf = Configuration(values=vals,
                             types=ik_joint_types,
                             joint_names=ik_joint_names)
        assert client.check_collisions(robot,
                                       conf,
                                       options={'diagnosis': diagnosis})
        cprint('robot link-obstacle collision - ground', 'cyan')
        vals = [
            0.33161255787892263, 1.4660765716752369, 0.27925268031909273,
            0.17453292519943295, 0.22689280275926285, 0.54105206811824214
        ]
        conf = Configuration(values=vals,
                             types=ik_joint_types,
                             joint_names=ik_joint_names)
        assert client.check_collisions(robot,
                                       conf,
                                       options={'diagnosis': diagnosis})

        cprint('Sweeping collision', 'cyan')
        vals = [
            -0.12217304763960307, -0.73303828583761843, 0.83775804095727824,
            -2.4609142453120048, 1.2391837689159739, -0.85521133347722145
        ]
        conf1 = Configuration(values=vals,
                              types=ik_joint_types,
                              joint_names=ik_joint_names)
        assert not client.check_collisions(
            robot, conf1, options={'diagnosis': diagnosis})
        # wait_if_gui()

        vals = [
            -0.12217304763960307, -0.73303828583761843, 0.83775804095727824,
            -2.4958208303518914, -1.5533430342749532, -0.85521133347722145
        ]
        conf2 = Configuration(values=vals,
                              types=ik_joint_types,
                              joint_names=ik_joint_names)
        assert not client.check_collisions(
            robot, conf2, options={'diagnosis': diagnosis})
        # wait_if_gui()

        assert client.check_sweeping_collisions(robot,
                                                conf1,
                                                conf2,
                                                options={
                                                    'diagnosis': diagnosis,
                                                    'line_width': 3.0
                                                })

        wait_if_gui("Finished.")
Beispiel #15
0
import time

from compas.datastructures import Mesh

import compas_fab
from compas_fab.backends import RosClient
from compas_fab.robots import CollisionMesh
from compas_fab.robots import PlanningScene

with RosClient('localhost') as client:
    robot = client.load_robot()

    scene = PlanningScene(robot)
    mesh = Mesh.from_stl(compas_fab.get('planning_scene/floor.stl'))
    cm = CollisionMesh(mesh, 'floor')
    scene.add_collision_mesh(cm)

    # sleep a bit before terminating the client
    #time.sleep(1)

    #scene.remove_collision_mesh('floor')

filepath = os.path.join(DATA, '048_flemish_bond.json')
# load from existing if calculation failed at one point...

clear_planning_scene = True

if os.path.isfile(PATH_TO):
    assembly = Assembly.from_json(PATH_TO)
    clear_planning_scene = False
else:
    assembly = Assembly.from_json(filepath)

# create an attached collision mesh to be attached to the robot's end effector.
T = Transformation.from_frame_to_frame(brick.gripping_frame, tool.frame)
brick_tool0 = brick.transformed(T)
attached_brick_mesh = AttachedCollisionMesh(
    CollisionMesh(brick_tool0.mesh, 'brick'), 'ee_link')

# ==============================================================================
# From here on: fill in code, whereever you see this dots ...


def plan_picking_motion(robot, picking_frame, savelevel_picking_frame,
                        start_configuration, attached_brick_mesh):
    """Returns a cartesian trajectory to pick an element.

    Parameters
    ----------
    robot : :class:`compas.robots.Robot`
    picking_frame : :class:`Frame`
    save_level_picking_frame : :class:`Frame`
    start_configuration : :class:`Configuration`
Beispiel #17
0
import time

from compas.datastructures import Mesh

import compas_fab
from compas_fab.backends import RosClient
from compas_fab.robots import CollisionMesh
from compas_fab.robots import PlanningScene

with RosClient() as client:
    robot = client.load_robot()
    scene = PlanningScene(robot)
    assert robot.name == 'ur5'

    # create collision object
    mesh = Mesh.from_stl(compas_fab.get('planning_scene/cone.stl'))
    cm = CollisionMesh(mesh, 'tip')

    # attach it to the end-effector
    group = robot.main_group_name
    scene.attach_collision_mesh_to_robot_end_effector(cm, group=group)

    # sleep a bit before removing the tip
    time.sleep(1)

    scene.reset()
with open(settings_file, 'r') as f:
    data = json.load(f)
# load Element
element0 = Element.from_data(data['element0'])
# picking frame
picking_frame = Frame.from_data(data['picking_frame'])
picking_configuration = Configuration.from_data(data['picking_configuration'])
# little tolerance to not 'crash' into collision objects
tolerance_vector = Vector.from_data(data['tolerance_vector'])
safelevel_vector = Vector.from_data(data['safelevel_vector'])
safelevel_picking_frame = picking_frame.copy()
safelevel_picking_frame.point += safelevel_vector
picking_frame.point += tolerance_vector
# collision_meshes
scene_collision_meshes = [
    CollisionMesh(Mesh.from_data(m), name)
    for m, name in zip(data['collision_meshes'], data['collision_names'])
]

# load assembly from file or from existing if calculation failed at one point...
filepath = os.path.join(DATA, "assembly.json")

if LOAD_FROM_EXISTING and os.path.isfile(PATH_TO):
    assembly = Assembly.from_json(PATH_TO)
else:
    assembly = Assembly.from_json(filepath)

# create an attached collision mesh to be attached to the robot's end effector.
T = Transformation.from_frame_to_frame(element0._tool_frame, tool.frame)
element0_tool0 = element0.transformed(T)
attached_element_mesh = AttachedCollisionMesh(