Exemplo n.º 1
0
    def test_urdf_insertion(self):
        gm = GeometryModel()

        sym_a = create_pos('a')
        sym_b = create_pos('b')
        sym_c = create_pos('c')

        box_shape = Geometry('my_box', se.eye(4), 'box')
        mesh_shape = Geometry('my_mesh',
                              se.eye(4),
                              'mesh',
                              mesh='package://kineverse/meshes/suzanne.obj')

        box_link = KinematicLink('world',
                                 translation3(sym_a, 1, 0),
                                 geometry={'0': box_shape},
                                 collision={'0': box_shape})
        mesh_link = KinematicLink('world',
                                  translation3(1, sym_b, 0),
                                  geometry={'0': mesh_shape},
                                  collision={'0': mesh_shape})

        robot = URDFRobot('my_bot')
        robot.links['my_box'] = box_link
        robot.links['my_mesh'] = mesh_link

        gm.set_data('my_bot', robot)
        gm.clean_structure()
        gm.dispatch_events()  # Generates the pose expressions for links

        sub_world = gm.get_active_geometry({sym_a})
        self.assertEquals(len(sub_world.names), 1)
        self.assertIn('my_bot/links/my_box', sub_world.names)
        self.assertIn('my_bot/links/my_box', sub_world.named_objects)

        sub_world = gm.get_active_geometry({sym_a, sym_b})
        self.assertEquals(len(sub_world.names), 2)
        self.assertIn('my_bot/links/my_box', sub_world.names)
        self.assertIn('my_bot/links/my_mesh', sub_world.names)
        self.assertIn('my_bot/links/my_box', sub_world.named_objects)
        self.assertIn('my_bot/links/my_mesh', sub_world.named_objects)

        sub_world = gm.get_active_geometry({sym_c})
        self.assertEquals(len(sub_world.names), 0)
                      'shoulder_pan_joint' : 0.3,
                      'elbow_flex_joint'   : 1.72,
                      'forearm_roll_joint' : -1.2,
                      'upperarm_roll_joint': -1.57,
                      'wrist_flex_joint'   : 1.66,
                      'shoulder_lift_joint': 1.4,
                      'torso_lift_joint'   : 0.2}
        start_pose = {gm.Position(Path(f'{robot_path}/{n}')): v for n, v in start_pose.items()}
    else:
        joint_symbols, \
        robot_controlled_symbols, \
        start_pose, \
        eef, \
        blacklist = generic_setup(km, robot_path, rospy.get_param('~eef', 'gripper_link'))

    collision_world = km.get_active_geometry(gm.free_symbols(handle.pose).union(gm.free_symbols(eef.pose)))

    # Init step
    grasp_in_handle = gm.dot(gm.translation3(0.04, 0, 0), gm.rotation3_rpy(math.pi * 0.5, 0, math.pi))
    goal_pose       = gm.dot(handle.pose, grasp_in_handle)
    goal_0_pose     = gm.subs(goal_pose, {s: 0 for s in gm.free_symbols(goal_pose)})

    start_state = {s: 0 for s in gm.free_symbols(collision_world)}
    start_state.update(start_pose)
    ik_err, robot_start_state = ik_solve_one_shot(km, eef.pose, start_state, goal_0_pose)

    start_state.update({s: 0 for s in gm.free_symbols(handle.pose)})
    start_state.update(robot_start_state)

    collision_world.update_world(start_state)
             base_joint.wheel_radius * 0.5 + base_joint.l_wheel_vel *
             gm.sin(base_joint.a_pos) * base_joint.wheel_radius * 0.5),
            base_joint.a_pos:
            base_joint.a_pos + DT_SYM *
            (base_joint.r_wheel_vel *
             (base_joint.wheel_radius / base_joint.wheel_distance) +
             base_joint.l_wheel_vel *
             (-base_joint.wheel_radius / base_joint.wheel_distance))
        }
    else:
        robot_controlled_symbols |= {
            gm.get_diff(x)
            for x in [base_joint.x_pos, base_joint.y_pos, base_joint.a_pos]
        }

    active_robot_world = km.get_active_geometry(joint_symbols)
    # c_avoidance_constraints = {f'collision avoidance {name}': SC.from_constraint(closest_distance_constraint_world(gm.get_data(Path(name) + ('pose',)),
    #                                                                              Path(name),
    #                                                                              0.03), 100) for name in active_robot_world.names}

    print('\n'.join([str(s) for s in robot_controlled_symbols]))

    n_iter = []
    total_dur = []

    for part_path in [Path(f'kitchen/links/{p}') for p in kitchen_parts]:
        # for part_path in [Path(f'nobilia/links/handle')]:
        print(f'Planning trajectory for "{part_path}"')
        printed_exprs = {}
        obj = km.get_data(part_path)
def main(create_figure=False,
         vis_mode=False,
         log_csv=True,
         min_n_dof=1,
         samples=300,
         n_observations=25,
         noise_lin=0.2,
         noise_ang=30,
         noise_steps=5):

    wait_duration = rospy.Duration(0.1)

    vis = ROSBPBVisualizer('ekf_vis', 'world') if vis_mode != 'none' else None
    km = GeometryModel()

    with open(res_pkg_path('package://iai_kitchen/urdf_obj/IAI_kitchen.urdf'),
              'r') as urdf_file:
        urdf_kitchen_str = urdf_file.read()
        kitchen_model = urdf_filler(
            URDF.from_xml_string(hacky_urdf_parser_fix(urdf_kitchen_str)))
        load_urdf(km, Path('kitchen'), kitchen_model)

    km.clean_structure()
    km.dispatch_events()

    kitchen = km.get_data('kitchen')

    tracking_pools = []
    for name, link in kitchen.links.items():
        symbols = gm.free_symbols(link.pose)
        if len(symbols) == 0:
            continue

        for x in range(len(tracking_pools)):
            syms, l = tracking_pools[x]
            if len(symbols.intersection(syms)
                   ) != 0:  # BAD ALGORITHM, DOES NOT CORRECTLY IDENTIFY SETS
                tracking_pools[x] = (syms.union(symbols),
                                     l + [(name, link.pose)])
                break
        else:
            tracking_pools.append((symbols, [(name, link.pose)]))

    # tracking_pools = [tracking_pools[7]]
    # print('Identified {} tracking pools:\n{}'.format(len(tracking_pools), tracking_pools))

    all_ekfs = [
        EKFModel(dict(poses), km.get_constraints_by_symbols(symbols))
        for symbols, poses in tracking_pools
    ]  # np.eye(len(symbols)) * 0.001
    print('Created {} EKF models'.format(len(all_ekfs)))
    print('\n'.join(str(e) for e in all_ekfs))

    # Sanity constraint
    min_n_dof = min(min_n_dof, len(all_ekfs))

    iteration_times = []

    for u in range(min_n_dof, len(all_ekfs) + 1):
        if rospy.is_shutdown():
            break

        ekfs = all_ekfs[:u]

        observed_poses = {}
        for ekf in ekfs:
            for link_name, _ in ekf.takers:
                observed_poses[link_name] = kitchen.links[link_name].pose
        names, poses = zip(*sorted(observed_poses.items()))

        state_symbols = union([gm.free_symbols(p) for p in poses])
        ordered_state_vars = [
            s for _, s in sorted((str(s), s) for s in state_symbols)
        ]

        state_constraints = {}
        for n, c in km.get_constraints_by_symbols(state_symbols).items():
            if gm.is_symbol(c.expr):
                s = gm.free_symbols(c.expr).pop()
                fs = gm.free_symbols(c.lower).union(gm.free_symbols(c.upper))
                if len(fs.difference({s})) == 0:
                    state_constraints[s] = (float(gm.subs(c.lower, {s: 0})),
                                            float(gm.subs(c.upper, {s: 0})))

        state_bounds = np.array([
            state_constraints[s]
            if s in state_constraints else [-np.pi * 0.5, np.pi * 0.5]
            for s in ordered_state_vars
        ])

        state_fn = gm.speed_up(gm.vstack(*poses), ordered_state_vars)
        subworld = km.get_active_geometry(state_symbols)

        # Generate observation noise
        print('Generating R matrices...')
        n_cov_obs = 400
        full_log = []

        dof_iters = []

        # EXPERIMENT
        for lin_std, ang_std in [(noise_lin, noise_ang * (np.pi / 180.0))]:
            # zip(np.linspace(0, noise_lin, noise_steps),
            #     np.linspace(0, noise_ang * (np.pi / 180.0), noise_steps)):
            if rospy.is_shutdown():
                break
            # INITIALIZE SENSOR MODEL
            training_obs = []
            state = np.random.uniform(state_bounds.T[0], state_bounds.T[1])
            observations = state_fn.call2(state)

            for _ in range(n_cov_obs):
                noisy_obs = {}
                for x, noise in enumerate([
                        t.dot(r) for t, r in zip(
                            random_normal_translation(len(poses), 0, lin_std),
                            random_rot_normal(len(poses), 0, ang_std))
                ]):
                    noisy_obs[names[x]] = observations[x * 4:x * 4 +
                                                       4, :4].dot(noise)
                training_obs.append(noisy_obs)

            for ekf in ekfs:
                ekf.generate_R(training_obs)
                # ekf.set_R(np.eye(len(ekf.ordered_vars)) * 0.1)

            # Generate figure
            gridsize = (4, samples)
            plot_size = (4, 4)
            fig = plt.figure(figsize=(gridsize[1] * plot_size[0], gridsize[0] *
                                      plot_size[1])) if create_figure else None

            gt_states = []
            states = [[] for x in range(samples)]
            variances = [[] for x in range(samples)]
            e_obs = [[] for x in range(samples)]

            print('Starting iterations')
            for k in tqdm(range(samples)):
                if rospy.is_shutdown():
                    break

                state = np.random.uniform(state_bounds.T[0], state_bounds.T[1])
                gt_states.append(state)
                observations = state_fn.call2(state).copy()
                gt_obs_d = {
                    n: observations[x * 4:x * 4 + 4, :4]
                    for x, n in enumerate(names)
                }
                subworld.update_world(dict(zip(ordered_state_vars, state)))

                if vis_mode == 'iter' or vis_mode == 'io':
                    vis.begin_draw_cycle('gt', 'noise', 'estimate', 't_n',
                                         't0')
                    vis.draw_world('gt', subworld, g=0, b=0)
                    vis.render('gt')

                estimates = []
                for ekf in ekfs:
                    particle = ekf.spawn_particle()
                    estimates.append(particle)

                initial_state = dict(
                    sum([[(s, v) for s, v in zip(ekf.ordered_vars, e.state)]
                         for e, ekf in zip(estimates, ekfs)], []))
                initial_state = np.array(
                    [initial_state[s] for s in ordered_state_vars])
                if initial_state.min() < state_bounds.T[0].min(
                ) or initial_state.max() > state_bounds.T[1].max():
                    raise Exception(
                        'Estimate initialization is out of bounds: {}'.format(
                            np.vstack([initial_state, state_bounds.T]).T))
                initial_delta = state - initial_state

                for y in range(n_observations):
                    # Add noise to observations
                    noisy_obs = {}
                    for x, noise in enumerate([
                            t.dot(r) for t, r in zip(
                                random_normal_translation(
                                    len(poses), 0, lin_std),
                                random_rot_normal(len(poses), 0, ang_std))
                    ]):
                        noisy_obs[names[x]] = observations[x * 4:x * 4 +
                                                           4, :4].dot(noise)

                    if vis_mode in {'iter', 'iter-trail'} or (vis_mode == 'io'
                                                              and y == 0):
                        for n, t in noisy_obs.items():
                            subworld.named_objects[Path(
                                ('kitchen', 'links', n))].np_transform = t
                        if vis_mode != 'iter-trail':
                            vis.begin_draw_cycle('noise')
                        vis.draw_world('noise', subworld, r=0, g=0, a=0.1)
                        vis.render('noise')

                    start_time = time()
                    for estimate, ekf in zip(estimates, ekfs):
                        if y > 0:
                            control = np.zeros(len(ekf.ordered_controls))
                            estimate.state, estimate.cov = ekf.predict(
                                estimate.state.flatten(), estimate.cov,
                                control)
                            obs_vector = ekf.gen_obs_vector(noisy_obs)
                            estimate.state, estimate.cov = ekf.update(
                                estimate.state, estimate.cov,
                                ekf.gen_obs_vector(noisy_obs))

                            if vis_mode in {'iter', 'iter-trail'}:
                                subworld.update_world({
                                    s: v
                                    for s, v in zip(ekf.ordered_vars,
                                                    estimate.state)
                                })
                        else:
                            obs_vector = ekf.gen_obs_vector(noisy_obs)

                            for _ in range(1):
                                h_prime = ekf.h_prime_fn.call2(estimate.state)
                                obs_delta = obs_vector.reshape(
                                    (len(obs_vector), 1)) - ekf.h_fn.call2(
                                        estimate.state)
                                estimate.state += (h_prime.T.dot(obs_delta) *
                                                   0.1).reshape(
                                                       estimate.state.shape)

                            if vis_mode in {'iter', 'io'}:
                                subworld.update_world({
                                    s: v
                                    for s, v in zip(ekf.ordered_vars,
                                                    estimate.state)
                                })

                    if vis_mode != 'none' and y == 0:
                        vis.draw_world('t0', subworld, b=0, a=1)
                        vis.render('t0')
                    elif vis_mode in {'iter', 'iter-trail'}:
                        if vis_mode != 'iter-trail':
                            vis.begin_draw_cycle('t_n')
                        vis.draw_world('t_n', subworld, b=0, a=1)
                        vis.render('t_n')

                    if log_csv or fig is not None:
                        e_state_d = dict(
                            sum([[(s, v)
                                  for s, v in zip(ekf.ordered_vars, e.state)]
                                 for e, ekf in zip(estimates, ekfs)], []))
                        covs = dict(
                            sum([[(s, v) for s, v in zip(
                                ekf.ordered_vars, np.sqrt(np.trace(e.cov)))]
                                 for e, ekf in zip(estimates, ekfs)], []))
                        e_state = np.hstack([
                            e_state_d[s] for s in ordered_state_vars
                        ]).reshape((len(e_state_d), ))

                        if log_csv:
                            full_log.append(
                                np.hstack(
                                    ([lin_std,
                                      ang_std], state, e_state.flatten(),
                                     np.array([
                                         covs[s] for s in ordered_state_vars
                                     ]))))

                        if fig is not None:
                            e_obs[k].append(
                                np.array([
                                    np.abs(
                                        ekf.gen_obs_vector(gt_obs_d) -
                                        ekf.h_fn.call2(e.state)).max()
                                    for e, ekf in zip(estimates, ekfs)
                                ]))
                            states[k].append(e_state)
                            variances[k].append(
                                np.array([covs[s]
                                          for s in ordered_state_vars]))
                else:
                    if vis_mode == 'io':
                        for estimate, ekf in zip(estimates, ekfs):
                            subworld.update_world({
                                s: v
                                for s, v in zip(ekf.ordered_vars,
                                                estimate.state)
                            })

                        vis.draw_world('t_n', subworld, r=0, b=0, a=1)
                        vis.render('t_n')

                    dof_iters.append(time() - start_time)

            if fig is not None:
                axes = [
                    plt.subplot2grid(gridsize, (y, 0), colspan=1, rowspan=1)
                    for y in range(gridsize[0])
                ]
                axes = np.array(
                    sum([[
                        plt.subplot2grid(gridsize, (y, x),
                                         colspan=1,
                                         rowspan=1,
                                         sharey=axes[y])
                        for y in range(gridsize[0])
                    ] for x in range(1, gridsize[1])], axes)).reshape(
                        (gridsize[1], gridsize[0]))

                for x, (gt_s, state, variance, obs_delta,
                        (ax_s, ax_d, ax_o, ax_v)) in enumerate(
                            zip(gt_states, states, variances, e_obs, axes)):

                    for y in gt_s:
                        ax_s.axhline(y, xmin=0.97, xmax=1.02)

                    ax_s.set_title('State; Sample: {}'.format(x))
                    ax_d.set_title('Delta from GT; Sample: {}'.format(x))
                    ax_o.set_title('Max Delta in Obs; Sample: {}'.format(x))
                    ax_v.set_title('Standard Deviation; Sample: {}'.format(x))
                    ax_s.plot(state)
                    ax_d.plot(gt_s - np.vstack(state))
                    ax_o.plot(obs_delta)
                    ax_v.plot(variance)
                    ax_s.grid(True)
                    ax_d.grid(True)
                    ax_o.grid(True)
                    ax_v.grid(True)

                fig.tight_layout()
                plt.savefig(
                    res_pkg_path(
                        'package://kineverse_experiment_world/test/ekf_object_tracker_{}_{}.png'
                        .format(lin_std, ang_std)))

        iteration_times.append(dof_iters)

        if log_csv:
            df = pd.DataFrame(
                columns=['lin_std', 'ang_std'] +
                ['gt_{}'.format(x) for x in range(len(state_symbols))] +
                ['ft_{}'.format(x) for x in range(len(state_symbols))] +
                ['var_{}'.format(x) for x in range(len(state_symbols))],
                data=full_log)
            df.to_csv(res_pkg_path(
                'package://kineverse_experiment_world/test/ekf_object_tracker.csv'
            ),
                      index=False)

    df = pd.DataFrame(
        columns=[str(x) for x in range(1,
                                       len(iteration_times) + 1)],
        data=np.vstack(iteration_times).T)
    df.to_csv(res_pkg_path(
        'package://kineverse_experiment_world/test/ekf_object_tracker_performance.csv'
    ),
              index=False)
    km = GeometryModel()
    vis = ROSBPBVisualizer('kineverse/nobilia/vis', base_frame='world')

    origin_pose = gm.translation3(x_loc_sym, 0, 0)

    debug = create_nobilia_shelf(km, Path('nobilia'), origin_pose)

    km.clean_structure()
    km.dispatch_events()

    shelf = km.get_data('nobilia')

    shelf_pos = shelf.joints['hinge'].position

    world = km.get_active_geometry({shelf_pos
                                    }.union(gm.free_symbols(origin_pose)))

    params = debug.tuning_params

    with dpg.window(label='Parameter settings'):
        for s, p in debug.tuning_params.items():

            def update_param(sender, value, symbol):
                params[symbol] = value
                draw_shelves(shelf, params, world, vis, steps=5)

            slider = dpg.add_slider_float(label=f'{s}',
                                          id=f'{s}',
                                          callback=update_param,
                                          user_data=s,
                                          min_value=p - 0.1,
                to_world_tf=gm.translation3(door_x, door_y, 0.1))

    km.clean_structure()
    km.dispatch_events()

    door = km.get_data('door')
    handle = door.links['handle']
    iiwa = km.get_data('iiwa')
    symbols = gm.free_symbols(door.links['handle'].pose).union(
        gm.free_symbols(iiwa.links['link_7'].pose))

    door_position = door.joints['hinge'].position
    handle_position = door.joints['handle'].position

    # Fun for visuals
    world = km.get_active_geometry(symbols)
    symbols = world.free_symbols

    eef = iiwa.links['wsg_50_tool_frame']

    goal_pose = gm.dot(handle.pose, gm.translation3(-0.08, 0.1, 0),
                       gm.rotation3_rpy(0, math.pi * 0.5, 0))

    ik_solver = IKSolver(km, eef.pose, visualizer)

    # Working config is
    #    x:  0.8333333333333333
    #    y: -0.1333333333333333

    for x_coord in [0.8]:  #np.linspace(0.5, 1.0, 4):
        for y_coord in [-0.1]:  #np.linspace(0.2, -0.8, 4):
Exemplo n.º 7
0
        #part = parts[0] # random.choice(parts)
        kitchen_path = Path('kitchen/links/{}/pose'.format(part))

        goal = point3(-0.4, 0.4, 1.2)
        dist = norm(goal - eef_pos)
        obj_pose = km.get_data(kitchen_path)
        robot_cp, object_cp, contact_normal = contact_geometry(
            eef_pose, obj_pose, eef_path[:-1], kitchen_path[:-1])
        geom_distance = dot(contact_normal, robot_cp - object_cp)

        cam_to_obj = pos_of(obj_pose) - cam_pos
        look_goal = 1 - (dot(cam_to_obj, cam_forward) / norm(cam_to_obj))
        #exit()

        #print('Symbols for subworld:\n  {}'.format('\n  '.join([str(x) for x in geom_distance.free_symbols])))
        coll_world = km.get_active_geometry(geom_distance.free_symbols)

        # QP CONFIGURTION
        base_joint = km.get_data('fetch/joints/to_world')
        joint_symbols = [
            j.position for j in km.get_data('fetch/joints').values()
            if hasattr(j, 'position') and type(j.position) is Symbol
        ]
        k_joint_symbols = [
            j.position for j in km.get_data('kitchen/joints').values()
            if hasattr(j, 'position') and type(j.position) is Symbol
        ]
        controlled_symbols = {get_diff_symbol(j)
                              for j in joint_symbols}.union({
                                  get_diff_symbol(j)
                                  for j in obj_pose.free_symbols