def create_path(start, stop, n_path, rx_samples=5, ry_samples=5, rz_samples=90):
    R_pt = rot_z(np.pi / 2) @ rot_x(3 * np.pi / 4)
    pos_tol = 3 * [NoTolerance()]
    rot_tol = [
        SymmetricTolerance(np.deg2rad(10), rx_samples),
        SymmetricTolerance(np.deg2rad(15), ry_samples),
        Tolerance(-np.pi, np.pi, rz_samples),
    ]

    start_pt = TolEulerPt(start, Quaternion(matrix=R_pt), pos_tol, rot_tol)
    return create_line(start_pt, stop, n_path)
Esempio n. 2
0
    def test_transform_to_rel_tolerance_deviation(self):
        tol = [SymmetricTolerance(0.1, 3), Tolerance(0.2, 1.0, 3), NoTolerance()]
        rot_tol = [NoTolerance(), NoTolerance(), SymmetricTolerance(0.1, 3)]
        quat = Quaternion(angle=np.pi / 2, axis=np.array([0, 0, 1]))
        pt = TolEulerPt([1, 2, 3], quat, tol, rot_tol)

        quat2 = Quaternion(angle=np.pi / 2 - 0.05, axis=np.array([0, 0, 1]))
        tf = quat2.transformation_matrix
        tf[:3, 3] = np.array([1.06, 1.91, 3])

        p_rel = pt.transform_to_rel_tolerance_deviation(tf)

        assert p_rel.shape == (6,)

        p_desired = np.array([-0.09, -0.06, 0.0, 0.0, 0.0, -0.05])

        assert_almost_equal(p_rel, p_desired)
Esempio n. 3
0
 def test_create_line(self):
     pos = [1, 2, 3]
     tol = [
         SymmetricTolerance(1, 10),
         SymmetricTolerance(1, 10),
         SymmetricTolerance(1, 10),
     ]
     start_pt = TolPositionPt(pos, Quaternion.random(), tol)
     path = create_line(start_pt, np.array([2, 2, 3]), 3)
     assert path[-1].pos[0] == 2
     assert_almost_equal(path[1].pos[0], 1.5)
     assert path[-1].pos[1] == pos[1]
     assert path[-1].pos[1] == pos[1]
     assert path[-1].pos[2] == pos[2]
     assert path[-1].pos[2] == pos[2]
     assert path[-1].pos[0] == pos[0] + 1
     assert path[-1].pos[0] == pos[0] + 1
def test_state_cost():
    robot = Kuka()

    table = Box(0.5, 0.5, 0.1)
    table_tf = np.array(
        [[1, 0, 0, 0.80], [0, 1, 0, 0.00], [0, 0, 1, 0.00], [0, 0, 0, 1]]
    )
    scene1 = Scene([table], [table_tf])

    # create path
    quat = Quaternion(axis=np.array([1, 0, 0]), angle=-3 * np.pi / 4)

    pos_tol = 3 * [NoTolerance()]
    # rot_tol = 3 * [NoTolerance()]
    rot_tol = [
        NoTolerance(),
        SymmetricTolerance(np.pi / 4, 20),
        SymmetricTolerance(np.pi, 20),
    ]
    first_point = TolEulerPt(np.array([0.9, -0.1, 0.2]), quat, pos_tol, rot_tol)
    # end_position = np.array([0.9, 0.1, 0.2])

    # path = create_line(first_point, end_position, 5)
    path = create_arc(
        first_point, np.array([0.9, 0.0, 0.2]), np.array([0, 0, 1]), 2 * np.pi, 5
    )

    planner_settings = SamplingSetting(
        SearchStrategy.GRID,
        iterations=1,
        tolerance_reduction_factor=2,
        use_state_cost=True,
        state_cost_weight=10.0,
    )

    solver_settings = SolverSettings(
        SolveMethod.sampling_based,
        CostFuntionType.sum_squared,
        sampling_settings=planner_settings,
    )

    setup = PlanningSetup(robot, path, scene1)

    sol = solve(setup, solver_settings)
    assert sol.success
Esempio n. 5
0
    def test_grid(self):
        pos = [1, 2, 3]
        pos_tol = [NoTolerance()] * 3
        rot_tol = [NoTolerance(), NoTolerance(), SymmetricTolerance(np.pi, 3)]
        pt = TolEulerPt(pos, Quaternion(), pos_tol, rot_tol)

        tf_samples = pt.sample_grid()
        assert_almost_equal(tf_samples[0], tf_samples[2])
        assert_almost_equal(tf_samples[1][:3, :3], np.eye(3))
Esempio n. 6
0
    def test_transform_to_rel_tolerance_deviation(self):
        tol = [SymmetricTolerance(0.1, 3), Tolerance(0.2, 1.0, 3), NoTolerance()]
        quat = Quaternion(angle=np.pi / 2, axis=np.array([0, 0, 1]))
        pt = TolPositionPt([1, 2, 3], quat, tol)

        tf = quat.transformation_matrix
        tf[:3, 3] = np.array([1.06, 1.91, 3])

        p_rel = pt.transform_to_rel_tolerance_deviation(tf)
        p_desired = np.array([-0.09, -0.06, 0.0])

        assert_almost_equal(p_rel, p_desired)
Esempio n. 7
0
    def test_sample_grid_2(self):
        """
        Rotate with pi / 2 around z, give a tolerance along x, 
        expect a grid sampled along y
        """
        tol = [SymmetricTolerance(0.1, 3), NoTolerance(), NoTolerance()]
        pt = TolPositionPt(
            [1, 2, 3], Quaternion(angle=np.pi / 2, axis=np.array([0, 0, 1])), tol
        )

        tf_samples = pt.sample_grid()
        g = [tf[:3, 3] for tf in tf_samples]
        g_desired = np.array([[1, 1.9, 3], [1, 2, 3], [1, 2.1, 3]])
        assert_almost_equal(g, g_desired)
Esempio n. 8
0
    def test_incremental(self):
        pos = [1, 2, 3]
        pos_tol = [NoTolerance()] * 3
        rot_tol = [NoTolerance(), NoTolerance(), SymmetricTolerance(np.pi, 3)]
        pt = TolEulerPt(pos, Quaternion(), pos_tol, rot_tol)

        tf_samples = pt.sample_incremental(10, SampleMethod.random_uniform)

        euler = [rotation_matrix_to_rpy(tf[:3, :3]) for tf in tf_samples]

        for i in range(10):
            assert_almost_equal(euler[i][0], 0)
            assert_almost_equal(euler[i][1], 0)
            assert_in_range(euler[i][2], -np.pi, np.pi)
Esempio n. 9
0
    def test_sample_incremental_2(self):
        tol = [SymmetricTolerance(0.1, 3), Tolerance(0.2, 1.0, 3), NoTolerance()]
        pt = TolPositionPt(
            [1, 2, 3], Quaternion(angle=np.pi / 2, axis=np.array([0, 0, 1])), tol
        )

        g = pt.sample_incremental(10, SampleMethod.random_uniform)

        pos_samples = [tf[:3, 3] for tf in g]
        for sample in pos_samples:
            assert_almost_equal(sample[2], 3)

            assert_in_range(sample[0], 0, 3)  # 1 + (-1, 2)
            assert_in_range(sample[1], 1.9, 2.1)  # 2 + (-0.1, 0.1)
Esempio n. 10
0
    def test_create_arc(self):
        pos = [1, 0, 3]
        pos_tol = [NoTolerance(), NoTolerance(), NoTolerance()]
        rot_tol = [
            SymmetricTolerance(0.5, 10),
            SymmetricTolerance(0.5, 10),
            SymmetricTolerance(0.5, 10),
        ]
        start_pt = TolEulerPt(pos, Quaternion(), pos_tol, rot_tol)
        path = create_arc(start_pt, np.zeros(3), np.array([0, 0, 1]), np.pi / 2, 3)
        assert len(path) == 3
        p1, p2, p3 = path[0], path[1], path[2]

        assert_almost_equal(p1.pos[0], 1)
        assert_almost_equal(p1.pos[1], 0)
        assert_almost_equal(p1.pos[2], 3)

        assert_almost_equal(p2.pos[0], np.sqrt(2) / 2)
        assert_almost_equal(p2.pos[1], np.sqrt(2) / 2)
        assert_almost_equal(p2.pos[2], 3)

        assert_almost_equal(p3.pos[0], 0)
        assert_almost_equal(p3.pos[1], 1)
        assert_almost_equal(p3.pos[2], 3)
Esempio n. 11
0
def test_to_joint_solutions():
    for search_strategy in SearchStrategy:
        tol = [SymmetricTolerance(0.1, 3), NoTolerance(), NoTolerance()]
        pt = TolPositionPt(
            [1, 2, 3], Quaternion(angle=np.pi / 2, axis=np.array([0, 0, 1])), tol
        )
        robot = DummyRobot(is_colliding=True)
        settings = setting_generator(search_strategy)
        if search_strategy is not SearchStrategy.MIN_INCREMENTAL:
            joint_solutions = pt.to_joint_solutions(robot, settings)
            assert len(joint_solutions) == 0
        else:
            with pytest.raises(Exception) as info:
                joint_solutions = pt.to_joint_solutions(robot, settings)
            msg = "Maximum iterations reached in to_joint_solutions."
            assert msg in str(info.value)
Esempio n. 12
0
    def test_sample_incremental_1(self):
        """
        Rotate with pi / 2 around z, give a tolerance along x, 
        expect a grid sampled along y
        """
        tol = [SymmetricTolerance(0.1, 3), NoTolerance(), NoTolerance()]
        pt = TolPositionPt(
            [1, 2, 3], Quaternion(angle=np.pi / 2, axis=np.array([0, 0, 1])), tol
        )

        g = pt.sample_incremental(10, SampleMethod.random_uniform)
        pos_samples = [tf[:3, 3] for tf in g]

        for sample in pos_samples:
            assert_almost_equal(sample[0], 1)
            assert_almost_equal(sample[2], 3)

            assert_in_range(sample[1], 1.9, 2.1)
def test_tol_position_pt_planning_problem():
    robot = Kuka()

    table = Box(0.5, 0.5, 0.1)
    table_tf = np.array(
        [[1, 0, 0, 0.80], [0, 1, 0, 0.00], [0, 0, 1, 0.12], [0, 0, 0, 1]]
    )
    scene1 = Scene([table], [table_tf])

    # create path
    quat = Quaternion(axis=np.array([1, 0, 0]), angle=np.pi)
    tolerance = [NoTolerance(), SymmetricTolerance(0.05, 10), NoTolerance()]
    first_point = TolPositionPt(np.array([0.9, -0.2, 0.2]), quat, tolerance)
    # end_position = np.array([0.9, 0.2, 0.2])

    # path = create_line(first_point, end_position, 5)
    path = create_arc(
        first_point, np.array([0.9, 0.0, 0.2]), np.array([0, 0, 1]), 2 * np.pi, 5
    )

    planner_settings = SamplingSetting(SearchStrategy.GRID, iterations=1)

    solver_settings = SolverSettings(
        SolveMethod.sampling_based,
        CostFuntionType.sum_squared,
        sampling_settings=planner_settings,
    )

    setup = PlanningSetup(robot, path, scene1)

    sol = solve(setup, solver_settings)
    assert sol.success

    for qi, pt in zip(sol.joint_positions, path):
        fk = robot.fk(qi)
        pos_fk = fk[:3, 3]
        pos_pt = pt.pos
        R_pt = pt.rotation_matrix
        pos_error = R_pt.T @ (pos_fk - pos_pt)
        assert_almost_equal(pos_error[0], 0)
        assert_almost_equal(pos_error[2], 0)
        assert pos_error[1] <= (0.05 + 1e-6)
        assert pos_error[1] >= -(0.05 + 1e-6)
Esempio n. 14
0
# Position samples
# ==================================================================================
R_pt = rot_z(np.deg2rad(30))
pos_pt = np.array([0.5, 0.5, 0.0])

pos_tol = [Tolerance(-0.1, 0.1, 3), Tolerance(-0.3, 0.3, 5), NoTolerance()]

pt_pos = TolPositionPt(pos_pt, Quaternion(matrix=R_pt), pos_tol)

# ==================================================================================
# Euler constraints samples
# ==================================================================================
R_pt = np.eye(3)
pos_tol = 3 * [NoTolerance()]
rot_tol = [
    SymmetricTolerance(np.deg2rad(15), 5),
    NoTolerance(),
    Tolerance(0, np.pi / 2, 10),
]

pt_eul = TolEulerPt(np.zeros(3), Quaternion(matrix=R_pt), pos_tol, rot_tol)

# ==================================================================================
# Quaternion constraints samples
# ==================================================================================
R_pt = np.eye(4)
pos_tol = 3 * [NoTolerance()]
quat_tol = QuaternionTolerance(0.1)

pt_quat = TolQuatPt(np.zeros(3), Quaternion(matrix=R_pt), pos_tol, quat_tol)