Skip to content

Commit

Permalink
tests: add tests for new rally/fence loader classes
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Jun 4, 2022
1 parent c7a785f commit 92e23c8
Showing 1 changed file with 60 additions and 0 deletions.
60 changes: 60 additions & 0 deletions tests/test_wp.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,9 @@
import os
import pkg_resources
import sys

os.environ["MAVLINK20"] = "1"

from pymavlink import mavwp
from pymavlink import mavutil

Expand Down Expand Up @@ -52,6 +55,8 @@ def make_wps(self):
def test_add_remove(self):
"""Test we can add/remove waypoints to/from mavwp"""
loader = mavwp.MAVWPLoader()
self.assertEqual(loader.mav_mission_type(),
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)

waypoints = self.make_wps()

Expand All @@ -67,6 +72,11 @@ def test_add_remove(self):
self.assertEqual(loader.wp(0).z, 0)
self.assertEqual(loader.wp(1).z, 1)
self.assertEqual(loader.wp(2).z, 2)
# short test for the new item() method:
self.assertEqual(loader.item(0).z, 0)
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])
Expand Down Expand Up @@ -185,11 +195,61 @@ 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))
self.assertTrue(loader.is_location_command(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT))
self.assertTrue(loader.is_location_command(mavutil.mavlink.MAV_CMD_NAV_LOITER_TURNS))

class RallyTest(unittest.TestCase):
'''tests functions related to loading waypoints and transfering them
via the mission-item-protocol'''
def test_rally_load(self):
'''test loading rally points from old RALLY style file'''
loader = mavwp.MissionItemProtocol_Rally()
self.assertEqual(loader.mav_mission_type(),
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
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")
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")
loader.load(rally_filepath)
self.assertEqual(loader.count(), 2)
self.assertEqual(loader.wp(0).command, mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT)

class FenceTest(unittest.TestCase):
def test_fence_load(self):
'''test loading rally points from old RALLY style file'''
loader = mavwp.MissionItemProtocol_Fence()
self.assertEqual(loader.mav_mission_type(),
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
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")
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")
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
# fence closing point.
self.assertEqual(loader.count(), 5)
self.assertEqual(loader.wp(0).command, mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT)
self.assertEqual(loader.wp(3).command, mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION)

if __name__ == '__main__':
unittest.main()

0 comments on commit 92e23c8

Please sign in to comment.