def test_allocate_four_resources_failure(self): """ Similar to test_allocate_permutation_two_resources(), but here there are more permutations, so the allocator gives up after the initial failure. """ pool = ResourcePool( KnownResources(resources=[ CurrentStatus(uri=DUDE1_NAME, rapps={TELEOP_RAPP}), CurrentStatus(uri=DUDE2_NAME, rapps={TELEOP_RAPP}), CurrentStatus(uri=DUDE3_NAME, rapps={TELEOP_RAPP}), CurrentStatus(uri=DUDE4_NAME, rapps={TELEOP_RAPP, EXAMPLE_RAPP}) ])) rq = ActiveRequest( Request(id=unique_id.toMsg(RQ_UUID), resources=[ Resource(rapp=TELEOP_RAPP, uri=ANY_NAME), Resource(rapp=EXAMPLE_RAPP, uri=DUDE4_NAME), Resource(rapp=TELEOP_RAPP, uri=DUDE2_NAME), Resource(rapp=TELEOP_RAPP, uri=DUDE3_NAME) ])) self.assertRaises(InvalidRequestError, pool.allocate, rq) for name in [DUDE1_NAME, DUDE2_NAME, DUDE3_NAME, DUDE4_NAME]: self.assertEqual(pool[name].status, CurrentStatus.AVAILABLE) self.assertIsNone(pool[name].owner)
def test_matching_allocation_one_resource(self): pool = ResourcePool(SINGLETON_POOL) self.assertEqual(len(pool), 1) self.assertEqual(pool.known_resources(), SINGLETON_POOL) self.assertFalse(pool.changed) res = Resource(rapp=TELEOP_RAPP, uri=ANY_NAME) subset = pool._match_subset(res, {CurrentStatus.AVAILABLE}) self.assertNotIn(MARVIN_NAME, subset) self.assertIn(ROBERTO_NAME, subset) self.assertEqual(subset, set([ROBERTO_NAME])) self.assertEqual( pool.match_list([ROBERTO_RESOURCE], {CurrentStatus.AVAILABLE}), [set([ROBERTO_NAME])]) rq = copy.deepcopy(ANY_REQUEST) alloc = pool.allocate(rq) self.assertTrue(alloc) self.assertTrue(pool.changed) self.assertEqual(alloc[0], ROBERTO_RESOURCE) self.assertEqual(pool[ROBERTO_NAME].status, CurrentStatus.ALLOCATED) self.assertEqual(pool[ROBERTO_NAME].owner, RQ_UUID) self.assertTrue(pool.changed) self.assertEqual( pool.known_resources(), KnownResources(resources=[ CurrentStatus(uri=ROBERTO_NAME, rapps=TEST_RAPPS, status=CurrentStatus.ALLOCATED, owner=unique_id.toMsg(RQ_UUID)) ])) self.assertFalse(pool.changed)
def test_allocate_permutation_two_resources(self): """ Request a regexp allocation followed by an exact allocation. Initially the exact resource gets assigned to the regexp, so the second part of the request fails. The allocator must try the other permutation for it to succeed. """ pool = ResourcePool( KnownResources(resources=[ CurrentStatus(uri=MARVIN_NAME, rapps={TELEOP_RAPP, EXAMPLE_RAPP}), CurrentStatus(uri=ROBERTO_NAME, rapps={TELEOP_RAPP}) ])) rq = ActiveRequest( Request(id=unique_id.toMsg(RQ_UUID), resources=[ Resource(rapp=TELEOP_RAPP, uri=ANY_NAME), Resource(rapp=EXAMPLE_RAPP, uri=MARVIN_NAME) ])) alloc = pool.allocate(rq) self.assertTrue(alloc) self.assertEqual(len(alloc), 2) self.assertEqual(pool[MARVIN_NAME].status, CurrentStatus.ALLOCATED) self.assertEqual(pool[MARVIN_NAME].owner, RQ_UUID) self.assertEqual(pool[ROBERTO_NAME].status, CurrentStatus.ALLOCATED) self.assertEqual(pool[ROBERTO_NAME].owner, RQ_UUID) self.assertEqual(alloc[0], Resource(rapp=TELEOP_RAPP, uri=ROBERTO_NAME)) self.assertEqual(alloc[1], Resource(rapp=EXAMPLE_RAPP, uri=MARVIN_NAME))
def test_allocate_four_resources_success(self): """ Similar to test_allocate_four_resources_failure(), but the order of the request is different, so the allocator succeeds. """ pool = ResourcePool( KnownResources(resources=[ CurrentStatus(uri=DUDE1_NAME, rapps={TELEOP_RAPP}), CurrentStatus(uri=DUDE2_NAME, rapps={TELEOP_RAPP}), CurrentStatus(uri=DUDE3_NAME, rapps={TELEOP_RAPP}), CurrentStatus(uri=DUDE4_NAME, rapps={TELEOP_RAPP, EXAMPLE_RAPP}) ])) rq = ActiveRequest( Request(id=unique_id.toMsg(RQ_UUID), resources=[ Resource(rapp=EXAMPLE_RAPP, uri=DUDE4_NAME), Resource(rapp=TELEOP_RAPP, uri=DUDE2_NAME), Resource(rapp=TELEOP_RAPP, uri=DUDE3_NAME), Resource(rapp=TELEOP_RAPP, uri=ANY_NAME) ])) alloc = pool.allocate(rq) self.assertTrue(alloc) bot_names = [DUDE4_NAME, DUDE2_NAME, DUDE3_NAME, DUDE1_NAME] for name, i in zip(bot_names, range(4)): self.assertEqual(pool[name].status, CurrentStatus.ALLOCATED) self.assertEqual(alloc[i].uri, name)
def known_resources(self): """ Convert resource pool to ``scheduler_msgs/KnownResources``. """ msg = KnownResources() for resource in self.pool.values(): msg.resources.append(resource.current_status()) self.changed = False return msg
def test_empty_update(self): pool = ResourcePool() self.assertEqual(len(pool), 0) self.assertTrue(pool.changed) self.assertEqual(pool.known_resources(), KnownResources()) self.assertFalse(pool.changed) pool.update([]) self.assertEqual(len(pool), 0) self.assertFalse(pool.changed)
def test_empty_constructor(self): pool = ResourcePool() self.assertIsNotNone(pool) self.assertEqual(len(pool), 0) self.assertNotIn(MARVIN_NAME, pool) self.assertMultiLineEqual(str(pool), 'pool contents:') self.assertTrue(pool.changed) self.assertEqual(pool.known_resources(), KnownResources()) self.assertFalse(pool.changed)
def test_insufficient_resources(self): # ask for two when there's only one pool = ResourcePool(KnownResources(resources=[ROBERTO])) rq1 = ActiveRequest( Request(id=unique_id.toMsg(RQ_UUID), resources=[ANY_RESOURCE, ANY_RESOURCE])) alloc1 = pool.allocate(rq1) self.assertFalse(alloc1) self.assertEqual(pool[ROBERTO_NAME].status, CurrentStatus.AVAILABLE) self.assertIsNone(pool[ROBERTO_NAME].owner)
def test_one_update_new(self): pool = ResourcePool() self.assertEqual(len(pool), 0) self.assertTrue(pool.changed) self.assertEqual(pool.known_resources(), KnownResources()) self.assertFalse(pool.changed) pool.update([ ConcertClient( name='roberto', platform_info=PlatformInfo(uri=ROBERTO_NAME), state=ConcertClientState.AVAILABLE, rapps=[Rapp(name=TELEOP_RAPP), Rapp(name=EXAMPLE_RAPP)]) ]) self.assertEqual(len(pool), 1) self.assertIn(ROBERTO_NAME, pool) self.assertTrue(pool.changed) self.assertEqual(pool.known_resources(), SINGLETON_POOL) self.assertFalse(pool.changed)
priority: 0 rapps: """ + EXAMPLE_RAPP) ANY_NAME = 'rocon:/turtlebot' NOT_TURTLEBOT_NAME = 'rocon:/pr2/farnsworth' DUDE1_NAME = 'rocon:/turtlebot/dude1' DUDE2_NAME = 'rocon:/turtlebot/dude2' DUDE3_NAME = 'rocon:/turtlebot/dude3' DUDE4_NAME = 'rocon:/turtlebot/dude4' MARVIN_NAME = 'rocon:/turtlebot/marvin' ROBERTO_NAME = 'rocon:/turtlebot/roberto' MARVIN = CurrentStatus(uri=MARVIN_NAME, rapps=TEST_RAPPS) ROBERTO = CurrentStatus(uri=ROBERTO_NAME, rapps=TEST_RAPPS) SINGLETON_POOL = KnownResources(resources=[ROBERTO]) DOUBLETON_POOL = KnownResources(resources=[MARVIN, ROBERTO]) # some useful Resource and Request messages ANY_RESOURCE = Resource(rapp=TELEOP_RAPP, uri=ANY_NAME) ANY_REQUEST = ActiveRequest( Request(id=unique_id.toMsg(RQ_UUID), resources=[ANY_RESOURCE])) MARVIN_RESOURCE = Resource(rapp=TELEOP_RAPP, uri=MARVIN_NAME) ROBERTO_RESOURCE = Resource(rapp=TELEOP_RAPP, uri=ROBERTO_NAME) ROBERTO_REQUEST = ActiveRequest( Request(id=unique_id.toMsg(RQ_UUID), resources=[ROBERTO_RESOURCE])) NOT_TURTLEBOT_RESOURCE = Resource(rapp=TELEOP_RAPP, uri=NOT_TURTLEBOT_NAME) NOT_TURTLEBOT_REQUEST = ActiveRequest( Request(id=unique_id.toMsg(RQ_UUID), resources=[NOT_TURTLEBOT_RESOURCE]))