class TestHandleRCs(unittest.TestCase): def setUp(self): mgr = Mock(spec=["sendPacket", "remapper", "rcMgr", "appMgr"]) mgr.currentShot = shots.APP_SHOT_CABLECAM mgr.buttonManager = Mock() mgr.getParam = Mock(return_value=500.0) self.mock_vehicle = mock.create_autospec(Vehicle) self.controller = CableCamShot(self.mock_vehicle, mgr) self.mock_vehicle.location.global_relative_frame = LocationGlobalRelative( 37.242124, -122.12841, 15.3) self.controller.recordLocation() self.mock_vehicle.location.global_relative_frame = LocationGlobalRelative( 30.13241, 10.112135, 0.0) self.controller.recordLocation() self.controller.yawPitchOffsetter = Mock() self.controller.yawPitchOffsetter.yawOffset = 2.0 def testRCsMax(self): """ Test RCs Max """ channels = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] self.controller.handleRCs(channels) def testRCsMin(self): """ Test RCs Min """ channels = [-1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0] self.controller.handleRCs(channels) def testRCsZero(self): """ Test RCs Max """ channels = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] self.controller.handleRCs(channels) def testRCs2(self): """ Test RCs Max """ channels = [0.2, 0.2, 0.2, 0.2, 0.2, 0.2, 0.2, 0.2] self.controller.handleRCs(channels) def testIsNearTarget(self): ''' Test that pause is activated when we reach a target ''' channels = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] self.controller.handleRCs(channels) self.controller.pathHandler.isNearTarget = Mock(return_value=True) self.controller.pathHandler.pause = Mock() self.controller.handleRCs(channels) self.controller.pathHandler.pause.assert_called_with()
class TestHandleRCsSetupTargeting(unittest.TestCase): def setUp(self): mgr = Mock(spec=["sendPacket", "remapper", "appMgr"]) mgr.currentShot = shots.APP_SHOT_CABLECAM mgr.buttonManager = Mock() mgr.getParam = Mock(return_value=500.0) self.mock_vehicle = mock.create_autospec(Vehicle) self.controller = CableCamShot(self.mock_vehicle, mgr) self.mock_vehicle.location.global_relative_frame = LocationGlobalRelative( 37.242124, -122.12841, 15.3) self.controller.recordLocation() self.mock_vehicle.location.global_relative_frame = LocationGlobalRelative( 30.13241, 10.112135, 0.0) self.controller.recordLocation() self.controller.setupTargeting = Mock() def testSetupTargetingCalled(self): """ setupTargeting should be called when we get into guided """ self.mock_vehicle.mode.name = "GUIDED" channels = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] self.controller.handleRCs(channels) self.controller.setupTargeting.assert_called_with() self.assertTrue(self.controller.haveSetupTargeting) def testSetupTargetingNotCalled(self): """ Don't call this if we're not yet in guided """ self.mock_vehicle.mode.name = "LOITER" channels = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] self.controller.handleRCs(channels) self.assertFalse(self.controller.setupTargeting.called) self.assertFalse(self.controller.haveSetupTargeting) def testSetupTargetingAlready(self): """ Already set up targeting """ self.mock_vehicle.mode.name = "GUIDED" channels = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] self.controller.haveSetupTargeting = True self.controller.handleRCs(channels) self.assertFalse(self.controller.setupTargeting.called)
class TestSetButtonMappings(unittest.TestCase): def setUp(self): self.v = mock.create_autospec(Vehicle) self.v.location.global_relative_frame = LocationGlobalRelative( 30.13241, 10.112135, 0.0) self.mockMgr = Mock() self.mockMgr.buttonManager = Mock() self.mockMgr.getParam = Mock(return_value=500.0) self.controller = CableCamShot(self.v, self.mockMgr) def testSetButtonMappingsNoWaypoints(self): """ Testing setting button mappings when we have no recorded points """ self.controller.setButtonMappings() calls = [ call(btn_msg.ButtonA, shots.APP_SHOT_CABLECAM, btn_msg.ARTOO_BITMASK_ENABLED, "Record Point\0"), call(btn_msg.ButtonB, shots.APP_SHOT_CABLECAM, 0, "\0") ] self.mockMgr.buttonManager.setArtooButton.assert_has_calls( calls, any_order=False) def testSetButtonMappings1Waypoint(self): """ Testing setting button mappings when we have one recorded point """ self.controller.recordLocation() self.controller.setButtonMappings() calls = [ call(btn_msg.ButtonA, shots.APP_SHOT_CABLECAM, 0, "\0"), call(btn_msg.ButtonB, shots.APP_SHOT_CABLECAM, btn_msg.ARTOO_BITMASK_ENABLED, "Record Point\0") ] self.mockMgr.buttonManager.setArtooButton.assert_has_calls( calls, any_order=False) def testSetButtonMappings(self): """ Testing setting button mappings when we have locked on """ self.controller.recordLocation() self.v.location.global_relative_frame = LocationGlobalRelative( 50.13241, 10.112135, 0.0) self.controller.recordLocation() self.controller.setButtonMappings() calls = [ call(btn_msg.ButtonA, shots.APP_SHOT_CABLECAM, 0, "\0"), call(btn_msg.ButtonB, shots.APP_SHOT_CABLECAM, 0, "\0") ] self.mockMgr.buttonManager.setArtooButton.assert_has_calls( calls, any_order=False)
class TestRecordLocation(unittest.TestCase): def setUp(self): self.v = mock.create_autospec(Vehicle) mgr = Mock(spec=["sendPacket", "remapper", "appMgr"]) mgr.buttonManager = Mock() mgr.getParam = Mock(return_value=500.0) self.controller = CableCamShot(self.v, mgr) def testRecordingLocations(self): """ Test recording locations """ self.v.location.global_relative_frame = LocationGlobalRelative( 37.242124, -122.12841, 15.3) self.controller.recordLocation() self.v.location.global_relative_frame = LocationGlobalRelative( 30.13241, 10.112135, 0.0) self.controller.recordLocation() self.v.location.global_relative_frame = LocationGlobalRelative( -14.654861, 108.4645, 32.6545) self.controller.recordLocation() self.assertTrue(len(self.controller.waypoints) == 3) def testRecordingSameLocations(self): """ Test recording the same locations """ self.v.location.global_relative_frame = LocationGlobalRelative( 37.242124, -122.12841, 15.3) self.controller.recordLocation() self.controller.recordLocation() self.controller.recordLocation() self.assertTrue(len(self.controller.waypoints) == 1) def testCallSetButtonMappings(self): """ Make sure setButtonMappings is called when recording a location """ self.controller.setButtonMappings = Mock() self.v.location.global_relative_frame = LocationGlobalRelative( 37.242124, -122.12841, 15.3) self.controller.recordLocation() self.controller.setButtonMappings.assert_called_with() self.controller.setButtonMappings = Mock() self.v.location.global_relative_frame = LocationGlobalRelative( 30.13241, 10.112135, 0.0) self.controller.recordLocation() self.controller.setButtonMappings.assert_called_with()