def __init__(self, component_fqn): super(ManagedNode, self).__init__() self._lm = LifecycleManager(component_fqn) self._lm.set_transition_callback(Transition.CONFIGURE, self._on_configure) self._lm.set_transition_callback(Transition.CLEANUP, self._on_cleanup) self._lm.set_transition_callback(Transition.ACTIVATE, self._on_activate) self._lm.set_transition_callback(Transition.DEACTIVATE, self._on_deactivate) self._lm.set_transition_callback(Transition.SHUTDOWN, self._on_shutdown) self._lm.set_error_cb(self._on_error) #start the action server self._lm.start()
def test_simulate_failure_during_activating(self): ROSINIT() lm = LifecycleManager(NODE_NAME) lm.set_transition_callback(Transition.ACTIVATE, return_false) self.assertTrue(lm.configure()) self.assertEquals(State.INACTIVE, lm.get_current_state()) self.assertFalse(lm.activate()) self.assertEquals(State.INACTIVE, lm.get_current_state())
def test_simulate_failure_during_configuring(self): ROSINIT() lm = LifecycleManager(NODE_NAME) lm.set_transition_callback(Transition.CONFIGURE, return_false) self.assertFalse(lm.configure()) self.assertEquals(State.UNCONFIGURED, lm.get_current_state())
def test_simulate_failure_on_set_error_cb(self): ROSINIT() lm = LifecycleManager(NODE_NAME) with self.assertRaises(LifecycleCbException): lm.set_error_cb(ERROR_CB) with self.assertRaises(LifecycleCbException): lm.set_error_cb(ERROR_CB1)
def test_simulate_failure_on_set_transition_callback(self): ROSINIT() lm = LifecycleManager(NODE_NAME) with self.assertRaises(LifecycleCbException): lm.set_transition_callback(Transition.ACTIVATE, CB) with self.assertRaises(LifecycleCbException): lm.set_transition_callback(Transition.ACTIVATE, CB1)
class ManagedNode(object): __metaclass__ = ABCMeta def __init__(self, component_fqn): super(ManagedNode, self).__init__() self._lm = LifecycleManager(component_fqn) self._lm.set_transition_callback(Transition.CONFIGURE, self._on_configure) self._lm.set_transition_callback(Transition.CLEANUP, self._on_cleanup) self._lm.set_transition_callback(Transition.ACTIVATE, self._on_activate) self._lm.set_transition_callback(Transition.DEACTIVATE, self._on_deactivate) self._lm.set_transition_callback(Transition.SHUTDOWN, self._on_shutdown) self._lm.set_error_cb(self._on_error) #start the action server self._lm.start() def __del__(self): self._lm.__del__() def _on_configure(self): return True def _on_cleanup(self): return False '''A node must not start directly after process creation when the life-cycle is in use, so the user needs to provide an on_activate callback and this is enforced by using abstractmethod.''' @abstractmethod def _on_activate(self): return True def _on_deactivate(self): return False def _on_shutdown(self): return True def _on_error(self, ex): return False
def test_through_action_client(self): ROSINIT() lm = LifecycleManager(NODE_NAME) lm.start()
def test_internal(self): ROSINIT() lm = LifecycleManager(NODE_NAME) lm.configure() self.assertEquals(State.INACTIVE, lm.get_current_state()) lm.cleanup() self.assertEquals(State.UNCONFIGURED, lm.get_current_state()) lm.configure() lm.activate() self.assertEquals(State.ACTIVE, lm.get_current_state()) lm.shutdown() self.assertEquals(State.FINALIZED, lm.get_current_state())
def test_simulate_error_in_secondary_state(self): ROSINIT() lm = LifecycleManager(NODE_NAME) lm.set_error_cb(lambda ex: True) lm.set_transition_callback(Transition.CONFIGURE, lambda: lm.raise_error(Exception('Test'))) lm.configure() self.assertEquals(State.UNCONFIGURED, lm.get_current_state()) lm.set_error_cb(lambda ex: False) lm.configure() self.assertEquals(State.FINALIZED, lm.get_current_state())
def test_simulate_error_in_inactive(self): ROSINIT() lm = LifecycleManager(NODE_NAME) lm.set_error_cb(lambda ex: True) lm.configure() self.assertEquals(State.INACTIVE, lm.get_current_state()) lm.raise_error(Exception('Test')) self.assertEquals(State.UNCONFIGURED, lm.get_current_state()) lm.set_error_cb(lambda ex: False) lm.configure() self.assertEquals(State.INACTIVE, lm.get_current_state()) lm.raise_error(Exception('Test')) self.assertEquals(State.FINALIZED, lm.get_current_state())
def test_publish_transition(self): ROSINIT() lm = LifecycleManager(NODE_NAME) lm.start() state_sub = rospy.Subscriber(NODE_NAME + '/' + LIFECYCLE_STATE_TOPIC, Lifecycle, self.subscriber_cb) spin_thread = SpinThread(2, "SubscriberCB_Thread", 2) spin_thread.setDaemon(True) spin_thread.start() lm.configure() self.assertEquals(State.INACTIVE, lm.get_current_state()) rospy.sleep(1.0) lm.cleanup() self.assertEquals(State.UNCONFIGURED, lm.get_current_state()) rospy.sleep(1.0) lm.configure() rospy.sleep(1.0) lm.activate() self.assertEquals(State.ACTIVE, lm.get_current_state()) rospy.sleep(1.0) lm.shutdown() self.assertEquals(State.FINALIZED, lm.get_current_state()) rospy.sleep(3.0) self.assertEquals(5, self.Count) spin_thread.join(1.0) lm.__del__()
def test_transitions_for_active(self): ROSINIT() lm = LifecycleManager(NODE_NAME) lm.configure() lm.activate() self.assertEquals(State.ACTIVE, lm.get_current_state()) # make sure these are not accepted with self.assertRaises(IllegalTransitionException): lm.configure() self.assertEquals(State.ACTIVE, lm.get_current_state()) with self.assertRaises(IllegalTransitionException): lm.activate() self.assertEquals(State.ACTIVE, lm.get_current_state()) with self.assertRaises(IllegalTransitionException): lm.cleanup() self.assertEquals(State.ACTIVE, lm.get_current_state()) # now make sure all the valid ones are accepted self.assertTrue(lm.deactivate()) self.assertEquals(State.INACTIVE, lm.get_current_state()) # go back lm.activate() self.assertEquals(State.ACTIVE, lm.get_current_state()) self.assertTrue(lm.shutdown()) self.assertEquals(State.FINALIZED, lm.get_current_state())