Example #1
0
    def makeIkOptions(self, fields):

        options = pydrakeik.IKoptions(self.rigidBodyTree)
        options.setQ(np.diag(fields.positionCosts))
        #options.setQv()
        #options.setQa()
        #options.setDebug(True)

        options.setMajorOptimalityTolerance(
            fields.options.majorOptimalityTolerance)
        options.setMajorFeasibilityTolerance(
            fields.options.majorFeasibilityTolerance)
        options.setMajorIterationsLimit(fields.options.majorIterationsLimit)
        #options.setIterationsLimit(limit)
        #options.setSuperbasicsLimit(limit)

        # for ik pointwise, whether to use q_seed at each point (False),
        # or to use the solution from the previous point (True)
        #options.setSequentialSeedFlag(True)

        # for ik traj, if initial state is not fixed
        # then here you can set the lb/ub of initial q
        options.setFixInitialState(fields.options.fixInitialState)
        #options.setq0(lb, ub)

        # for ik traj, set lower and upper bound of
        # initial and final velocity
        #options.setqd0(lb, ub)
        #options.setqdf(lb, ub)

        # for ik traj, additional time samples in addition to knot points
        # to check constraints
        #options.setAdditionaltSamples([])

        return options
Example #2
0
def setup_scene(rbt):
    AddFlatTerrainToWorld(rbt)

    instances = []
    num_objects = np.random.randint(10) + 1
    for i in range(num_objects):
        object_ind = np.random.randint(len(objects.keys()))
        pose = np.zeros(6)
        pose[0:2] = (np.random.random(2) - 0.5) * 0.05
        pose[2] = np.random.random() * 0.1 + 0.05
        pose[3:6] = np.random.random(3) * np.pi * 2.
        object_init_frame = RigidBodyFrame("object_init_frame", rbt.world(),
                                           pose[0:3], pose[3:6])
        object_path = objects[objects.keys()[object_ind]]["model_path"]
        if object_path.split(".")[-1] == "urdf":
            AddModelInstanceFromUrdfFile(object_path,
                                         FloatingBaseType.kRollPitchYaw,
                                         object_init_frame, rbt)
        else:
            AddModelInstancesFromSdfString(
                open(object_path).read(), FloatingBaseType.kRollPitchYaw,
                object_init_frame, rbt)
        instances.append({
            "class": objects.keys()[object_ind],
            "pose": pose.tolist()
        })
    rbt.compile()

    # Project arrangement to nonpenetration with IK
    constraints = []

    constraints.append(
        ik.MinDistanceConstraint(model=rbt,
                                 min_distance=0.01,
                                 active_bodies_idx=list(),
                                 active_group_names=set()))

    for body_i in range(2, 1 + num_objects):
        constraints.append(
            ik.WorldPositionConstraint(model=rbt,
                                       body=body_i,
                                       pts=np.array([0., 0., 0.]),
                                       lb=np.array([-0.5, -0.5, 0.0]),
                                       ub=np.array([0.5, 0.5, 0.5])))

    q0 = np.zeros(rbt.get_num_positions())
    options = ik.IKoptions(rbt)
    options.setDebug(True)
    options.setMajorIterationsLimit(10000)
    options.setIterationsLimit(100000)
    results = ik.InverseKin(rbt, q0, q0, constraints, options)

    qf = results.q_sol[0]
    info = results.info[0]
    print "Projected with info %d" % info
    return qf, instances
Example #3
0
    def ComputeTargetPosture(self,
                             x_seed,
                             target_manipuland_pose,
                             backoff_distance=0.0):
        q_des_full = np.zeros(self.nq)
        q_des_full[self.nq - 3:] = target_manipuland_pose

        desired_positions = self.transform_grasp_points_manipuland(q_des_full)
        desired_normals = self.transform_grasp_normals_manipuland(q_des_full)
        desired_positions -= backoff_distance * desired_normals  # back off a bit
        desired_angles = [
            math.atan2(desired_normals[1, k], desired_normals[0, k])
            for k in range(desired_normals.shape[1])
        ]
        constraints = []

        # Constrain the fingertips to lie on the grasp points,
        # facing approximately along the grasp angles.
        for i in range(len(self.grasp_points)):
            constraints.append(
                ik.WorldPositionConstraint(
                    self.hand,
                    self.finger_link_indices[self.grasp_finger_assignments[i]
                                             [0]],
                    self.grasp_finger_assignments[i][1],
                    desired_positions[:, i] - 0.01,  # lb
                    desired_positions[:, i] + 0.01)  # ub
            )

            constraints.append(
                ik.WorldEulerConstraint(
                    self.hand,
                    self.finger_link_indices[self.grasp_finger_assignments[i]
                                             [0]],
                    [-0.01, -0.01, desired_angles[i] - 1.0],  # lb
                    [0.01, 0.01, desired_angles[i] + 1.0])  # ub
            )

        posture_constraint = ik.PostureConstraint(self.hand)
        # Disambiguate the continuous rotation joint angle choices
        # for the hand.
        posture_constraint.setJointLimits(np.arange(self.nq - 3),
                                          -np.ones(self.nq - 3) * math.pi,
                                          np.ones(self.nq - 3) * math.pi)
        # Constrain the manipuland to be in the target position.
        posture_constraint.setJointLimits(
            [self.nq - 3, self.nq - 2, self.nq - 1],
            target_manipuland_pose - 0.01, target_manipuland_pose + 0.01)
        constraints.append(posture_constraint)

        options = ik.IKoptions(self.hand)
        results = ik.InverseKin(self.hand, x_seed[0:self.nq],
                                self.x_nom[0:self.nq], constraints, options)
        return results.q_sol[0], results.info[0]
Example #4
0
def plan_ee_configuration(rbt,
                          q0,
                          qseed,
                          ee_pose,
                          ee_body,
                          ee_point,
                          allow_collision=True,
                          active_bodies_idx=list(),
                          euler_limits=0.3):
    ''' Performs IK for a single point in time
        to get the Kuka's gripper to a specified
        pose in space. '''
    nq = rbt.get_num_positions()

    controlled_joint_names = [
        "iiwa_joint_1", "iiwa_joint_2", "iiwa_joint_3", "iiwa_joint_4",
        "iiwa_joint_5", "iiwa_joint_6", "iiwa_joint_7"
    ]
    free_config_inds, constrained_config_inds = \
        kuka_utils.extract_position_indices(rbt, controlled_joint_names)

    # Assemble IK constraints
    constraints = []

    if not allow_collision:
        constraints.append(
            ik.MinDistanceConstraint(model=rbt,
                                     min_distance=1E-6,
                                     active_bodies_idx=active_bodies_idx,
                                     active_group_names=set()))

    # Constrain the non-searched-over joints
    posture_constraint = ik.PostureConstraint(rbt)
    posture_constraint.setJointLimits(constrained_config_inds,
                                      q0[constrained_config_inds] - 0.001,
                                      q0[constrained_config_inds] + 0.001)
    constraints.append(posture_constraint)

    # Constrain the ee frame to lie on the target point
    # facing in the target orientation
    constraints.append(
        ik.WorldPositionConstraint(rbt, ee_body, ee_point, ee_pose[0:3] - 0.01,
                                   ee_pose[0:3] + 0.01))
    constraints.append(
        ik.WorldEulerConstraint(rbt, ee_body, ee_pose[3:6] - euler_limits,
                                ee_pose[3:6] + euler_limits))

    options = ik.IKoptions(rbt)
    results = ik.InverseKin(rbt, q0, qseed, constraints, options)
    #print "plan ee config info %d" % results.info[0]
    return results.q_sol[0], results.info[0]
Example #5
0
    def testPostureConstraint(self):
        r = pydrake.rbtree.RigidBodyTree(
            os.path.join(pydrake.getDrakePath(),
                         "examples/Pendulum/Pendulum.urdf"))
        q = -0.9
        posture_constraint = ik.PostureConstraint(r)
        posture_constraint.setJointLimits(np.array([[6]], dtype=np.int32),
                                          np.array([[q]]),
                                          np.array([[q]]))
        # Choose a seed configuration (randomly) and a nominal configuration
        # (at 0)
        q_seed = np.vstack((np.zeros((6, 1)),
                            0.8147))
        q_nom = np.vstack((np.zeros((6, 1)),
                           0.))

        options = ik.IKoptions(r)
        results = ik.InverseKin(
            r, q_seed, q_nom, [posture_constraint], options)
        self.assertEqual(results.info[0], 1)
        self.assertAlmostEqual(results.q_sol[0][6], q, 1e-9)

        # Run the tests again both pointwise and as a trajectory to
        # validate the interfaces.
        t = np.array([0., 1.])
        q_seed_array = np.transpose(np.array([q_seed, q_seed]))[0]
        q_nom_array = np.transpose(np.array([q_nom, q_nom]))[0]

        results = ik.InverseKinPointwise(r, t, q_seed_array, q_nom_array,
                                         [posture_constraint], options)
        self.assertEqual(len(results.info), 2)
        self.assertEqual(len(results.q_sol), 2)
        self.assertEqual(results.info[0], 1)

        # The pointwise result will go directly to the constrained
        # value.
        self.assertAlmostEqual(results.q_sol[0][6], q, 1e-9)
        self.assertEqual(results.info[1], 1)
        self.assertAlmostEqual(results.q_sol[1][6], q, 1e-9)

        results = ik.InverseKinTraj(r, t, q_seed_array, q_nom_array,
                                    [posture_constraint], options)
        self.assertEqual(len(results.info), 1)
        self.assertEqual(len(results.q_sol), 2)
        self.assertEqual(results.info[0], 1)

        # The trajectory result starts at the initial value and moves
        # to the constrained value.
        self.assertAlmostEqual(results.q_sol[0][6], q_seed[6], 1e-9)
        self.assertAlmostEqual(results.q_sol[1][6], q, 1e-9)
Example #6
0
    def testPostureConstraint(self):
        r = pydrake.rbtree.RigidBodyTree(
            os.path.join(pydrake.getDrakePath(),
                         "examples/Pendulum/Pendulum.urdf"))
        q = -0.9
        posture_constraint = ik.PostureConstraint(r)
        posture_constraint.setJointLimits(np.array([[6]], dtype=np.int32),
                                          np.array([[q]]), np.array([[q]]))
        # Choose a seed configuration (randomly) and a nominal configuration (at 0)
        q_seed = np.vstack((np.zeros((6, 1)), 0.8147))
        q_nom = np.vstack((np.zeros((6, 1)), 0.))

        options = ik.IKoptions(r)
        results = ik.inverseKinSimple(r, q_seed, q_nom, [posture_constraint],
                                      options)
        self.assertAlmostEqual(results.q_sol[6], q, 1e-9)
Example #7
0
def plan_grasping_configuration(rbt, q0, target_ee_pose):
    ''' Performs IK for a single point in time
        to get the Kuka's gripper to a specified
        pose in space. '''
    nq = rbt.get_num_positions()
    q_des_full = np.zeros(nq)

    controlled_joint_names = [
        "iiwa_joint_1", "iiwa_joint_2", "iiwa_joint_3", "iiwa_joint_4",
        "iiwa_joint_5", "iiwa_joint_6", "iiwa_joint_7"
    ]
    free_config_inds, constrained_config_inds = \
        kuka_utils.extract_position_indices(rbt, controlled_joint_names)

    # Assemble IK constraints
    constraints = []

    # Constrain the non-searched-over joints
    posture_constraint = ik.PostureConstraint(rbt)
    posture_constraint.setJointLimits(constrained_config_inds,
                                      q0[constrained_config_inds] - 0.01,
                                      q0[constrained_config_inds] + 0.01)
    constraints.append(posture_constraint)

    # Constrain the ee frame to lie on the target point
    # facing in the target orientation
    ee_frame = rbt.findFrame("iiwa_frame_ee").get_frame_index()
    constraints.append(
        ik.WorldPositionConstraint(rbt, ee_frame, np.zeros(
            (3, 1)), target_ee_pose[0:3] - 0.01, target_ee_pose[0:3] + 0.01))
    constraints.append(
        ik.WorldEulerConstraint(rbt, ee_frame, target_ee_pose[3:6] - 0.01,
                                target_ee_pose[3:6] + 0.01))

    options = ik.IKoptions(rbt)
    results = ik.InverseKin(rbt, q0, q0, constraints, options)
    print results.q_sol, "info %d" % results.info[0]
    return results.q_sol[0], results.info[0]
    def solveIK(self, target):
        constraints = list()

        constraints.append(
            ik.WorldGazeTargetConstraint(
                self.robot,
                self.bodies[self.config["optical_frame"]],  # Body to constrain
                np.array([0.0, 0.0, 0.1]).reshape(3, 1),  # Gaze axis
                target.reshape(3, 1),  # Gaze target (world frame)
                np.zeros([3, 1]),  # Gaze origin (body frame)
                self.config["cone_threshold"]  # Cone threshold
            ))

        q_seed = self.robot.getZeroConfiguration()
        options = ik.IKoptions(self.robot)
        result = ik.InverseKin(self.robot, q_seed, q_seed, constraints,
                               options)

        if result.info[0] != 1:
            print "Outside joint limits! (Result = {})".format(result.info[0])

        # If we're out of bounds, result is the best-effort solution
        return result.q_sol[0][:2]  # Only return head pose
Example #9
0
    def project_rbt_to_nearest_feasible_on_table(self, rbt, q0):
        # Project arrangement to nonpenetration with IK
        constraints = []

        q0 = np.clip(q0, rbt.joint_limit_min, rbt.joint_limit_max)

        constraints.append(ik.MinDistanceConstraint(
            model=rbt, min_distance=1E-3,
            active_bodies_idx=self.manipuland_body_indices +
            self.tabletop_indices,
            active_group_names=set()))

        options = ik.IKoptions(rbt)
        options.setMajorIterationsLimit(10000)
        options.setIterationsLimit(100000)
        options.setQ(np.eye(rbt.get_num_positions())*1E6)
        results = ik.InverseKin(
            rbt, q0, q0, constraints, options)

        qf = results.q_sol[0]
        info = results.info[0]
        print "Projected to feasibility with info %d" % info
        return qf
Example #10
0
    def runIK(self, pose_mat):
        # Set up constraints
        constraints = list()

        xyz = transf.translation_from_matrix(pose_mat)
        pos_delta = self.config["pose_delta"]
        constraints.append(
            ik.WorldPositionConstraint(
                self.robot,
                self.robot.bodies["iiwa_tool_frame"],  # Frame of reference
                np.array([0.0, 0.0,
                          0.0]),  # Point to constrain (in frame of reference)
                xyz - pos_delta,  # Lower bound
                xyz + pos_delta  # Upper bound
            ))

        rpy = np.array(transf.euler_from_matrix(pose_mat))
        quat_tol = self.config["quat_tol"]
        constraints.append(
            ik.WorldEulerConstraint(
                self.robot,
                self.robot.bodies["iiwa_tool_frame"],  # Frame of reference
                rpy - quat_tol,  # Lower bound
                rpy + quat_tol  # Upper bound
            ))

        # Run the IK
        q_seed = self.robot.getZeroConfiguration()
        options = ik.IKoptions(self.robot)

        result = ik.InverseKin(self.robot, q_seed, q_seed, constraints,
                               options)

        if result.info[0] == 1:
            return result.q_sol[0][2:], True
        else:
            return [], False
Example #11
0
def plan_grasping_trajectory(rbt, q0, target_reach_pose, target_grasp_pose,
                             n_knots, reach_time, grasp_time):
    ''' Solves IK at a series of sample times (connected with a
    cubic spline) to generate a trajectory to bring the Kuka from an
    initial pose q0 to a final end effector pose in the specified
    time, using the specified number of knot points.

    Uses an intermediate pose reach_pose as an intermediate target
    to hit at the knot point closest to reach_time.

    See http://drake.mit.edu/doxygen_cxx/rigid__body__ik_8h.html
    for the "inverseKinTraj" entry. At the moment, the Python binding
    for this function uses "inverseKinTrajSimple" -- i.e., it doesn't
    return derivatives. '''
    nq = rbt.get_num_positions()
    q_des_full = np.zeros(nq)

    # Create knot points
    ts = np.linspace(0., grasp_time, n_knots)
    # Figure out the knot just before reach time
    reach_start_index = np.argmax(ts >= reach_time) - 1

    controlled_joint_names = [
        "iiwa_joint_1", "iiwa_joint_2", "iiwa_joint_3", "iiwa_joint_4",
        "iiwa_joint_5", "iiwa_joint_6", "iiwa_joint_7"
    ]
    free_config_inds, constrained_config_inds = \
        kuka_utils.extract_position_indices(rbt, controlled_joint_names)

    # Assemble IK constraints
    constraints = []

    # Constrain the non-searched-over joints for all time
    all_tspan = np.array([0., grasp_time])
    posture_constraint = ik.PostureConstraint(rbt, all_tspan)
    posture_constraint.setJointLimits(constrained_config_inds,
                                      q0[constrained_config_inds] - 0.01,
                                      q0[constrained_config_inds] + 0.01)
    constraints.append(posture_constraint)

    # Constrain all joints to be the initial posture at the start time
    start_tspan = np.array([0., 0.])
    posture_constraint = ik.PostureConstraint(rbt, start_tspan)
    posture_constraint.setJointLimits(free_config_inds,
                                      q0[free_config_inds] - 0.01,
                                      q0[free_config_inds] + 0.01)
    constraints.append(posture_constraint)

    # Constrain the ee frame to lie on the target point
    # facing in the target orientation in between the
    # reach and final times
    ee_frame = rbt.findFrame("iiwa_frame_ee").get_frame_index()
    for i in range(reach_start_index, n_knots):
        this_tspan = np.array([ts[i], ts[i]])
        interp = float(i - reach_start_index) / (n_knots - reach_start_index)
        target_pose = (1. -
                       interp) * target_reach_pose + interp * target_grasp_pose
        constraints.append(
            ik.WorldPositionConstraint(rbt,
                                       ee_frame,
                                       np.zeros((3, 1)),
                                       target_pose[0:3] - 0.01,
                                       target_pose[0:3] + 0.01,
                                       tspan=this_tspan))
        constraints.append(
            ik.WorldEulerConstraint(rbt,
                                    ee_frame,
                                    target_pose[3:6] - 0.05,
                                    target_pose[3:6] + 0.05,
                                    tspan=this_tspan))

    # Seed and nom are both the initial repeated for the #
    # of knot points
    q_seed = np.tile(q0, [1, n_knots])
    q_nom = np.tile(q0, [1, n_knots])
    options = ik.IKoptions(rbt)
    # Set bounds on initial and final velocities
    zero_velocity = np.zeros(rbt.get_num_velocities())
    options.setqd0(zero_velocity, zero_velocity)
    options.setqdf(zero_velocity, zero_velocity)
    results = ik.InverseKinTraj(rbt, ts, q_seed, q_nom, constraints, options)

    qtraj = PiecewisePolynomial.Pchip(ts, np.vstack(results.q_sol).T, True)

    print "IK returned a solution with info %d" % results.info[0]
    print "(Info 1 is good, other values are dangerous)"
    return qtraj, results.info[0]
    def trajectoryIK(self, start, end):

        dur = self.config["trajectory_duration"]

        joints = np.array(
            [self.positions[joint] for joint in self.joint_names],
            dtype=np.int32
        ).reshape(9, 1)

        constraints = list()
        # Constrain the start position
        start_pose = np.concatenate(start).reshape(9, 1)
        start_constraint = ik.PostureConstraint( self.robot,
            np.array([0.0, 0.0]).reshape([2,1])    # Active time
        )
        start_constraint.setJointLimits(
            joints,
            start_pose - self.config['pose_tol'],
            start_pose + self.config['pose_tol']
        )
        constraints.append(start_constraint)

        # Constrain the end position
        end_pose = np.concatenate(end).reshape(9, 1)
        end_constraint = ik.PostureConstraint( self.robot,
            np.array([dur, dur]).reshape([2,1])    # Active time
        )
        end_constraint.setJointLimits(
            joints,
            end_pose - self.config['pose_tol'],
            end_pose + self.config['pose_tol']
        )
        constraints.append(end_constraint)

        # Constrain against collisions
        constraints.append( ik.MinDistanceConstraint ( self.robot,
            self.config['collision_min_distance'],   # Minimum distance between bodies
            list(),                                  # Active bodies (empty set means all bodies)
            set()                                    # Active collision groups (not filter groups! Empty set means all)
        ))

        # Prepare times of interest for trajectory solve
        times = np.linspace(0, dur, num=self.config['trajectory_count'], endpoint=True)

        # Compute cubic interpolation as seed trajectory
        x = np.array([0, dur])
        y = np.hstack([start_pose, end_pose])
        f = CubicSpline(x, y, axis=1, bc_type='clamped')
        q_seed = f(times)
        # print "q_seed:", q_seed

        # Solve the IK problem
        options = ik.IKoptions(self.robot)
        options.setMajorIterationsLimit(400)
        options.setFixInitialState(True)
        # print "Iterations limit:", options.getMajorIterationsLimit()
        result = ik.InverseKinTraj(self.robot, times, q_seed, q_seed, constraints, options)

        if result.info[0] != 1:
            print "Could not find safe trajectory!"
            print "Start pose:", start_pose.flatten()
            print "End pose:  ", end_pose.flatten()
            print "Result:", result.info
            return None
        else:
            # Clean up: Pack solutions as a matrix, with time as first column
            q_sol = np.vstack(result.q_sol)
            q_sol = np.insert(q_sol, [0], times[:, None], axis=1)

            return q_sol
                               np.array([np.nan, np.nan, 0.0])),
    ik.WorldPositionConstraint(robot, base_body_id, np.array([1.0, 0.0, 0.0]),
                               np.array([np.nan, np.nan, 0.0]),
                               np.array([np.nan, np.nan, 0.0])),
    ik.WorldPositionConstraint(robot, base_body_id, np.array([0.0, 1.0, 0.0]),
                               np.array([np.nan, np.nan, 0.0]),
                               np.array([np.nan, np.nan, 0.0])),

    # This constraint exactly specifies the desired position of the
    # hand frame we defined earlier.
    ik.WorldPositionConstraint(robot, hand_frame_id, np.array([0.0, 0.0, 0.0]),
                               np.array([0.5, 0.0, 0.6]),
                               np.array([0.5, 0.0, 0.6])),
    # And this specifies the orientation of that frame
    ik.WorldEulerConstraint(robot, hand_frame_id, np.array([0.0, 0.0, 0.0]),
                            np.array([0.0, 0.0, 0.0]))
]

q_seed = robot.getZeroConfiguration()
options = ik.IKoptions(robot)
results = ik.InverseKin(robot, q_seed, q_seed, constraints, options)

# Each entry (only one is present in this case, since InverseKin()
# only returns a single result) in results.info gives the output
# status of SNOPT. info = 1 is good, anything less than 10 is OK, and
# any info >= 10 indicates an infeasibility or failure of the
# optimizer.
assert results.info[0] == 1

print(repr(results.q_sol[0]))
Example #14
0
def plan_trajectory_to_posture(rbt, q0, qf, n_knots, duration, start_time=0.):
    ''' Solves IK at a series of sample times (connected with a
    cubic spline) to generate a trajectory to bring the Kuka from an
    initial pose q0 to a final end effector pose in the specified
    time, using the specified number of knot points.

    Uses an intermediate pose reach_pose as an intermediate target
    to hit at the knot point closest to reach_time.

    See http://drake.mit.edu/doxygen_cxx/rigid__body__ik_8h.html
    for the "inverseKinTraj" entry. At the moment, the Python binding
    for this function uses "inverseKinTrajSimple" -- i.e., it doesn't
    return derivatives. '''
    nq = rbt.get_num_positions()

    # Create knot points
    ts = np.linspace(0., duration, n_knots)

    controlled_joint_names = [
        "iiwa_joint_1", "iiwa_joint_2", "iiwa_joint_3", "iiwa_joint_4",
        "iiwa_joint_5", "iiwa_joint_6", "iiwa_joint_7"
    ]
    free_config_inds, constrained_config_inds = \
        kuka_utils.extract_position_indices(rbt, controlled_joint_names)

    # Assemble IK constraints
    constraints = []

    q0 = np.clip(q0, rbt.joint_limit_min, rbt.joint_limit_max)
    qf = np.clip(qf, rbt.joint_limit_min[free_config_inds],
                 rbt.joint_limit_max[free_config_inds])

    #constraints.append(ik.MinDistanceConstraint(
    #    model=rbt, min_distance=0.01, active_bodies_idx=list(),
    #    active_group_names=set()))

    # Constrain the non-searched-over joints for all time
    all_tspan = np.array([0., duration])
    posture_constraint = ik.PostureConstraint(rbt, all_tspan)
    posture_constraint.setJointLimits(constrained_config_inds,
                                      q0[constrained_config_inds] - 0.01,
                                      q0[constrained_config_inds] + 0.01)
    constraints.append(posture_constraint)

    # Constrain all joints to be the initial posture at the start time
    # TODO: actually freeze these, rather than letting them be searched over.
    # No point actually searching over these, and makes IK way slower
    start_tspan = np.array([0., 0.])
    posture_constraint = ik.PostureConstraint(rbt, start_tspan)
    posture_constraint.setJointLimits(free_config_inds,
                                      q0[free_config_inds] - 0.01,
                                      q0[free_config_inds] + 0.01)
    constraints.append(posture_constraint)

    # Constrain constrainted joints to be the final posture at the final time
    end_tspan = np.array([duration, duration])
    posture_constraint = ik.PostureConstraint(rbt, end_tspan)
    posture_constraint.setJointLimits(free_config_inds,
                                      qf[free_config_inds] - 0.01,
                                      qf[free_config_inds] + 0.01)
    constraints.append(posture_constraint)

    # Seed is joint-space linear interpolation of the
    # initial and final posture (a reasonable initial guess)
    q_seed = np.zeros([q0.shape[0], n_knots])
    qf_full = q0 * 0.
    qf_full[free_config_inds] = qf
    for i, t in enumerate(ts):
        frac = t / duration
        q_seed[:, i] = q0 * (1. - frac) + qf_full * (frac)
    # Nominal is the final posture
    q_nom = np.tile(qf_full, [1, n_knots])
    options = ik.IKoptions(rbt)
    # Set bounds on initial and final velocities
    zero_velocity = np.zeros(rbt.get_num_velocities())
    options.setqd0(zero_velocity, zero_velocity)
    options.setqdf(zero_velocity, zero_velocity)
    results = ik.InverseKinTraj(rbt, ts, q_seed, q_nom, constraints, options)

    ts += start_time
    qtraj = PiecewisePolynomial.Pchip(ts, np.vstack(results.q_sol).T, True)

    print "IK returned a solution with info %d" % results.info[0]
    return qtraj, results.info[0]
Example #15
0
def plan_ee_trajectory(rbt,
                       q0,
                       traj_seed,
                       ee_times,
                       ee_poses,
                       ee_body,
                       ee_point,
                       n_knots,
                       start_time=0.,
                       avoid_collision_tspans=[],
                       active_bodies_idx=list()):
    nq = rbt.get_num_positions()

    # Create knot points
    ts = np.linspace(0., ee_times[-1], n_knots)

    # Insert one more for each ee time if not already in there
    for t in ee_times:
        if t not in ts:
            ts = np.insert(ts, np.argmax(ts >= t), t)
    print "times ", ts, " for times ", ee_times

    controlled_joint_names = [
        "iiwa_joint_1", "iiwa_joint_2", "iiwa_joint_3", "iiwa_joint_4",
        "iiwa_joint_5", "iiwa_joint_6", "iiwa_joint_7"
    ]
    free_config_inds, constrained_config_inds = \
        kuka_utils.extract_position_indices(rbt, controlled_joint_names)

    # Assemble IK constraints
    constraints = []

    for tspan in avoid_collision_tspans:
        constraints.append(
            ik.MinDistanceConstraint(model=rbt,
                                     min_distance=1E-6,
                                     active_bodies_idx=active_bodies_idx,
                                     active_group_names=set(),
                                     tspan=tspan))
        print "active for ", tspan

    # Make starting constraint sensible if it's out of joint limits
    q0 = np.clip(q0, rbt.joint_limit_min, rbt.joint_limit_max)

    # Constrain the non-searched-over joints for all time
    all_tspan = np.array([0., ts[-1]])
    posture_constraint = ik.PostureConstraint(rbt, all_tspan)
    posture_constraint.setJointLimits(constrained_config_inds,
                                      q0[constrained_config_inds] - 0.05,
                                      q0[constrained_config_inds] + 0.05)
    constraints.append(posture_constraint)

    # Constrain all joints to be the initial posture at the start time
    start_tspan = np.array([0., 0.])
    posture_constraint = ik.PostureConstraint(rbt, start_tspan)
    posture_constraint.setJointLimits(free_config_inds,
                                      q0[free_config_inds] - 0.01,
                                      q0[free_config_inds] + 0.01)
    constraints.append(posture_constraint)

    # Constrain the ee frame to lie on the target point
    # facing in the target orientation in between the
    # reach and final times)
    for t, pose in zip(ee_times, ee_poses):
        this_tspan = np.array([t - 0.01, t + 0.01])
        constraints.append(
            ik.WorldPositionConstraint(rbt,
                                       ee_body,
                                       ee_point,
                                       pose[0:3] - 0.01,
                                       pose[0:3] + 0.01,
                                       tspan=this_tspan))
        constraints.append(
            ik.WorldEulerConstraint(rbt,
                                    ee_body,
                                    pose[3:6] - 0.05,
                                    pose[3:6] + 0.05,
                                    tspan=this_tspan))

    # Seed and nom are both the initial repeated for the #
    # of knot points
    q_seed = np.hstack([traj_seed.value(t) for t in ts])
    q_nom = np.tile(q0, [ts.shape[0], 1]).T
    options = ik.IKoptions(rbt)
    # Set bounds on initial and final velocities
    zero_velocity = np.zeros(rbt.get_num_velocities())
    options.setqd0(zero_velocity, zero_velocity)
    options.setqdf(zero_velocity, zero_velocity)
    Q = np.eye(q0.shape[0], q0.shape[0])
    Q[free_config_inds[-2:], free_config_inds[-2:]] *= 1
    options.setQ(Q)
    options.setQv(np.eye(q0.shape[0], q0.shape[0]) * 10)

    results = ik.InverseKinTraj(rbt, ts, q_nom, q_seed, constraints, options)

    qtraj = PiecewisePolynomial.Pchip(ts + start_time,
                                      np.vstack(results.q_sol).T, True)

    print "IK returned a solution with info %d" % results.info[0]
    return qtraj, results.info[0], results.q_sol
    def solveIK(self, pose, target):
        """
        pose: np.array([latitude, longitude, depth])
        target: np.array([x, y, z, quat[4]]) of view target in "world" frame
        """

        # Duration of motion for solver
        dur = self.config["trajectory_duration"]

        constraints = list()

        # Constrain the gaze
        constraints.append(
            ik.WorldGazeTargetConstraint(
                self.robot,
                self.bodies[self.config["optical_frame"]],  # Body to constrain
                np.array([0.0, 0.0, 1.0]).reshape(3, 1),  # Gaze axis
                target[0:3, None],  # Gaze target (world frame)
                np.zeros([3, 1]),  # Gaze origin (body frame)
                self.config["cone_threshold"]  # Cone threshold
                # np.array([dur, dur]).reshape([2,1])       # Valid times
            ))

        # Constrain the position
        # NOTE: Due to weirdness with the Aruco tag, Y is up and -Z is front
        # So, longitude rotates around Y
        #     latitude rotates around -X
        #     depth is in positive Z
        # ... This is easier just doing trig by hand
        camera_pose = np.array([
            pose[2] * math.cos(pose[0]) * math.sin(pose[1]),  # X
            pose[2] * math.sin(pose[0]),  # Y
            pose[2] * math.cos(pose[0]) * math.cos(pose[1])  # Z
        ])

        print "Pose:       ", pose
        print "Camera:     ", camera_pose

        constraints.append(
            ik.RelativePositionConstraint(
                self.robot,
                np.zeros([3, 1]),  # Point relative to Body A (optical frame)
                camera_pose - self.
                config['pose_tol'],  # Lower bound relative to Body B (target)
                camera_pose + self.
                config['pose_tol'],  # Upper bound relative to Body B (target)
                self.bodies[self.config['optical_frame']],  # Body A
                self.bodies["world"],  # Body B
                target.reshape(7, 1)  # Transform from B to reference point
            ))

        # Avoid collisions
        # NOTE: How do we avoid colliding with the table?
        #       * Table needs to be in the RBT
        # constraints.append( ik.MinDistanceConstraint ( self.robot,
        #     self.config['collision_min_distance'],   # Minimum distance between bodies
        #     list(),                                  # Active bodies (empty set means all bodies)
        #     set()                                    # Active collision groups (not filter groups! Empty set means all)
        # ))

        # Seed with current configuration (eventually!)
        q_seed = self.robot.getZeroConfiguration()

        options = ik.IKoptions(self.robot)
        result = ik.InverseKin(self.robot, q_seed, q_seed, constraints,
                               options)

        if result.info[0] != 1:
            print "IK Failed! Result:", result.info
            return None

        print
        return result.q_sol[0]
    def computePoses(self):
        # Precompute poses
        head_poses = self.computeHeadPoses()
        plate_poses = self.computePlatePoses()
        print "Total head poses:", len(head_poses)
        print "Total plate poses:", len(plate_poses)
        print

        if self.config["save_ik"]:
            filename = self.config["ik_save_path"]
            print "IK save path: {}".format(filename)
            if os.path.isfile(filename):
                self.config["save_ik"] = False
                print "WARNING! IK save path already exists. IK saving disabled"
                print

        print "Performing IK..."
        # Solve all the IK
        all_poses = list()
        for i, head_pose in enumerate(head_poses):
            for plate_pose in plate_poses:
                # Generate constraints and solve IK
                constraints = list()

                # Constrain the head pose
                head_constraint = ik.PostureConstraint( self.robot )
                head_constraint.setJointLimits(
                    np.array([self.positions['ptu_pan'], self.positions['ptu_tilt']], dtype=np.int32).reshape(2, 1),
                    head_pose - self.config['head_pose_tol'],
                    head_pose + self.config['head_pose_tol']
                )
                constraints.append(head_constraint)

                # Set the calibration plate position
                constraints.append( ik.RelativePositionConstraint ( self.robot,
                    np.zeros([3,1]),                                                    # Point relative to Body A (calibration target)
                    plate_pose - self.config['arm_pos_tol'], # Lower bound relative to Body B (optical frame)
                    plate_pose + self.config['arm_pos_tol'], # Upper bound relative to Body B (optical frame)
                    self.bodies['calibration_target'],                            # Body A
                    self.bodies[self.config['optical_frame']],                    # Body B
                    np.concatenate([                                                    # Transform from B to reference point
                        np.zeros(3),                                                    #   Translation (identity)
                        np.array([1, 0, 0, 0])                                          #   Rotation (identity)
                    ]).reshape(7, 1)
                ))

                # Set the calibration plate orientation
                constraints.append( ik.RelativeGazeDirConstraint ( self.robot,
                    self.bodies['calibration_target'],                   # Body A
                    self.bodies[self.config['optical_frame']],           # Body B
                    np.array([0, 0,  1], dtype=np.float64).reshape(3,1), # Body A axis
                    np.array([0, 0, -1], dtype=np.float64).reshape(3,1), # Body B axis
                    self.config['gaze_dir_tol']                          # Cone tolerance in radians
                ))

                # Avoid self-collision
                constraints.append( ik.MinDistanceConstraint ( self.robot,
                    self.config['collision_min_distance'],   # Minimum distance between bodies
                    list(),                                  # Active bodies (empty set means all bodies)
                    set()                                    # Active collision groups (not filter groups! Empty set means all)
                ))

                # Actually solve the IK!
                # Since we're solving ahead of time, just use the zero as seed
                # NOTE: Could possibly track last solution as seed...
                q_seed = self.robot.getZeroConfiguration()
                options = ik.IKoptions(self.robot)
                result = ik.InverseKin(self.robot, q_seed, q_seed, constraints, options)

                if result.info[0] != 1:
                    pass
                else:
                    # Tuple: head_pose, arm_pose
                    all_poses.append((result.q_sol[0][0:2],result.q_sol[0][2:]))
                    if self.config["save_ik"]:
                        with open(self.config["ik_save_path"],'a') as fp:
                            np.savetxt(fp, result.q_sol[0][None, :], delimiter=',')

            # Show status info after every head pose
            attempted = (i+1) * len(plate_poses)
            success = len(all_poses)
            total = len(head_poses)*len(plate_poses)
            completion = attempted*100 / total
            print "[{:>3d}%] {}/{} solutions found".format(completion, success, attempted)

        return all_poses
Example #18
0
def testIkPlan():

    ikPlanner = robotSystem.ikPlanner

    constraints = buildConstraints()
    poses = ce.getPlanPoses(constraints, ikPlanner)

    global robot

    robot = loadRigidBodyTree(getIkUrdfFilename())


    tspan = np.array([1.0, 1.0])

    handLinkNames = [ikPlanner.getHandLink('left'), ikPlanner.getHandLink('right')]
    footLinkNames = [robotSystem.directorConfig['leftFootLink'], robotSystem.directorConfig['rightFootLink']]

    leftHandBodyId = robot.FindBody(str(handLinkNames[0])).get_body_index()
    rightHandBodyId = robot.FindBody(str(handLinkNames[1])).get_body_index()
    leftFootBodyId = robot.FindBody(str(footLinkNames[0])).get_body_index()
    rightFootBodyId = robot.FindBody(str(footLinkNames[1])).get_body_index()

    lfootContactPts, rfootContactPts = getFootContactPoints()
    #lfootContactPts, rfootContactPts = = robotSystem.footstepsDriver.getContactPts()


    for i in xrange(robot.get_num_bodies()):
        body = robot.get_body(i)
        print i, body.get_name()
        assert robot.FindBodyIndex(body.get_name()) == i

    q = np.zeros(robot.get_num_positions())
    v = np.zeros(robot.get_num_velocities())
    kinsol = robot.doKinematics(q,v)

    t = robot.relativeTransform(kinsol, robot.FindBodyIndex('world'), robot.FindBodyIndex(str(footLinkNames[0])))
    tt = transformUtils.getTransformFromNumpy(t)

    pos = transformUtils.transformations.translation_from_matrix(t)
    quat = transformUtils.transformations.quaternion_from_matrix(t)



    footConstraints = []

    for linkName in footLinkNames:
        t = robotSystem.robotStateModel.getLinkFrame(linkName)
        pos, quat = transformUtils.poseFromTransform(t)

        if False and linkName == footLinkNames[0]:
            pc = pydrakeik.WorldPositionConstraint(robot, robot.findLink(str(linkName)).get_body_index(), np.zeros((3,)), pos + [-10,-10,0], pos+[10,10,0], tspan)
        else:
            pc = pydrakeik.WorldPositionConstraint(robot, robot.findLink(str(linkName)).get_body_index(), np.zeros((3,)), pos, pos, tspan)

        qc = pydrakeik.WorldQuatConstraint(robot, robot.findLink(str(linkName)).get_body_index(), quat, 0.01, tspan)
        footConstraints.append(pc)
        footConstraints.append(qc)


    qsc = pydrakeik.QuasiStaticConstraint(robot, tspan)
    qsc.setActive(True)
    qsc.setShrinkFactor(1.0)
    qsc.addContact([leftFootBodyId], lfootContactPts.transpose())
    qsc.addContact([rightFootBodyId], rfootContactPts.transpose())


    #q_seed = robot.getZeroConfiguration()
    #q_seed = robotSystem.robotStateJointController.getPose('q_nom').copy()

    # todo, joint costs, and other options
    global options
    options = pydrakeik.IKoptions(robot)


    jointIndexMap = np.zeros(robotSystem.robotStateJointController.numberOfJoints)
    drakePositionNames = [robot.get_position_name(i) for i in xrange(robot.get_num_positions())]
    for i, name in enumerate(robotSystem.robotStateJointController.jointNames):
        jointIndexMap[i] = drakePositionNames.index(name)

    jointIndexMap = list(jointIndexMap)
    print jointIndexMap

    q_seed = np.zeros(robot.get_num_positions())
    q_seed[jointIndexMap] = robotSystem.robotStateJointController.getPose('q_nom').copy()

    # setup costs

    costs = np.ones(robot.get_num_positions())


    groupCosts = [
      ('Left Leg', 1e3),
      ('Right Leg', 1e3),
      ('Left Arm', 1),
      ('Right Arm', 1),
      ('Back', 1e4),
      ('Neck', 1e6),
      ]

    for groupName, costValue in groupCosts:
        names = robotSystem.ikPlanner.getJointGroup(groupName)
        inds = [drakePositionNames.index(name) for name in names]
        print costValue, names
        costs[inds] = costValue

    costs[drakePositionNames.index('base_x')] = 0
    costs[drakePositionNames.index('base_y')] = 0
    costs[drakePositionNames.index('base_z')] = 0
    costs[drakePositionNames.index('base_roll')] = 1e3
    costs[drakePositionNames.index('base_pitch')] = 1e3
    costs[drakePositionNames.index('base_yaw')] = 0


    print costs
    options.setQ(np.diag(costs))


    def solveAndDraw(constraints):

        #print q_seed.shape

        global results
        global constraintList
        constraintList = constraints
        results = pydrakeik.InverseKin(robot, q_seed, q_seed, constraints, options)
        pose = results.q_sol[0]

        #print results.info[0]

        pose = pose[jointIndexMap]

        robotSystem.robotStateJointController.setPose('pose_end', pose)


    def onFrameModified(obj):

        pos, quat = transformUtils.poseFromTransform(obj.transform)

        pc = pydrakeik.WorldPositionConstraint(robot, leftHandBodyId,
                                              np.zeros((3,)),
                                              pos,
                                              pos, tspan)

        qc = pydrakeik.WorldQuatConstraint(robot, leftHandBodyId,
                          quat, 0.01, tspan)

        solveAndDraw([qsc, pc, qc] + footConstraints)

        #solveAndDraw([pc])


    frameObj = vis.updateFrame(robotSystem.robotStateModel.getLinkFrame(ikPlanner.getHandLink('left')), 'left hand frame')
    frameObj.setProperty('Edit', True)
    frameObj.setProperty('Scale', 0.2)
    frameObj.connectFrameModified(onFrameModified)
Example #19
0
def testIkPlan():

    ikPlanner = robotSystem.ikPlanner
    ikPlanner.pushToMatlab = False

    constraints = buildConstraints()
    poses = ce.getPlanPoses(constraints, ikPlanner)

    robot = loadRigidBodyTree(getIkUrdfFilename())

    #for i, body in enumerate(robot.bodies):
    #    print i, body.linkname

    tspan = np.array([1.0, 1.0])

    handLinkNames = [
        ikPlanner.getHandLink('left'),
        ikPlanner.getHandLink('right')
    ]
    footLinkNames = [
        robotSystem.directorConfig['leftFootLink'],
        robotSystem.directorConfig['rightFootLink']
    ]

    leftHandBodyId = robot.findLink(str(handLinkNames[0])).body_index
    rightHandBodyId = robot.findLink(str(handLinkNames[1])).body_index
    leftFootBodyId = robot.findLink(str(footLinkNames[0])).body_index
    rightFootBodyId = robot.findLink(str(footLinkNames[1])).body_index

    lfootContactPts, rfootContactPts = robotSystem.footstepsDriver.getContactPts(
    )

    footConstraints = []

    for linkName in footLinkNames:
        t = robotSystem.robotStateModel.getLinkFrame(linkName)
        pos, quat = transformUtils.poseFromTransform(t)

        pc = ik.WorldPositionConstraint(
            robot,
            robot.findLink(str(linkName)).body_index, np.zeros((3, )), pos,
            pos, tspan)
        qc = ik.WorldQuatConstraint(robot,
                                    robot.findLink(str(linkName)).body_index,
                                    quat, 0.0, tspan)
        footConstraints.append(pc)
        footConstraints.append(qc)

    qsc = ik.QuasiStaticConstraint(robot, tspan)
    qsc.setActive(True)
    qsc.setShrinkFactor(0.5)
    qsc.addContact([leftFootBodyId], lfootContactPts.transpose())
    qsc.addContact([rightFootBodyId], rfootContactPts.transpose())

    #q_seed = robot.getZeroConfiguration()
    q_seed = robotSystem.robotStateJointController.getPose('q_nom').copy()

    # todo, joint costs, and other options
    options = ik.IKoptions(robot)

    def solveAndDraw(constraints):

        results = ik.inverseKinSimple(robot, q_seed, q_seed, constraints,
                                      options)
        pose = results.q_sol
        robotSystem.robotStateJointController.setPose('pose_end', pose)

    def onFrameModified(obj):

        pos, quat = transformUtils.poseFromTransform(obj.transform)

        pc = ik.WorldPositionConstraint(robot, leftHandBodyId, np.zeros((3, )),
                                        pos, pos, tspan)

        qc = ik.WorldQuatConstraint(robot, leftHandBodyId, quat, 0.0, tspan)

        solveAndDraw([qsc, pc, qc] + footConstraints)

    frameObj = vis.updateFrame(
        robotSystem.robotStateModel.getLinkFrame(
            ikPlanner.getHandLink('left')), 'left hand frame')
    frameObj.setProperty('Edit', True)
    frameObj.setProperty('Scale', 0.2)
    frameObj.connectFrameModified(onFrameModified)