diff --git a/flexbe_core/test/test_core.py b/flexbe_core/test/test_core.py index d73e3ab..af30d59 100755 --- a/flexbe_core/test/test_core.py +++ b/flexbe_core/test/test_core.py @@ -44,7 +44,7 @@ import rclpy from rclpy.executors import MultiThreadedExecutor -from std_msgs.msg import Bool, Empty, Int32, String, UInt32 +from std_msgs.msg import Bool, Empty, Int32, UInt32 class CoreTestState(EventState): @@ -144,7 +144,7 @@ def setUp(self): def tearDown(self): """Tear down the TestCore test.""" self.node.get_logger().info(' shutting down core test %d ... ' % (self.test)) - for _ in range(int(0.25*TestCore.__LOOP_COUNT)): + for _ in range(int(0.25 * TestCore.__LOOP_COUNT)): # Allow any lingering pub/sub to clear up rclpy.spin_once(self.node, executor=self.executor, timeout_sec=TestCore.__EXECUTE_TIMEOUT_SEC) @@ -161,7 +161,7 @@ def tearDown(self): # Kill it with fire to make sure not stray published topics are available rclpy.shutdown(context=self.context) - time.sleep(TestCore.__TIME_SLEEP*2) + time.sleep(TestCore.__TIME_SLEEP * 2) def _create(self): """Create the test.""" @@ -215,9 +215,9 @@ def _execute_state(self, state): return outcome except Exception as exc: self.node.get_logger().error(f" exception in state execute for '{state.name}' ... ") - self.node.get_logger().info(f"{exc}") + self.node.get_logger().info(f'{exc}') import traceback - self.node.get_logger().info(f"{traceback.format_exc()}") + self.node.get_logger().info(f'{traceback.format_exc()}') def assertMessage(self, sub, topic, msg, timeout=1): """Check message.""" @@ -748,7 +748,7 @@ def execute(self, userdata): sm = OperatableStateMachine(outcomes=['done']) sm._state_id = 8192 sm.userdata.outside = 'outside_data' - sm.set_name("outer_sm") # No one sets this name, while .add sets names of inner states + sm.set_name('outer_sm') # No one sets this name, while .add sets names of inner states with sm: OperatableStateMachine.add('before_state', TestUserdataState(), transitions={'done': 'inner_sm'}, remapping={'data_in': 'outside'}, diff --git a/flexbe_core/test/test_exceptions.py b/flexbe_core/test/test_exceptions.py index 8a072e9..4aefd02 100755 --- a/flexbe_core/test/test_exceptions.py +++ b/flexbe_core/test/test_exceptions.py @@ -82,7 +82,7 @@ def tearDown(self): # Kill it with fire to make sure not stray published topics are available rclpy.shutdown(context=self.context) - time.sleep(TestExceptions.__TIME_SLEEP*2) + time.sleep(TestExceptions.__TIME_SLEEP * 2) def test_invalid_outcome(self): """Test invalid outcome.""" diff --git a/flexbe_core/test/test_exceptions_spin.py b/flexbe_core/test/test_exceptions_spin.py index fca7b03..2edd2c9 100644 --- a/flexbe_core/test/test_exceptions_spin.py +++ b/flexbe_core/test/test_exceptions_spin.py @@ -69,7 +69,7 @@ def setUp(self): def tearDown(self): """Tear down the TestExceptionsSpin test.""" self.node.get_logger().info(' shutting down exceptions test %d (%d) ... ' % (self.test, self.context.ok())) - rclpy.spin_once(self.node, executor=self.executor, timeout_sec=2*TestExceptionsSpin.__EXECUTE_TIMEOUT_SEC) + rclpy.spin_once(self.node, executor=self.executor, timeout_sec=2 * TestExceptionsSpin.__EXECUTE_TIMEOUT_SEC) self.node.get_logger().info(' shutting down proxies in core test %d ... ' % (self.test)) shutdown_proxies() @@ -84,7 +84,7 @@ def tearDown(self): # Kill it with fire to make sure not stray published topics are available rclpy.shutdown(context=self.context) - time.sleep(TestExceptionsSpin.__TIME_SLEEP*2) + time.sleep(TestExceptionsSpin.__TIME_SLEEP * 2) def test_invalid_outcome(self): """Test invalid outcome.""" diff --git a/flexbe_core/test/test_logger.py b/flexbe_core/test/test_logger.py index 630d023..17a1526 100644 --- a/flexbe_core/test/test_logger.py +++ b/flexbe_core/test/test_logger.py @@ -81,7 +81,7 @@ def tearDown(self): # Kill it with fire to make sure not stray published topics are available rclpy.shutdown(context=self.context) - time.sleep(TestLogger.__TIME_SLEEP*2) + time.sleep(TestLogger.__TIME_SLEEP * 2) def test_throttle_logger_one(self): """Test throttle logger one.""" @@ -202,7 +202,7 @@ def execute(self, userdata): while outcome is None: outcome = sm.execute(None) self.assertTrue(1 < len(Logger._last_logged) <= Logger.MAX_LAST_LOGGED_SIZE) - rclpy.spin_once(self.node, executor=self.executor, timeout_sec=TestLogger.__EXECUTE_TIMEOUT_SEC*0.5) + rclpy.spin_once(self.node, executor=self.executor, timeout_sec=TestLogger.__EXECUTE_TIMEOUT_SEC * 0.5) self.assertEqual(outcome, 'done') self.assertEqual(state_instance._trials, 0) @@ -247,7 +247,7 @@ def execute(self, userdata): while outcome is None: outcome = sm.execute(None) self.assertTrue(1 < len(Logger._last_logged) <= Logger.MAX_LAST_LOGGED_SIZE) - rclpy.spin_once(self.node, executor=self.executor, timeout_sec=TestLogger.__EXECUTE_TIMEOUT_SEC*.5) + rclpy.spin_once(self.node, executor=self.executor, timeout_sec=TestLogger.__EXECUTE_TIMEOUT_SEC * 0.5) self.assertEqual(outcome, 'done') self.assertEqual(state_instance._trials, 0) diff --git a/flexbe_core/test/test_proxies.py b/flexbe_core/test/test_proxies.py index 261191a..a08659e 100755 --- a/flexbe_core/test/test_proxies.py +++ b/flexbe_core/test/test_proxies.py @@ -93,7 +93,7 @@ def tearDown(self): # Kill it with fire to make sure not stray published topics are available rclpy.shutdown(context=self.context) - time.sleep(TestProxies.__TIME_SLEEP*5) + time.sleep(TestProxies.__TIME_SLEEP * 5) def test_publish_subscribe(self): """Test publish and subscribe."""