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))
    def test_det(self):

        a = np.array([[1, 2], [3, 4]])
        self.assertAlmostEqual(np.linalg.det(a), det(a))

        x, y = sym.symbol('x y')
        a = np.array([[x, y], [y, x]])
        self.assertEqual(det(a), x**2 - y**2)
    def test_norm(self):
        self.assertAlmostEqual(norm([0, 0, 0]), 0)
        self.assertAlmostEqual(normsq([1, 2, 3]), 14)
        self.assertAlmostEqual(normsq(np.r_[1, 2, 3]), 14)

        x, y = sym.symbol('x y')
        v = [x, y]
        self.assertEqual(normsq(v), x**2 + y**2)
        self.assertEqual(normsq(np.r_[v]), x**2 + y**2)
    def test_norm(self):
        self.assertAlmostEqual(norm([0, 0, 0]), 0)
        self.assertAlmostEqual(norm([1, 2, 3]), math.sqrt(14))
        self.assertAlmostEqual(norm(np.r_[1, 2, 3]), math.sqrt(14))

        x, y = sym.symbol('x y')
        v = [x, y]
        self.assertEqual(norm(v), sym.sqrt(x**2 + y**2))
        self.assertEqual(norm(np.r_[v]), sym.sqrt(x**2 + y**2))
        :return: gear ratio
        :rtype: float

        - ``link.G = ...`` checks and sets the gear ratio

        .. note::
            - The ratio of motor motion : link motion
            - The gear ratio can be negative, see also the ``flip`` attribute.

        :seealso: :func:`flip`
        """
        return self._G

    @G.setter
    @_listen_dyn
    def G(self, G_new):
        self._G = G_new

if __name__ == "__main__":  # pragma nocover

    import roboticstoolbox as rtb
    from spatialmath.base import sym

    ET = rtb.ETS

    d, a, theta = sym.symbol('d, a, theta')

    e = ET.tx(d) * ET.ty(a) * ET.rz(theta)
    print(e)
    link = rtb.ELink()