def test_rt2tr(self):
        # 3D
        R = rotx(0.2)
        t = [3, 4, 5]
        T = rt2tr(R, t)
        nt.assert_array_almost_equal(t2r(T), R)
        nt.assert_array_almost_equal(transl(T), np.array(t))

        theta = sym.symbol('theta')
        R = rotx(theta)
        self.assertEqual(r2t(R).dtype, 'O')

        # 2D
        R = rot2(0.2)
        t = [3, 4]
        T = rt2tr(R, t)
        nt.assert_array_almost_equal(t2r(T), R)
        nt.assert_array_almost_equal(transl2(T), np.array(t))

        theta = sym.symbol('theta')
        R = rot2(theta)
        self.assertEqual(r2t(R).dtype, 'O')

        with self.assertRaises(ValueError):
            rt2tr(3, 4)

        with self.assertRaises(ValueError):
            rt2tr(np.eye(3, 4), [1, 2, 3, 4])
    def test_r2t(self):
        # 3D
        R = rotx(0.3)
        T = r2t(R)
        nt.assert_array_almost_equal(T[0:3, 3], np.r_[0, 0, 0])
        nt.assert_array_almost_equal(T[:3, :3], R)

        theta = sym.symbol('theta')
        R = rotx(theta)
        T = r2t(R)
        self.assertEqual(r2t(R).dtype, 'O')
        nt.assert_array_almost_equal(T[0:3, 3], np.r_[0, 0, 0])
        # nt.assert_array_almost_equal(T[:3,:3], R)
        self.assertTrue((T[:3, :3] == R).all())

        # 2D
        R = rot2(0.3)
        T = r2t(R)
        nt.assert_array_almost_equal(T[0:2, 2], np.r_[0, 0])
        nt.assert_array_almost_equal(T[:2, :2], R)

        theta = sym.symbol('theta')
        R = rot2(theta)
        T = r2t(R)
        self.assertEqual(r2t(R).dtype, 'O')
        nt.assert_array_almost_equal(T[0:2, 2], np.r_[0, 0])
        nt.assert_array_almost_equal(T[:2, :2], R)

        with self.assertRaises(ValueError):
            r2t(3)

        with self.assertRaises(ValueError):
            r2t(np.eye(3, 4))