def compute_circle_path(circle_center=np.array([2, 0, 0.2]),
                        circle_r=0.2,
                        angle_range=(-0.5 * np.pi, 0.5 * np.pi)):
    # generate a circle path to test IK and Cartesian planning
    ee_poses = []
    n_pt = int(abs(angle_range[1] - angle_range[0]) / (np.pi / 180 * 5))
    for a in np.linspace(*angle_range, num=n_pt):
        pt = circle_center + circle_r * np.array([np.cos(a), np.sin(a), 0])
        circ_pose = multiply(Pose(point=pt, euler=Euler(yaw=a + np.pi / 2)),
                             Pose(euler=Euler(roll=np.pi * 3 / 4)))
        draw_pose(circ_pose, length=0.01)
        ee_poses.append(circ_pose)
    return ee_poses
def test_client(fixed_waam_setup, viewer):
    # https://github.com/gramaziokohler/algorithmic_details/blob/e1d5e24a34738822638a157ca29a98afe05beefd/src/algorithmic_details/accessibility/reachability_map.py#L208-L231
    urdf_filename, semantics, _ = fixed_waam_setup
    move_group = 'robotA'

    with PyChoreoClient(viewer=viewer) as client:
        robot = client.load_robot(urdf_filename)
        robot.semantics = semantics
        robot_uid = client.get_robot_pybullet_uid(robot)
        tool_link_name = robot.get_end_effector_link_name(group=move_group)

        # * draw EE pose
        tool_link = link_from_name(robot_uid, tool_link_name)
        tcp_pose = get_link_pose(robot_uid, tool_link)
        draw_pose(tcp_pose)

        assert robot_uid in get_bodies()

        wait_if_gui()
def test_frame_variant_generator(viewer):
    pose = unit_pose()
    frame = frame_from_pose(pose)

    options = {'delta_yaw': np.pi / 6, 'yaw_sample_size': 30}
    frame_gen = PyChoreoFiniteEulerAngleVariantGenerator(
        options).generate_frame_variant
    with PyChoreoClient(viewer=viewer) as client:
        draw_pose(pose)
        cnt = 0
        for frame in frame_gen(frame):
            draw_pose(pose_from_frame(frame))
            cnt += 1
        assert cnt == options['yaw_sample_size']
        wait_if_gui()
        remove_all_debug()

        # overwrite class options
        cnt = 0
        new_options = {'delta_yaw': np.pi / 3, 'yaw_sample_size': 60}
        for frame in frame_gen(frame, new_options):
            draw_pose(pose_from_frame(frame))
            cnt += 1
        assert cnt == new_options['yaw_sample_size']
        wait_if_gui()
Exemplo n.º 4
0
def sequenced_picknplace_plan(assembly_pkg_json_path, solve_method='sparse_ladder_graph', viewer=False, scale=1e-3,
    sample_time=5, sparse_time_out=2, jt_res=0.1, pos_step_size=0.01, ori_step_size=np.pi/16,
    viz_inspect=False, warning_pause=False, save_dir=None, **kwargs):
    """call pychoreo's planner to solve for picknplace Cartesian & transition trajectories.

    Robot setup is specified in coop_assembly.choreo_interface.robot_setup

    Parameters
    ----------
    assembly_pkg_json_path : [type]
        [description]
    solve_method : str, optional
        [description], by default 'sparse_ladder_graph'
    viewer : bool, optional
        [description], by default False
    scale : [type], optional
        [description], by default 1e-3
    sample_time : int, optional
        [description], by default 5
    sparse_time_out : int, optional
        [description], by default 2
    jt_res : float, optional
        joint resolution for transition planning, by default 0.1
    pos_step_size : float, optional
        interpolation step size for the end effector Cartesia movements, by default 0.01 (meter)
    ori_step_size : [type], optional
        [description], by default np.pi/16
    viz_inspect : bool, optional
        visualize planning process in a pybullet window (slow!), by default False
    warning_pause : bool, optional
        wait for user input if any of the planning process cannot find a solution, by default False
    save_dir : string, optional
        absolute directory path to save the planning result json file, by default None

    Returns
    -------
    [type]
        [description]

    Raises
    ------
    ValueError
        [description]
    """
    # TODO: assert solve method in avaiable list

    # * load robot setup data
    (robot_urdf, base_link_name, tool_root_link_name, ee_link_name, ik_joint_names, disabled_self_collision_link_names), \
    (workspace_urdf, workspace_robot_disabled_link_names) = get_picknplace_robot_data()
    picknplace_end_effector_urdf = get_picknplace_end_effector_urdf()
    picknplace_tcp_def = get_picknplace_tcp_def()

    # * create robot and pb environment
    connect(use_gui=viewer)

    # * adjust camera pose (optional)
    if has_gui():
        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)

    with HideOutput():
        # * pybullet can handle ROS-package path URDF automatically now (ver 2.5.7)!
        robot = load_pybullet(robot_urdf, fixed_base=True)
        workspace = load_pybullet(workspace_urdf, fixed_base=True)
        # ee_body = create_obj(picknplace_end_effector_urdf)
        ee_body = load_pybullet(picknplace_end_effector_urdf)

    # * set robot idle configuration
    ik_joints = joints_from_names(robot, ik_joint_names)
    robot_start_conf = get_robot_init_conf()
    set_joint_positions(robot, ik_joints, robot_start_conf)

    # * create tool and tool TCP from flange (tool0) transformation
    root_link = link_from_name(robot, tool_root_link_name)
    # create end effector body
    ee_attach = Attachment(robot, root_link, unit_pose(), ee_body)
    # set up TCP transformation, just a renaming here
    root_from_tcp = picknplace_tcp_def
    if has_gui() :
        # draw_tcp pose
        ee_attach.assign()
        ee_link_pose = get_pose(ee_attach.child)
        draw_pose(multiply(ee_link_pose, root_from_tcp))

    # * specify ik fn wrapper
    ik_fn = IK_MODULE.get_ik
    def get_sample_ik_fn(robot, ik_fn, ik_joint_names, base_link_name, tool_from_root=None):
        def sample_ik_fn(world_from_tcp):
            if tool_from_root:
                world_from_tcp = multiply(world_from_tcp, tool_from_root)
            return sample_tool_ik(ik_fn, robot, ik_joint_names, base_link_name, world_from_tcp, get_all=True) #,sampled=[0])
        return sample_ik_fn
    # ik generation function stays the same for all cartesian processes
    sample_ik_fn = get_sample_ik_fn(robot, ik_fn, ik_joint_names, base_link_name, invert(root_from_tcp))

    # * load shape & collision data
    with open(assembly_pkg_json_path, 'r') as f:
        json_data = json.loads(f.read())
    assembly = Assembly.from_package(json_data)
    elements = assembly.elements
    for element in elements.values():
        for unit_geo in element.unit_geometries:
            unit_geo.rescale(scale)
    # TODO: scale derived from the assembly package unit
    # static_obstacles = []
    # for ug in assembly.static_obstacle_geometries.values():
    #     static_obstacles.extend(ug.mesh)

    # * load precomputed sequence / use assigned sequence
    # TODO: load this as function argument
    # element_seq = elements.keys()
    element_seq = [0, 1, 2, 3, 4, 5]
    # element_seq = [3, 4, 5]
    print('sequence: ', element_seq)

    # visualize goal pose
    if has_gui():
        # viz_len = 0.003
        with WorldSaver():
            for e_id in element_seq:
                element = elements[e_id]
                with LockRenderer():
                    print('e_id #{} : {}'.format(e_id, element))
                    for unit_geo in element.unit_geometries:
                        for pb_geo in unit_geo.pybullet_bodies:
                            set_pose(pb_geo, random.choice(unit_geo.get_goal_frames(get_pb_pose=True)))
                # print('---------')
                # wait_for_user()
        # wait_for_user()

    # * construct ignored body-body links for collision checking
    # in this case, including self-collision between links of the robot
    disabled_self_collisions = get_disabled_collisions(robot, disabled_self_collision_link_names)
    # and links between the robot and the workspace (e.g. robot_base_link to base_plate)
    extra_disabled_collisions = get_body_body_disabled_collisions(robot, workspace, workspace_robot_disabled_link_names)
    # TODO: extra disabled collisions as function argument
    extra_disabled_collisions.update({
        ((robot, link_from_name(robot, 'robot_link_5')), (ee_body, link_from_name(ee_body, 'eef_base_link'))),
        ((robot, link_from_name(robot, 'robot_link_6')), (ee_body, link_from_name(ee_body, 'eef_base_link')))
        })

    # * create cartesian processes without a sequence being given, with random pose generators
    cart_process_seq = build_picknplace_cartesian_process_seq(
        element_seq, elements,
        robot, ik_joint_names, root_link, sample_ik_fn,
        ee_attachs=[ee_attach], self_collisions=True, disabled_collisions=disabled_self_collisions,
        obstacles=[workspace],extra_disabled_collisions=extra_disabled_collisions,
        tool_from_root=invert(root_from_tcp), viz_step=False, pick_from_same_rack=True,
        pos_step_size=pos_step_size, ori_step_size=ori_step_size)

    # specifically for UR5, because of its wide joint range, we need to apply joint value snapping
    for cp in cart_process_seq:
        cp.target_conf = robot_start_conf

    with LockRenderer(not viz_inspect):
        if solve_method == 'ladder_graph':
            print('\n'+'#' * 10)
            print('Solving with the vanilla ladder graph search algorithm.')
            cart_process_seq = solve_ladder_graph_from_cartesian_process_list(cart_process_seq,
                verbose=True, warning_pause=warning_pause, viz_inspect=viz_inspect, check_collision=False, start_conf=robot_start_conf)
        elif solve_method == 'sparse_ladder_graph':
            print('\n'+'#' * 10)
            print('Solving with the sparse ladder graph search algorithm.')
            sparse_graph = SparseLadderGraph(cart_process_seq)
            sparse_graph.find_sparse_path(verbose=True, vert_timeout=sample_time, sparse_sample_timeout=sparse_time_out)
            cart_process_seq = sparse_graph.extract_solution(verbose=True, start_conf=robot_start_conf)
        else:
            raise ValueError('Invalid solve method!')
        assert all(isinstance(cp, CartesianProcess) for cp in cart_process_seq)

        pnp_trajs = [[] for _ in range(len(cart_process_seq))]
        for cp_id, cp in enumerate(cart_process_seq):
            element_attachs = []
            for sp_id, sp in enumerate(cp.sub_process_list):
                assert sp.trajectory, '{}-{} does not have a Cartesian plan found!'.format(cp, sp)
                # ! reverse engineer the grasp pose
                if sp.trajectory.tag == 'pick_retreat':
                    unit_geo = elements[sp.trajectory.element_id].unit_geometries[0]
                    e_bodies = unit_geo.pybullet_bodies
                    for e_body in e_bodies:
                        set_pose(e_body, unit_geo.get_initial_frames(get_pb_pose=True)[0])
                        set_joint_positions(sp.trajectory.robot, sp.trajectory.joints, sp.trajectory.traj_path[0])
                        element_attachs.append(create_attachment(sp.trajectory.robot, root_link, e_body))

                if sp.trajectory.tag == 'pick_retreat' or sp.trajectory.tag == 'place_approach':
                    sp.trajectory.attachments= element_attachs
                pnp_trajs[cp_id].append(sp.trajectory)
        full_trajs = pnp_trajs

        # * transition motion planning between extrusions
        return2idle = True
        transition_traj = solve_transition_between_picknplace_processes(pnp_trajs, elements, robot_start_conf,
                                                                        disabled_collisions=disabled_self_collisions,
                                                                        extra_disabled_collisions=extra_disabled_collisions,
                                                                        obstacles=[workspace], return2idle=return2idle,
                                                                        resolutions=[jt_res]*len(ik_joints),
                                                                        **kwargs)

    # * weave the Cartesian and transition processses together
    for cp_id, print_trajs in enumerate(full_trajs):
        print_trajs.insert(0, transition_traj[cp_id][0])
        print_trajs.insert(3, transition_traj[cp_id][1])
    if return2idle:
        full_trajs[-1].append(transition_traj[-1][-1])

    if save_dir is None:
        here = os.path.dirname(__file__)
        save_dir = os.path.join(here, 'results')
    export_trajectory(save_dir, full_trajs, ee_link_name, indent=1, shape_file_path=assembly_pkg_json_path,
        include_robot_data=True, include_link_path=True)

    # * disconnect and close pybullet engine used for planning, visualizing trajectories will start a new one
    reset_simulation()
    disconnect()

    if viewer:
        cart_time_step = None
        tr_time_step = None
        display_picknplace_trajectories(robot_urdf, ik_joint_names,
                                        assembly_pkg_json_path, full_trajs, tool_root_link_name,
                                        ee_urdf=picknplace_end_effector_urdf, workspace_urdf=workspace_urdf, animate=True,
                                        cart_time_step=cart_time_step, tr_time_step=tr_time_step)
Exemplo n.º 5
0
def descartes_demo(viewer=True, scaling_test=False, draw_graph=True):
    connect(use_gui=viewer)
    with HideOutput():
        robot = load_pybullet(KUKA_ROBOT_URDF, fixed_base=True)

    # * adjust camera pose (optional)
    # has_gui checks if the GUI mode is enabled
    if has_gui():
        camera_base_pt = (0,0,0)
        camera_pt = np.array(camera_base_pt) + np.array([1, -0.5, 1])
        set_camera_pose(tuple(camera_pt), camera_base_pt)

    cprint('Hello robot world! <ctrl+left mouse> to pan', 'green')
    wait_if_gui()

    ik_joints = get_movable_joints(robot)
    ik_joint_names = get_joint_names(robot, ik_joints)
    print('ik joint names: {}'.format(ik_joint_names))

    lower_limits, upper_limits = get_custom_limits(robot, ik_joints)
    print('joint lower limit: {}'.format(lower_limits))
    print('joint upper limit: {}'.format(upper_limits))
    # we can also read these velocities from the SRDF file (using e.g. COMPAS_FAB)
    # I'm a bit lazy, just handcode the values here
    vel_limits = {0 : 6.28318530718,
                  1 : 5.23598775598,
                  2 : 6.28318530718,
                  3 : 6.6497044501,
                  4 : 6.77187749774,
                  5 : 10.7337748998}

    # set the robot to a "comfortable" start configuration, optional
    robot_start_conf = [0,-np.pi/2,np.pi/2,0,0,0]
    set_joint_positions(robot, ik_joints, robot_start_conf)

    tool_link = link_from_name(robot, EE_LINK_NAME)
    robot_base_link = link_from_name(robot, ROBOT_BASE_LINK_NAME)
    # tool_from_root = get_relative_pose(robot, root_link, tool_link)

    # * draw EE pose
    if has_gui() :
        tcp_pose = get_link_pose(robot, tool_link)
        draw_pose(tcp_pose)

    circle_center = np.array([0.6, 0, 0.2])
    circle_r = 0.1
    # * generate multiple circles
    ee_poses = []
    full_angle = 2*2*np.pi
    # total num of path pts, one path point per 5 degree
    n_pt = int(full_angle / (np.pi/180 * 5))
    # full_angle = np.pi
    for a in np.linspace(0.0, full_angle, num=n_pt):
        pt = circle_center + circle_r*np.array([np.cos(a), np.sin(a), 0])
        circ_pose = multiply(Pose(point=pt, euler=Euler(yaw=a+np.pi/2)), Pose(euler=Euler(roll=np.pi*3/4)))
        draw_pose(circ_pose, length=0.01)
        ee_poses.append(circ_pose)

    # def get_ee_sample_fn(roll_gen, pitch_gen, yaw_gen):
    #     def ee_sample_fn(ee_pose):
    #         # a finite generator
    #         for roll, pitch, yaw in product(roll_gen, pitch_gen, yaw_gen):
    #             yield multiply(ee_pose, Pose(euler=Euler(roll=roll, pitch=pitch, yaw=yaw)))
    #     return ee_sample_fn
    # roll_sample_size = 3
    # pitch_sample_size = 3
    # yaw_sample_size = 1
    # delta_roll = np.pi/12
    # delta_pitch = np.pi/12
    # roll_gen = np.linspace(-delta_roll, delta_roll, num=roll_sample_size)
    # pitch_gen = np.linspace(-delta_pitch, delta_pitch, num=pitch_sample_size)
    # yaw_gen = np.linspace(0.0, 2*np.pi, num=yaw_sample_size)
    # ee_sample_fn = get_ee_sample_fn(roll_gen, pitch_gen, yaw_gen)

    # for ep in ee_sample_fn(ee_poses[0]):
    #     draw_pose(ep, length=0.03)

    # * baseline, keeping the EE z axis rotational dof fixed
    st_time = time.time()
    path = plan_cartesian_motion(robot, robot_base_link, tool_link, ee_poses)
    print('Solving time: {}'.format(elapsed_time(st_time)))
    if path is None:
        cprint('Gradient-based ik cartesian planning cannot find a plan!', 'red')
    else:
        cprint('Gradient-based ik cartesian planning find a plan!', 'green')
        time_step = 0.03
        for conf in path:
            set_joint_positions(robot, ik_joints, conf)
            wait_for_duration(time_step)
        if draw_graph:
            print('drawing graph...')
            plot_joint_val(path, lower_limits, upper_limits, method='GradIK')
    print('='*20)

    # * Now, let's try if using ladder graph without releasing the ee dof can give us a good trajectory
    # you should be doing something similar in your picture, right?

    # First, we will need ikfast to obtain ik solution variance, same in Descartes
    ik_fn = ikfast_kuka_kr6_r900.get_ik

    # we have to specify ik fn wrapper and feed it into pychoreo
    def get_sample_ik_fn(robot, ik_fn, robot_base_link, ik_joints, tool_from_root=None):
        def sample_ik_fn(world_from_tcp):
            if tool_from_root:
                world_from_tcp = multiply(world_from_tcp, tool_from_root)
            return sample_tool_ik(ik_fn, robot, ik_joints, world_from_tcp, robot_base_link, get_all=True)
        return sample_ik_fn
    # ik generation function stays the same for all cartesian processes
    sample_ik_fn = get_sample_ik_fn(robot, ik_fn, robot_base_link, ik_joints)

    # we ignore self collision in this tutorial, the collision_fn only considers joint limit now
    # See : https://github.com/yijiangh/pybullet_planning/blob/dev/tests/test_collisions.py
    # for more info on examples on using collision function
    collision_fn = get_collision_fn(robot, ik_joints, obstacles=[],
                                       attachments=[], self_collisions=False,
                                    #    disabled_collisions=disabled_collisions,
                                    #    extra_disabled_collisions=extra_disabled_collisions,
                                       custom_limits={})

    # Let's check if our ik sampler is working properly
    # uncomment the following if you want to play with this
    # for p in ee_poses:
    #     print('-'*5)
    #     pb_q = inverse_kinematics(robot, tool_link, p)
    #     if pb_q is None:
    #         cprint('pb ik can\'t find an ik solution', 'red')
    #     qs = sample_ik_fn(p)
    #     if qs is not None:
    #         cprint('But Ikfast does find one! {}'.format(qs[0]), 'green')
    #         # set_joint_positions(robot, ik_joints, qs[0])
    #         # wait_if_gui()
    #     else:
    #         cprint('ikfast can\'t find an ik solution', 'red')

    # * Ok, now we have the ik sampler and collision function ready, let's see if we can find a valid cartesian trajectory!
    ee_vel = 0.005 # m/s

    # st_time = time.time()
    # path, cost = plan_cartesian_motion_lg(robot, ik_joints, ee_poses, sample_ik_fn, collision_fn, \
    #     custom_vel_limits=vel_limits, ee_vel=ee_vel)
    # print('Solving time: {}'.format(elapsed_time(st_time)))
    # if path is None:
    #     cprint('ladder graph (w/o releasing dof) cartesian planning cannot find a plan!', 'red')
    # else:
    #     cprint('ladder graph (w/o releasing dof) cartesian planning find a plan!', 'green')
    #     cprint('Cost: {}'.format(cost), 'yellow')
    #     time_step = 0.03
    #     for conf in path:
    #         # cprint('conf: {}'.format(conf))
    #         set_joint_positions(robot, ik_joints, conf)
    #         wait_for_duration(time_step)
    #     if draw_graph:
    #         print('drawing graph...')
    #         plot_joint_val(path, lower_limits, upper_limits, method='IKFast+LadderGraph')
    # print('='*20)

    # * Now, let's see if releasing EE z axis dof can bring down the cost
    # First, let's build an end effector pose sampler to release the EE z axis dof!
    ## * EE z axis dof generator
    def get_ee_sample_fn(roll_gen, pitch_gen, yaw_gen):
        def ee_sample_fn(ee_pose):
            # a finite generator
            for roll, pitch, yaw in product(roll_gen, pitch_gen, yaw_gen):
                yield multiply(ee_pose, Pose(euler=Euler(roll=roll, pitch=pitch, yaw=yaw)))
        return ee_sample_fn

    # by increasing this number we can see the cost go down
    roll_sample_size = 10
    pitch_sample_size = 10
    yaw_sample_size = 10
    delta_roll = np.pi/6
    delta_pitch = np.pi/6
    delta_yaw = np.pi/6
    roll_gen = np.linspace(-delta_roll, delta_roll, num=roll_sample_size)
    pitch_gen = np.linspace(-delta_pitch, delta_pitch, num=pitch_sample_size)
    yaw_gen = np.linspace(-delta_yaw, delta_yaw, num=yaw_sample_size)
    ee_sample_fn = get_ee_sample_fn(roll_gen, pitch_gen, yaw_gen)

    st_time = time.time()
    path, cost = plan_cartesian_motion_lg(robot, ik_joints, ee_poses, sample_ik_fn, collision_fn, sample_ee_fn=ee_sample_fn, \
        custom_vel_limits=vel_limits, ee_vel=ee_vel)
    print('Solving time: {}'.format(elapsed_time(st_time)))

    # TODO: plot ee z axis deviation plot

    # the ladder graph cost is just summation of all adjacent joint difference
    # so the following assertion should be true
    # conf_array = np.array(path)
    # conf_diff = np.abs(conf_array[:-1,:] - conf_array[1:,:])
    # np_cost = np.sum(conf_diff)
    # assert np.allclose(np_cost, cost), '{} - {}'.format(np_cost, cost)

    if path is None:
        cprint('ladder graph (releasing EE z dof) cartesian planning cannot find a plan!', 'red')
    else:
        cprint('ladder graph (releasing EE z dof) cartesian planning find a plan!', 'cyan')
        cprint('Cost: {}'.format(cost), 'yellow')
        time_step = 0.03
        for conf in path:
            # cprint('conf: {}'.format(conf))
            set_joint_positions(robot, ik_joints, conf)
            wait_for_duration(time_step)
        if draw_graph:
            print('drawing graph...')
            plot_joint_val(path, lower_limits, upper_limits, method='IKFast+LadderGraph+release z dof-res{}'.format(yaw_sample_size))
    print('='*20)

    # Now, let's do a scaling test:
    # if scaling_test:
        # res_sc = list(range(4,30))
        # cost_sc = []
        # for res in res_sc:
        #     yaw_sample_size = res
        #     yaw_gen = np.linspace(0.0, 2*np.pi, num=yaw_sample_size)
        #     ee_sample_fn = get_ee_sample_fn(yaw_gen)
        #     path, cost = plan_cartesian_motion_lg(robot, ik_joints, ee_poses, sample_ik_fn, collision_fn, sample_ee_fn=ee_sample_fn)
        #     assert path is not None
        #     cost_sc.append(cost)
        #     if res % 5 == 0:
        #         if draw_graph:
        #             plot_joint_val(path, lower_limits, upper_limits, method='IKFast+LadderGraph+release z dof-res{}'.format(yaw_sample_size))

        # fig, ax = plt.subplots()
        # ax.plot(res_sc, cost_sc)
        # ax.set(xlabel='yaw angle discr resolution', ylabel='total joint difference cost',
        #        title='Total joint diff scaling test')
        # ax.grid()
        # fig.savefig(os.path.join(HERE, 'images', 'tota_diff-scaling.png'))
        # # plt.show()

    wait_if_gui('Press enter to exit')
def test_circle_cartesian(fixed_waam_setup, viewer, planner_ik_conf):
    urdf_filename, semantics, robotA_tool = fixed_waam_setup
    planner_id, ik_engine = planner_ik_conf

    move_group = 'robotA'
    print('\n')
    print('=' * 10)
    cprint(
        'Cartesian planner {} with IK engine {}'.format(planner_id, ik_engine),
        'yellow')

    with PyChoreoClient(viewer=viewer) as client:
        robot = client.load_robot(urdf_filename)
        robot.semantics = semantics
        robot_uid = client.get_robot_pybullet_uid(robot)

        base_link_name = robot.get_base_link_name(group=move_group)
        ik_joint_names = robot.get_configurable_joint_names(group=move_group)
        tool_link_name = robot.get_end_effector_link_name(group=move_group)
        base_frame = robot.get_base_frame(group=move_group)

        if ik_engine == 'default-single':
            ik_solver = None
        elif ik_engine == 'lobster-analytical':
            ik_solver = InverseKinematicsSolver(robot, move_group,
                                                ik_abb_irb4600_40_255,
                                                base_frame, robotA_tool.frame)
        elif ik_engine == 'ikfast-analytical':
            ikfast_fn = get_ik_fn_from_ikfast(ikfast_abb_irb4600_40_255.get_ik)
            ik_solver = InverseKinematicsSolver(robot, move_group, ikfast_fn,
                                                base_frame, robotA_tool.frame)
        else:
            raise ValueError('invalid ik engine name.')

        init_conf = Configuration.from_revolute_values(np.zeros(6),
                                                       ik_joint_names)

        # replace default ik function with a customized one
        if ik_solver is not None:
            client.planner.inverse_kinematics = ik_solver.inverse_kinematics_function(
            )

        tool_link = link_from_name(robot_uid, tool_link_name)
        robot_base_link = link_from_name(robot_uid, base_link_name)
        ik_joints = joints_from_names(robot_uid, ik_joint_names)

        # * draw EE pose
        tcp_pose = get_link_pose(robot_uid, tool_link)
        draw_pose(tcp_pose)

        # * generate multiple circles
        circle_center = np.array([2, 0, 0.2])
        circle_r = 0.2
        # full_angle = np.pi
        # full_angle = 2*2*np.pi
        angle_range = (-0.5 * np.pi, 0.5 * np.pi)
        # total num of path pts, one path point per 5 degree
        ee_poses = compute_circle_path(circle_center, circle_r, angle_range)
        ee_frames_WCF = [frame_from_pose(ee_pose) for ee_pose in ee_poses]

        options = {'planner_id': planner_id}
        if planner_id == 'LadderGraph':
            client.set_robot_configuration(robot, init_conf)
            st_time = time.time()

            # options.update({'ik_function' : lambda pose: compute_inverse_kinematics(ikfast_abb_irb4600_40_255.get_ik, pose, sampled=[])})

            trajectory = client.plan_cartesian_motion(robot,
                                                      ee_frames_WCF,
                                                      group=move_group,
                                                      options=options)
            cprint(
                'W/o frame variant solving time: {}'.format(
                    elapsed_time(st_time)), 'blue')
            cprint(
                'Cost: {}'.format(
                    compute_trajectory_cost(trajectory,
                                            init_conf_val=init_conf.values)),
                'blue')
            print('-' * 5)

            f_variant_options = {'delta_yaw': np.pi / 3, 'yaw_sample_size': 5}
            options.update({
                'frame_variant_generator':
                PyChoreoFiniteEulerAngleVariantGenerator(
                    options=f_variant_options)
            })
            print('With frame variant config: {}'.format(f_variant_options))

        client.set_robot_configuration(robot, init_conf)
        st_time = time.time()
        trajectory = client.plan_cartesian_motion(robot,
                                                  ee_frames_WCF,
                                                  group=move_group,
                                                  options=options)
        cprint(
            '{} solving time: {}'.format(
                'With frame variant '
                if planner_id == 'LadderGraph' else 'Direct',
                elapsed_time(st_time)), 'cyan')
        cprint(
            'Cost: {}'.format(
                compute_trajectory_cost(trajectory,
                                        init_conf_val=init_conf.values)),
            'cyan')

        if trajectory is None:
            cprint(
                'Client Cartesian planner {} CANNOT find a plan!'.format(
                    planner_id), 'red')
        else:
            cprint(
                'Client Cartesian planning {} find a plan!'.format(planner_id),
                '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()
Exemplo n.º 7
0
def test_collision_checker(rfl_setup, itj_beam_cm, viewer, diagnosis):
    # modified from https://github.com/yijiangh/pybullet_planning/blob/dev/tests/test_collisions.py
    urdf_filename, semantics = rfl_setup
    move_group = 'robot11_eaXYZ'  # 'robot12_eaYZ'

    with PyChoreoClient(viewer=viewer) as client:
        cprint(urdf_filename, 'green')
        with LockRenderer():
            robot = client.load_robot(urdf_filename)
        robot.semantics = semantics
        robot_uid = client.get_robot_pybullet_uid(robot)

        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)

        ee_touched_link_names = ['robot12_tool0', 'robot12_link_6']
        # ee_acms = [AttachedCollisionMesh(ee_cm, flange_link_name, ee_touched_link_names) for ee_cm in itj_TC_PG500_cms]
        # beam_acm = AttachedCollisionMesh(itj_beam_cm, flange_link_name, ee_touched_link_names)

        draw_pose(unit_pose(), length=1.)

        cam = rfl_camera()
        set_camera_pose(cam['target'], cam['location'])

        ik_joints = joints_from_names(robot_uid, ik_joint_names)
        flange_link = link_from_name(robot_uid, flange_link_name)
        # robot_base_link = link_from_name(robot_uid, base_link_name)

        r11_start_conf_vals = np.array([22700.0, 0.0, -4900.0, \
            0.0, -80.0, 65.0, 65.0, 20.0, -20.0])
        r12_start_conf_vals = np.array([-4056.0883789999998, -4000.8486330000001, \
            0.0, -22.834741999999999, -30.711554, 0.0, 57.335655000000003, 0.0])
        full_start_conf = to_rlf_robot_full_conf(r11_start_conf_vals,
                                                 r12_start_conf_vals)
        # full_joints = joints_from_names(robot_uid, full_start_conf.joint_names)

        client.set_robot_configuration(robot, full_start_conf)

        # # * add attachment
        # for ee_acm in ee_acms:
        #     client.add_attached_collision_mesh(ee_acm, options={'robot' : robot, 'mass': 1})
        # client.add_attached_collision_mesh(beam_acm, options={'robot' : robot, 'mass': 1})

        # safe start conf
        start_confval = np.hstack([
            r11_start_conf_vals[:3] * 1e-3,
            np.radians(r11_start_conf_vals[3:])
        ])
        conf = Configuration(values=start_confval.tolist(),
                             types=ik_joint_types,
                             joint_names=ik_joint_names)
        assert not client.check_collisions(
            robot, conf, options={'diagnosis': diagnosis})

        # TODO add more tests
        from pybullet_planning import get_link_subtree, prune_fixed_joints, clone_body, get_movable_joints, get_all_links, \
            set_color, child_link_from_joint
        first_joint = ik_joints[0]
        target_link = flange_link

        # selected_links = get_link_subtree(robot_uid, first_joint) # TODO: child_link_from_joint?
        selected_links = [child_link_from_joint(joint) for joint in ik_joints]

        selected_movable_joints = prune_fixed_joints(robot_uid, selected_links)
        assert (target_link in selected_links)
        selected_target_link = selected_links.index(target_link)
        sub_robot = clone_body(robot_uid,
                               links=selected_links,
                               visual=True,
                               collision=True)  # TODO: joint limits
        sub_movable_joints = get_movable_joints(sub_robot)

        # conf = Configuration(values=[0.]*6, types=ik_joint_types, joint_names=ik_joint_names)
        # assert not client.configuration_in_collision(conf, group=move_group, options={'diagnosis':True})
        wait_if_gui()