def __init__(self, km,
                       actuated_pose,
                       goal_pose,
                       controlled_symbols,
                       weight_override=None,
                       draw_fn=None):
        
        eef = actuated_pose
        goal_pos_error = gm.norm(gm.pos_of(eef) - gm.pos_of(goal_pose))
        self.eef_rot = eef[:3, :3]
        self.goal_rot = goal_pose[:3, :3]
        self.rot_error_matrix = self.eef_rot - self.goal_rot
        goal_rot_error = gm.norm(self.rot_error_matrix)

        rot_align_scale = gm.exp(-3 * goal_rot_error) 

        goal_constraints = {'align position': SC(-goal_pos_error * rot_align_scale,
                                                 -goal_pos_error * rot_align_scale, 10, goal_pos_error),
                            'align rotation': SC(-goal_rot_error, -goal_rot_error, 1, goal_rot_error)}

        self.goal_rot_error = goal_rot_error

        constraints = km.get_constraints_by_symbols(gm.free_symbols(eef).union(controlled_symbols))
        cvs, constraints = generate_controlled_values(constraints, controlled_symbols, weights=weight_override)
        cvs = depth_weight_controlled_values(km, cvs, exp_factor=1.02)

        self.draw_fn = draw_fn

        self.qp = TQPB(constraints,
                       goal_constraints,
                       cvs)
示例#2
0
    def __init__(self, km, controlled_symbols, resting_pose, camera_path=None):
        tucking_constraints = {}
        if resting_pose is not None:
            tucking_constraints = {
                f'tuck {s}': SC(p - s, p - s, 1, s)
                for s, p in resting_pose.items()
            }
            # print('Tuck state:\n  {}\nTucking constraints:\n  {}'.format('\n  '.join(['{}: {}'.format(k, v) for k, v in self._resting_pose.items()]), '\n  '.join(tucking_constraints.keys())))

        # tucking_constraints.update(self.taxi_constraints)

        self.use_camera = camera_path is not None
        if camera_path is not None:
            self._poi_pos = gm.Symbol('poi')
            poi = gm.point3(1.5, 0.5, 0.0) + gm.vector3(
                0, self._poi_pos * 2.0, 0)

            camera = km.get_data(camera_path)
            cam_to_poi = poi - gm.pos_of(camera.pose)
            lookat_dot = 1 - gm.dot_product(gm.x_of(camera.pose),
                                            cam_to_poi) / gm.norm(cam_to_poi)
            tucking_constraints['sweeping gaze'] = SC(-lookat_dot * 5,
                                                      -lookat_dot * 5, 1,
                                                      lookat_dot)

        symbols = set()
        for c in tucking_constraints.values():
            symbols |= gm.free_symbols(c.expr)

        joint_symbols = {
            s
            for s in symbols if gm.get_symbol_type(s) != gm.TYPE_UNKNOWN
        }
        controlled_symbols = {gm.DiffSymbol(s) for s in joint_symbols}

        hard_constraints = km.get_constraints_by_symbols(
            symbols.union(controlled_symbols))

        controlled_values, hard_constraints = generate_controlled_values(
            hard_constraints, controlled_symbols)
        controlled_values = depth_weight_controlled_values(
            km, controlled_values)

        self.qp = TQPB(hard_constraints, tucking_constraints,
                       controlled_values)
        self._start = Time.now()
示例#3
0
    def test_revolute_and_continuous_joint(self):
        ks = ArticulationModel()

        a  = Position('a')
        b  = Position('b')
        c  = Position('c')
        parent_pose     = frame3_axis_angle(vector3(0,1,0), a, point3(0, b, 5))
        joint_transform = translation3(7, -5, 33)
        axis            = vector3(1, -3, 7)
        axis            = axis / norm(axis)
        position        = c
        child_pose      = parent_pose * joint_transform * rotation3_axis_angle(axis, position)

        ks.apply_operation('create parent', CreateComplexObject(Path('parent'), KinematicLink('', parent_pose)))
        ks.apply_operation('create child', CreateComplexObject(Path('child'),  KinematicLink('', se.eye(4))))
        self.assertTrue(ks.has_data('parent/pose'))
        self.assertTrue(ks.has_data('child/pose'))

        ks.apply_operation('connect parent child', 
                           SetRevoluteJoint(Path('parent/pose'), 
                                            Path('child/pose'), 
                                            Path('fixed_joint'), 
                                            joint_transform,
                                            axis,
                                            position,
                                            -1, 2, 0.5))
        self.assertTrue(ks.has_data('fixed_joint'))
        self.assertEquals(ks.get_data('child/pose'), child_pose)
        ks.remove_operation('connect parent child')
        ks.apply_operation('connect parent child',
                           SetContinuousJoint(Path('parent/pose'), 
                                              Path('child/pose'), 
                                              Path('fixed_joint'), 
                                              joint_transform,
                                              axis,
                                              position, 0.5))
    collision_world.update_world(start_state)

    vis.begin_draw_cycle('ik_solution')
    vis.draw_world('ik_solution', collision_world)
    vis.render('ik_solution')

    print(f'IK error: {ik_err}')
    
    def gen_dv_cvs(km, constraints, controlled_symbols):
        cvs, constraints = generate_controlled_values(constraints, controlled_symbols)
        cvs = depth_weight_controlled_values(km, cvs, exp_factor=1.02)
        print('\n'.join(f'{cv.symbol}: {cv.weight_id}' for _, cv in sorted(cvs.items())))
        return cvs, constraints

    dyn_goal_pos_error = gm.norm(gm.pos_of(eef.pose) - gm.pos_of(goal_pose))
    dyn_goal_rot_error = gm.norm(eef.pose[:3, :3] - goal_pose[:3, :3])

    o_vars, bounds, _ = static_var_bounds(km, gm.free_symbols(handle.pose))

    lead_goal_constraints = {f'open_object {s}': SC(ub - s,
                                                    ub - s, 1, s) for s, (_, ub) in zip(o_vars, bounds)}

    follower_goal_constraints = {'keep position': SC(-dyn_goal_pos_error,
                                                     -dyn_goal_pos_error, 10, dyn_goal_pos_error),
                                 'keep rotation': SC(-dyn_goal_rot_error, -dyn_goal_rot_error, 1, dyn_goal_rot_error)}

    solver = CascadingQP(km, 
                         lead_goal_constraints, 
                         follower_goal_constraints, 
                         f_gen_follower_cvs=gen_dv_cvs,
示例#5
0
    def behavior_update(self):
        state_count = 0

        while not rospy.is_shutdown() and not self._kys:
            loop_start = rospy.Time.now()

            with self._state_lock:
                if self._robot_state_update_count <= state_count:
                    rospy.sleep(0.01)
                    continue
                state_count = self._robot_state_update_count

            if self.controller is not None:
                now = rospy.Time.now()
                with self._state_lock:
                    deltaT = 0.05 if self._last_controller_update is None else (
                        now - self._last_controller_update).to_sec()
                    try:
                        command = self.controller.get_cmd(self._state,
                                                          deltaT=deltaT)
                    except Exception as e:
                        print(traceback.format_exc())
                        rospy.signal_shutdown('die lol')

                self.robot_command_processor.send_command(command)
                self._last_controller_update = now

            # Lets not confuse the tracker
            if self._phase != 'opening' and self._last_external_cmd_msg is not None:
                # Ensure that velocities are assumed to be 0 when not operating anything
                self._last_external_cmd_msg.value = [0] * len(
                    self._last_external_cmd_msg.value)
                self.pub_external_command.publish(self._last_external_cmd_msg)
                self._last_external_cmd_msg = None

            if self._phase == 'idle':
                # if there is no controller, instantiate idle

                # check for new target
                # -> open gripper
                #    instantiate 6d controller
                #    switch to "grasping"
                if self.controller is None:
                    self.gripper_wrapper.sync_set_gripper_position(0.07)
                    self.controller = self._idle_controller

                with self._state_lock:
                    for s, p in self._target_map.items():
                        if s in self._state and self._state[
                                s] < self._var_upper_bound[
                                    s] * self.monitoring_threshold:  # Some thing in the scene is closed
                            self._current_target = p
                            print(f'New target is {self._current_target}')
                            self.gripper_wrapper.sync_set_gripper_position(
                                0.07)
                            self._last_controller_update = None
                            print('Gripper is open. Proceeding to grasp...')
                            draw_fn = None

                            eef_pose = self.km.get_data(self.eef_path).pose

                            if self.visualizer is not None:
                                self.visualizer.begin_draw_cycle('grasp pose')
                                self.visualizer.draw_poses(
                                    'grasp pose', np.eye(4), 0.2, 0.01, [
                                        gm.subs(self._grasp_poses[p],
                                                self._state)
                                    ])
                                self.visualizer.render('grasp pose')

                                def draw_fn(state):
                                    self.visualizer.begin_draw_cycle(
                                        'debug_grasp')
                                    self.visualizer.draw_poses(
                                        'debug_grasp', np.eye(4), 1.0, 0.01, [
                                            gm.subs(eef_pose, state),
                                            gm.subs(self._grasp_poses[p],
                                                    state)
                                        ])
                                    self.visualizer.render('debug_grasp')
                                    # print('\n'.join(f'{s}: {v}' for s, v in state.items()))

                            self.controller = SixDPoseController(
                                self.km, eef_pose, self._grasp_poses[p],
                                self.controlled_symbols, self.weights, draw_fn)

                            self._phase = 'grasping'
                            print(f'Now entering {self._phase} state')
                            break
                    else:
                        print(
                            'None of the monitored symbols are closed:\n  {}'.
                            format('\n  '.join(
                                f'{self._state[s]} < {self._var_upper_bound[s]}'
                                for s in self._target_map.keys()
                                if s in self._state)))
            elif self._phase == 'grasping':
                # check if grasp is acheived
                # -> close gripper
                #    instantiate cascading controller
                #    switch to "opening"
                # if there is no more command but the goal error is too great -> "homing"
                if self.controller.equilibrium_reached(0.03, -0.03):
                    if self.controller.current_error() > 0.01:
                        self.controller = self._idle_controller
                        self._phase = 'homing'
                        print(f'Now entering {self._phase} state')
                    else:
                        print('Closing gripper...')
                        self.gripper_wrapper.sync_set_gripper_position(0, 80)
                        print('Generating opening controller')

                        eef = self.km.get_data(self.eef_path)
                        obj = self.km.get_data(self._current_target)
                        with self._state_lock:
                            static_eef_pose = gm.subs(eef.pose, self._state)
                            static_object_pose = gm.subs(obj.pose, self._state)

                        offset_pose = np_inverse_frame(static_object_pose).dot(
                            static_eef_pose)
                        print(offset_pose)

                        goal_pose = gm.dot(obj.pose, gm.Matrix(offset_pose))

                        goal_pos_error = gm.norm(
                            gm.pos_of(eef.pose) - gm.pos_of(goal_pose))
                        goal_rot_error = gm.norm(eef.pose[:3, :3] -
                                                 goal_pose[:3, :3])

                        target_symbols = self._target_body_map[
                            self._current_target]
                        lead_goal_constraints = {
                            f'open_{s}': SC(self._var_upper_bound[s] - s, 1000,
                                            1, s)
                            for s in target_symbols
                            if s in self._var_upper_bound
                        }
                        for n, c in lead_goal_constraints.items():
                            print(f'{n}: {c}')

                        follower_goal_constraints = {
                            'keep position':
                            SC(-goal_pos_error, -goal_pos_error, 10,
                               goal_pos_error),
                            'keep rotation':
                            SC(-goal_rot_error, -goal_rot_error, 1,
                               goal_rot_error)
                        }

                        blacklist = {
                            gm.Velocity(Path('pr2/torso_lift_joint'))
                        }.union({
                            gm.DiffSymbol(s)
                            for s in gm.free_symbols(obj.pose)
                            if 'location' in str(s)
                        })
                        # blacklist = {gm.DiffSymbol(s) for s in gm.free_symbols(obj.pose) if 'location' in str(s)}

                        self.controller = CascadingQP(
                            self.km,
                            lead_goal_constraints,
                            follower_goal_constraints,
                            f_gen_follower_cvs=gen_dv_cvs,
                            controls_blacklist=blacklist,
                            t_follower=GQPB,
                            visualizer=None  # self.visualizer
                        )
                        print(self.controller)

                        # def debug_draw(vis, state, cmd):
                        #     vis.begin_draw_cycle('lol')
                        #     vis.draw_poses('lol', np.eye(4), 0.2, 0.01,
                        #                    [gm.subs(goal_pose, state),
                        #                     gm.subs(eef.pose, state)])
                        #     vis.render('lol')

                        # self.controller.follower_qp._cb_draw = debug_draw

                        # self.gripper_wrapper.sync_set_gripper_position(0.07)
                        # rospy.signal_shutdown('die lol')
                        # return
                        self._last_controller_update = None
                        self._phase = 'opening'
                        print(f'Now entering {self._phase} state')
            elif self._phase == 'opening':
                # Wait for monitored symbols to be in open position
                # -> open gripper
                #    generate 6d retraction goal: -10cm in tool frame
                #    spawn 6d controller
                #    switch to "retracting"

                # self.visualizer.begin_draw_cycle('world state')
                # with self._state_lock:
                #     self._world.update_world(self._state)
                # self.visualizer.draw_world('world state', self._world, b=0)
                # self.visualizer.render('world state')

                external_command = {
                    s: v
                    for s, v in command.items()
                    if s not in self.controlled_symbols
                }
                ext_msg = ValueMapMsg()
                ext_msg.header.stamp = now
                ext_msg.symbol, ext_msg.value = zip(
                    *[(str(s), v) for s, v in external_command.items()])
                self.pub_external_command.publish(ext_msg)
                self._last_external_cmd_msg = ext_msg

                with self._state_lock:
                    current_external_error = {
                        s: self._state[s]
                        for s in self._target_body_map[self._current_target]
                    }
                print('Current error state:\n  {}'.format('\n  '.join(
                    [f'{s}: {v}' for s, v in current_external_error.items()])))

                gripper_err = self.gripper_wrapper.get_latest_error()
                # if gripper_err < 0.0005: # Grasped object is thinner than 5mm aka we lost it
                #     self.controller = self._idle_controller
                #     self._phase = 'homing'
                #     print(f'Grasped object seems to have slipped ({gripper_err}). Returning to home...')
                #     return

                if min([
                        v >=
                        self._var_upper_bound[s] * self.acceptance_threshold
                        for s, v in current_external_error.items()
                ]):
                    print('Target fulfilled. Setting it to None')
                    self._current_target = None

                    eef = self.km.get_data(self.eef_path)
                    with self._state_lock:
                        static_eef_pose = gm.subs(eef.pose, self._state)
                    goal_pose = static_eef_pose.dot(
                        np.array([[1, 0, 0, -0.12], [0, 1, 0, 0], [0, 0, 1, 0],
                                  [0, 0, 0, 1]]))

                    self.controller = SixDPoseController(
                        self.km, eef.pose, goal_pose, self.controlled_symbols,
                        self.weights)

                    self.gripper_wrapper.sync_set_gripper_position(0.07)
                    self._last_controller_update = None
                    self._phase = 'retracting'
                    print(f'Now entering {self._phase} state')
                else:
                    remainder = (1 / 3) - (rospy.Time.now() -
                                           loop_start).to_sec()
                    if remainder > 0:
                        rospy.sleep(remainder)

            elif self._phase == 'retracting':
                # Wait for retraction to complete (Currently just skipping)
                # -> spawn idle controller
                #    switch to "homing"
                if self.controller.equilibrium_reached(0.035, -0.035):
                    self.controller = self._idle_controller
                    self._phase = 'homing'
                    print(f'Now entering {self._phase} state')
            elif self._phase == 'homing':
                # Wait for idle controller to have somewhat low error
                # -> switch to "idle"
                if self.controller is None:
                    self.gripper_wrapper.sync_set_gripper_position(0.07)
                    self.controller = self._idle_controller
                    continue

                if self.controller.equilibrium_reached(0.1, -0.1):
                    self._phase = 'idle'
                    print(f'Now entering {self._phase} state')
            else:
                raise Exception(f'Unknown state "{self._phase}')
def create_nobilia_shelf(km,
                         prefix,
                         origin_pose=gm.eye(4),
                         parent_path=Path('world')):
    km.apply_operation(
        f'create {prefix}',
        ExecFunction(prefix, MarkedArticulatedObject, str(prefix)))

    shelf_height = 0.72
    shelf_width = 0.6
    shelf_body_depth = 0.35

    wall_width = 0.016

    l_prefix = prefix + ('links', )
    geom_body_wall_l = Box(
        l_prefix + ('body', ),
        gm.translation3(0, 0.5 * (shelf_width - wall_width), 0),
        gm.vector3(shelf_body_depth, wall_width, shelf_height))
    geom_body_wall_r = Box(
        l_prefix + ('body', ),
        gm.translation3(0, -0.5 * (shelf_width - wall_width), 0),
        gm.vector3(shelf_body_depth, wall_width, shelf_height))

    geom_body_ceiling = Box(
        l_prefix + ('body', ),
        gm.translation3(0, 0, 0.5 * (shelf_height - wall_width)),
        gm.vector3(shelf_body_depth, shelf_width - wall_width, wall_width))
    geom_body_floor = Box(
        l_prefix + ('body', ),
        gm.translation3(0, 0, -0.5 * (shelf_height - wall_width)),
        gm.vector3(shelf_body_depth, shelf_width - wall_width, wall_width))

    geom_body_shelf_1 = Box(
        l_prefix + ('body', ),
        gm.translation3(0.02, 0, -0.2 * (shelf_height - wall_width)),
        gm.vector3(shelf_body_depth - 0.04, shelf_width - wall_width,
                   wall_width))

    geom_body_shelf_2 = Box(
        l_prefix + ('body', ),
        gm.translation3(0.02, 0, 0.2 * (shelf_height - wall_width)),
        gm.vector3(shelf_body_depth - 0.04, shelf_width - wall_width,
                   wall_width))

    geom_body_back = Box(
        l_prefix + ('body', ),
        gm.translation3(0.5 * (shelf_body_depth - 0.005), 0, 0),
        gm.vector3(0.005, shelf_width - 2 * wall_width,
                   shelf_height - 2 * wall_width))

    shelf_geom = [
        geom_body_wall_l, geom_body_wall_r, geom_body_ceiling, geom_body_floor,
        geom_body_back, geom_body_shelf_1, geom_body_shelf_2
    ]

    rb_body = RigidBody(parent_path,
                        origin_pose,
                        geometry=dict(enumerate(shelf_geom)),
                        collision=dict(enumerate(shelf_geom)))

    geom_panel_top = Box(l_prefix + ('panel_top', ), gm.eye(4),
                         gm.vector3(0.357, 0.595, wall_width))
    geom_panel_bottom = Box(l_prefix + ('panel_bottom', ), gm.eye(4),
                            gm.vector3(0.357, 0.595, wall_width))

    handle_width = 0.16
    handle_depth = 0.05
    handle_diameter = 0.012

    geom_handle_r = Box(
        l_prefix + ('handle', ),
        gm.translation3(0.5 * handle_depth,
                        0.5 * (handle_width - handle_diameter), 0),
        gm.vector3(handle_depth, handle_diameter, handle_diameter))
    geom_handle_l = Box(
        l_prefix + ('handle', ),
        gm.translation3(0.5 * handle_depth,
                        -0.5 * (handle_width - handle_diameter), 0),
        gm.vector3(handle_depth, handle_diameter, handle_diameter))
    geom_handle_bar = Box(
        l_prefix + ('handle', ),
        gm.translation3(handle_depth - 0.5 * handle_diameter, 0, 0),
        gm.vector3(handle_diameter, handle_width - handle_diameter,
                   handle_diameter))

    handle_geom = [geom_handle_l, geom_handle_r, geom_handle_bar]

    # Sketch of mechanism
    #
    #           T ---- a
    #         ----      \  Z
    #       b ..... V    \
    #       |      ...... d
    #    B  |       ------
    #       c ------
    #                L
    #
    # Diagonal V is virtual
    #
    #
    # Angles:
    #   a -> alpha (given)
    #   b -> gamma_1 + gamma_2 = gamma
    #   c -> don't care
    #   d -> delta_1 + delta_2 = delta
    #

    opening_position = gm.Position(prefix + ('door', ))

    # Calibration results
    #
    # Solution top hinge: cost = 0.03709980624159568 [ 0.08762252 -0.01433833  0.2858676   0.00871125]
    # Solution bottom hinge: cost = 0.025004236048128934 [ 0.1072496  -0.01232362  0.27271013  0.00489996]

    # Added 180 deg rotation due to -x being the forward facing side in this model
    top_hinge_in_body_marker = gm.translation3(0.08762252 - 0.015, 0,
                                               -0.01433833)
    top_panel_marker_in_top_hinge = gm.translation3(0.2858676 - 0.003,
                                                    -wall_width + 0.0025,
                                                    0.00871125 - 0.003)
    front_hinge_in_top_panel_maker = gm.translation3(0.1072496 - 0.02, 0,
                                                     -0.01232362 + 0.007)
    bottom_panel_marker_in_front_hinge = gm.translation3(
        0.27271013, 0, 0.00489996)

    # Top hinge - Data taken from observation
    body_marker_in_body = gm.dot(
        gm.rotation3_axis_angle(gm.vector3(0, 0, 1), math.pi),
        gm.translation3(0.5 * shelf_body_depth - 0.062,
                        -0.5 * shelf_width + 0.078, 0.5 * shelf_height))
    top_panel_marker_in_top_panel = gm.translation3(
        geom_panel_top.scale[0] * 0.5 - 0.062,
        -geom_panel_top.scale[1] * 0.5 + 0.062, geom_panel_top.scale[2] * 0.5)
    bottom_panel_marker_in_bottom_panel = gm.translation3(
        geom_panel_bottom.scale[0] * 0.5 - 0.062,
        -geom_panel_bottom.scale[1] * 0.5 + 0.062,
        geom_panel_bottom.scale[2] * 0.5)

    top_hinge_in_body = gm.dot(body_marker_in_body, top_hinge_in_body_marker)
    top_panel_in_top_hinge = gm.dot(
        top_panel_marker_in_top_hinge,
        gm.inverse_frame(top_panel_marker_in_top_panel))
    front_hinge_in_top_panel = gm.dot(top_panel_marker_in_top_panel,
                                      front_hinge_in_top_panel_maker)
    bottom_panel_in_front_hinge = gm.dot(
        bottom_panel_marker_in_front_hinge,
        gm.inverse_frame(bottom_panel_marker_in_bottom_panel))

    # Point a in body reference frame
    point_a = gm.dot(gm.diag(1, 0, 1, 1), gm.pos_of(top_hinge_in_body))
    point_d = gm.point3(-shelf_body_depth * 0.5 + 0.09, 0,
                        shelf_height * 0.5 - 0.192)
    # point_d  = gm.point3(-shelf_body_depth * 0.5 + gm.Symbol('point_d_x'), 0, shelf_height * 0.5 - gm.Symbol('point_d_z'))
    # Zero alpha along the vertical axis
    vec_a_to_d = gm.dot(point_d - point_a)
    alpha = gm.atan2(vec_a_to_d[0], -vec_a_to_d[2]) + opening_position

    top_panel_in_body = gm.dot(
        top_hinge_in_body,  # Translation hinge to body frame
        gm.rotation3_axis_angle(gm.vector3(0, 1, 0), -opening_position +
                                0.5 * math.pi),  # Hinge around y
        top_panel_in_top_hinge)
    front_hinge_in_body = gm.dot(top_panel_in_body, front_hinge_in_top_panel)

    # Point b in top panel reference frame
    point_b_in_top_hinge = gm.pos_of(
        gm.dot(gm.diag(1, 0, 1, 1), front_hinge_in_top_panel,
               top_panel_in_top_hinge))
    point_b = gm.dot(gm.diag(1, 0, 1, 1), gm.pos_of(front_hinge_in_body))
    # Hinge lift arm in body reference frame
    point_c_in_bottom_panel = gm.dot(
        gm.diag(1, 0, 1, 1),
        bottom_panel_marker_in_bottom_panel,
        gm.point3(-0.094, -0.034, -0.072),
        # gm.point3(-gm.Symbol('point_c_x'), -0.034, -gm.Symbol('point_c_z'))
    )
    point_c_in_front_hinge = gm.dot(
        gm.diag(1, 0, 1, 1),
        gm.dot(bottom_panel_in_front_hinge, point_c_in_bottom_panel))
    length_z = gm.norm(point_a - point_d)

    vec_a_to_b = point_b - point_a
    length_t = gm.norm(vec_a_to_b)
    length_b = gm.norm(point_c_in_front_hinge[:3])
    # length_l = gm.Symbol('length_l') # 0.34
    length_l = 0.372

    vec_b_to_d = point_d - point_b
    length_v = gm.norm(vec_b_to_d)
    gamma_1 = inner_triangle_angle(length_t, length_v, length_z)
    gamma_2 = inner_triangle_angle(length_b, length_v, length_l)

    top_panel_offset_angle = gm.atan2(point_b_in_top_hinge[2],
                                      point_b_in_top_hinge[0])
    bottom_offset_angle = gm.atan2(point_c_in_front_hinge[2],
                                   point_c_in_front_hinge[0])

    gamma = gamma_1 + gamma_2

    rb_panel_top = RigidBody(l_prefix + ('body', ),
                             gm.dot(rb_body.pose, top_panel_in_body),
                             top_panel_in_body,
                             geometry={0: geom_panel_top},
                             collision={0: geom_panel_top})

    # old offset: 0.5 * geom_panel_top.scale[2] + 0.03
    tf_bottom_panel = gm.dot(
        front_hinge_in_top_panel,
        gm.rotation3_axis_angle(
            gm.vector3(0, 1, 0),
            math.pi + bottom_offset_angle - top_panel_offset_angle),
        gm.rotation3_axis_angle(gm.vector3(0, -1, 0), gamma),
        bottom_panel_in_front_hinge)

    rb_panel_bottom = RigidBody(l_prefix + ('panel_top', ),
                                gm.dot(rb_panel_top.pose, tf_bottom_panel),
                                tf_bottom_panel,
                                geometry={0: geom_panel_bottom},
                                collision={0: geom_panel_bottom})

    handle_transform = gm.dot(
        gm.translation3(geom_panel_bottom.scale[0] * 0.5 - 0.08, 0,
                        0.5 * wall_width),
        gm.rotation3_axis_angle(gm.vector3(0, 1, 0), -math.pi * 0.5))
    rb_handle = RigidBody(l_prefix + ('panel_bottom', ),
                          gm.dot(rb_panel_bottom.pose, handle_transform),
                          handle_transform,
                          geometry={x: g
                                    for x, g in enumerate(handle_geom)},
                          collision={x: g
                                     for x, g in enumerate(handle_geom)})
    # Only debugging
    point_c = gm.dot(rb_panel_bottom.pose, point_c_in_bottom_panel)
    vec_b_to_c = point_c - point_b

    km.apply_operation(f'create {prefix}/links/body',
                       CreateValue(rb_panel_top.parent, rb_body))
    km.apply_operation(f'create {prefix}/links/panel_top',
                       CreateValue(rb_panel_bottom.parent, rb_panel_top))
    km.apply_operation(
        f'create {prefix}/links/panel_bottom',
        CreateValue(l_prefix + ('panel_bottom', ), rb_panel_bottom))
    km.apply_operation(f'create {prefix}/links/handle',
                       CreateValue(l_prefix + ('handle', ), rb_handle))
    km.apply_operation(
        f'create {prefix}/joints/hinge',
        ExecFunction(
            prefix + Path('joints/hinge'), RevoluteJoint,
            CPath(rb_panel_top.parent), CPath(rb_panel_bottom.parent),
            opening_position, gm.vector3(0, 1, 0), gm.eye(4), 0, 1.84, **{
                f'{opening_position}':
                Constraint(0 - opening_position, 1.84 - opening_position,
                           opening_position),
                f'{gm.DiffSymbol(opening_position)}':
                Constraint(-0.25, 0.25, gm.DiffSymbol(opening_position))
            }))
    m_prefix = prefix + ('markers', )
    km.apply_operation(
        f'create {prefix}/markers/body',
        ExecFunction(m_prefix + ('body', ), Frame,
                     CPath(l_prefix + ('body', )),
                     gm.dot(rb_body.pose,
                            body_marker_in_body), body_marker_in_body))
    km.apply_operation(
        f'create {prefix}/markers/top_panel',
        ExecFunction(m_prefix + ('top_panel', ), Frame,
                     CPath(l_prefix + ('panel_top', )),
                     gm.dot(rb_panel_top.pose, top_panel_marker_in_top_panel),
                     top_panel_marker_in_top_panel))
    km.apply_operation(
        f'create {prefix}/markers/bottom_panel',
        ExecFunction(
            m_prefix + ('bottom_panel', ), Frame,
            CPath(l_prefix + ('panel_bottom', )),
            gm.dot(rb_panel_bottom.pose, bottom_panel_marker_in_bottom_panel),
            bottom_panel_marker_in_bottom_panel))

    return NobiliaDebug(
        [
            top_hinge_in_body,
            gm.dot(
                top_hinge_in_body,
                gm.rotation3_axis_angle(gm.vector3(0, 1, 0),
                                        -opening_position + 0.5 * math.pi),
                top_panel_in_top_hinge, front_hinge_in_top_panel),
            body_marker_in_body,
            gm.dot(rb_panel_top.pose, top_panel_marker_in_top_panel),
            gm.dot(rb_panel_bottom.pose, bottom_panel_marker_in_bottom_panel)
        ], [(point_a, vec_a_to_d), (point_a, vec_a_to_b),
            (point_b, vec_b_to_d), (point_b, vec_b_to_c)],
        {
            'gamma_1':
            gamma_1,
            'gamma_1 check_dot':
            gamma_1 - gm.acos(
                gm.dot_product(-vec_a_to_b / gm.norm(vec_a_to_b),
                               vec_b_to_d / gm.norm(vec_b_to_d))),
            'gamma_1 check_cos':
            gamma_1 - inner_triangle_angle(
                gm.norm(vec_a_to_b), gm.norm(vec_b_to_d), gm.norm(vec_a_to_d)),
            'gamma_2':
            gamma_2,
            'gamma_2 check_dot':
            gamma_2 - gm.acos(
                gm.dot_product(vec_b_to_c / gm.norm(vec_b_to_c),
                               vec_b_to_d / gm.norm(vec_b_to_d))),
            'length_v':
            length_v,
            'length_b':
            length_b,
            'length_l':
            length_l,
            'position':
            opening_position,
            'alpha':
            alpha,
            'dist c d':
            gm.norm(point_d - point_c)
        }, {
            gm.Symbol('point_c_x'): 0.094,
            gm.Symbol('point_c_z'): 0.072,
            gm.Symbol('point_d_x'): 0.09,
            gm.Symbol('point_d_z'): 0.192,
            gm.Symbol('length_l'): 0.372
        })
示例#7
0
def generate_push_closing(km,
                          grounding_state,
                          controlled_symbols,
                          eef_pose,
                          obj_pose,
                          eef_path,
                          obj_path,
                          nav_method='cross',
                          cp_offset=0,
                          static_symbols=set()):
    # CONTACT GEOMETRY
    robot_cp, object_cp, contact_normal = contact_geometry(
        eef_pose, obj_pose, eef_path, obj_path)
    object_cp = object_cp - contact_normal * cp_offset
    geom_distance = gm.dot_product(contact_normal, robot_cp - object_cp)
    coll_world = km.get_active_geometry(gm.free_symbols(geom_distance))

    # GEOMETRY NAVIGATION LOGIC
    # This is exploiting task knowledge which makes this function inflexible.
    contact_grad = sum([
        sign(-grounding_state[s]) *
        gm.vector3(gm.diff(object_cp[0], s), gm.diff(object_cp[1], s),
                   gm.diff(object_cp[2], s))
        for s in gm.free_symbols(obj_pose) if s not in static_symbols
    ], gm.vector3(0, 0, 0))
    neutral_tangent = gm.cross(contact_grad, contact_normal)
    active_tangent = gm.cross(neutral_tangent, contact_normal)

    contact_constraints, in_contact = generate_contact_model(
        robot_cp, controlled_symbols, object_cp, contact_normal,
        gm.free_symbols(obj_pose))

    target_pos = None
    if nav_method == 'linear':
        geom_distance = gm.norm(object_cp + active_tangent * geom_distance +
                                contact_grad * 0.05 - robot_cp)
    elif nav_method == 'cubic':
        dist_scaling = 2**(-0.5 * ((geom_distance - 0.2) / (0.2 * 0.2))**2)
        geom_distance = gm.norm(object_cp + active_tangent * dist_scaling -
                                robot_cp)
    elif nav_method == 'cross':
        geom_distance = gm.norm(object_cp +
                                active_tangent * gm.norm(neutral_tangent) +
                                contact_grad * 0.05 - robot_cp)
    elif nav_method == 'cross_deep':
        geom_distance = gm.norm(object_cp +
                                active_tangent * gm.norm(neutral_tangent) +
                                contact_grad *
                                -gm.dot_product(contact_normal, contact_grad) -
                                robot_cp)
    elif nav_method == 'none' or nav_method is None:
        pass
    elif nav_method == 'proj':
        obj_cp_dist = gm.dot_product(contact_normal,
                                     object_cp - gm.pos_of(obj_pose))
        target_pos = gm.pos_of(
            obj_pose
        ) + contact_normal * obj_cp_dist - contact_normal * 0.02  # Drive into the surface
        geom_distance = gm.norm(robot_cp - target_pos)

    contact_relative_pos = gm.dot(gm.rot_of(obj_pose),
                                  robot_cp - gm.pos_of(obj_pose))
    contact_relative_vel = gm.vector3(
        sum([gm.diff(contact_relative_pos[0], s) for s in controlled_symbols],
            0),
        sum([gm.diff(contact_relative_pos[1], s) for s in controlled_symbols],
            0),
        sum([gm.diff(contact_relative_pos[2], s) for s in controlled_symbols],
            0))

    # PUSH CONSTRAINT GENERATION
    constraints = km.get_constraints_by_symbols(
        gm.free_symbols(geom_distance).union(controlled_symbols))
    constraints.update(contact_constraints)

    # for x, n in enumerate('xyz'):
    #     constraints[f'zero tangent vel_{n}'] = Constraint((1 -  in_contact) * -1e3,
    #                                                       (1 -  in_contact) *  1e3, contact_relative_pos[x] * (1.0 + 0.1 * x))

    def debug_draw(vis, state, cmd):
        vis.begin_draw_cycle('debug_vecs')
        s_object_cp = gm.subs(object_cp, state)
        s_neutral_tangent = gm.subs(neutral_tangent, state)
        vis.draw_vector('debug_vecs',
                        s_object_cp,
                        gm.subs(contact_grad, state),
                        r=0,
                        b=0)
        vis.draw_vector('debug_vecs',
                        s_object_cp,
                        gm.subs(active_tangent, state),
                        r=0,
                        b=1)
        vis.draw_vector('debug_vecs',
                        s_object_cp,
                        gm.subs(neutral_tangent, state),
                        r=1,
                        g=1,
                        b=0)
        if target_pos is not None:
            vis.draw_sphere('debug_vecs',
                            gm.subs(target_pos, state),
                            0.01,
                            r=0,
                            b=1)
        # print(f'{gm.norm(gm.subs(contact_normal, state))}')
        # vis.draw_vector('debug_vecs', s_object_cp, s_ortho_vel_vec, r=1, b=0)
        vis.render('debug_vecs')

    return constraints, geom_distance, coll_world, PushingInternals(
        robot_cp, contact_normal, contact_relative_pos, contact_relative_vel,
        debug_draw)
示例#8
0
    def __init__(self,
                 km,
                 actuated_object_path,
                 target_object_path,
                 controlled_symbols,
                 start_state,
                 camera_path=None,
                 navigation_method='cross',
                 visualizer=None,
                 weight_override=None,
                 collision_avoidance_paths=None):
        print(f'{actuated_object_path}\n{target_object_path}')

        actuated_object = km.get_data(actuated_object_path)
        target_object = km.get_data(target_object_path)

        all_controlled_symbols = controlled_symbols.union({
            gm.DiffSymbol(j)
            for j in gm.free_symbols(target_object.pose)
            if 'location' not in str(j)
        })
        static_symbols = {
            s
            for s in gm.free_symbols(target_object.pose)
            if 'location' in str(s)
        }

        # Generate push problem
        constraints, \
        geom_distance, \
        coll_world, \
        self.p_internals = generate_push_closing(km,
                                                 start_state,
                                                 all_controlled_symbols,
                                                 actuated_object.pose,
                                                 target_object.pose,
                                                 actuated_object_path,
                                                 target_object_path,
                                                 navigation_method,
                                                 static_symbols=static_symbols)

        start_state.update({s: 0.0 for s in gm.free_symbols(coll_world)})

        weight_override = {} if weight_override is None else weight_override

        controlled_values, \
        constraints = generate_controlled_values(constraints,
                                                 all_controlled_symbols)
        controlled_values = depth_weight_controlled_values(km,
                                                           controlled_values,
                                                           exp_factor=1.1)

        goal_constraints = {
            'reach_point': PIDC(geom_distance, geom_distance, 1, k_i=0.00)
        }

        for s, w in weight_override.items():
            for cv in controlled_values.values():
                if cv.symbol is s:
                    cv.weight_id = w
                    break

        # CAMERA STUFF
        if camera_path is not None:
            camera = km.get_data(camera_path)
            cam_pos = gm.pos_of(camera.pose)
            cam_to_obj = gm.pos_of(target_object.pose) - cam_pos
            cam_forward = gm.dot(camera.pose, gm.vector3(1, 0, 0))
            look_goal = 1 - (gm.dot_product(cam_to_obj, cam_forward) /
                             gm.norm(cam_to_obj))
            goal_constraints['look_at_obj'] = SC(-look_goal, -look_goal, 1,
                                                 look_goal)

        # GOAL CONSTAINT GENERATION
        # 'avoid_collisions': SC.from_constraint(closest_distance_constraint_world(eef_pose, eef_path[:-1], 0.03), 100)
        # }

        if collision_avoidance_paths is not None:
            for p in collision_avoidance_paths:
                obj = km.get_data(p)
                goal_constraints[f'avoid_collision {p}'] = SC.from_constraint(
                    closest_distance_constraint(actuated_object.pose, obj.pose,
                                                actuated_object_path, p, 0.01),
                    100)

        goal_constraints.update({
            f'open_object_{x}': PIDC(s, s, 1)
            for x, s in enumerate(gm.free_symbols(target_object.pose))
        })

        self.look_goal = look_goal if camera_path is not None else None
        self.in_contact = gm.less_than(geom_distance, 0.01)
        self.controlled_values = controlled_values
        self.geom_distance = geom_distance

        self.qpb = GQPB(coll_world,
                        constraints,
                        goal_constraints,
                        controlled_values,
                        visualizer=visualizer)
        self.qpb._cb_draw = self.p_internals.f_debug_draw
    def post_physics_update(self, simulator, deltaT):
        """Implements post physics step behavior.
        :type simulator: BasicSimulator
        :type deltaT: float
        """
        if not self._enabled:
            return

        self._last_update += deltaT
        if self._last_update >= self._update_wait:
            self._last_update = 0
            cf_tuple = self.multibody.get_link_state(self.camera_link).worldFrame
            camera_frame = gm.frame3_quaternion(cf_tuple.position.x, cf_tuple.position.y, cf_tuple.position.z, *cf_tuple.quaternion)
            cov_proj = gm.rot_of(camera_frame)[:3, :3]
            inv_cov_proj = cov_proj.T

            out = PSAMsg()

            if self.visualizer is not None:
                self.visualizer.begin_draw_cycle()
                poses = []

            for name, body in simulator.bodies.items():
                if body == self.multibody:
                    continue

                if isinstance(body, MultiBody):
                    poses_to_process = [('{}/{}'.format(name, l), body.get_link_state(l).worldFrame) for l in body.links]
                else:
                    poses_to_process = [(name, body.pose())]

                for pname, pose in poses_to_process:
                    if not pname in self.message_templates:
                        msg = PoseStampedMsg()
                        msg.header.frame_id = pname
                        self.message_templates[pname] = msg
                    else:
                        msg = self.message_templates[pname]

                    obj_pos = gm.point3(*pose.position)
                    c2o  = obj_pos - gm.pos_of(camera_frame)
                    dist = gm.norm(c2o)
                    if dist < self.far and dist > self.near and gm.dot_product(c2o, gm.x_of(camera_frame)) > gm.cos(self.fov * 0.5) * dist:


                        noise = 2 ** (self.noise_exp * dist) - 1
                        (n_quat, )  = np_random_quat_normal(1, 0, noise)
                        (n_trans, ) = np_random_normal_offset(1, 0, noise)

                        n_pose = pb.Transform(pb.Quaternion(*pose.quaternion), pb.Vector3(*pose.position)) *\
                                     pb.Transform(pb.Quaternion(*n_quat), pb.Vector3(*n_trans[:3]))

                        if self.visualizer is not None:
                            poses.append(transform_to_matrix(n_pose))
                        msg.pose.position.x = n_pose.origin.x
                        msg.pose.position.y = n_pose.origin.y
                        msg.pose.position.z = n_pose.origin.z
                        msg.pose.orientation.x = n_pose.rotation.x
                        msg.pose.orientation.y = n_pose.rotation.y
                        msg.pose.orientation.z = n_pose.rotation.z
                        msg.pose.orientation.w = n_pose.rotation.w
                        out.poses.append(msg)


                self.publisher.publish(out)

            if self.visualizer is not None:
                self.visualizer.draw_poses('debug', gm.se.eye(4), 0.1, 0.02, poses)
                self.visualizer.render()
                collision_avoidance_paths=active_parts_to_avoid)

        if robot in start_poses:
            start_state.update({
                gm.Position(Path(robot) + (k, )): v
                for k, v in start_poses[robot].items()
            })

        start_state.update({
            c.symbol: 0.0
            for c in pushing_controller.controlled_values.values()
        })
        # start_state.update({s: 1.84 for s in gm.free_symbols(obj.pose)})
        start_state.update({s: 0.4 for s in gm.free_symbols(obj.pose)})

        printed_exprs['relative_vel'] = gm.norm(
            pushing_controller.p_internals.relative_pos)

        integrator = CommandIntegrator(pushing_controller.qpb,
                                       integration_rules,
                                       equilibrium=0.0004,
                                       start_state=start_state,
                                       recorded_terms={
                                           'distance':
                                           pushing_controller.geom_distance,
                                           'gaze_align':
                                           pushing_controller.look_goal,
                                           'in contact':
                                           pushing_controller.in_contact,
                                           'location_x': base_joint.x_pos,
                                           'location_y': base_joint.y_pos,
                                           'rotation_a': base_joint.a_pos
示例#11
0
    def _generate_pose_constraints(self, str_path, model):
        with self.lock:
            if str_path in self.tracked_poses:
                align_rotation = '{} align rotation'.format(str_path)
                align_position = '{} align position'.format(str_path)
                if model is not None:
                    m_free_symbols = cm.free_symbols(model.pose)
                    if len(m_free_symbols) > 0:
                        te = self.tracked_poses[str_path]

                        self.joints |= m_free_symbols
                        self.joint_aliases = {s: str(s) for s in self.joints}

                        r_dist = norm(
                            cm.rot_of(model.pose) - cm.rot_of(te.pose))
                        self.soft_constraints[align_rotation] = SC(
                            -r_dist, -r_dist, 1, r_dist)

                        # print(align_position)
                        # print(model.pose)
                        dist = norm(cm.pos_of(model.pose) - cm.pos_of(te.pose))
                        # print('Distance expression:\n{}'.format(dist))
                        # print('Distance expression symbol overlap:\n{}'.format(m_free_symbols.intersection(cm.free_symbols(dist))))
                        # for s in m_free_symbols:
                        #     print('Diff w.r.t {}:\n{}'.format(s, cm.diff(dist, s)))
                        self.soft_constraints[align_position] = SC(
                            -dist, -dist, 1, dist)
                        self.generate_opt_problem()

                        # Avoid crashes due to insufficient perception data. This is not fully correct.
                        if str_path in self._unintialized_poses:
                            state = self.integrator.state.copy(
                            ) if self.integrator is not None else {}
                            state.update({
                                s: 0.0
                                for s in m_free_symbols if s not in state
                            })
                            null_pose = cm.subs(model.pose, state)
                            pos = cm.pos_of(null_pose)
                            quat = real_quat_from_matrix(cm.rot_of(null_pose))
                            msg = PoseMsg()
                            msg.position.x = pos[0]
                            msg.position.y = pos[1]
                            msg.position.z = pos[2]
                            msg.orientation.x = quat[0]
                            msg.orientation.y = quat[1]
                            msg.orientation.z = quat[2]
                            msg.orientation.w = quat[3]
                            te.update_state(msg, self.integrator.state)
                else:
                    regenerate_problem = False
                    if align_position in self.soft_constraints:
                        del self.soft_constraints[align_position]
                        regenerate_problem = True

                    if align_rotation in self.soft_constraints:
                        del self.soft_constraints[align_rotation]
                        regenerate_problem = True

                    if regenerate_problem:
                        self.generate_opt_problem()
            err_ik, q_ik_goal = ik_solve_one_shot(km, eef.pose, ik_goal_start,
                                                  goal_pose)

            world.update_world(q_ik_goal)
            visualizer.begin_draw_cycle('pre_open_world')
            visualizer.draw_poses('pre_open_world', gm.eye(4), 0.2, 0.01, [
                gm.subs(goal_pose, {s: 0
                                    for s in gm.free_symbols(goal_pose)}),
                gm.subs(eef.pose, q_ik_goal)
            ])
            visualizer.draw_world('pre_open_world', world, g=0.6, b=0.6)
            visualizer.render('pre_open_world')

            # Build Door opening problem

            grasp_err_rot = gm.norm(gm.rot_of(goal_pose - eef.pose).elements())
            grasp_err_lin = gm.norm(gm.pos_of(goal_pose - eef.pose))

            active_symbols = {s for s in gm.free_symbols(eef.pose) if gm.get_symbol_type(s) == gm.TYPE_POSITION}\
                             .union({door_position, handle_position})
            controlled_symbols = {gm.DiffSymbol(s) for s in active_symbols}

            controlled_values, constraints = generate_controlled_values(
                km.get_constraints_by_symbols(
                    controlled_symbols.union(active_symbols)),
                controlled_symbols)

            # Static grasp goal
            goal_grasp_lin = SoftConstraint(-grasp_err_lin, -grasp_err_lin,
                                            100.0, grasp_err_lin)
            goal_grasp_ang = SoftConstraint(-grasp_err_rot, -grasp_err_rot,