# TestMultipoint.py # shotmanager # # Unit tests for the multipoint smart shot. # # Created by Will Silva 1/22/2015. # Copyright (c) 2016 3D Robotics. # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 # # Unless required by applicable law or agreed to in writing, software # distributed under the License is distributed on an "AS IS" BASIS, # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. import multipoint from multipoint import * import shotManager from shotManager import ShotManager import unittest import mock from mock import call from mock import Mock from mock import MagicMock from mock import patch class TestHandleRCs(unittest.TestCase): def setUp(self): #Create a mock vehicle object vehicle = mock.create_autospec(Vehicle) #Create a mock shotManager object shotmgr = mock.create_autospec(ShotManager) shotmgr.getParam.return_value = 0 # so mock doesn't do lazy binds #Run the shot constructor self.shot = multipoint.MultipointShot(vehicle, shotmgr) #Mock checkToNotifyApp() self.shot.checkToNotifyApp = Mock() #Mock listenForAttach() self.shot.listenForAttach = Mock() #attaching self.shot.attaching = False #Cable cam playing self.shot.cableCamPlaying = True #Cruise speed self.shot.cruiseSpeed = 0. #Mock cableController self.shot.cable = mock.create_autospec(CableController) self.shot.cable.position = Vector3() self.shot.cable.velocity = Vector3() self.shot.splineOrigin = LocationGlobalRelative(37.873168,-122.302062, 0) #Mock interpolateCamera() self.shot.interpolateCamera = Mock(return_value=(0,0)) #Mock yawPitchOffsetter self.shot.yawPitchOffsetter.Update = Mock() #channels throttle = 0.0 roll = 0.0 pitch = 0.0 yaw = 0.0 self.channels = [throttle, roll, pitch, yaw, 0.0, 0.0, 0.0, 0.0] def testCableCamNotReady(self): ''' Test that HandleRCs returns if cable cam isn't ready yet ''' self.shot.cableCamPlaying = False self.shot.handleRCs(self.channels) assert not self.shot.checkToNotifyApp.called def testCableCamAttaching(self): '''Test that listenForAttach() is called when attaching''' self.shot.attaching = True self.shot.handleRCs(self.channels) self.shot.listenForAttach.assert_called_with() def testCallCheckToNotifyApp(self): '''Test that checkToNotifyApp() is called''' self.shot.handleRCs(self.channels) self.shot.checkToNotifyApp.assert_called_with() def testRollGreaterThanPitch(self): '''Test that Roll value is used if greater than Pitch value''' #channels throttle = 0.0 roll = 1.0 pitch = 0.5 yaw = 0.0 self.channels = [throttle, roll, pitch, yaw, 0.0, 0.0, 0.0, 0.0] self.shot.handleRCs(self.channels) self.assertEqual(self.shot.desiredSpeed,MAX_SPEED) def testPitchGreaterThanRoll(self): '''Test that Pitch value is used if greater than Roll value''' #channels throttle = 0.0 roll = 0.5 pitch = 1.0 yaw = 0.0 self.channels = [throttle, roll, pitch, yaw, 0.0, 0.0, 0.0, 0.0] self.shot.handleRCs(self.channels) self.assertEqual(self.shot.desiredSpeed,-MAX_SPEED) def testZeroCruiseSpeed(self): '''Test that if cruiseSpeed is zero, stick value scales MAX_SPEED''' #channels throttle = 0.0 roll = 0.7 pitch = 0.0 yaw = 0.0 self.channels = [throttle, roll, pitch, yaw, 0.0, 0.0, 0.0, 0.0] self.shot.handleRCs(self.channels) self.assertEqual(self.shot.desiredSpeed, 0.7 * MAX_SPEED) def testStickWithCruiseSpeed(self): '''Test that if cruiseSpeed is non-zero, stick in same direction increases speed''' #channels throttle = 0.0 roll = 0.7 pitch = 0.0 yaw = 0.0 self.channels = [throttle, roll, pitch, yaw, 0.0, 0.0, 0.0, 0.0] self.shot.cruiseSpeed = 4 #m/s self.shot.handleRCs(self.channels) self.assertEqual(self.shot.desiredSpeed, 4 + (MAX_SPEED - 4) * 0.7) def testStickAgainstCruiseSpeed(self): '''Test that if cruiseSpeed is non-zero, stick in opposite direction decreases speed''' #channels throttle = 0.0 roll = -0.7 pitch = 0.0 yaw = 0.0 self.channels = [throttle, roll, pitch, yaw, 0.0, 0.0, 0.0, 0.0] self.shot.cruiseSpeed = 4 #m/s self.shot.handleRCs(self.channels) self.assertEqual(self.shot.desiredSpeed, 4 * (1. - 0.7)) def testLimitSpeedDemandToMAX_SPEED(self): '''Test that the speed demand is limited to MAX_SPEED''' #channels throttle = 0.0 roll = 1.0 pitch = 0.0 yaw = 0.0 self.channels = [throttle, roll, pitch, yaw, 0.0, 0.0, 0.0, 0.0] self.shot.cruiseSpeed = MAX_SPEED #m/s self.shot.handleRCs(self.channels) self.assertEqual(self.shot.desiredSpeed, MAX_SPEED) def testCarryOverCruiseSpeedSign(self): '''If cruiseSpeed < 0, carry its sign over''' self.shot.cruiseSpeed = -4 self.shot.handleRCs(self.channels) self.assertEqual(self.shot.desiredSpeed, -4) def testSetTargetPositiveDesiredSpeed(self): '''Test that targetP is set to 1.0 if desiredSpeed is > 0''' self.shot.cruiseSpeed = 4 self.shot.handleRCs(self.channels) self.assertEqual(self.shot.targetP, 1.0) def testSetTargetZeroDesiredSpeed(self): '''Test that targetP is set to 1.0 if desiredSpeed is = 0''' self.shot.handleRCs(self.channels) self.assertEqual(self.shot.targetP, 0.0) def testSetTargetNegativeDesiredSpeed(self): '''Test that targetP is set to 0.0 if desiredSpeed is < 0''' self.shot.cruiseSpeed = -4 self.shot.handleRCs(self.channels) self.assertEqual(self.shot.targetP, 0.0) def testUpdatingCableController(self): '''Tests that the cableController update functions are called''' self.shot.handleRCs(self.channels) self.shot.cable.setTargetP.assert_called_with(0.0) self.shot.cable.trackSpeed.assert_called_with(0.0) self.shot.cable.update.assert_called_with(UPDATE_TIME) def testPosVelMessage(self): '''Test that pos-vel message is formed correctly''' self.shot.handleRCs(self.channels) self.shot.vehicle.message_factory.set_position_target_global_int_encode.assert_called_with( 0, # time_boot_ms (not used) 0, 1, # target system, target component mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, # frame 0b0000110111000000, # type_mask - enable pos/vel int(37.873168 * 10000000), # latitude (degrees*1.0e7) int(-122.302062 * 10000000), # longitude (degrees*1.0e7) 0, # altitude (meters) 0.0, 0.0, 0.0, # North, East, Down velocity (m/s) 0, 0, 0, # x, y, z acceleration (not used) 0, 0) # yaw, yaw_rate (not used) self.shot.vehicle.send_mavlink.assert_called_with(mock.ANY) def testInterpolateCamON(self): ''' InterpolateCamera should be called if the option is on ''' self.shot.camInterpolation = 0 self.shot.handleRCs(self.channels) self.shot.interpolateCamera.assert_called_with() def testInterpolateCamOFF(self): ''' InterpolateCamera should NOT be called if the option is off ''' self.shot.camInterpolation = 1 self.shot.handleRCs(self.channels) assert not self.shot.interpolateCamera.called def testCallingYawPitchOffsetterUpdate(self): '''yawPitchOffsetter.Update() should always be called''' self.shot.handleRCs(self.channels) self.shot.yawPitchOffsetter.Update.assert_called_with(self.channels) def testWithGimbal(self): ''' Test message packaging if we have a gimbal''' self.shot.vehicle.mount_status = [0.0, ] self.shot.handleRCs(self.channels) self.shot.vehicle.message_factory.mount_control_encode.assert_called_with( 0, 1, # target system, target component mock.ANY, # pitch is in centidegrees 0.0, # roll mock.ANY, # yaw is in centidegrees 0 # save position ) def testWithNoGimbal(self): ''' Test message packaging if we don't have a gimbal''' self.shot.vehicle.mount_status = [None, ] self.shot.handleRCs(self.channels) self.shot.vehicle.message_factory.command_long_encode.assert_called_with( 0, 0, # target system, target component mavutil.mavlink.MAV_CMD_CONDITION_YAW, # command 0, # confirmation mock.ANY, # param 1 - target angle mock.ANY, # param 2 - yaw speed 0, # param 3 - direction, always shortest route for now... 0.0, # relative offset 0, 0, 0 # params 5-7 (unused) ) class TestInterpolateCamera(unittest.TestCase): def setUp(self): #Create a mock vehicle object vehicle = mock.create_autospec(Vehicle) #Create a mock shotManager object shotmgr = mock.create_autospec(ShotManager) shotmgr.getParam.return_value = 0 # so mock doesn't do lazy binds #Run the shot constructor self.shot = multipoint.MultipointShot(vehicle, shotmgr) #Mock cableController self.shot.cable = mock.create_autospec(CableController) self.shot.cable.currentU = 0.5 # half-way through spline self.shot.cable.currentSeg = 0 # create two waypoints loc = LocationGlobalRelative(37.873168,-122.302062, 0) self.shot.waypoints.append(Waypoint(loc,-90,0)) self.shot.waypoints.append(Waypoint(loc,0,90)) self.shot.camSpline = CatmullRom([Vector2(-180, -90), Vector2(-90, 0), Vector2(0, 90), Vector2(90, 180)]) def testNewPitchYaw(self): '''Make sure newYaw is linearly interpolating between two target yaws''' newPitch, newYaw = self.shot.interpolateCamera() self.assertEqual(newYaw, 45) self.assertEqual(newPitch, -45) @mock.patch('location_helpers.wrapTo360') def testCurrentUGreaterThanOne(self, location_helpers_wrapTo360): '''Test that if cable.currentU is greater than 1, then it is set to 1''' self.shot.cable.currentU = 1.2 self.shot.camSpline.position = Mock() self.shot.interpolateCamera() self.shot.camSpline.position.assert_called_with(0,1.0) @mock.patch('location_helpers.wrapTo360') def testCurrentULessThanZero(self, location_helpers_wrapTo360): '''Test that if cable.currentU is less than zero, then it is set to 0''' self.shot.cable.currentU = -0.1 self.shot.camSpline.position = Mock() self.shot.interpolateCamera() self.shot.camSpline.position.assert_called_with(0,0.0) class TestRecordLocation(unittest.TestCase): def setUp(self): #Create a mock vehicle object vehicle = mock.create_autospec(Vehicle) #Create a mock shotManager object shotmgr = mock.create_autospec(ShotManager) shotmgr.getParam.return_value = 0 # so mock doesn't do lazy binds shotmgr.appMgr = Mock() #Run the shot constructor self.shot = multipoint.MultipointShot(vehicle, shotmgr) #Mock setButtonMappings() self.shot.setButtonMappings = Mock() self.shot.duplicateCheck = Mock(return_value=False) def testRecordInPlayMode(self): '''Try recording a location when in PLAY mode''' self.shot.vehicle.location.global_relative_frame = LocationGlobalRelative(37.242124, -122.12841, 15.3) self.shot.cableCamPlaying = True self.shot.recordLocation() assert not self.shot.duplicateCheck.called def testRecordingLocations(self): ''' Test if recording locations ''' self.shot.vehicle.location.global_relative_frame = LocationGlobalRelative(37.242124, -122.12841, 15.3) self.shot.recordLocation() self.shot.vehicle.location.global_relative_frame = LocationGlobalRelative(30.13241, 10.112135, 0.0) self.shot.recordLocation() self.shot.vehicle.location.global_relative_frame = LocationGlobalRelative(37.873115, -122.303307, 25.0) self.shot.recordLocation() self.assertTrue(len(self.shot.waypoints) == 3) @patch('camera.getPitch') @patch('camera.getYaw') def testRecordingSameLocations(self, mock_getPitch, mock_getYaw): ''' Test if recording the same locations ''' mock_getPitch.return_value = 0 mock_getYaw.return_value = 0 self.shot.vehicle.location.global_relative_frame = LocationGlobalRelative(37.242124, -122.12841, 15.3) self.shot.vehicle.location.global_frame.alt = 0 self.shot.recordLocation() mock_getPitch.return_value = 45 mock_getYaw.return_value = 45 self.shot.duplicateCheck.return_value = True self.shot.recordLocation() self.assertTrue(len(self.shot.waypoints) == 1) packet = struct.pack('