diff --git a/tests/test_mavlogdump.py b/tests/test_mavlogdump.py index fd7e9b15c..c32024cee 100755 --- a/tests/test_mavlogdump.py +++ b/tests/test_mavlogdump.py @@ -4,10 +4,11 @@ """ regression tests for mavlogdump.py """ -import unittest import os -import pkg_resources -import sys +import unittest +from pathlib import Path + +here = Path(__file__).parent class MAVLogDumpTest(unittest.TestCase): @@ -21,9 +22,7 @@ def __init__(self, *args, **kwargs): def test_dump_same(self): """Test dump of file is what we expect""" - test_filename = "test.BIN" - test_filepath = pkg_resources.resource_filename(__name__, - test_filename) + test_filepath = str(here / "test.BIN") dump_filename = "tmp.dump" os.system("mavlogdump.py %s >%s" % (test_filepath, dump_filename)) with open(dump_filename) as f: @@ -33,8 +32,7 @@ def test_dump_same(self): "test.BIN.dumped"] success = False for expected in possibles: - expected_filepath = pkg_resources.resource_filename(__name__, - expected) + expected_filepath = str(here / expected) with open(expected_filepath) as e: expected = e.read() diff --git a/tests/test_mavxml.py b/tests/test_mavxml.py index 7979eaeaa..36c0589a3 100755 --- a/tests/test_mavxml.py +++ b/tests/test_mavxml.py @@ -4,11 +4,13 @@ """ import unittest -import pkg_resources +from pathlib import Path from pymavlink.generator.mavparse import MAVXML from pymavlink.generator.mavparse import MAVParseError +here = Path(__file__).parent + class MAVXMLTest(unittest.TestCase): """ Class to test MAVXML @@ -16,16 +18,12 @@ class MAVXMLTest(unittest.TestCase): def test_fields_number(self): """Test that a message can have at most 64 fields""" - test_filename = "64-fields.xml" - test_filepath = pkg_resources.resource_filename(__name__, - test_filename) + test_filepath = str(here / "64-fields.xml") xml = MAVXML(test_filepath) count = len(xml.message[0].fields) self.assertEqual(count, 64) - test_filename = "65-fields.xml" - test_filepath = pkg_resources.resource_filename(__name__, - test_filename) + test_filepath = str(here / "65-fields.xml") with self.assertRaises(MAVParseError): _ = MAVXML(test_filepath) diff --git a/tests/test_trim.py b/tests/test_trim.py index f79450c80..17bb4d10b 100755 --- a/tests/test_trim.py +++ b/tests/test_trim.py @@ -6,9 +6,7 @@ """ import unittest -import os -import pkg_resources -import sys + from pymavlink import mavutil class PayLoadTrimZeros(unittest.TestCase): diff --git a/tests/test_wp.py b/tests/test_wp.py index d87d1a850..b6388bc01 100755 --- a/tests/test_wp.py +++ b/tests/test_wp.py @@ -4,16 +4,17 @@ regression tests for mavwp.py """ -import unittest import os -import pkg_resources -import sys +import unittest +from pathlib import Path os.environ["MAVLINK20"] = "1" from pymavlink import mavwp from pymavlink import mavutil +here = Path(__file__).parent + class MAVWPTest(unittest.TestCase): """ @@ -42,14 +43,9 @@ def makewp(self, seq): seq, # wp.z ) - def make_wps(self): - # create waypoints - count = 4 - waypoints = [] - for i in range(count): - waypoints.append(self.makewp(i)) - - return waypoints + def make_wps(self, count: int = 4): + # create count waypoints + return [self.makewp(i) for i in range(count)] def test_add_remove(self): """Test we can add/remove waypoints to/from mavwp""" @@ -60,9 +56,9 @@ def test_add_remove(self): waypoints = self.make_wps() # make sure basic addition works - for i in range(len(waypoints)): + for i, waypoint in enumerate(waypoints): self.assertEqual(loader.count(), i) - loader.add(waypoints[i]) + loader.add(waypoint) self.assertEqual(loader.count(), i+1) self.assertEqual(loader.wp(0).seq, 0) @@ -76,7 +72,6 @@ def test_add_remove(self): self.assertEqual(loader.item(1).z, 1) self.assertEqual(loader.item(2).z, 2) - # remove a middle one, make sure things get renumbered loader.remove(waypoints[0]) self.assertEqual(loader.wp(0).seq, 0) @@ -194,8 +189,6 @@ def test_wp_is_loiter(self): self.assertFalse(loader.wp_is_loiter(1)) self.assertFalse(loader.wp_is_loiter(2)) - assert True - def test_is_location_command(self): loader = mavwp.MAVWPLoader() self.assertFalse(loader.is_location_command(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH)) @@ -213,13 +206,13 @@ def test_rally_load(self): self.assertTrue(loader.is_location_command(mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT)) # test loading a QGC WPL 110 file: - rally_filepath = pkg_resources.resource_filename(__name__, "rally-110.txt") + rally_filepath = str(here / "rally-110.txt") loader.load(rally_filepath) self.assertEqual(loader.count(), 2) self.assertEqual(loader.wp(0).command, mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT) # test loading tradition "RALLY" style format: - rally_filepath = pkg_resources.resource_filename(__name__, "rally.txt") + rally_filepath = str(here / "rally.txt") loader.load(rally_filepath) self.assertEqual(loader.count(), 2) self.assertEqual(loader.wp(0).command, mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT) @@ -233,15 +226,13 @@ def test_fence_load(self): self.assertTrue(loader.is_location_command(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION)) # test loading a QGC WPL 110 file: - fence_filepath = pkg_resources.resource_filename(__name__, - "fence-110.txt") + fence_filepath = str(here / "fence-110.txt") loader.load(fence_filepath) self.assertEqual(loader.count(), 10) self.assertEqual(loader.wp(3).command, mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION) # test loading tradition lat/lng-pair style format: - fence_filepath = pkg_resources.resource_filename(__name__, - "fence.txt") + fence_filepath = str(here / "fence.txt") loader.load(fence_filepath) # there are 6 lines in the file - one return point, four fence # points and a "fence closing point". We don't store the