示例#1
0
 def test_baxter_ik(self):
     env = ParamSetup.setup_env()
     baxter = ParamSetup.setup_baxter()
     can = ParamSetup.setup_green_can(geom=(0.02, 0.25))
     baxter_body = OpenRAVEBody(env, baxter.name, baxter.geom)
     can_body = OpenRAVEBody(env, can.name, can.geom)
     baxter_body.set_transparency(0.5)
     can_body.set_transparency(0.5)
     manip = baxter_body.env_body.GetManipulator('right_arm')
     robot = baxter_body.env_body
     can = can_body.env_body
     dof = robot.GetActiveDOFValues()
     #Open the Gripper so there won't be collisions between gripper and can
     dof[9], dof[-1] = 0.02, 0.02
     robot.SetActiveDOFValues(dof)
     iktype = IkParameterizationType.Transform6D
     thetas = np.linspace(0, np.pi * 2, 10)
     target_trans = OpenRAVEBody.transform_from_obj_pose([0.9, -0.23, 0.93],
                                                         [0, 0, 0])
     can_body.env_body.SetTransform(target_trans)
     target_trans[:3, :3] = target_trans[:3, :3].dot(
         matrixFromAxisAngle([0, np.pi / 2, 0])[:3, :3])
     can_trans = target_trans
     body_trans = np.eye(4)
     """
     To check whether baxter ik model works, uncomment the following
     """
     # env.SetViewer('qtcoin')
     for theta in thetas:
         can_trans[:3, :3] = target_trans[:3, :3].dot(
             matrixFromAxisAngle([theta, 0, 0])[:3, :3])
         solution = manip.FindIKSolutions(
             IkParameterization(can_trans, iktype),
             IkFilterOptions.CheckEnvCollisions)
         if len(solution) > 0:
             print "Solution found with pose and rotation:"
             print OpenRAVEBody.obj_pose_from_transform(can_trans)
         else:
             print "Solution not found with pose and rotation:"
             print OpenRAVEBody.obj_pose_from_transform(can_trans)
         for sols in solution:
             dof[10:17] = sols
             robot.SetActiveDOFValues(dof)
             time.sleep(.2)
             body_trans[:3, :3] = can_trans[:3, :3].dot(
                 matrixFromAxisAngle([0, -np.pi / 2, 0])[:3, :3])
             can_body.env_body.SetTransform(body_trans)
             self.assertTrue(
                 np.allclose([0.9, -0.23, 0.93],
                             manip.GetTransform()[:3, 3]))
    def test_ik_arm_pose(self):
        env = Environment()
        attrs = {"name": ["pr2"], "pose": [(0, 0, 0)], "_type": ["Robot"], "geom": [], "backHeight": [0.2], "lGripper": [0.5], "rGripper": [0.5]}
        attrs["lArmPose"] = [(0,0,0,0,0,0,0)]
        attrs["rArmPose"] = [(0,0,0,0,0,0,0)]
        attr_types = {"name": str, "pose": matrix.Vector3d, "_type": str, "geom": PR2, "backHeight": matrix.Value, "lArmPose": matrix.Vector7d, "rArmPose": matrix.Vector7d, "lGripper": matrix.Value, "rGripper": matrix.Value}
        robot = parameter.Object(attrs, attr_types)
        # Set the initial arm pose so that pose is not close to joint limit
        robot.lArmPose = np.array([[np.pi/4, np.pi/8, np.pi/2, -np.pi/2, np.pi/8, -np.pi/8, np.pi/2]]).T
        robot.rArmPose = np.array([[-np.pi/4, np.pi/8, -np.pi/2, -np.pi/2, -np.pi/8, -np.pi/8, np.pi/2]]).T

        attrs = {"name": ["can"], "geom": (0.04, 0.25), "pose": ["undefined"], "rotation": [(0, 0, 0)], "_type": ["Can"]}
        attr_types = {"name": str, "geom": BlueCan, "pose": matrix.Vector3d, "rotation": matrix.Vector3d, "_type": str}
        can = parameter.Object(attrs, attr_types)
        can.pose = np.array([[5.77887566e-01,  -1.26743678e-01,   8.37601627e-01]]).T
        can.rotation = np.array([[np.pi/4, np.pi/4, np.pi/4]]).T
        # Create openRAVEBody for each parameter
        can_body = OpenRAVEBody(env, can.name, can.geom)
        robot_body = OpenRAVEBody(env, robot.name, robot.geom)
        # Set the poses and dof values for each body
        can_body.set_pose(can.pose, can.rotation)
        robot_body.set_pose(robot.pose)
        robot_body.set_dof(robot.backHeight, robot.lArmPose, robot.lGripper, robot.rArmPose, robot.rGripper)
        # Solve the IK solution
        ik_arm = robot_body.ik_arm_pose(can.pose, can.rotation)[0]
        robot_body.set_dof(ik_arm[:1], robot.lArmPose, robot.lGripper, ik_arm[1:], robot.rGripper)
        robot_trans = robot_body.env_body.GetLink("r_gripper_tool_frame").GetTransform()
        robot_pos = OpenRAVEBody.obj_pose_from_transform(robot_trans)
        # resulted robot eepose should be exactly the same as that can pose
        self.assertTrue(np.allclose(can.pose.flatten(), robot_pos[:3], atol = 1e-4))
        self.assertTrue(np.allclose(can.rotation.flatten(), robot_pos[3:], atol = 1e-4))
        """
示例#3
0
 def get_robot_info(self, robot_body):
     # Provide functionality of Obtaining Robot information
     tool_link = robot_body.env_body.GetLink("right_gripper")
     manip_trans = tool_link.GetTransform()
     # This manip_trans is off by 90 degree
     pose = OpenRAVEBody.obj_pose_from_transform(manip_trans)
     robot_trans = OpenRAVEBody.get_ik_transform(pose[:3], pose[3:])
     arm_inds = list(range(10, 17))
     return robot_trans, arm_inds
示例#4
0
def get_col_free_armPose_ik(pred, negated, t, plan):
    ee_pose = OpenRAVEBody.obj_pose_from_transform(
        body.env_body.GetManipulator('right_arm').GetTransform())
    pos, rot = ee_pose[:3], ee_pose[3:]
    while arm_pose is None and iteration < const.MAX_ITERATION_STEP:
        # for i in range(const.NUM_RESAMPLES):
        pos_bias = np.random.random_sample(
            (3, )) * const.BIAS_RADIUS * 2 - const.BIAS_RADIUS
        rot_bias = np.random.random_sample(
            (3, )) * const.ROT_BIAS * 2 - const.ROT_BIAS
        # print pos_bias, rot_bias, iteration
        print pos_bias, rot_bias
        iteration += 1
        arm_pose = get_ik_from_pose(pos + pos_bias, rot + rot_bias,
                                    body.env_body, 'right_arm')
        if arm_pose is not None:
            print iteration
            body.set_dof({'rArmPose': arm_pose})
示例#5
0
    def sample_ee_from_target(self, target):
        """
            Sample all possible EE Pose that pr2 can grasp with

            target: parameter of type Target
            return: list of tuple in the format of (ee_pos, ee_rot)
        """
        possible_ee_poses = []
        targ_pos, targ_rot = target.value.flatten(), target.rotation.flatten()
        ee_pos = targ_pos.copy()
        target_trans = OpenRAVEBody.transform_from_obj_pose(targ_pos, targ_rot)
        # rotate can's local z-axis by the amount of linear spacing between 0 to 2pi
        angle_range = np.linspace(0, np.pi * 2, num=SAMPLE_SIZE)
        for rot in angle_range:
            target_trans = OpenRAVEBody.transform_from_obj_pose(targ_pos, targ_rot)
            # rotate new ee_pose around can's rotation axis
            rot_mat = matrixFromAxisAngle([0, 0, rot])
            ee_trans = target_trans.dot(rot_mat)
            ee_rot = OpenRAVEBody.obj_pose_from_transform(ee_trans)[3:]
            possible_ee_poses.append((ee_pos, ee_rot))
        return possible_ee_poses
示例#6
0
def get_ee_from_target(targ_pos, targ_rot):
    """
        Sample all possible EE Pose that pr2 can grasp with

        target_pos: position of target we want to sample ee_pose form
        target_rot: rotation of target we want to sample ee_pose form
        return: list of ee_pose tuple in the format of (ee_pos, ee_rot) around target axis
    """
    possible_ee_poses = []
    ee_pos = targ_pos.copy()
    target_trans = OpenRAVEBody.transform_from_obj_pose(targ_pos, targ_rot)
    # rotate can's local z-axis by the amount of linear spacing between 0 to 2pi
    angle_range = np.linspace(0, PI * 2, num=const.EE_ANGLE_SAMPLE_SIZE)
    for rot in angle_range:
        target_trans = OpenRAVEBody.transform_from_obj_pose(targ_pos, targ_rot)
        # rotate new ee_pose around can's rotation axis
        rot_mat = matrixFromAxisAngle([0, 0, rot])
        ee_trans = target_trans.dot(rot_mat)
        ee_rot = OpenRAVEBody.obj_pose_from_transform(ee_trans)[3:]
        possible_ee_poses.append((ee_pos, ee_rot))
    return possible_ee_poses
示例#7
0
def resample_rrt_planner(pred, netgated, t, plan):
    startp, endp = pred.startp, pred.endp
    robot = pred.robot
    body = pred._param_to_body[robot].env_body
    manip_trans = body.GetManipulator("right_arm").GetTransform()
    pose = OpenRAVEBody.obj_pose_from_transform(manip_trans)
    manip_trans = OpenRAVEBody.get_ik_transform(pose[:3], pose[3:])
    gripper_direction = manip_trans[:3, :3].dot(np.array([-1, 1, 0]))
    lift_direction = manip_trans[:3, :3].dot(np.array([0, 0, -1]))
    active_dof = body.GetManipulator("right_arm").GetArmIndices()
    attr_inds = OrderedDict()
    res = []
    pred_test = [not pred.test(k, negated) for k in range(20)]
    resample_ts = np.where(pred_test)[0]
    start, end = resample_ts[0] - 1, resample_ts[-1] + 1

    rave_body = pred._param_to_body[pred.robot]
    dof_value_map = {
        "lArmPose": pred.robot.lArmPose[:, start],
        "lGripper": 0.02,
        "rArmPose": pred.robot.rArmPose[:, start],
        "rGripper": 0.02
    }
    rave_body.set_dof(dof_value_map)
    rave_body.set_pose([0, 0, pred.robot.pose[:, start][0]])

    body = pred._param_to_body[pred.robot].env_body
    active_dof = body.GetManipulator('right_arm').GetArmIndices()
    r_arm = pred.robot.rArmPose
    traj = get_rrt_traj(plan.env, body, active_dof, r_arm[:, start],
                        r_arm[:, end])
    result = process_traj(traj, end - start)
    body.SetActiveDOFs(range(18))
    for time in range(start + 1, end):
        robot_attr_name_val_tuples = [('rArmPose', result[:,
                                                          time - start - 1])]
        add_to_attr_inds_and_res(time, attr_inds, res, pred.robot,
                                 robot_attr_name_val_tuples)
    return np.array(res), attr_inds
示例#8
0
    def sample_ee_from_target(self, target):
        """
            Sample all possible EE Pose that pr2 can grasp with

            target: parameter of type Target
            return: list of tuple in the format of (ee_pos, ee_rot)
        """
        possible_ee_poses = []
        targ_pos, targ_rot = target.value.flatten(), target.rotation.flatten()
        ee_pos = targ_pos.copy()
        target_trans = OpenRAVEBody.transform_from_obj_pose(targ_pos, targ_rot)
        # rotate can's local z-axis by the amount of linear spacing between 0 to 2pi
        angle_range = np.linspace(0, np.pi * 2, num=SAMPLE_SIZE)
        for rot in angle_range:
            target_trans = OpenRAVEBody.transform_from_obj_pose(
                targ_pos, targ_rot)
            # rotate new ee_pose around can's rotation axis
            rot_mat = matrixFromAxisAngle([0, 0, rot])
            ee_trans = target_trans.dot(rot_mat)
            ee_rot = OpenRAVEBody.obj_pose_from_transform(ee_trans)[3:]
            possible_ee_poses.append((ee_pos, ee_rot))
        return possible_ee_poses
示例#9
0
def resample_eereachable(pred, negated, t, plan):
    attr_inds, res = OrderedDict(), []
    robot, rave_body = pred.robot, pred._param_to_body[pred.robot]
    target_pos, target_rot = pred.ee_pose.value.flatten(
    ), pred.ee_pose.rotation.flatten()
    body = rave_body.env_body
    rave_body.set_pose([0, 0, robot.pose[0, t]])
    # Resample poses at grasping time
    grasp_arm_pose = get_ik_from_pose(target_pos, target_rot, body,
                                      'right_arm')
    add_to_attr_inds_and_res(t, attr_inds, res, robot,
                             [('rArmPose', grasp_arm_pose.copy())])

    plan.sampling_trace.append({
        'type': robot.get_type(),
        'data': {
            'rArmPose': grasp_arm_pose
        },
        'timestep': t,
        'pred': pred,
        'action': "grasp"
    })

    # Setting poses for environments to extract transform infos
    dof_value_map = {
        "lArmPose": robot.lArmPose[:, t].reshape((7, )),
        "lGripper": 0.02,
        "rArmPose": grasp_arm_pose,
        "rGripper": 0.02
    }
    rave_body.set_dof(dof_value_map)
    # Prepare grasping direction and lifting direction
    manip_trans = body.GetManipulator("right_arm").GetTransform()
    pose = OpenRAVEBody.obj_pose_from_transform(manip_trans)
    manip_trans = OpenRAVEBody.get_ik_transform(pose[:3], pose[3:])
    gripper_direction = manip_trans[:3, :3].dot(np.array([-1, 0, 0]))
    lift_direction = manip_trans[:3, :3].dot(np.array([0, 0, -1]))
    # Resample grasping and retreating traj
    for i in range(const.EEREACHABLE_STEPS):
        approach_pos = target_pos - gripper_direction / np.linalg.norm(
            gripper_direction) * const.APPROACH_DIST * (3 - i)
        # rave_body.set_pose([0,0,robot.pose[0, t-3+i]])
        approach_arm_pose = get_ik_from_pose(approach_pos, target_rot, body,
                                             'right_arm')
        # rave_body.set_dof({"rArmPose": approach_arm_pose})
        add_to_attr_inds_and_res(t - 3 + i, attr_inds, res, robot,
                                 [('rArmPose', approach_arm_pose)])

        retreat_pos = target_pos + lift_direction / np.linalg.norm(
            lift_direction) * const.RETREAT_DIST * (i + 1)
        # rave_body.set_pose([0,0,robot.pose[0, t+1+i]])
        retreat_arm_pose = get_ik_from_pose(retreat_pos, target_rot, body,
                                            'right_arm')
        add_to_attr_inds_and_res(t + 1 + i, attr_inds, res, robot,
                                 [('rArmPose', retreat_arm_pose)])

    robot._free_attrs['rArmPose'][:, t - const.EEREACHABLE_STEPS:t +
                                  const.EEREACHABLE_STEPS + 1] = 0
    robot._free_attrs['pose'][:, t - const.EEREACHABLE_STEPS:t +
                              const.EEREACHABLE_STEPS + 1] = 0
    return np.array(res), attr_inds
示例#10
0
def resample_eereachable_rrt(pred, negated, t, plan, inv=False):
    # Preparing the variables
    attr_inds, res = OrderedDict(), []
    robot, rave_body = pred.robot, pred.robot.openrave_body
    target_pos, target_rot = pred.ee_pose.value.flatten(
    ), pred.ee_pose.rotation.flatten()
    body = rave_body.env_body
    manip_name = "right_arm"
    active_dof = body.GetManipulator(manip_name).GetArmIndices()
    active_dof = np.hstack([[0], active_dof])
    # Make sure baxter is well positioned in the env
    rave_body.set_pose([0, 0, robot.pose[:, t]])
    rave_body.set_dof({
        'lArmPose': robot.lArmPose[:, t].flatten(),
        'rArmPose': robot.rArmPose[:, t].flatten(),
        "lGripper": np.array([0.02]),
        "rGripper": np.array([0.02])
    })
    for param in plan.params.values():
        if not param.is_symbol() and param != robot:
            param.openrave_body.set_pose(param.pose[:, t].flatten(),
                                         param.rotation[:, t].flatten())
    # Resample poses at grasping time
    grasp_arm_pose = get_ik_from_pose(target_pos, target_rot, body, manip_name)

    # When Ik infeasible
    if grasp_arm_pose is None:
        return None, None
    add_to_attr_inds_and_res(t, attr_inds, res, robot,
                             [('rArmPose', grasp_arm_pose.copy()),
                              ('pose', robot.pose[:, t])])
    # Store sampled pose
    plan.sampling_trace.append({
        'type': robot.get_type(),
        'data': {
            'rArmPose': grasp_arm_pose
        },
        'timestep': t,
        'pred': pred,
        'action': "grasp"
    })
    # Prepare grasping direction and lifting direction
    manip_trans = body.GetManipulator("right_arm").GetTransform()
    pose = OpenRAVEBody.obj_pose_from_transform(manip_trans)
    manip_trans = OpenRAVEBody.get_ik_transform(pose[:3], pose[3:])
    if inv:
        # inverse resample_eereachable used in putdown action
        approach_dir = manip_trans[:3, :3].dot(np.array([0, 0, -1]))
        retreat_dir = manip_trans[:3, :3].dot(np.array([-1, 0, 0]))
        approach_dir = approach_dir / np.linalg.norm(
            approach_dir) * const.APPROACH_DIST
        retreat_dir = -retreat_dir / np.linalg.norm(
            retreat_dir) * const.RETREAT_DIST
    else:
        # Normal resample eereachable used in grasp action
        approach_dir = manip_trans[:3, :3].dot(np.array([-1, 0, 0]))
        retreat_dir = manip_trans[:3, :3].dot(np.array([0, 0, -1]))
        approach_dir = -approach_dir / np.linalg.norm(
            approach_dir) * const.APPROACH_DIST
        retreat_dir = retreat_dir / np.linalg.norm(
            retreat_dir) * const.RETREAT_DIST

    resample_failure = False
    # Resample entire approaching and retreating traj
    for i in range(const.EEREACHABLE_STEPS):
        approach_pos = target_pos + approach_dir * (3 - i)
        approach_arm_pose = get_ik_from_pose(approach_pos, target_rot, body,
                                             'right_arm')
        retreat_pos = target_pos + retreat_dir * (i + 1)
        retreat_arm_pose = get_ik_from_pose(retreat_pos, target_rot, body,
                                            'right_arm')

        if approach_arm_pose is None or retreat_arm_pose is None:
            resample_failure = True
        add_to_attr_inds_and_res(t - 3 + i, attr_inds, res, robot,
                                 [('rArmPose', approach_arm_pose)])
        add_to_attr_inds_and_res(t + 1 + i, attr_inds, res, robot,
                                 [('rArmPose', retreat_arm_pose)])
    # Ik infeasible
    if resample_failure:
        plan.sampling_trace[-1]['reward'] = -1
        return None, None
    # lock the variables
    robot._free_attrs['rArmPose'][:, t - const.EEREACHABLE_STEPS:t +
                                  const.EEREACHABLE_STEPS + 1] = 0
    robot._free_attrs['pose'][:, t - const.EEREACHABLE_STEPS:t +
                              const.EEREACHABLE_STEPS + 1] = 0
    # finding initial pose
    init_timestep, ref_index = 0, 0
    for i in range(len(plan.actions)):
        act_range = plan.actions[i].active_timesteps
        if act_range[0] <= t <= act_range[1]:
            init_timestep = act_range[0]
            ref_index = i

    if pred.ee_resample is True and ref_index > 0:
        init_timestep = plan.actions[ref_index - 1].active_timesteps[0]

    init_dof = robot.rArmPose[:, init_timestep].flatten()
    init_dof = np.hstack([robot.pose[:, init_timestep], init_dof])
    end_dof = robot.rArmPose[:, t - const.EEREACHABLE_STEPS].flatten()
    end_dof = np.hstack([robot.pose[:, t - const.EEREACHABLE_STEPS], end_dof])
    timesteps = t - const.EEREACHABLE_STEPS - init_timestep + 2

    raw_traj = get_rrt_traj(plan.env, body, active_dof, init_dof, end_dof)
    # Restore dof0
    dof = body.GetActiveDOFValues()
    dof[0] = 0
    body.SetActiveDOFValues(dof)
    # trajectory is infeasible
    if raw_traj == None:
        plan.sampling_trace[-1]['reward'] = -1
        return None, None
    # initailize feasible trajectory
    result_traj = process_traj(raw_traj, timesteps).T[1:-1]
    ts = 1
    for traj in result_traj:
        add_to_attr_inds_and_res(init_timestep + ts, attr_inds, res, robot,
                                 [('rArmPose', traj[1:]), ('pose', traj[:1])])
        ts += 1

    pred.ee_resample = True
    can = plan.params['can0']
    can.openrave_body.set_pose(can.pose[:, t], can.rotation[:, t])
    rave_body.set_dof({'rArmPose': robot.rArmPose[:, t]})
    return np.array(res), attr_inds
示例#11
0
    def test_ik_arm_pose(self):
        env = Environment()
        attrs = {
            "name": ["pr2"],
            "pose": [(0, 0, 0)],
            "_type": ["Robot"],
            "geom": [],
            "backHeight": [0.2],
            "lGripper": [0.5],
            "rGripper": [0.5]
        }
        attrs["lArmPose"] = [(0, 0, 0, 0, 0, 0, 0)]
        attrs["rArmPose"] = [(0, 0, 0, 0, 0, 0, 0)]
        attr_types = {
            "name": str,
            "pose": matrix.Vector3d,
            "_type": str,
            "geom": PR2,
            "backHeight": matrix.Value,
            "lArmPose": matrix.Vector7d,
            "rArmPose": matrix.Vector7d,
            "lGripper": matrix.Value,
            "rGripper": matrix.Value
        }
        robot = parameter.Object(attrs, attr_types)
        # Set the initial arm pose so that pose is not close to joint limit
        robot.lArmPose = np.array([[
            np.pi / 4, np.pi / 8, np.pi / 2, -np.pi / 2, np.pi / 8, -np.pi / 8,
            np.pi / 2
        ]]).T
        robot.rArmPose = np.array([[
            -np.pi / 4, np.pi / 8, -np.pi / 2, -np.pi / 2, -np.pi / 8,
            -np.pi / 8, np.pi / 2
        ]]).T

        attrs = {
            "name": ["can"],
            "geom": (0.04, 0.25),
            "pose": ["undefined"],
            "rotation": [(0, 0, 0)],
            "_type": ["Can"]
        }
        attr_types = {
            "name": str,
            "geom": BlueCan,
            "pose": matrix.Vector3d,
            "rotation": matrix.Vector3d,
            "_type": str
        }
        can = parameter.Object(attrs, attr_types)
        can.pose = np.array([[5.77887566e-01, -1.26743678e-01,
                              8.37601627e-01]]).T
        can.rotation = np.array([[np.pi / 4, np.pi / 4, np.pi / 4]]).T
        # Create openRAVEBody for each parameter
        can_body = OpenRAVEBody(env, can.name, can.geom)
        robot_body = OpenRAVEBody(env, robot.name, robot.geom)
        # Set the poses and dof values for each body
        can_body.set_pose(can.pose, can.rotation)
        robot_body.set_pose(robot.pose)
        robot_body.set_dof(robot.backHeight, robot.lArmPose, robot.lGripper,
                           robot.rArmPose, robot.rGripper)
        # Solve the IK solution
        ik_arm = robot_body.ik_arm_pose(can.pose, can.rotation)[0]
        robot_body.set_dof(ik_arm[:1], robot.lArmPose, robot.lGripper,
                           ik_arm[1:], robot.rGripper)
        robot_trans = robot_body.env_body.GetLink(
            "r_gripper_tool_frame").GetTransform()
        robot_pos = OpenRAVEBody.obj_pose_from_transform(robot_trans)
        # resulted robot eepose should be exactly the same as that can pose
        self.assertTrue(
            np.allclose(can.pose.flatten(), robot_pos[:3], atol=1e-4))
        self.assertTrue(
            np.allclose(can.rotation.flatten(), robot_pos[3:], atol=1e-4))
        """