From 9cdd2bf6cb565992ada53d0ae7661b0900d3aa3e Mon Sep 17 00:00:00 2001 From: Miro Wengner Date: Thu, 19 Dec 2024 17:38:56 +0100 Subject: [PATCH] 75: countdown timeouts review and removals (#90) 1. sleep removals 2. switch statements 3. tests improvements --- pom.xml | 2 +- .../java/com/robo4j/AttributeDescriptor.java | 4 +- .../com/robo4j/ConfigurationException.java | 3 + .../robo4j/DefaultAttributeDescriptor.java | 43 +- .../com/robo4j/LocalReferenceAdapter.java | 6 +- .../main/java/com/robo4j/RoboApplication.java | 128 -- .../com/robo4j/RoboApplicationException.java | 34 - .../src/main/java/com/robo4j/RoboBuilder.java | 40 +- .../java/com/robo4j/RoboBuilderException.java | 3 + .../main/java/com/robo4j/RoboReference.java | 2 +- .../src/main/java/com/robo4j/RoboSystem.java | 131 +- .../src/main/java/com/robo4j/RoboUnit.java | 447 ++++--- .../ConfigurationFactoryException.java | 3 + .../configuration/DefaultConfiguration.java | 278 ++-- .../XmlConfigurationFactory.java | 19 +- .../robo4j/net/ClientRemoteRoboContext.java | 230 ++-- .../java/com/robo4j/net/ContextEmitter.java | 34 +- .../java/com/robo4j/net/ContextMessage.java | 27 - .../com/robo4j/net/HearbeatMessageCodec.java | 6 +- .../com/robo4j/net/LookupServiceImpl.java | 20 +- .../java/com/robo4j/net/MessageClient.java | 126 +- .../java/com/robo4j/net/MessageServer.java | 125 +- .../com/robo4j/net/ReferenceDescriptor.java | 2 +- .../com/robo4j/net/RoboContextDescriptor.java | 71 +- .../robo4j/net/ServerRemoteRoboContext.java | 4 +- .../com/robo4j/reflect/ReflectionScan.java | 18 +- .../reflect/ReflectionScanException.java | 3 + .../robo4j/scheduler/DefaultScheduler.java | 19 +- .../robo4j/scheduler/RoboThreadFactory.java | 27 + .../java/com/robo4j/units/CounterUnit.java | 132 -- .../java/com/robo4j/util/AttributeUtils.java | 2 +- .../src/main/java/com/robo4j/util/IOUtil.java | 8 +- .../java/com/robo4j/util/StreamException.java | 5 +- .../java/com/robo4j/util/StringConstants.java | 1 - .../main/java/com/robo4j/util/SystemUtil.java | 8 +- .../java/com/robo4j/util/Utf8Constant.java | 1 + .../java/com/robo4j/CounterUnitTests.java | 84 -- .../java/com/robo4j/RoboApplicationTests.java | 90 -- .../java/com/robo4j/RoboBuilderTests.java | 50 +- .../java/com/robo4j/RoboSchedulerTests.java | 112 +- .../java/com/robo4j/RoboUnitTestUtils.java | 13 + .../test/java/com/robo4j/RoboUnitTests.java | 126 +- .../RunnableProcessCounterUnitTests.java | 146 +++ .../com/robo4j/net/AckingStringConsumer.java | 18 +- .../com/robo4j/net/LookupServiceTests.java | 49 +- .../com/robo4j/net/MessageServerTest.java | 87 +- .../com/robo4j/net/RemoteContextTests.java | 70 +- .../com/robo4j/net/RemoteStringProducer.java | 13 +- .../robo4j/net/RemoteTestMessageProducer.java | 14 +- .../java/com/robo4j/net/RoboTestContext.java | 2 +- .../com/robo4j/net/RoboTestReference.java | 2 +- .../robo4j/units/ConfigurationConsumer.java | 6 +- .../java/com/robo4j/units/CounterCommand.java | 2 +- .../java/com/robo4j/units/CounterUnit.java | 196 +++ .../com/robo4j/units/IntegerConsumer.java | 25 +- .../java/com/robo4j/units/StringConsumer.java | 12 +- .../robo4j/units/StringConsumerWorker.java | 77 +- .../java/com/robo4j/units/StringProducer.java | 4 +- .../robo4j/units/StringScheduledEmitter.java | 4 +- .../i2c/adafruitoled/SSD1306DeviceTest.java | 4 +- .../CalibratedMagnetometerExample.java | 7 +- .../MagnetometerLSM303Example.java | 7 +- .../robo4j/hw/rpi/i2c/pwm/ServoTester.java | 4 +- .../com/robo4j/hw/rpi/imu/Bno055Example.java | 7 +- .../hw/rpi/camera/CameraClientException.java | 3 + .../com/robo4j/hw/rpi/camera/RaspiDevice.java | 1 + .../java/com/robo4j/hw/rpi/gps/Location.java | 100 +- .../java/com/robo4j/hw/rpi/gps/NmeaUtils.java | 120 +- .../AccelerometerLSM303Device.java | 8 +- .../adafruitbackpack/AbstractBackpack.java | 70 +- .../adafruitbackpack/AlphanumericDevice.java | 2 +- .../BiColor8x8MatrixDevice.java | 1 + .../adafruitbackpack/LedBackpackFactory.java | 21 +- .../i2c/adafruitbackpack/MatrixRotation.java | 36 +- .../robo4j/hw/rpi/i2c/adafruitlcd/Button.java | 92 +- .../hw/rpi/i2c/adafruitlcd/Message.java | 8 +- .../i2c/adafruitlcd/impl/AdafruitLcdImpl.java | 1118 ++++++++--------- .../adafruitlcd/mockup/AdafruitLcdMockup.java | 27 +- .../rpi/i2c/adafruitoled/SSD1306Device.java | 2 +- .../com/robo4j/hw/rpi/i2c/gps/TitanX1GPS.java | 11 +- .../hw/rpi/i2c/gps/XA1110PositionEvent.java | 10 +- .../hw/rpi/i2c/gps/XA1110VelocityEvent.java | 10 +- .../hw/rpi/i2c/gyro/CalibratedGyro.java | 18 +- .../hw/rpi/i2c/pwm/HBridgeMC33926Device.java | 9 - .../robo4j/hw/rpi/i2c/pwm/PCA9685Servo.java | 2 +- .../hw/rpi/i2c/pwm/PWMPCA9685Device.java | 418 +++--- .../rpi/imu/bno/Bno055CalibrationStatus.java | 2 +- .../robo4j/hw/rpi/imu/bno/Bno055Device.java | 2 +- .../robo4j/hw/rpi/imu/bno/Bno080Device.java | 4 +- .../robo4j/hw/rpi/imu/bno/Bno080Factory.java | 8 +- .../robo4j/hw/rpi/imu/bno/DataEvent3f.java | 2 + .../robo4j/hw/rpi/imu/bno/VectorEvent.java | 2 + .../imu/bno/impl/AbstractBno055Device.java | 865 +++++++------ .../imu/bno/impl/AbstractBno080Device.java | 379 +++--- .../rpi/imu/bno/impl/Bno055SerialDevice.java | 44 +- .../hw/rpi/imu/bno/impl/Bno080SPIDevice.java | 48 +- .../hw/rpi/imu/bno/shtp/ShtpChannel.java | 2 +- .../rpi/imu/bno/shtp/ShtpPacketRequest.java | 2 +- .../robo4j/hw/rpi/imu/bno/shtp/ShtpUtils.java | 2 +- .../com/robo4j/hw/rpi/lcd/StringUtils.java | 10 +- .../hw/rpi/pad/LF710ButtonObserver.java | 217 ++-- .../com/robo4j/hw/rpi/pad/LF710Exception.java | 5 +- .../java/com/robo4j/hw/rpi/pad/LF710Part.java | 3 +- .../com/robo4j/hw/rpi/pad/LF710State.java | 2 +- .../com/robo4j/hw/rpi/serial/SerialUtil.java | 2 - .../robo4j/hw/rpi/serial/gps/MTK3339GPS.java | 15 +- .../robo4j/hw/rpi/serial/ydlidar/Command.java | 18 +- .../hw/rpi/serial/ydlidar/DataHeader.java | 9 +- .../hw/rpi/serial/ydlidar/DeviceInfo.java | 2 +- .../hw/rpi/serial/ydlidar/HealthInfo.java | 2 +- .../hw/rpi/serial/ydlidar/ResponseHeader.java | 25 +- .../hw/rpi/serial/ydlidar/YDLidarDevice.java | 23 +- .../math/features/FeatureExtraction.java | 2 +- .../math/geometry/CurvaturePoint2f.java | 6 +- .../com/robo4j/math/geometry/Matrix3d.java | 82 +- .../com/robo4j/math/geometry/Matrix3f.java | 54 +- .../com/robo4j/math/geometry/Matrix3i.java | 48 +- .../com/robo4j/math/geometry/Matrix4d.java | 125 +- .../com/robo4j/math/geometry/Matrix4f.java | 76 +- .../com/robo4j/math/geometry/Matrix4i.java | 82 +- .../com/robo4j/math/geometry/Point2f.java | 5 +- .../com/robo4j/math/geometry/Tuple3d.java | 10 +- .../com/robo4j/math/geometry/Tuple4d.java | 13 +- .../math/geometry/impl/ScanResultImpl.java | 17 +- .../http/request/RoboRequestCallable.java | 16 +- .../http/request/RoboRequestFactory.java | 12 +- .../socket/http/units/HttpServerUnit.java | 6 +- .../test/units/RoboDatagramClientTest.java | 26 +- .../test/units/RoboDatagramPingPongTest.java | 14 +- .../http/test/units/RoboHttpDynamicTests.java | 13 +- .../config/HttpOneAttributeGetController.java | 10 +- .../HttpTwoAttributesGetController.java | 8 +- .../units/config/PropertyListBuilder.java | 2 +- .../SocketMessageDecoratedProducerUnit.java | 12 +- .../test/units/config/StringConsumer.java | 12 +- .../test/units/config/StringProducerUnit.java | 8 +- .../config/enums/AdvancedTestCommandEnum.java | 4 +- .../http/test/utils/InternalUtilTests.java | 4 +- .../socket/http/test/utils/JsonUtilTests.java | 4 +- .../lego/BasicSonicSensorServoUnitMock.java | 2 +- .../robo4j/units/lego/SimpleTankUnitMock.java | 5 +- .../camera/CameraImageConsumerTestUnit.java | 19 +- .../CameraImageProducerDesTestUnit.java | 13 +- .../rpi/accelerometer/AccelerometerEvent.java | 2 +- .../AccelerometerLSM303Unit.java | 2 +- .../robo4j/units/rpi/camera/RaspiRequest.java | 20 +- .../units/rpi/camera/RaspistillRequest.java | 4 +- .../units/rpi/camera/RaspividRequest.java | 4 +- .../robo4j/units/rpi/camera/RaspividUnit.java | 15 +- .../com/robo4j/units/rpi/gps/MtkGPSUnit.java | 21 +- .../robo4j/units/rpi/gps/TitanGPSUnit.java | 12 +- .../com/robo4j/units/rpi/gyro/GyroEvent.java | 2 +- .../robo4j/units/rpi/gyro/GyroL3GD20Unit.java | 16 +- .../com/robo4j/units/rpi/imu/Bno080Unit.java | 11 +- .../units/rpi/lcd/AdafruitButtonUnit.java | 25 +- .../units/rpi/lcd/AdafruitException.java | 5 +- .../robo4j/units/rpi/lcd/AdafruitLcdUnit.java | 33 +- .../rpi/led/AbstractI2CBackpackUnit.java | 15 +- .../rpi/led/AdafruitAlphanumericUnit.java | 15 +- .../units/rpi/lidarlite/LaserScanner.java | 4 +- .../units/rpi/pwm/PCA9685ServoUnit.java | 4 +- 161 files changed, 3843 insertions(+), 4102 deletions(-) delete mode 100644 robo4j-core/src/main/java/com/robo4j/RoboApplication.java delete mode 100644 robo4j-core/src/main/java/com/robo4j/RoboApplicationException.java delete mode 100644 robo4j-core/src/main/java/com/robo4j/net/ContextMessage.java delete mode 100644 robo4j-core/src/main/java/com/robo4j/units/CounterUnit.java delete mode 100644 robo4j-core/src/test/java/com/robo4j/CounterUnitTests.java delete mode 100644 robo4j-core/src/test/java/com/robo4j/RoboApplicationTests.java create mode 100644 robo4j-core/src/test/java/com/robo4j/RunnableProcessCounterUnitTests.java rename robo4j-core/src/{main => test}/java/com/robo4j/units/CounterCommand.java (96%) create mode 100644 robo4j-core/src/test/java/com/robo4j/units/CounterUnit.java diff --git a/pom.xml b/pom.xml index 874a319b..95a2f0ff 100644 --- a/pom.xml +++ b/pom.xml @@ -124,7 +124,7 @@ 3.3.1 3.6.0 3.6.0 - 2.7.0-SNAPSHOT + 2.7.0 2.0.16 1.6.7 diff --git a/robo4j-core/src/main/java/com/robo4j/AttributeDescriptor.java b/robo4j-core/src/main/java/com/robo4j/AttributeDescriptor.java index 0be80533..87a786ba 100644 --- a/robo4j-core/src/main/java/com/robo4j/AttributeDescriptor.java +++ b/robo4j-core/src/main/java/com/robo4j/AttributeDescriptor.java @@ -28,12 +28,12 @@ public interface AttributeDescriptor { * * @return the attribute type. */ - Class getAttributeType(); + Class attributeType(); /** * Returns the name of the attribute. * * @return the attribute name. */ - String getAttributeName(); + String attributeName(); } diff --git a/robo4j-core/src/main/java/com/robo4j/ConfigurationException.java b/robo4j-core/src/main/java/com/robo4j/ConfigurationException.java index 2f31ba86..31fbcb85 100644 --- a/robo4j-core/src/main/java/com/robo4j/ConfigurationException.java +++ b/robo4j-core/src/main/java/com/robo4j/ConfigurationException.java @@ -16,6 +16,8 @@ */ package com.robo4j; +import java.io.Serial; + /** * Exception thrown when a problem occurs configuring a RoboUnit. * @@ -23,6 +25,7 @@ * @author Miroslav Wengner (@miragemiko) */ public class ConfigurationException extends Exception { + @Serial private static final long serialVersionUID = 1L; /** diff --git a/robo4j-core/src/main/java/com/robo4j/DefaultAttributeDescriptor.java b/robo4j-core/src/main/java/com/robo4j/DefaultAttributeDescriptor.java index a53751e6..a08b69eb 100644 --- a/robo4j-core/src/main/java/com/robo4j/DefaultAttributeDescriptor.java +++ b/robo4j-core/src/main/java/com/robo4j/DefaultAttributeDescriptor.java @@ -16,52 +16,37 @@ */ package com.robo4j; +import java.io.Serial; import java.io.Serializable; /** * Default implementation of an attribute descriptor. - * + * * @author Marcus Hirt (@hirt) * @author Miroslav Wengner (@miragemiko) */ -public class DefaultAttributeDescriptor implements AttributeDescriptor, Serializable { +public record DefaultAttributeDescriptor(Class attributeType, + String attributeName) implements AttributeDescriptor, Serializable { + @Serial private static final long serialVersionUID = 1L; - private final Class attributeType; - private final String attributeName; /** * Constructor. - * - * @param attributeType - * the type of the attribute. Needed since the generic type is - * erased. - * @param attributeName - * the name of the attribute. + * + * @param attributeType the type of the attribute. Needed since the generic type is + * erased. + * @param attributeName the name of the attribute. */ - public DefaultAttributeDescriptor(Class attributeType, String attributeName) { - this.attributeType = attributeType; - this.attributeName = attributeName; - } - - @Override - public Class getAttributeType() { - return attributeType; + public DefaultAttributeDescriptor { } - @Override - public String getAttributeName() { - return attributeName; - } /** * Factory method for creating attribute descriptors. - * - * @param attributeType - * the type of the attribute. - * @param attributeName - * the name of the attribute. - * @param - * attribute type class + * + * @param attributeType the type of the attribute. + * @param attributeName the name of the attribute. + * @param attribute type class * @return created attribute */ public static DefaultAttributeDescriptor create(Class attributeType, String attributeName) { diff --git a/robo4j-core/src/main/java/com/robo4j/LocalReferenceAdapter.java b/robo4j-core/src/main/java/com/robo4j/LocalReferenceAdapter.java index 13d446c5..71faa4e2 100644 --- a/robo4j-core/src/main/java/com/robo4j/LocalReferenceAdapter.java +++ b/robo4j-core/src/main/java/com/robo4j/LocalReferenceAdapter.java @@ -16,12 +16,12 @@ */ package com.robo4j; +import com.robo4j.configuration.Configuration; + import java.util.Collection; import java.util.Map; import java.util.concurrent.Future; -import com.robo4j.configuration.Configuration; - /** * This is a useful adapter to hand off a RoboReference to a unit which will * only use it as a callback. Note that this has several serious limits. First, @@ -56,7 +56,7 @@ public Configuration getConfiguration() { } @Override - public String getId() { + public String id() { return null; } diff --git a/robo4j-core/src/main/java/com/robo4j/RoboApplication.java b/robo4j-core/src/main/java/com/robo4j/RoboApplication.java deleted file mode 100644 index 5c8d139d..00000000 --- a/robo4j-core/src/main/java/com/robo4j/RoboApplication.java +++ /dev/null @@ -1,128 +0,0 @@ -/* - * Copyright (c) 2014, 2024, Marcus Hirt, Miroslav Wengner - * - * Robo4J is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Robo4J is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Robo4J. If not, see . - */ -package com.robo4j; - -import com.robo4j.scheduler.RoboThreadFactory; -import com.robo4j.util.SystemUtil; -import org.slf4j.Logger; -import org.slf4j.LoggerFactory; - -import java.io.IOException; -import java.io.InputStream; -import java.util.concurrent.CountDownLatch; -import java.util.concurrent.Executors; -import java.util.concurrent.ScheduledExecutorService; -import java.util.concurrent.TimeUnit; - -import static com.robo4j.util.SystemUtil.BREAK; -import static com.robo4j.util.SystemUtil.DELIMITER_HORIZONTAL; - -/** - * RoboApplication used for launchWithExit the application from the command line - * - * @author Marcus Hirt (@hirt) - * @author Miroslav Wengner (@miragemiko) - */ -public final class RoboApplication { - private static final Logger LOGGER = LoggerFactory.getLogger(RoboApplication.class); - - private static final class ShutdownThread extends Thread { - - private final CountDownLatch latch; - - private ShutdownThread(CountDownLatch latch) { - this.latch = latch; - } - - @Override - public void run() { - latch.countDown(); - } - } - - private static final ScheduledExecutorService executor = Executors.newScheduledThreadPool(1, - new RoboThreadFactory(new ThreadGroup("Robo4J-Launcher"), "Robo4J-App-", false)); - private static final CountDownLatch appLatch = new CountDownLatch(1); - - - public RoboApplication() { - } - - /** - * the method is called by standalone robo launcher. - * - * @param context robo context - */ - public void launch(RoboContext context) { - // Create a new Launcher thread and then wait for that thread to finish - Runtime.getRuntime().addShutdownHook(new ShutdownThread(appLatch)); - try { - // TODO : review, exception runtime? - Thread daemon = new Thread(() -> { - try { - System.in.read(); - appLatch.countDown(); - } catch (IOException e) { - LOGGER.error("launch", e); - } - - }); - daemon.setName("Robo4J-Launcher-listener"); - daemon.setDaemon(true); - daemon.start(); - context.start(); - - String logo = getBanner(Thread.currentThread().getContextClassLoader()); - LOGGER.info(logo); - LOGGER.info(SystemUtil.printStateReport(context)); - LOGGER.info("Press ..."); - // TODO : introduce timeout - appLatch.await(); - LOGGER.info("Going down..."); - context.shutdown(); - LOGGER.info("Bye!"); - } catch (InterruptedException e) { - throw new RoboApplicationException("unexpected", e); - } - } - - public void launchWithExit(RoboContext context, long delay, TimeUnit timeUnit) { - executor.schedule(() -> Runtime.getRuntime().exit(0), delay, timeUnit); - launch(context); - - } - - public void launchNoExit(RoboContext context, long delay, TimeUnit timeUnit) { - executor.schedule(appLatch::countDown, delay, timeUnit); - launch(context); - } - - private String getBanner(ClassLoader classLoader) { - final InputStream is = classLoader.getResourceAsStream("banner.txt"); - final byte[] logoBytes; - try { - logoBytes = is == null ? new byte[0] : is.readAllBytes(); - } catch (IOException e) { - throw new IllegalStateException("not allowed"); - } - - return new StringBuilder().append(BREAK).append(DELIMITER_HORIZONTAL) - .append(new String(logoBytes)).append(BREAK).append(DELIMITER_HORIZONTAL) - .toString(); - } - -} diff --git a/robo4j-core/src/main/java/com/robo4j/RoboApplicationException.java b/robo4j-core/src/main/java/com/robo4j/RoboApplicationException.java deleted file mode 100644 index f6ae2df0..00000000 --- a/robo4j-core/src/main/java/com/robo4j/RoboApplicationException.java +++ /dev/null @@ -1,34 +0,0 @@ -/* - * Copyright (c) 2014, 2024, Marcus Hirt, Miroslav Wengner - * - * Robo4J is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Robo4J is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Robo4J. If not, see . - */ -package com.robo4j; - -import java.io.Serial; - -/** - * RoboApplicationException {@link RoboApplication} - * - * @author Marcus Hirt (@hirt) - * @author Miroslav Wengner (@miragemiko) - */ -public class RoboApplicationException extends RuntimeException { - @Serial - private static final long serialVersionUID = 1L; - - public RoboApplicationException(String message, Throwable cause) { - super(message, cause); - } -} diff --git a/robo4j-core/src/main/java/com/robo4j/RoboBuilder.java b/robo4j-core/src/main/java/com/robo4j/RoboBuilder.java index 178e9007..37a9eeac 100644 --- a/robo4j-core/src/main/java/com/robo4j/RoboBuilder.java +++ b/robo4j-core/src/main/java/com/robo4j/RoboBuilder.java @@ -92,18 +92,14 @@ private class RoboXMLHandler extends DefaultHandler { @Override public void startElement(String uri, String localName, String qName, Attributes attributes) throws SAXException { switch (qName) { - case ELEMENT_ROBO_UNIT: - currentId = attributes.getValue("id"); - break; - case SystemXMLHandler.ELEMENT_SYSTEM: - inSystemElement = true; - break; - case XmlConfigurationFactory.ELEMENT_CONFIG: + case ELEMENT_ROBO_UNIT -> currentId = attributes.getValue("id"); + case SystemXMLHandler.ELEMENT_SYSTEM -> inSystemElement = true; + case XmlConfigurationFactory.ELEMENT_CONFIG -> { if (!configState && !inSystemElement) { currentConfiguration = StringConstants.EMPTY; configState = true; - break; } + } } lastElement = qName; if (configState) { @@ -147,14 +143,8 @@ public void characters(char[] ch, int start, int length) throws SAXException { // NOTE(Marcus/Jan 22, 2017): Seems these can be called repeatedly // for a single text() node. switch (lastElement) { - case XmlConfigurationFactory.ELEMENT_CONFIG: - currentConfiguration += toString(ch, start, length); - break; - case "class": - currentClassName += toString(ch, start, length); - break; - default: - break; + case XmlConfigurationFactory.ELEMENT_CONFIG -> currentConfiguration += toString(ch, start, length); + case XmlConfigurationFactory.ELEMENT_CLASS -> currentClassName += toString(ch, start, length); } } @@ -202,15 +192,13 @@ private static class SystemXMLHandler extends DefaultHandler { @Override public void startElement(String uri, String localName, String qName, Attributes attributes) throws SAXException { switch (qName) { - case ELEMENT_SYSTEM: - currentId = attributes.getValue("id"); - break; - case XmlConfigurationFactory.ELEMENT_CONFIG: + case ELEMENT_SYSTEM -> currentId = attributes.getValue("id"); + case XmlConfigurationFactory.ELEMENT_CONFIG -> { if (!configState) { currentConfiguration = StringConstants.EMPTY; configState = true; - break; } + } } lastElement = qName; if (configState) { @@ -249,12 +237,8 @@ public void characters(char[] ch, int start, int length) throws SAXException { } // NOTE(Marcus/Jan 22, 2017): Seems these can be called repeatedly // for a single text() node. - switch (lastElement) { - case XmlConfigurationFactory.ELEMENT_CONFIG: - currentConfiguration += toString(ch, start, length); - break; - default: - break; + if (lastElement.equals(XmlConfigurationFactory.ELEMENT_CONFIG)) { + currentConfiguration += toString(ch, start, length); } } @@ -443,7 +427,7 @@ private void internalAddUnit(RoboUnit unit) throws RoboBuilderException { throw new RoboBuilderException("Cannot add the null unit! Skipping"); } else if (units.contains(unit)) { throw new RoboBuilderException( - "Only one unit with the id " + unit.getId() + " can be active at a time. Skipping " + unit.toString()); + "Only one unit with the id " + unit.id() + " can be active at a time. Skipping " + unit.toString()); } units.add(unit); } diff --git a/robo4j-core/src/main/java/com/robo4j/RoboBuilderException.java b/robo4j-core/src/main/java/com/robo4j/RoboBuilderException.java index c808b7ca..edfcc8ae 100644 --- a/robo4j-core/src/main/java/com/robo4j/RoboBuilderException.java +++ b/robo4j-core/src/main/java/com/robo4j/RoboBuilderException.java @@ -16,6 +16,8 @@ */ package com.robo4j; +import java.io.Serial; + /** * Exception thrown from the RoboBuilder. * @@ -23,6 +25,7 @@ * @author Miroslav Wengner (@miragemiko) */ public class RoboBuilderException extends Exception { + @Serial private static final long serialVersionUID = 1L; /** diff --git a/robo4j-core/src/main/java/com/robo4j/RoboReference.java b/robo4j-core/src/main/java/com/robo4j/RoboReference.java index 96aaa089..ef5bc16f 100644 --- a/robo4j-core/src/main/java/com/robo4j/RoboReference.java +++ b/robo4j-core/src/main/java/com/robo4j/RoboReference.java @@ -34,7 +34,7 @@ public interface RoboReference { * * @return the id for the unit. */ - String getId(); + String id(); /** * Returns the life cycle state (@see {@link LifecycleState}) of this unit. diff --git a/robo4j-core/src/main/java/com/robo4j/RoboSystem.java b/robo4j-core/src/main/java/com/robo4j/RoboSystem.java index aad75d80..02d6e0d0 100644 --- a/robo4j-core/src/main/java/com/robo4j/RoboSystem.java +++ b/robo4j-core/src/main/java/com/robo4j/RoboSystem.java @@ -18,7 +18,10 @@ import com.robo4j.configuration.Configuration; import com.robo4j.configuration.ConfigurationBuilder; -import com.robo4j.net.*; +import com.robo4j.net.ContextEmitter; +import com.robo4j.net.MessageServer; +import com.robo4j.net.ReferenceDescriptor; +import com.robo4j.net.RoboContextDescriptor; import com.robo4j.scheduler.DefaultScheduler; import com.robo4j.scheduler.RoboThreadFactory; import com.robo4j.scheduler.Scheduler; @@ -33,8 +36,19 @@ import java.net.SocketException; import java.net.URI; import java.net.UnknownHostException; -import java.util.*; -import java.util.concurrent.*; +import java.util.Collection; +import java.util.EnumSet; +import java.util.HashMap; +import java.util.Map; +import java.util.Objects; +import java.util.Set; +import java.util.UUID; +import java.util.WeakHashMap; +import java.util.concurrent.Future; +import java.util.concurrent.LinkedBlockingQueue; +import java.util.concurrent.ScheduledFuture; +import java.util.concurrent.ThreadPoolExecutor; +import java.util.concurrent.TimeUnit; import java.util.concurrent.atomic.AtomicReference; import java.util.stream.Collectors; @@ -48,8 +62,8 @@ */ final class RoboSystem implements RoboContext { private static final Logger LOGGER = LoggerFactory.getLogger(RoboSystem.class); - private static final String NAME_BLOCKING_POOL = "Robo4J Blocking Pool"; - private static final String NAME_WORKER_POOL = "Robo4J Worker Pool"; + private static final String THREAD_GROUP_BLOCKING_NAME_BLOCKING_POOL = "Robo4J Blocking Pool"; + private static final String THREAD_GROUP_NAME_WORKER_POOL = "Robo4J Worker Pool"; private static final int DEFAULT_BLOCKING_POOL_SIZE = 4; private static final int DEFAULT_WORKER_POOL_SIZE = 2; private static final int DEFAULT_SCHEDULER_POOL_SIZE = 2; @@ -57,6 +71,8 @@ final class RoboSystem implements RoboContext { private static final EnumSet MESSAGE_DELIVERY_CRITERIA = EnumSet.of(LifecycleState.STARTED, LifecycleState.STOPPED, LifecycleState.STOPPING); + private static final int SERVER_LISTEN_URI_MILLIS = 100; + private static final int SERVER_LISTEN_REPEATS = 5; private final AtomicReference state = new AtomicReference<>(LifecycleState.UNINITIALIZED); private final Map> units = new HashMap<>(); @@ -65,6 +81,7 @@ final class RoboSystem implements RoboContext { private final Scheduler systemScheduler; private final ThreadPoolExecutor workExecutor; + // TODO: review usage of workQueue and blockingQueue, maybe better abstraction private final LinkedBlockingQueue workQueue = new LinkedBlockingQueue<>(); private final ThreadPoolExecutor blockingExecutor; @@ -119,8 +136,8 @@ private DeliveryPolicy deriveDeliveryPolicy(Class> clazz) } @Override - public String getId() { - return unit.getId(); + public String id() { + return unit.id(); } @Override @@ -153,22 +170,15 @@ public void sendMessage(T message) { @Override public String toString() { - return "LocalReference id: " + unit.getId() + " (system: " + uid + ")"; + return "LocalReference id: " + unit.id() + " (system: " + uid + ")"; } private void deliverOnQueue(T message) { switch (deliveryPolicy) { - case SYSTEM: - systemScheduler.execute(new Messenger(unit, message)); - break; - case WORK: - workExecutor.execute(new Messenger(unit, message)); - break; - case BLOCKING: - blockingExecutor.execute(new Messenger(unit, message)); - break; - default: - LOGGER_LOCAL.error("not supported policy: {}", deliveryPolicy); + case SYSTEM -> systemScheduler.execute(new Messenger(unit, message)); + case WORK -> workExecutor.execute(new Messenger(unit, message)); + case BLOCKING -> blockingExecutor.execute(new Messenger(unit, message)); + default -> LOGGER_LOCAL.error("not supported policy: {}", deliveryPolicy); } } @@ -194,7 +204,7 @@ public Class getMessageType() { @Serial Object writeReplace() throws ObjectStreamException { - return new ReferenceDescriptor(RoboSystem.this.getId(), getId(), getMessageType().getName()); + return new ReferenceDescriptor(RoboSystem.this.getId(), id(), getMessageType().getName()); } } @@ -214,7 +224,7 @@ public void run() { try { unit.onMessage(message); } catch (Throwable t) { - LOGGER_MESSENGER.error("Error processing message, unit:{}", unit.getId(), t); + LOGGER_MESSENGER.error("Error processing message, unit:{}", unit.id(), t); } } } @@ -242,10 +252,19 @@ public void run() { int schedulerPoolSize = configuration.getInteger(RoboBuilder.KEY_SCHEDULER_POOL_SIZE, DEFAULT_SCHEDULER_POOL_SIZE); int workerPoolSize = configuration.getInteger(RoboBuilder.KEY_WORKER_POOL_SIZE, DEFAULT_WORKER_POOL_SIZE); int blockingPoolSize = configuration.getInteger(RoboBuilder.KEY_BLOCKING_POOL_SIZE, DEFAULT_SCHEDULER_POOL_SIZE); - workExecutor = new ThreadPoolExecutor(workerPoolSize, workerPoolSize, KEEP_ALIVE_TIME, TimeUnit.SECONDS, workQueue, - new RoboThreadFactory(new ThreadGroup(NAME_WORKER_POOL), NAME_WORKER_POOL, true)); - blockingExecutor = new ThreadPoolExecutor(blockingPoolSize, blockingPoolSize, KEEP_ALIVE_TIME, TimeUnit.SECONDS, blockingQueue, - new RoboThreadFactory(new ThreadGroup(NAME_BLOCKING_POOL), NAME_BLOCKING_POOL, true)); + + var workThreadFactory = new RoboThreadFactory + .Builder(THREAD_GROUP_NAME_WORKER_POOL) + .addThreadPrefix(THREAD_GROUP_NAME_WORKER_POOL) + .build(); + + var blockingThreadFactory = new RoboThreadFactory + .Builder(THREAD_GROUP_BLOCKING_NAME_BLOCKING_POOL) + .addThreadPrefix(THREAD_GROUP_BLOCKING_NAME_BLOCKING_POOL) + .build(); + + workExecutor = new ThreadPoolExecutor(workerPoolSize, workerPoolSize, KEEP_ALIVE_TIME, TimeUnit.SECONDS, workQueue, workThreadFactory); + blockingExecutor = new ThreadPoolExecutor(blockingPoolSize, blockingPoolSize, KEEP_ALIVE_TIME, TimeUnit.SECONDS, blockingQueue, blockingThreadFactory); systemScheduler = new DefaultScheduler(this, schedulerPoolSize); messageServer = initServer(configuration.getChildConfiguration(RoboBuilder.KEY_CONFIGURATION_SERVER)); emitterConfiguration = configuration.getChildConfiguration(RoboBuilder.KEY_CONFIGURATION_EMITTER); @@ -296,34 +315,25 @@ public void addUnits(RoboUnit... units) { @Override public void start() { - if (state.compareAndSet(LifecycleState.STOPPED, LifecycleState.STARTING)) { - // NOTE(Marcus/Sep 4, 2017): Do we want to support starting a - // stopped system? - startUnits(); - } - if (state.compareAndSet(LifecycleState.INITIALIZED, LifecycleState.STARTING)) { - startUnits(); - } - - // This is only used from testing for now, it should never happen from - // the builder. - if (state.compareAndSet(LifecycleState.UNINITIALIZED, LifecycleState.STARTING)) { - startUnits(); + var currentState = state.get(); + switch (currentState) { + case INITIALIZED, STOPPED -> { + state.compareAndSet(currentState, LifecycleState.STARTING); + startUnits(); + } } - // If we have a server, start it, then set up emitter - blockingExecutor.execute(new Runnable() { - @Override - public void run() { - if (messageServer != null) { - try { - messageServer.start(); - } catch (IOException e) { - LOGGER.error("Could not start the message server. Proceeding without.", e); - } + blockingExecutor.execute(() -> { + if (messageServer != null) { + try { + messageServer.start(); + } catch (IOException e) { + LOGGER.error("Could not start the message server. Proceeding without.", e); } } }); + + // TODO : make emitter configurable final ContextEmitter emitter = initEmitter(emitterConfiguration, getListeningURI(messageServer)); if (emitter != null) { emitterFuture = getScheduler().scheduleAtFixedRate(emitter::emit, 0, emitter.getHeartBeatInterval(), TimeUnit.MILLISECONDS); @@ -369,12 +379,7 @@ public void shutdown() { // Then schedule shutdowns on the scheduler threads... for (RoboUnit unit : units.values()) { - getScheduler().execute(new Runnable() { - @Override - public void run() { - RoboSystem.shutdownUnit(unit); - } - }); + getScheduler().execute(() -> RoboSystem.shutdownUnit(unit)); } // Then shutdown the system scheduler. Will wait until the termination @@ -447,13 +452,13 @@ private RoboReference createReference(RoboUnit roboUnit) { } private void addToMap(Set> unitSet) { - unitSet.forEach(unit -> units.put(unit.getId(), unit)); + unitSet.forEach(unit -> units.put(unit.id(), unit)); } private void addToMap(RoboUnit... unitArray) { // NOTE(Marcus/Aug 9, 2017): Do not streamify... for (RoboUnit unit : unitArray) { - units.put(unit.getId(), unit); + units.put(unit.id(), unit); } } @@ -471,11 +476,9 @@ private static Configuration createConfiguration(int schedulerPoolSize, int work private MessageServer initServer(Configuration serverConfiguration) { if (serverConfiguration != null) { - return new MessageServer(new MessageCallback() { - @Override - public void handleMessage(String sourceUuid, String id, Object message) { - getReference(id).sendMessage(message); - } + return new MessageServer((sourceUuid, id, message) -> { + // TODO: save message null message or not registered id + Objects.requireNonNull(getReference(id)).sendMessage(message); }, serverConfiguration); } else { return null; @@ -517,14 +520,16 @@ private Map toStringMap(Configuration configuration) { private static URI getListeningURI(MessageServer server) { if (server != null) { - for (int i = 0; i < 5; i++) { + for (int i = 0; i < SERVER_LISTEN_REPEATS; i++) { URI uri = server.getListeningURI(); if (uri != null) { return uri; } - SystemUtil.sleep(100); + SystemUtil.sleep(SERVER_LISTEN_URI_MILLIS); } + LOGGER.warn("getListeningURI server:{}, not found", server); } + LOGGER.warn("getListeningURI undefined server"); return null; } } diff --git a/robo4j-core/src/main/java/com/robo4j/RoboUnit.java b/robo4j-core/src/main/java/com/robo4j/RoboUnit.java index 570ee9e1..dca09210 100644 --- a/robo4j-core/src/main/java/com/robo4j/RoboUnit.java +++ b/robo4j-core/src/main/java/com/robo4j/RoboUnit.java @@ -22,271 +22,252 @@ import java.util.Collections; import java.util.HashMap; import java.util.Map; +import java.util.Objects; import java.util.concurrent.Future; /** * The core component. Subclass this to provide a messaging capable agent for a * robot component. - * + * * @author Marcus Hirt (@hirt) * @author Miroslav Wengner (@miragemiko) */ public abstract class RoboUnit implements RoboReference { - // Yay for erasure - private final Class messageType; - private final RoboContext context; - private final String id; - private volatile LifecycleState state = LifecycleState.UNINITIALIZED; - private RoboReference reference; - private Configuration configuration; + // Yay for erasure + private final Class messageType; + private final RoboContext context; + private final String id; + private volatile LifecycleState state = LifecycleState.UNINITIALIZED; + private RoboReference reference; + private Configuration configuration; - /** - * Constructor. - * - * @param messageType - * messageType - * @param context - * desired Robo context - * @param id - * id of RoboUnit - */ - public RoboUnit(Class messageType, RoboContext context, String id) { - this.messageType = messageType; - this.context = context; - this.id = id; - if (context instanceof RoboSystem) { - reference = ((RoboSystem) context).getReference(this); - } - } + /** + * Constructor. + * + * @param messageType messageType + * @param context desired Robo context + * @param id id of RoboUnit + */ + public RoboUnit(Class messageType, RoboContext context, String id) { + this.messageType = messageType; + this.context = context; + this.id = id; + if (context instanceof RoboSystem) { + reference = ((RoboSystem) context).getReference(this); + } + } - /** - * @return the {@link RoboSystem} unique identifier for this unit. - */ - @Override - public String getId() { - return id; - } + /** + * @return the {@link RoboSystem} unique identifier for this unit. + */ + @Override + public String id() { + return id; + } - /** - * @return the {@link RoboContext} associated with this unit. - */ - public RoboContext getContext() { - return context; - } + /** + * @return the {@link RoboContext} associated with this unit. + */ + public RoboContext getContext() { + return context; + } - /** - * If initializing the unit programmatically, call unit with the proper - * configuration. - * - * @param configuration - * the {@link Configuration} provided. - * @throws ConfigurationException - * possible exception - */ - public void initialize(Configuration configuration) throws ConfigurationException { - setConfiguration(configuration); - onInitialization(configuration); - setState(LifecycleState.INITIALIZED); - } + /** + * If initializing the unit programmatically, call unit with the proper + * configuration. + * + * @param configuration the {@link Configuration} provided. + * @throws ConfigurationException possible exception + */ + public void initialize(Configuration configuration) throws ConfigurationException { + setConfiguration(configuration); + onInitialization(configuration); + setState(LifecycleState.INITIALIZED); + } - /** - * Should be implemented by subclasses to do the actual Unit specific part of - * the initialization. - * - * @param configuration - * the {@link Configuration} provided. - * @throws ConfigurationException - * possible exception - */ - protected void onInitialization(Configuration configuration) throws ConfigurationException { - } + /** + * Should be implemented by subclasses to do the actual Unit specific part of + * the initialization. + * + * @param configuration the {@link Configuration} provided. + * @throws ConfigurationException possible exception + */ + protected void onInitialization(Configuration configuration) throws ConfigurationException { + } - /** - * Should be overridden in subclasses which need to do some initialization on - * start. - */ - public void start() { - } + /** + * Should be overridden in subclasses which need to do some initialization on + * start. + */ + public void start() { + } - /** - * Should be overridden in subclasses needing to do some work when stopping. - */ - public void stop() { - } + /** + * Should be overridden in subclasses needing to do some work when stopping. + */ + public void stop() { + } - /** - * Should be overridden in subclasses needing to do some work when shutting - * down. - */ - public void shutdown() { - } + /** + * Should be overridden in subclasses needing to do some work when shutting + * down. + */ + public void shutdown() { + } - /** - * Returns the state of this unit. - * - * @return the state in the life cycle of this unit. - */ - @Override - public LifecycleState getState() { - return state; - } + /** + * Returns the state of this unit. + * + * @return the state in the life cycle of this unit. + */ + @Override + public LifecycleState getState() { + return state; + } - /** - * It is considered good form to return the types that you can respond to. This - * method should be overriden in subclasses. Note that it is allowed for an - * agent to return the empty set. Returning null is not allowed. - * - * @return the message types accepted by this unit. - */ - public Collection> getAcceptedMessageTypes() { - return Collections.emptySet(); - } + /** + * It is considered good form to return the types that you can respond to. This + * method should be overriden in subclasses. Note that it is allowed for an + * agent to return the empty set. Returning null is not allowed. + * + * @return the message types accepted by this unit. + */ + public Collection> getAcceptedMessageTypes() { + return Collections.emptySet(); + } - /** - * Changes the {@link LifecycleState}. - * - * @param state - * the state to change to. - * - * @see LifecycleState for allowable transitions. - */ - public void setState(LifecycleState state) { - this.state = state; - } + /** + * Changes the {@link LifecycleState}. + * + * @param state the state to change to. + * @see LifecycleState for allowable transitions. + */ + public void setState(LifecycleState state) { + this.state = state; + } - @Override - public Configuration getConfiguration() { - return configuration; - } + @Override + public Configuration getConfiguration() { + return configuration; + } - /** - * Sends a message to this unit by posting a message on the message bus. - * - * @see #onMessage(Object) - */ - @Override - public void sendMessage(T message) { - reference.sendMessage(message); - } + /** + * Sends a message to this unit by posting a message on the message bus. + * + * @see #onMessage(Object) + */ + @Override + public void sendMessage(T message) { + reference.sendMessage(message); + } - /** - * Will post a message to get the attributes on the message queue. - * - * @see #onGetAttributes() - */ - @Override - public Future, Object>> getAttributes() { - return reference.getAttributes(); - } + /** + * Will post a message to get the attributes on the message queue. + * + * @see #onGetAttributes() + */ + @Override + public Future, Object>> getAttributes() { + return reference.getAttributes(); + } - /** - * Retrieves an attribute from this unit. - * - * @see #getAttribute(AttributeDescriptor) - */ - @Override - public Future getAttribute(AttributeDescriptor attribute) { - return reference.getAttribute(attribute); - } + /** + * Retrieves an attribute from this unit. + * + * @see #getAttribute(AttributeDescriptor) + */ + @Override + public Future getAttribute(AttributeDescriptor attribute) { + return reference.getAttribute(attribute); + } - /** - * Override in subclasses to expose the attributes known. - */ - @Override - public Collection> getKnownAttributes() { - return Collections.emptyList(); - } + /** + * Override in subclasses to expose the attributes known. + */ + @Override + public Collection> getKnownAttributes() { + return Collections.emptyList(); + } - @Override - public Class getMessageType() { - return messageType; - } + @Override + public Class getMessageType() { + return messageType; + } - /** - * Should be overridden in subclasses to define the behaviour of the unit. This - * method should normally not be called directly, unless you have a very good - * reason. It is used by the system to deliver messages to the unit. - * - * @param message - * the message received by this unit. - * - */ - public void onMessage(T message) { - // Note that this method is public so the scheduler has access. We may - // want to consider other means of accessing it to keep it protected. - } + /** + * Should be overridden in subclasses to define the behaviour of the unit. This + * method should normally not be called directly, unless you have a very good + * reason. It is used by the system to deliver messages to the unit. + * + * @param message the message received by this unit. + */ + public void onMessage(T message) { + // Note that this method is public so the scheduler has access. We may + // want to consider other means of accessing it to keep it protected. + } - /** - * May be overridden in subclasses for more performance. The default - * implementation will get the job done though. - * - * @return the map of all the attributes. - */ - protected Map, Object> onGetAttributes() { - Map, Object> result = new HashMap<>(); - Collection> knownAttributes = getKnownAttributes(); - for (AttributeDescriptor descriptor : knownAttributes) { - result.put(descriptor, getAttribute(descriptor)); - } - return result; - } + /** + * May be overridden in subclasses for more performance. The default + * implementation will get the job done though. + * + * @return the map of all the attributes. + */ + protected Map, Object> onGetAttributes() { + var result = new HashMap, Object>(); + Collection> knownAttributes = getKnownAttributes(); + for (AttributeDescriptor descriptor : knownAttributes) { + result.put(descriptor, getAttribute(descriptor)); + } + return result; + } - /** - * Should be overridden in subclasses to provide attributes. - * - * @param descriptor - * the descriptor for which to return the attribute. - * @param - * attribute descriptor - * @return the attribute value. - */ - protected R onGetAttribute(AttributeDescriptor descriptor) { - return null; - } + /** + * Should be overridden in subclasses to provide attributes. + * + * @param descriptor the descriptor for which to return the attribute. + * @param attribute descriptor + * @return the attribute value. + */ + protected R onGetAttribute(AttributeDescriptor descriptor) { + return null; + } - /** - * @return a RoboReference. Internal use only. - */ - RoboReference internalGetReference() { - // NOTE(Marcus/Jan 27, 2017): Can we avoid this? - if (reference == null) { - return getContext().getReference(getId()); - } else { - return reference; - } - } + /** + * @return a RoboReference. Internal use only. + */ + RoboReference internalGetReference() { + // NOTE(Marcus/Jan 27, 2017): Can we avoid this? + if (reference == null) { + return getContext().getReference(id()); + } else { + return reference; + } + } - private void setConfiguration(Configuration configuration) { - this.configuration = configuration; - } + private void setConfiguration(Configuration configuration) { + this.configuration = configuration; + } - @Override - public int hashCode() { - return id.hashCode(); - } + @Override + public boolean equals(Object object) { + if (this == object) return true; + if (object == null) return false; + RoboUnit roboUnit = (RoboUnit) object; + return Objects.equals(id, roboUnit.id); + } - @Override - public boolean equals(Object obj) { - if (this == obj) - return true; - if (obj == null) - return false; - RoboUnit other = (RoboUnit) obj; - if (id == null) { - if (other.id != null) - return false; - } else if (!id.equals(other.id)) - return false; - return true; - } + @Override + public int hashCode() { + return Objects.hashCode(id); + } - /* - * (non-Javadoc) - * - * @see java.lang.Object#toString() - */ - @Override - public String toString() { - return String.format("%s [id=%s]", getClass().getName(), getId()); - } + /* + * (non-Javadoc) + * + * @see java.lang.Object#toString() + */ + @Override + public String toString() { + return String.format("%s [id=%s]", getClass().getName(), id()); + } } diff --git a/robo4j-core/src/main/java/com/robo4j/configuration/ConfigurationFactoryException.java b/robo4j-core/src/main/java/com/robo4j/configuration/ConfigurationFactoryException.java index d3fde59b..6e575c85 100644 --- a/robo4j-core/src/main/java/com/robo4j/configuration/ConfigurationFactoryException.java +++ b/robo4j-core/src/main/java/com/robo4j/configuration/ConfigurationFactoryException.java @@ -16,6 +16,8 @@ */ package com.robo4j.configuration; +import java.io.Serial; + /** * Exception for when failing to create a configuration. * @@ -23,6 +25,7 @@ * @author Miroslav Wengner (@miragemiko) */ public class ConfigurationFactoryException extends Exception { + @Serial private static final long serialVersionUID = 1L; /** diff --git a/robo4j-core/src/main/java/com/robo4j/configuration/DefaultConfiguration.java b/robo4j-core/src/main/java/com/robo4j/configuration/DefaultConfiguration.java index 8360b464..3faa2eae 100644 --- a/robo4j-core/src/main/java/com/robo4j/configuration/DefaultConfiguration.java +++ b/robo4j-core/src/main/java/com/robo4j/configuration/DefaultConfiguration.java @@ -16,164 +16,148 @@ */ package com.robo4j.configuration; +import java.io.Serial; import java.util.HashMap; import java.util.Map; +import java.util.Objects; import java.util.Set; /** * Default implementation of a {@link Configuration}. - * + * *

* Internal Use Only *

- * + * * @author Marcus Hirt (@hirt) * @author Miroslav Wengner (@miragemiko) */ class DefaultConfiguration implements Configuration { - private static final long serialVersionUID = 1L; - private final Map settings = new HashMap<>(); - private final Map configurations = new HashMap<>(); - - @Override - public Configuration getChildConfiguration(String name) { - return configurations.get(name); - } - - @Override - public Double getDouble(String name, Double defaultValue) { - return (Double) getVal(name, defaultValue); - } - - @Override - public Long getLong(String name, Long defaultValue) { - return (Long) getVal(name, defaultValue); - } - - @Override - public String getString(String name, String defaultValue) { - return (String) getVal(name, defaultValue); - } - - public void setString(String name, String s) { - settings.put(name, s); - } - - @Override - public Character getCharacter(String name, Character defaultValue) { - return (Character) getVal(name, defaultValue); - } - - @Override - public Integer getInteger(String name, Integer defaultValue) { - return (Integer) getVal(name, defaultValue); - } - - @Override - public Float getFloat(String name, Float defaultValue) { - return (Float) getVal(name, defaultValue); - } - - @Override - public Set getValueNames() { - return settings.keySet(); - } - - @Override - public Set getChildNames() { - return configurations.keySet(); - } - - @Override - public Object getValue(String name, Object defaultValue) { - return getVal(name, defaultValue); - } - - @Override - public Boolean getBoolean(String name, Boolean defaultValue) { - return (Boolean) getVal(name, defaultValue); - } - - public Configuration createChildConfiguration(String name) { - DefaultConfiguration config = new DefaultConfiguration(); - configurations.put(name, config); - return config; - } - - public void setBoolean(String name, Boolean b) { - settings.put(name, b); - } - - public void setCharacter(String name, Character s) { - settings.put(name, s); - } - - public void setLong(String name, Long l) { - settings.put(name, l); - } - - public void setDouble(String name, Double d) { - settings.put(name, d); - } - - public void setInteger(String name, Integer i) { - settings.put(name, i); - } - - public void setFloat(String name, Float f) { - settings.put(name, f); - } - - - private Object getVal(String name, Object defaultValue) { - Object val = settings.get(name); - if (val == null) { - return defaultValue; - } - return val; - } - - // TODO : we may have it wrong here hashCode, equals - @Override - public int hashCode() { - final int prime = 31; - int result = 1; - result = prime * result + ((configurations == null) ? 0 : configurations.hashCode()); - result = prime * result + ((settings == null) ? 0 : settings.hashCode()); - return result; - } - - @Override - public boolean equals(Object obj) { - if (this == obj) - return true; - if (obj == null) - return false; - if (getClass() != obj.getClass()) - return false; - DefaultConfiguration other = (DefaultConfiguration) obj; - if (configurations == null) { - if (other.configurations != null) - return false; - } else if (!configurations.equals(other.configurations)) - return false; - if (settings == null) { - if (other.settings != null) - return false; - } else if (!settings.equals(other.settings)) - return false; - return true; - } - - @Override - public String toString() { - return "Settings: " + settings.toString() + " Configurations: " + configurations.toString(); - } - - /* - * Package local, to be used by the builder. - */ - void addChildConfiguration(String name, Configuration config) { - configurations.put(name, config); - } + @Serial + private static final long serialVersionUID = 1L; + private final Map settings = new HashMap<>(); + private final Map configurations = new HashMap<>(); + + @Override + public Configuration getChildConfiguration(String name) { + return configurations.get(name); + } + + @Override + public Double getDouble(String name, Double defaultValue) { + return (Double) getVal(name, defaultValue); + } + + @Override + public Long getLong(String name, Long defaultValue) { + return (Long) getVal(name, defaultValue); + } + + @Override + public String getString(String name, String defaultValue) { + return (String) getVal(name, defaultValue); + } + + public void setString(String name, String s) { + settings.put(name, s); + } + + @Override + public Character getCharacter(String name, Character defaultValue) { + return (Character) getVal(name, defaultValue); + } + + @Override + public Integer getInteger(String name, Integer defaultValue) { + return (Integer) getVal(name, defaultValue); + } + + @Override + public Float getFloat(String name, Float defaultValue) { + return (Float) getVal(name, defaultValue); + } + + @Override + public Set getValueNames() { + return settings.keySet(); + } + + @Override + public Set getChildNames() { + return configurations.keySet(); + } + + @Override + public Object getValue(String name, Object defaultValue) { + return getVal(name, defaultValue); + } + + @Override + public Boolean getBoolean(String name, Boolean defaultValue) { + return (Boolean) getVal(name, defaultValue); + } + + public Configuration createChildConfiguration(String name) { + DefaultConfiguration config = new DefaultConfiguration(); + configurations.put(name, config); + return config; + } + + public void setBoolean(String name, Boolean b) { + settings.put(name, b); + } + + public void setCharacter(String name, Character s) { + settings.put(name, s); + } + + public void setLong(String name, Long l) { + settings.put(name, l); + } + + public void setDouble(String name, Double d) { + settings.put(name, d); + } + + public void setInteger(String name, Integer i) { + settings.put(name, i); + } + + public void setFloat(String name, Float f) { + settings.put(name, f); + } + + + private Object getVal(String name, Object defaultValue) { + Object val = settings.get(name); + if (val == null) { + return defaultValue; + } + return val; + } + + @Override + public boolean equals(Object object) { + if (this == object) return true; + if (object == null || getClass() != object.getClass()) return false; + DefaultConfiguration that = (DefaultConfiguration) object; + return Objects.equals(settings, that.settings) && Objects.equals(configurations, that.configurations); + } + + @Override + public int hashCode() { + return Objects.hash(settings, configurations); + } + + @Override + public String toString() { + return "Settings: " + settings.toString() + " Configurations: " + configurations.toString(); + } + + /* + * Package local, to be used by the builder. + */ + void addChildConfiguration(String name, Configuration config) { + configurations.put(name, config); + } } diff --git a/robo4j-core/src/main/java/com/robo4j/configuration/XmlConfigurationFactory.java b/robo4j-core/src/main/java/com/robo4j/configuration/XmlConfigurationFactory.java index ff681b95..2b52d51c 100644 --- a/robo4j-core/src/main/java/com/robo4j/configuration/XmlConfigurationFactory.java +++ b/robo4j-core/src/main/java/com/robo4j/configuration/XmlConfigurationFactory.java @@ -16,20 +16,18 @@ */ package com.robo4j.configuration; -import java.io.ByteArrayInputStream; -import java.io.IOException; -import java.util.ArrayDeque; -import java.util.Deque; - -import javax.xml.parsers.ParserConfigurationException; -import javax.xml.parsers.SAXParser; -import javax.xml.parsers.SAXParserFactory; - +import com.robo4j.util.StringConstants; import org.xml.sax.Attributes; import org.xml.sax.SAXException; import org.xml.sax.helpers.DefaultHandler; -import com.robo4j.util.StringConstants; +import javax.xml.parsers.ParserConfigurationException; +import javax.xml.parsers.SAXParser; +import javax.xml.parsers.SAXParserFactory; +import java.io.ByteArrayInputStream; +import java.io.IOException; +import java.util.ArrayDeque; +import java.util.Deque; /** * Factory for creating configurations from XML and vice versa. @@ -39,6 +37,7 @@ */ public class XmlConfigurationFactory { public static final String ELEMENT_CONFIG = "config"; + public static final String ELEMENT_CLASS = "class"; public static final String ATTRIBUTE_NAME = "name"; public static final String ATTRIBUTE_TYPE = "type"; public static final String ATTRIBUTE_PATH = "path"; diff --git a/robo4j-core/src/main/java/com/robo4j/net/ClientRemoteRoboContext.java b/robo4j-core/src/main/java/com/robo4j/net/ClientRemoteRoboContext.java index eda8ffa1..cbcefe4c 100644 --- a/robo4j-core/src/main/java/com/robo4j/net/ClientRemoteRoboContext.java +++ b/robo4j-core/src/main/java/com/robo4j/net/ClientRemoteRoboContext.java @@ -23,6 +23,8 @@ import com.robo4j.configuration.Configuration; import com.robo4j.configuration.ConfigurationFactory; import com.robo4j.scheduler.Scheduler; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; import java.io.IOException; import java.net.InetAddress; @@ -32,128 +34,116 @@ import java.util.concurrent.Future; /** - * * @author Marcus Hirt (@hirt) * @author Miroslav Wengner (@miragemiko) */ public class ClientRemoteRoboContext implements RoboContext { - private final RoboContextDescriptorEntry descriptorEntry; - private final MessageClient client; - - private class ClientRemoteRoboReference implements RoboReference { - - private final String id; - - public ClientRemoteRoboReference(String id) { - this.id = id; - } - - @Override - public String getId() { - return id; - } - - @Override - public LifecycleState getState() { - throw new UnsupportedOperationException("Not supported yet!"); - } - - @Override - public void sendMessage(Object message) { - try { - if (!client.isConnected()) { - client.connect(); - } - client.sendMessage(id, message); - } catch (IOException e) { - // TODO: Error handling - e.printStackTrace(); - } - } - - @Override - public Class getMessageType() { - throw new UnsupportedOperationException("Not supported yet!"); - } - - @Override - public Configuration getConfiguration() { - throw new UnsupportedOperationException("Not supported yet!"); - } - - @Override - public Future getAttribute(AttributeDescriptor attribute) { - throw new UnsupportedOperationException("Not supported yet!"); - } - - @Override - public Collection> getKnownAttributes() { - throw new UnsupportedOperationException("Not supported yet!"); - } - - @Override - public Future, Object>> getAttributes() { - throw new UnsupportedOperationException("Not supported yet!"); - } - - } - - public ClientRemoteRoboContext(RoboContextDescriptorEntry descriptorEntry) { - this.descriptorEntry = descriptorEntry; - client = initializeClient(descriptorEntry); - } - - private static MessageClient initializeClient(RoboContextDescriptorEntry descriptorEntry) { - MessageClient client = new MessageClient(URI.create(descriptorEntry.descriptor.getMetadata().get(RoboContextDescriptor.KEY_URI)), - descriptorEntry.descriptor.getId(), ConfigurationFactory.createEmptyConfiguration()); - return client; - } - - @Override - public LifecycleState getState() { - return null; - } - - @Override - public void shutdown() { - } - - @Override - public void stop() { - } - - @Override - public void start() { - } - - @Override - public RoboReference getReference(String id) { - return new ClientRemoteRoboReference<>(id); - } - - @Override - public Collection> getUnits() { - // TODO Auto-generated method stub - return null; - } - - @Override - public Scheduler getScheduler() { - throw new UnsupportedOperationException("Accessing the Scheduler remotely is not supported. Use the local scheduler."); - } - - @Override - public String getId() { - return descriptorEntry.descriptor.getId(); - } - - public InetAddress getAddress() { - return descriptorEntry.address; - } - - @Override - public Configuration getConfiguration() { - // TODO Auto-generated method stub - return null; - } + private record ClientRemoteRoboReference(String id, MessageClient client) implements RoboReference { + private static final Logger LOGGER = LoggerFactory.getLogger(ClientRemoteRoboReference.class); + + + @Override + public LifecycleState getState() { + throw new UnsupportedOperationException("Not supported yet!"); + } + + @Override + public void sendMessage(Object message) { + try { + if (!client.isConnected()) { + client.connect(); + } + client.sendMessage(id, message); + } catch (IOException e) { + LOGGER.error(e.getMessage(), e); + } + } + + @Override + public Class getMessageType() { + throw new UnsupportedOperationException("Not supported yet!"); + } + + @Override + public Configuration getConfiguration() { + throw new UnsupportedOperationException("Not supported yet!"); + } + + @Override + public Future getAttribute(AttributeDescriptor attribute) { + throw new UnsupportedOperationException("Not supported yet!"); + } + + @Override + public Collection> getKnownAttributes() { + throw new UnsupportedOperationException("Not supported yet!"); + } + + @Override + public Future, Object>> getAttributes() { + throw new UnsupportedOperationException("Not supported yet!"); + } + + } + + private static MessageClient initializeClient(RoboContextDescriptorEntry descriptorEntry) { + return new MessageClient(URI.create(descriptorEntry.descriptor.getMetadata().get(RoboContextDescriptor.KEY_URI)), + descriptorEntry.descriptor.getId(), ConfigurationFactory.createEmptyConfiguration()); + } + + private final RoboContextDescriptorEntry descriptorEntry; + private final MessageClient client; + + ClientRemoteRoboContext(RoboContextDescriptorEntry descriptorEntry) { + this.descriptorEntry = descriptorEntry; + client = initializeClient(descriptorEntry); + } + + @Override + public LifecycleState getState() { + return null; + } + + @Override + public void shutdown() { + } + + @Override + public void stop() { + } + + @Override + public void start() { + } + + @Override + public RoboReference getReference(String id) { + return new ClientRemoteRoboReference<>(id, client); + } + + @Override + public Collection> getUnits() { + // TODO Auto-generated method stub + return null; + } + + @Override + public Scheduler getScheduler() { + throw new UnsupportedOperationException("Accessing the Scheduler remotely is not supported. Use the local scheduler."); + } + + @Override + public String getId() { + return descriptorEntry.descriptor.getId(); + } + + public InetAddress getAddress() { + return descriptorEntry.address; + } + + @Override + public Configuration getConfiguration() { + // TODO Auto-generated method stub + return null; + } } diff --git a/robo4j-core/src/main/java/com/robo4j/net/ContextEmitter.java b/robo4j-core/src/main/java/com/robo4j/net/ContextEmitter.java index cd29e44b..51cc0565 100644 --- a/robo4j-core/src/main/java/com/robo4j/net/ContextEmitter.java +++ b/robo4j-core/src/main/java/com/robo4j/net/ContextEmitter.java @@ -22,7 +22,11 @@ import org.slf4j.LoggerFactory; import java.io.IOException; -import java.net.*; +import java.net.DatagramPacket; +import java.net.DatagramSocket; +import java.net.InetAddress; +import java.net.SocketException; +import java.net.UnknownHostException; /** * This class is used by the {@link RoboContext} to make it discoverable. This @@ -69,19 +73,19 @@ public final class ContextEmitter { /** * Constructor. * - * @param entry the information to emit. - * @param multicastAddress the address to emit to. - * @param port the port. - * @param heartBeatInterval the heart beat interval + * @param entry the information to emit. + * @param multicastAddress the address to emit to. + * @param port the port. + * @param heartBeatIntervalMills the heart beat interval in milliseconds * @throws SocketException possible exception */ - public ContextEmitter(RoboContextDescriptor entry, InetAddress multicastAddress, int port, int heartBeatInterval) + public ContextEmitter(RoboContextDescriptor entry, InetAddress multicastAddress, int port, int heartBeatIntervalMills) throws SocketException { this.multicastAddress = multicastAddress; this.port = port; - this.heartBeatInterval = heartBeatInterval; - socket = new DatagramSocket(); - message = HearbeatMessageCodec.encode(entry); + this.heartBeatInterval = heartBeatIntervalMills; + this.socket = new DatagramSocket(); + this.message = HearbeatMessageCodec.encode(entry); } public ContextEmitter(RoboContextDescriptor entry, Configuration emitterConfiguration) @@ -100,21 +104,23 @@ public void emit() { try { emitWithException(); } catch (IOException e) { + // TODO: properly report the exception LOGGER.error("Failed to emit heartbeat message", e); } } + + public int getHeartBeatInterval() { + return heartBeatInterval; + } + /** * Emits a context heartbeat message. Will throw an exception on trouble. * * @throws IOException exception */ - public void emitWithException() throws IOException { + private void emitWithException() throws IOException { DatagramPacket packet = new DatagramPacket(message, message.length, multicastAddress, port); socket.send(packet); } - - public int getHeartBeatInterval() { - return heartBeatInterval; - } } diff --git a/robo4j-core/src/main/java/com/robo4j/net/ContextMessage.java b/robo4j-core/src/main/java/com/robo4j/net/ContextMessage.java deleted file mode 100644 index 34c7f8ca..00000000 --- a/robo4j-core/src/main/java/com/robo4j/net/ContextMessage.java +++ /dev/null @@ -1,27 +0,0 @@ -/* - * Copyright (c) 2014, 2024, Marcus Hirt, Miroslav Wengner - * - * Robo4J is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Robo4J is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Robo4J. If not, see . - */ -package com.robo4j.net; - -/** - * Context messages. Used internally. - * - * @author Marcus Hirt (@hirt) - * @author Miroslav Wengner (@miragemiko) - */ -enum ContextMessage { - Start, End, Shutdown -} diff --git a/robo4j-core/src/main/java/com/robo4j/net/HearbeatMessageCodec.java b/robo4j-core/src/main/java/com/robo4j/net/HearbeatMessageCodec.java index f0d3a018..7d72c47a 100644 --- a/robo4j-core/src/main/java/com/robo4j/net/HearbeatMessageCodec.java +++ b/robo4j-core/src/main/java/com/robo4j/net/HearbeatMessageCodec.java @@ -55,7 +55,7 @@ public static byte[] encode(RoboContextDescriptor entry) { } public static RoboContextDescriptor decode(byte[] message) { - if (!isHeartBeatMessage(message)) { + if (notHeartBeatMessage(message)) { throw new IllegalArgumentException("Invalid message! Must start with the proper magic."); } int version = getSupportedVersion(message); @@ -73,8 +73,8 @@ public static boolean isSupportedVersion(byte[] data) { return data[2] == PROTOCOL_VERSION; } - public static boolean isHeartBeatMessage(byte[] message) { - return message[0] == MAGIC[0] && message[1] == MAGIC[1]; + public static boolean notHeartBeatMessage(byte[] message) { + return message[0] != MAGIC[0] || message[1] != MAGIC[1]; } public static String parseId(byte[] message) { diff --git a/robo4j-core/src/main/java/com/robo4j/net/LookupServiceImpl.java b/robo4j-core/src/main/java/com/robo4j/net/LookupServiceImpl.java index 570491f6..f8519a45 100644 --- a/robo4j-core/src/main/java/com/robo4j/net/LookupServiceImpl.java +++ b/robo4j-core/src/main/java/com/robo4j/net/LookupServiceImpl.java @@ -22,13 +22,21 @@ import org.slf4j.LoggerFactory; import java.io.IOException; -import java.net.*; +import java.net.DatagramPacket; +import java.net.InetSocketAddress; +import java.net.MulticastSocket; +import java.net.NetworkInterface; +import java.net.SocketAddress; +import java.net.SocketException; +import java.net.UnknownHostException; import java.util.Collections; import java.util.HashMap; import java.util.Map; import java.util.Map.Entry; import java.util.concurrent.ConcurrentHashMap; +import static com.robo4j.net.HearbeatMessageCodec.notHeartBeatMessage; + /** * Package local default implementation of the {@link LookupService}. Will * listen on the broadcast address for lookup service related packets and @@ -41,6 +49,8 @@ */ class LookupServiceImpl implements LookupService { private static final Logger LOGGER = LoggerFactory.getLogger(LookupServiceImpl.class); + private static final int PORT_ZERO = 0; + private static final NetworkInterface LOCAL_NETWORK_INTERFACE_NULL = null; // FIXME(marcus/6 Nov 2017): This should be calculated, and used when // constructing the packet private final static int MAX_PACKET_SIZE = 1500; @@ -72,7 +82,7 @@ public void run() { private void process(DatagramPacket packet) { // First a few quick checks. We want to reject updating anything as // early as possible - if (!HearbeatMessageCodec.isHeartBeatMessage(packet.getData())) { + if (notHeartBeatMessage(packet.getData())) { LOGGER.debug("Non-heartbeat packet sent to LookupService! Ignoring."); return; } @@ -122,8 +132,7 @@ public void stop() { } } - public LookupServiceImpl(String address, int port, float missedHeartbeatsBeforeRemoval, LocalLookupServiceImpl localContexts) - throws SocketException, UnknownHostException { + public LookupServiceImpl(String address, int port, float missedHeartbeatsBeforeRemoval, LocalLookupServiceImpl localContexts) throws SocketException, UnknownHostException { this.address = address; this.port = port; this.localContexts = localContexts; @@ -155,7 +164,8 @@ public RoboContext getContext(String id) { public synchronized void start() throws IOException { stop(); socket = new MulticastSocket(port); - socket.joinGroup(InetAddress.getByName(address)); + socket.joinGroup(new InetSocketAddress(address, PORT_ZERO), LOCAL_NETWORK_INTERFACE_NULL); +// socket.joinGroup(InetAddress.getByName(address)); currentUpdater = new Updater(); Thread t = new Thread(currentUpdater, "LookupService listener"); t.setDaemon(true); diff --git a/robo4j-core/src/main/java/com/robo4j/net/MessageClient.java b/robo4j-core/src/main/java/com/robo4j/net/MessageClient.java index 6e657ef1..3a2fc428 100644 --- a/robo4j-core/src/main/java/com/robo4j/net/MessageClient.java +++ b/robo4j-core/src/main/java/com/robo4j/net/MessageClient.java @@ -18,17 +18,21 @@ import com.robo4j.RoboContext; import com.robo4j.configuration.Configuration; +import com.robo4j.scheduler.RoboThreadFactory; import org.slf4j.Logger; import org.slf4j.LoggerFactory; -import java.io.*; +import java.io.BufferedInputStream; +import java.io.BufferedOutputStream; +import java.io.IOException; +import java.io.ObjectInputStream; +import java.io.ObjectOutputStream; import java.net.Socket; import java.net.SocketTimeoutException; import java.net.URI; import java.net.UnknownHostException; import java.util.concurrent.ExecutorService; import java.util.concurrent.Executors; -import java.util.concurrent.ThreadFactory; /** * Message client. Normally used by RemoteRoboContext to communicate with a @@ -39,23 +43,25 @@ */ public class MessageClient { private static final Logger LOGGER = LoggerFactory.getLogger(MessageClient.class); - public final static String KEY_SO_TIMEOUT = "timeout"; - public final static String KEY_KEEP_ALIVE = "keepAlive"; - public final static String KEY_RETRIES = "retries"; - public final static int DEFAULT_SO_TIMEOUT = 2000000; - public final static boolean DEFAULT_KEEP_ALIVE = true; + public static final String KEY_SO_TIMEOUT_MILLS = "timeout"; + public static final String KEY_KEEP_ALIVE = "keepAlive"; + public static final String KEY_RETRIES = "retries"; + public static final int DEFAULT_SO_TIMEOUT_MILLS = 2000000; + public static final int DEFAULT_FAILED_CONNECTION_MAX = 3; + public static final boolean DEFAULT_KEEP_ALIVE = true; + private final String sourceUUID; + private final Configuration configuration; + private final URI messageServerURI; + private final int maxFailCount; + private Socket socket; + private ObjectOutputStream objectOutputStream; + private int failCount; + private RemoteReferenceListener remoteReferenceListener; /* * Executor for incoming messages from the server */ - private final ExecutorService remoteReferenceCallExecutor = Executors.newSingleThreadExecutor(new ThreadFactory() { - @Override - public Thread newThread(Runnable r) { - Thread t = new Thread(r, "RemoteReferenceCallExecutor for " + messageServerURI); - t.setDaemon(true); - return t; - } - }); + private final ExecutorService remoteReferenceCallExecutor; /* * Listening to incoming messages from the server, initiated by serialized @@ -107,28 +113,21 @@ public void shutdown() { } - private final URI messageServerURI; - private final String sourceUUID; - private final Configuration configuration; - private Socket socket; - private ObjectOutputStream objectOutputStream; - private int failCount; - private final int maxFailCount; - private RemoteReferenceListener remoteReferenceListener; - public MessageClient(URI messageServerURI, String sourceUUID, Configuration configuration) { this.messageServerURI = messageServerURI; this.sourceUUID = sourceUUID; this.configuration = configuration; - this.maxFailCount = configuration.getInteger(KEY_RETRIES, 3); + this.maxFailCount = configuration.getInteger(KEY_RETRIES, DEFAULT_FAILED_CONNECTION_MAX); + this.remoteReferenceCallExecutor = Executors.newSingleThreadExecutor( + new RoboThreadFactory.Builder("Message-Client") + .addThreadPrefix("RemoteReferenceCallExecutor for " + messageServerURI).build()); } public void connect() throws UnknownHostException, IOException { if (socket == null || socket.isClosed() || !socket.isConnected()) { -// socket = new Socket(messageServerURI.getHost(), messageServerURI.getPort()); socket = new Socket(messageServerURI.getHost(), messageServerURI.getPort()); socket.setKeepAlive(configuration.getBoolean(KEY_KEEP_ALIVE, DEFAULT_KEEP_ALIVE)); - socket.setSoTimeout(configuration.getInteger(KEY_SO_TIMEOUT, DEFAULT_SO_TIMEOUT)); + socket.setSoTimeout(configuration.getInteger(KEY_SO_TIMEOUT_MILLS, DEFAULT_SO_TIMEOUT_MILLS)); } objectOutputStream = new ObjectOutputStream(new BufferedOutputStream(socket.getOutputStream())); objectOutputStream.writeShort(MessageProtocolConstants.MAGIC); @@ -152,37 +151,50 @@ public void sendMessage(String id, Object message) throws IOException { } private void deliverMessage(String id, Object message) throws IOException { - // TODO : replace by switch objectOutputStream.writeUTF(id); - if (message instanceof String) { - objectOutputStream.writeByte(MessageProtocolConstants.MOD_UTF8); - objectOutputStream.writeUTF((String) message); - } else if (message instanceof Number) { - if (message instanceof Float) { - objectOutputStream.writeByte(MessageProtocolConstants.FLOAT); - objectOutputStream.writeFloat((Float) message); - } else if (message instanceof Integer) { - objectOutputStream.writeByte(MessageProtocolConstants.INT); - objectOutputStream.writeInt((Integer) message); - } else if (message instanceof Double) { - objectOutputStream.writeByte(MessageProtocolConstants.DOUBLE); - objectOutputStream.writeDouble((Double) message); - } else if (message instanceof Long) { - objectOutputStream.writeByte(MessageProtocolConstants.LONG); - objectOutputStream.writeLong((Long) message); - } else if (message instanceof Byte) { - objectOutputStream.writeByte(MessageProtocolConstants.BYTE); - objectOutputStream.writeByte((Byte) message); - } else if (message instanceof Short) { - objectOutputStream.writeByte(MessageProtocolConstants.SHORT); - objectOutputStream.writeShort((Short) message); + switch (message) { + case String s -> { + objectOutputStream.writeByte(MessageProtocolConstants.MOD_UTF8); + objectOutputStream.writeUTF(s); + } + case Number number -> { + switch (number) { + case Float v -> { + objectOutputStream.writeByte(MessageProtocolConstants.FLOAT); + objectOutputStream.writeFloat(v); + } + case Integer i -> { + objectOutputStream.writeByte(MessageProtocolConstants.INT); + objectOutputStream.writeInt(i); + } + case Double v -> { + objectOutputStream.writeByte(MessageProtocolConstants.DOUBLE); + objectOutputStream.writeDouble(v); + } + case Long l -> { + objectOutputStream.writeByte(MessageProtocolConstants.LONG); + objectOutputStream.writeLong(l); + } + case Byte b -> { + objectOutputStream.writeByte(MessageProtocolConstants.BYTE); + objectOutputStream.writeByte(b); + } + case Short i -> { + objectOutputStream.writeByte(MessageProtocolConstants.SHORT); + objectOutputStream.writeShort(i); + } + default -> { + } + } + } + case Character c -> { + objectOutputStream.writeByte(MessageProtocolConstants.CHAR); + objectOutputStream.writeChar(c); + } + case null, default -> { + objectOutputStream.writeByte(MessageProtocolConstants.OBJECT); + objectOutputStream.writeObject(message); } - } else if (message instanceof Character) { - objectOutputStream.writeByte(MessageProtocolConstants.CHAR); - objectOutputStream.writeChar((Character) message); - } else { - objectOutputStream.writeByte(MessageProtocolConstants.OBJECT); - objectOutputStream.writeObject(message); } objectOutputStream.flush(); } @@ -199,7 +211,7 @@ public void shutdown() { remoteReferenceCallExecutor.shutdown(); socket.close(); } catch (IOException e) { - // Do not care. + LOGGER.error("Failed to close remote reference listener!", e); } } } diff --git a/robo4j-core/src/main/java/com/robo4j/net/MessageServer.java b/robo4j-core/src/main/java/com/robo4j/net/MessageServer.java index 586742af..9cb25f2e 100644 --- a/robo4j-core/src/main/java/com/robo4j/net/MessageServer.java +++ b/robo4j-core/src/main/java/com/robo4j/net/MessageServer.java @@ -17,13 +17,23 @@ package com.robo4j.net; import com.robo4j.configuration.Configuration; +import com.robo4j.scheduler.RoboThreadFactory; import org.slf4j.Logger; import org.slf4j.LoggerFactory; import java.io.BufferedInputStream; import java.io.IOException; import java.io.ObjectInputStream; -import java.net.*; +import java.net.InetAddress; +import java.net.ServerSocket; +import java.net.Socket; +import java.net.URI; +import java.net.URISyntaxException; +import java.util.concurrent.ExecutorService; +import java.util.concurrent.Executors; +import java.util.concurrent.atomic.AtomicBoolean; + +import static com.robo4j.util.StringConstants.EMPTY; /** * This is a server that listens on messages, and sends them off to the @@ -35,35 +45,23 @@ * @author Miroslav Wengner (@miragemiko) */ public class MessageServer { - private static final Logger LOGGER = LoggerFactory.getLogger(MessageServer.class); - public final static String KEY_HOST_NAME = "hostname"; + public static final String KEY_HOST_NAME = "hostname"; public static final String KEY_PORT = "port"; + public static final String DEFAULT_SCHEME_ROBO4J = "robo4j"; - private volatile int listeningPort = 0; - private volatile String listeningHost; - private volatile boolean running = false; - private volatile Thread startingThread = null; - private final MessageCallback callback; - private final Configuration configuration; - - private class MessageHandler implements Runnable { - private final Socket socket; - - public MessageHandler(Socket socket) { - this.socket = socket; - } + private record MessageHandler(Socket socket, MessageCallback callback, + AtomicBoolean serverActive) implements Runnable { @Override public void run() { - try (ObjectInputStream objectInputStream = new ObjectInputStream( - new BufferedInputStream(socket.getInputStream()))) { + try (ObjectInputStream objectInputStream = new ObjectInputStream(new BufferedInputStream(socket.getInputStream()))) { // Init protocol. First check magic... if (checkMagic(objectInputStream.readShort())) { - final String uuid = objectInputStream.readUTF(); - final ServerRemoteRoboContext context = new ServerRemoteRoboContext(uuid, socket.getOutputStream()); + final var uuid = objectInputStream.readUTF(); + final var serverRemoteContext = new ServerRemoteRoboContext(uuid, socket.getOutputStream()); // Then keep reading string, byte, data triplets until dead - ReferenceDescriptor.setCurrentContext(context); - while (running) { + ReferenceDescriptor.setCurrentContext(serverRemoteContext); + while (serverActive.get()) { String id = objectInputStream.readUTF(); Object message = decodeMessage(objectInputStream); callback.handleMessage(uuid, id, message); @@ -77,35 +75,24 @@ public void run() { } catch (ClassNotFoundException e) { LOGGER.error("Could not find class to deserialize message to - will stop receiving messages from {}", socket.getRemoteSocketAddress(), e); } - LOGGER.info("Shutting down socket {}", socket.toString()); + LOGGER.info("Shutting down socket {}", socket); } private Object decodeMessage(ObjectInputStream objectInputStream) throws IOException, ClassNotFoundException { byte dataType = objectInputStream.readByte(); - // TODO: replace by better switch - switch (dataType) { - case MessageProtocolConstants.OBJECT: - return objectInputStream.readObject(); - case MessageProtocolConstants.MOD_UTF8: - return objectInputStream.readUTF(); - case MessageProtocolConstants.BYTE: - return objectInputStream.readByte(); - case MessageProtocolConstants.SHORT: - return objectInputStream.readShort(); - case MessageProtocolConstants.FLOAT: - return objectInputStream.readFloat(); - case MessageProtocolConstants.INT: - return objectInputStream.readInt(); - case MessageProtocolConstants.DOUBLE: - return objectInputStream.readDouble(); - case MessageProtocolConstants.LONG: - return objectInputStream.readLong(); - case MessageProtocolConstants.CHAR: - return objectInputStream.readChar(); - default: - throw new IOException("The type with id " + dataType + " is not supported!"); - } + return switch (dataType) { + case MessageProtocolConstants.OBJECT -> objectInputStream.readObject(); + case MessageProtocolConstants.MOD_UTF8 -> objectInputStream.readUTF(); + case MessageProtocolConstants.BYTE -> objectInputStream.readByte(); + case MessageProtocolConstants.SHORT -> objectInputStream.readShort(); + case MessageProtocolConstants.FLOAT -> objectInputStream.readFloat(); + case MessageProtocolConstants.INT -> objectInputStream.readInt(); + case MessageProtocolConstants.DOUBLE -> objectInputStream.readDouble(); + case MessageProtocolConstants.LONG -> objectInputStream.readLong(); + case MessageProtocolConstants.CHAR -> objectInputStream.readChar(); + default -> throw new IOException("The type with id " + dataType + " is not supported!"); + }; } private boolean checkMagic(short magic) { @@ -113,6 +100,18 @@ private boolean checkMagic(short magic) { } } + private static final Logger LOGGER = LoggerFactory.getLogger(MessageServer.class); + private static final String NAME_COMMUNICATION_WORKER_POOL = "Robo4J Communication Worker Pool"; + private static final String NAME_COMMUNICATION_THREAD_PREFIX = "Robo4J-Communication-Worker"; + + private volatile int listeningPort = 0; + private volatile String listeningHost; + private final AtomicBoolean serverActive = new AtomicBoolean(false); + private final MessageCallback callback; + private final Configuration configuration; + private final ExecutorService executors; + + /** * Constructor * @@ -122,6 +121,11 @@ private boolean checkMagic(short magic) { public MessageServer(MessageCallback callback, Configuration configuration) { this.callback = callback; this.configuration = configuration; + var roboThreadFactory = new RoboThreadFactory + .Builder(NAME_COMMUNICATION_WORKER_POOL) + .addThreadPrefix(NAME_COMMUNICATION_THREAD_PREFIX) + .build(); + this.executors = Executors.newCachedThreadPool(roboThreadFactory); } /** @@ -131,7 +135,6 @@ public MessageServer(MessageCallback callback, Configuration configuration) { * @throws IOException exception */ public void start() throws IOException { - startingThread = Thread.currentThread(); String host = configuration.getString(KEY_HOST_NAME, null); InetAddress bindAddress = null; if (host != null) { @@ -142,26 +145,20 @@ public void start() throws IOException { configuration.getInteger("backlog", 20), bindAddress)) { listeningHost = serverSocket.getInetAddress().getHostAddress(); listeningPort = serverSocket.getLocalPort(); - ThreadGroup g = new ThreadGroup("Robo4J communication threads"); - running = true; - while (running) { - MessageHandler handler = new MessageHandler(serverSocket.accept()); - Thread t = new Thread(g, handler, "Communication [" + handler.socket.getRemoteSocketAddress() + "]"); - t.setDaemon(true); - t.start(); + serverActive.set(true); + while (serverActive.get()) { + var messageHandler = new MessageHandler(serverSocket.accept(), callback, serverActive); + executors.submit(messageHandler); } } finally { - running = false; - startingThread = null; + serverActive.set(false); + executors.shutdown(); } } public void stop() { - running = false; - Thread startingThread = this.startingThread; - if (startingThread != null) { - startingThread.interrupt(); - } + serverActive.set(false); + executors.shutdown(); } public int getListeningPort() { @@ -174,16 +171,16 @@ public int getListeningPort() { * configured. */ public URI getListeningURI() { - if (!running) { + if (!serverActive.get()) { return null; } try { String host = configuration.getString(KEY_HOST_NAME, null); if (host != null) { - return new URI("robo4j", "", host, listeningPort, "", "", ""); + return new URI(DEFAULT_SCHEME_ROBO4J, EMPTY, host, listeningPort, EMPTY, EMPTY, EMPTY); } else { - return new URI("robo4j", "", listeningHost, listeningPort, "", "", ""); + return new URI(DEFAULT_SCHEME_ROBO4J, EMPTY, listeningHost, listeningPort, EMPTY, EMPTY, EMPTY); } } catch (URISyntaxException e) { LOGGER.error("Could not create URI for listening URI"); diff --git a/robo4j-core/src/main/java/com/robo4j/net/ReferenceDescriptor.java b/robo4j-core/src/main/java/com/robo4j/net/ReferenceDescriptor.java index 05735c1e..08f67426 100644 --- a/robo4j-core/src/main/java/com/robo4j/net/ReferenceDescriptor.java +++ b/robo4j-core/src/main/java/com/robo4j/net/ReferenceDescriptor.java @@ -49,7 +49,7 @@ public ReferenceDescriptor(String ctxId, String id, String fqn) { Object readResolve() throws ObjectStreamException { ServerRemoteRoboContext remoteRoboContext = ACTIVE_CONTEXT.get(); if (remoteRoboContext == null) { - LOGGER.error("No remote context set!"); + LOGGER.warn("No remote context set!"); return null; } return remoteRoboContext.getRoboReference(ctxId, id, fqn); diff --git a/robo4j-core/src/main/java/com/robo4j/net/RoboContextDescriptor.java b/robo4j-core/src/main/java/com/robo4j/net/RoboContextDescriptor.java index c74dc935..a2982571 100644 --- a/robo4j-core/src/main/java/com/robo4j/net/RoboContextDescriptor.java +++ b/robo4j-core/src/main/java/com/robo4j/net/RoboContextDescriptor.java @@ -25,47 +25,44 @@ * @author Miroslav Wengner (@miragemiko) */ public class RoboContextDescriptor { - public static final String KEY_URI = "uri"; + public static final String KEY_URI = "uri"; - private final String id; - private final int heartBeatInterval; - private final Map metaData; + private final String id; + private final int heartBeatInterval; + private final Map metaData; - /** - * Constructor. - * - * @param id - * the robo reference id. - * @param heartBeatInterval - * how often to send a heart beat - * @param metaData - * the metadata describing the RoboContext. - */ - public RoboContextDescriptor(String id, int heartBeatInterval, Map metaData) { - this.id = id; - this.heartBeatInterval = heartBeatInterval; - this.metaData = metaData; - } + /** + * Constructor. + * + * @param id the robo reference id. + * @param heartBeatInterval how often to send a heart beat in milliseconds + * @param metaData the metadata describing the RoboContext. + */ + public RoboContextDescriptor(String id, int heartBeatInterval, Map metaData) { + this.id = id; + this.heartBeatInterval = heartBeatInterval; + this.metaData = metaData; + } - public String getId() { - return id; - } + public String getId() { + return id; + } - public Map getMetadata() { - return metaData; - } + public Map getMetadata() { + return metaData; + } - /** - * The heart beat interval for this RoboContext, in ms. - * - * @return the heart beat interval in ms. - */ - public int getHeartBeatInterval() { - return heartBeatInterval; - } + /** + * The heart beat interval for this RoboContext, in ms. + * + * @return the heart beat interval in milliseconds. + */ + public int getHeartBeatInterval() { + return heartBeatInterval; + } - @Override - public String toString() { - return "RoboContextDescriptor [id=" + id + ", heartbeat=" + heartBeatInterval + ", metadata=[" + metaData.toString() + "]"; - } + @Override + public String toString() { + return "RoboContextDescriptor [id=" + id + ", heartbeat=" + heartBeatInterval + ", metadata=[" + metaData.toString() + "]"; + } } diff --git a/robo4j-core/src/main/java/com/robo4j/net/ServerRemoteRoboContext.java b/robo4j-core/src/main/java/com/robo4j/net/ServerRemoteRoboContext.java index cbb23c32..e23171f9 100644 --- a/robo4j-core/src/main/java/com/robo4j/net/ServerRemoteRoboContext.java +++ b/robo4j-core/src/main/java/com/robo4j/net/ServerRemoteRoboContext.java @@ -65,7 +65,7 @@ public String getTargetContextId() { } @Override - public String getId() { + public String id() { return id; } @@ -103,7 +103,7 @@ public void sendMessage(Object message) { // FIXME: Change the serialization to be the same as for the // client to server outputStream.writeUTF(getTargetContextId()); - outputStream.writeUTF(getId()); + outputStream.writeUTF(id()); outputStream.writeObject(message); } catch (IOException e) { LOGGER.error("send message:{}", message, e); diff --git a/robo4j-core/src/main/java/com/robo4j/reflect/ReflectionScan.java b/robo4j-core/src/main/java/com/robo4j/reflect/ReflectionScan.java index 64c25b6d..f2a43570 100644 --- a/robo4j-core/src/main/java/com/robo4j/reflect/ReflectionScan.java +++ b/robo4j-core/src/main/java/com/robo4j/reflect/ReflectionScan.java @@ -26,12 +26,18 @@ import java.io.FileNotFoundException; import java.io.IOException; import java.net.URL; -import java.util.*; +import java.util.ArrayList; +import java.util.Collections; +import java.util.Enumeration; +import java.util.List; +import java.util.Objects; import java.util.stream.Collectors; import java.util.stream.Stream; import java.util.zip.ZipEntry; import java.util.zip.ZipInputStream; +import static com.robo4j.util.Utf8Constant.UTF8_EXCLAMATION; + /** * Util class for reflection scan. * @@ -42,7 +48,6 @@ public final class ReflectionScan { private static final Logger LOGGER = LoggerFactory.getLogger(ReflectionScan.class); private static final String FILE = "file:"; private static final String SUFFIX = ".class"; - private static final String EXCLAMATION = "\u0021"; //Exclamation mark ! private static final char SLASH = '/'; private static final char DOT = '.'; @@ -84,7 +89,7 @@ private List scanJarPackage(ClassLoader loader, String packageName) thro StreamUtils.streamOfEnumeration(resources, false).map(url -> { try { - String jarFile = url.getFile().split(EXCLAMATION)[0].replace(FILE, StringConstants.EMPTY); + String jarFile = url.getFile().split(UTF8_EXCLAMATION)[0].replace(FILE, StringConstants.EMPTY); if (new File(jarFile).isDirectory()) { return null; } @@ -129,12 +134,11 @@ private List findClassesIntern(File dir, String path) { // TODO review StringBuilders result.addAll(findClassesIntern(file, new StringBuilder().append(path).append(DOT).append(file.getName()).toString())); } else if (file.getName().endsWith(SUFFIX)) { - final StringBuilder sb = new StringBuilder(); - sb.append(path.replace(File.separatorChar, DOT)) + var sb = new StringBuilder().append(path.replace(File.separatorChar, DOT)) .append(DOT) - .append(file.getName(), 0, file.getName().length() - SUFFIX.length()); + .append(file.getName(), 0, file.getName().length() - SUFFIX.length()).toString(); - result.add(sb.toString()); + result.add(sb); } }); return result; diff --git a/robo4j-core/src/main/java/com/robo4j/reflect/ReflectionScanException.java b/robo4j-core/src/main/java/com/robo4j/reflect/ReflectionScanException.java index 1a096503..8b7574d3 100644 --- a/robo4j-core/src/main/java/com/robo4j/reflect/ReflectionScanException.java +++ b/robo4j-core/src/main/java/com/robo4j/reflect/ReflectionScanException.java @@ -16,6 +16,8 @@ */ package com.robo4j.reflect; +import java.io.Serial; + /** * ReflectionScanException. * @@ -23,6 +25,7 @@ * @author Miro Wengner (@miragemiko) */ public class ReflectionScanException extends RuntimeException { + @Serial private static final long serialVersionUID = 1L; public ReflectionScanException(String message, Throwable cause) { diff --git a/robo4j-core/src/main/java/com/robo4j/scheduler/DefaultScheduler.java b/robo4j-core/src/main/java/com/robo4j/scheduler/DefaultScheduler.java index c0e644b9..938edd6d 100644 --- a/robo4j-core/src/main/java/com/robo4j/scheduler/DefaultScheduler.java +++ b/robo4j-core/src/main/java/com/robo4j/scheduler/DefaultScheduler.java @@ -22,7 +22,12 @@ import org.slf4j.Logger; import org.slf4j.LoggerFactory; -import java.util.concurrent.*; +import java.util.concurrent.Callable; +import java.util.concurrent.Future; +import java.util.concurrent.ScheduledExecutorService; +import java.util.concurrent.ScheduledFuture; +import java.util.concurrent.ScheduledThreadPoolExecutor; +import java.util.concurrent.TimeUnit; /** * This is the default scheduler used in Robo4J. @@ -30,10 +35,12 @@ * @author Marcus Hirt (@hirt) * @author Miroslav Wengner (@miragemiko) */ -public class DefaultScheduler implements Scheduler { +public final class DefaultScheduler implements Scheduler { private static final Logger LOGGER = LoggerFactory.getLogger(DefaultScheduler.class); private static final int DEFAULT_NUMBER_OF_THREADS = 2; private static final int TERMINATION_TIMEOUT_SEC = 4; + private static final String THREAD_GROUP_SCHEDULER_NAME = "Robo4J Scheduler"; + private static final String THREAD_PREFIX_SCHEDULER_NAME = "Robo4J-Scheduler-"; private final ScheduledExecutorService executor; private final RoboContext context; @@ -55,8 +62,12 @@ public DefaultScheduler(RoboContext context) { */ public DefaultScheduler(RoboContext context, int numberOfThreads) { this.context = context; - this.executor = new ScheduledThreadPoolExecutor(numberOfThreads, - new RoboThreadFactory(new ThreadGroup("Robo4J Scheduler"), "Robo4J Scheduler", true)); + var schedulerThreadFactory = new RoboThreadFactory + .Builder(THREAD_GROUP_SCHEDULER_NAME) + .addThreadPrefix(THREAD_PREFIX_SCHEDULER_NAME) + .build(); + + this.executor = new ScheduledThreadPoolExecutor(numberOfThreads, schedulerThreadFactory); } @Override diff --git a/robo4j-core/src/main/java/com/robo4j/scheduler/RoboThreadFactory.java b/robo4j-core/src/main/java/com/robo4j/scheduler/RoboThreadFactory.java index 310e3b7b..a590f681 100644 --- a/robo4j-core/src/main/java/com/robo4j/scheduler/RoboThreadFactory.java +++ b/robo4j-core/src/main/java/com/robo4j/scheduler/RoboThreadFactory.java @@ -26,6 +26,33 @@ * @author Miroslav Wengner (@miragemiko) */ public class RoboThreadFactory implements ThreadFactory { + + public static final class Builder { + private final String groupName; + private String threadPrefix = "robo4j-worker-"; + private boolean isDaemon = true; + + public Builder(String groupName) { + this.groupName = groupName; + } + + public Builder addThreadPrefix(String prefix) { + this.threadPrefix = prefix; + return this; + } + + public Builder setDaemonThread(boolean daemon) { + this.isDaemon = daemon; + return this; + } + + public RoboThreadFactory build() { + var roboThreadGroup = new ThreadGroup(groupName); + return new RoboThreadFactory(roboThreadGroup, threadPrefix, isDaemon); + } + + } + /** * The thread group to use. */ diff --git a/robo4j-core/src/main/java/com/robo4j/units/CounterUnit.java b/robo4j-core/src/main/java/com/robo4j/units/CounterUnit.java deleted file mode 100644 index e536aa15..00000000 --- a/robo4j-core/src/main/java/com/robo4j/units/CounterUnit.java +++ /dev/null @@ -1,132 +0,0 @@ -/* - * Copyright (c) 2014, 2024, Marcus Hirt, Miroslav Wengner - * - * Robo4J is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Robo4J is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Robo4J. If not, see . - */ -package com.robo4j.units; - -import com.robo4j.*; -import com.robo4j.configuration.Configuration; -import org.slf4j.Logger; -import org.slf4j.LoggerFactory; - -import java.util.concurrent.ScheduledFuture; -import java.util.concurrent.TimeUnit; -import java.util.concurrent.atomic.AtomicInteger; - -/** - * A simple unit which will count upwards from zero. Useful, for example, as a - * heart beat generator. - * - * @author Marcus Hirt (@hirt) - * @author Miro Wengner (@miragemiko) - */ -public class CounterUnit extends RoboUnit { - private static final Logger LOGGER = LoggerFactory.getLogger(CounterUnit.class); - private final AtomicInteger counter = new AtomicInteger(0); - - private int interval; - - /** - * This configuration key controls the interval between the updates, in ms. - */ - public static final String KEY_INTERVAL = "interval"; - - /** - * The default period, if no period is configured. - */ - public static final int DEFAULT_INTERVAL = 1000; - - /** - * This configuration key controls the target of the counter updates. This - * configuration key is mandatory. Also, the target must exist when the - * counter unit is started, and any change whilst running will be ignored. - */ - public static final String KEY_TARGET = "target"; - - /* - * The currently running timer updater. - */ - private ScheduledFuture scheduledFuture; - - /* - * The id of the target. - */ - private String targetId; - - private final class CounterUnitAction implements Runnable { - private final RoboReference target; - - public CounterUnitAction(RoboReference target) { - this.target = target; - } - - @Override - public void run() { - if (target != null) { - target.sendMessage(counter.getAndIncrement()); - } else { - LOGGER.error("The target {} for the CounterUnit does not exist! Could not send count!", targetId); - } - } - } - - /** - * Constructor. - * - * @param context the RoboContext. - * @param id the id of the RoboUnit. - */ - public CounterUnit(RoboContext context, String id) { - super(CounterCommand.class, context, id); - } - - @Override - protected void onInitialization(Configuration configuration) throws ConfigurationException { - interval = configuration.getInteger(KEY_INTERVAL, DEFAULT_INTERVAL); - targetId = configuration.getString(KEY_TARGET, null); - if (targetId == null) { - throw ConfigurationException.createMissingConfigNameException(KEY_TARGET); - } - } - - @Override - public void onMessage(CounterCommand message) { - synchronized (this) { - super.onMessage(message); - switch (message) { - case START: - scheduledFuture = getContext().getScheduler().scheduleAtFixedRate( - new CounterUnitAction(getContext().getReference(targetId)), 0, interval, TimeUnit.MILLISECONDS); - break; - case STOP: - scheduledFuture.cancel(false); - break; - case RESET: - counter.set(0); - break; - } - } - } - - @SuppressWarnings("unchecked") - @Override - public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals("Counter") && attribute.getAttributeType() == Integer.class) { - return (R) (Integer) counter.get(); - } - return null; - } - -} diff --git a/robo4j-core/src/main/java/com/robo4j/util/AttributeUtils.java b/robo4j-core/src/main/java/com/robo4j/util/AttributeUtils.java index 155bfa8d..3a6d0d52 100644 --- a/robo4j-core/src/main/java/com/robo4j/util/AttributeUtils.java +++ b/robo4j-core/src/main/java/com/robo4j/util/AttributeUtils.java @@ -43,6 +43,6 @@ private AttributeUtils() { */ public static boolean validateAttributeByNameAndType(AttributeDescriptor descriptor, String name, Class clazz) { - return (descriptor.getAttributeName().equals(name) && descriptor.getAttributeType() == clazz); + return (descriptor.attributeName().equals(name) && descriptor.attributeType() == clazz); } } diff --git a/robo4j-core/src/main/java/com/robo4j/util/IOUtil.java b/robo4j-core/src/main/java/com/robo4j/util/IOUtil.java index 434802f8..6ad58c32 100644 --- a/robo4j-core/src/main/java/com/robo4j/util/IOUtil.java +++ b/robo4j-core/src/main/java/com/robo4j/util/IOUtil.java @@ -16,6 +16,9 @@ */ package com.robo4j.util; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + import java.io.BufferedInputStream; import java.io.ByteArrayOutputStream; import java.io.Closeable; @@ -34,9 +37,10 @@ * @author Miroslav Wengner (@miragemiko) */ public final class IOUtil { + private static final Logger LOGGER = LoggerFactory.getLogger(IOUtil.class); private IOUtil() { - throw new UnsupportedOperationException("Toolkit!"); + throw new UnsupportedOperationException("Not allowed!"); } public static String readStringFromUTF8Stream(InputStream is) throws IOException { @@ -66,7 +70,7 @@ public static void close(Closeable c) { try { c.close(); } catch (IOException e) { - // Ignore + LOGGER.error(e.getMessage(), e); } } diff --git a/robo4j-core/src/main/java/com/robo4j/util/StreamException.java b/robo4j-core/src/main/java/com/robo4j/util/StreamException.java index 2c242969..62c44975 100644 --- a/robo4j-core/src/main/java/com/robo4j/util/StreamException.java +++ b/robo4j-core/src/main/java/com/robo4j/util/StreamException.java @@ -16,12 +16,15 @@ */ package com.robo4j.util; +import java.io.Serial; + /** * @author Marcus Hirt (@hirt) * @author Miro Wengner (@miragemiko) */ public class StreamException extends RuntimeException { - private static final long serialVersionUID = 1L; + @Serial + private static final long serialVersionUID = 1L; public StreamException(String message) { super(message); diff --git a/robo4j-core/src/main/java/com/robo4j/util/StringConstants.java b/robo4j-core/src/main/java/com/robo4j/util/StringConstants.java index cba139c5..f9b03d57 100644 --- a/robo4j-core/src/main/java/com/robo4j/util/StringConstants.java +++ b/robo4j-core/src/main/java/com/robo4j/util/StringConstants.java @@ -24,5 +24,4 @@ */ public final class StringConstants { public static final String EMPTY = ""; - public static final String SPACE = "\u0020"; } diff --git a/robo4j-core/src/main/java/com/robo4j/util/SystemUtil.java b/robo4j-core/src/main/java/com/robo4j/util/SystemUtil.java index adb2acb0..5393565a 100644 --- a/robo4j-core/src/main/java/com/robo4j/util/SystemUtil.java +++ b/robo4j-core/src/main/java/com/robo4j/util/SystemUtil.java @@ -42,7 +42,7 @@ private SystemUtil() { // no instances } - public static final Comparator> ID_COMPARATOR = Comparator.comparing(RoboReference::getId); + public static final Comparator> ID_COMPARATOR = Comparator.comparing(RoboReference::id); public static InputStream getInputStreamByResourceName(String resourceName) { return Thread.currentThread().getContextClassLoader().getResourceAsStream(resourceName); @@ -58,7 +58,7 @@ public static String printStateReport(RoboContext ctx) { .append(DELIMITER_HORIZONTAL).append(BREAK); for (RoboReference reference : references) { builder.append( - String.format(" %-25s %13s", reference.getId(), reference.getState().getLocalizedName())) + String.format(" %-25s %13s", reference.id(), reference.getState().getLocalizedName())) .append(BREAK); } // formatter:on @@ -68,7 +68,7 @@ public static String printStateReport(RoboContext ctx) { // TODO: 1/25/18 (miro) convert it to JSON message public static String printSocketEndPoint(RoboReference point, RoboReference codecUnit) { final int port = point.getConfiguration().getInteger("port", 0); - StringBuilder sb = new StringBuilder(); + var sb = new StringBuilder(); //@formatter:off sb.append("RoboSystem end-points:") .append(BREAK) @@ -79,7 +79,7 @@ public static String printSocketEndPoint(RoboReference point, RoboReference. - */ -package com.robo4j; - -import com.robo4j.configuration.Configuration; -import com.robo4j.configuration.ConfigurationBuilder; -import com.robo4j.units.CounterCommand; -import com.robo4j.units.CounterUnit; -import com.robo4j.units.IntegerConsumer; -import org.junit.jupiter.api.Test; - -import java.util.ArrayList; -import java.util.concurrent.ExecutionException; - -import static org.junit.jupiter.api.Assertions.*; - -/** - * Test for the CounterUnit. - * - * @author Marcus Hirt (@hirt) - * @author Miroslav Wengner (@miragemiko) - */ -class CounterUnitTests { - private static final String ID_COUNTER = "counter"; - private static final String ID_CONSUMER = "consumer"; - private static final AttributeDescriptor NUMBER_OF_MESSAGES = new DefaultAttributeDescriptor<>(Integer.class, - "NumberOfReceivedMessages"); - private static final AttributeDescriptor COUNTER = new DefaultAttributeDescriptor<>(Integer.class, "Counter"); - - @SuppressWarnings({"unchecked", "rawtypes"}) - private static final AttributeDescriptor> MESSAGES = new DefaultAttributeDescriptor>( - (Class>) new ArrayList().getClass(), "ReceivedMessages"); - - - // TODO : review the test and comment, simplify it - @Test - void test() throws RoboBuilderException, InterruptedException, ExecutionException { - // FIXME(Marcus/Aug 20, 2017): We really should get rid of the sleeps - // here and use waits with timeouts... - RoboBuilder builder = new RoboBuilder(); - builder.add(IntegerConsumer.class, ID_CONSUMER); - builder.add(CounterUnit.class, getCounterConfiguration(ID_CONSUMER, 1000), ID_COUNTER); - RoboContext context = builder.build(); - context.start(); - assertEquals(LifecycleState.STARTED, context.getState()); - RoboReference counter = context.getReference(ID_COUNTER); - RoboReference consumer = context.getReference(ID_CONSUMER); - counter.sendMessage(CounterCommand.START); - Thread.sleep(2500); - assertTrue(consumer.getAttribute(NUMBER_OF_MESSAGES).get() > 2); - counter.sendMessage(CounterCommand.STOP); - Thread.sleep(200); - Integer count = consumer.getAttribute(NUMBER_OF_MESSAGES).get(); - Thread.sleep(2500); - assertEquals(count, consumer.getAttribute(NUMBER_OF_MESSAGES).get()); - ArrayList messages = consumer.getAttribute(MESSAGES).get(); - assertNotEquals(0, messages.size()); - assertNotEquals(0, (int) messages.get(messages.size() - 1)); - counter.sendMessage(CounterCommand.RESET); - Thread.sleep(1000); - assertEquals(0, (int) counter.getAttribute(COUNTER).get()); - } - - private Configuration getCounterConfiguration(String target, int interval) { - Configuration configuration = new ConfigurationBuilder().addString(CounterUnit.KEY_TARGET, target) - .addInteger(CounterUnit.KEY_INTERVAL, interval).build(); - return configuration; - } - -} diff --git a/robo4j-core/src/test/java/com/robo4j/RoboApplicationTests.java b/robo4j-core/src/test/java/com/robo4j/RoboApplicationTests.java deleted file mode 100644 index 001a014e..00000000 --- a/robo4j-core/src/test/java/com/robo4j/RoboApplicationTests.java +++ /dev/null @@ -1,90 +0,0 @@ -/* - * Copyright (c) 2014, 2024, Marcus Hirt, Miroslav Wengner - * - * Robo4J is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Robo4J is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Robo4J. If not, see . - */ -package com.robo4j; - -import org.junit.jupiter.api.Disabled; -import org.junit.jupiter.api.Test; - -import java.io.InputStream; -import java.util.concurrent.TimeUnit; - -import static org.junit.jupiter.api.Assertions.assertEquals; - -/** - * RoboApplicationTests contains tests for {@link RoboApplication} - * - * @author Marcus Hirt (@hirt) - * @author Miroslav Wengner (@miragemiko) - */ -@Disabled("individual test") -class RoboApplicationTests { - - /** - * Build and shutdown the system - * - * @throws RoboBuilderException - * unexpected - */ - @Test - void roboApplicationLifeCycleTestNoExit() throws RoboBuilderException { - final InputStream contextIS = Thread.currentThread().getContextClassLoader().getResourceAsStream("test.xml"); - final RoboBuilder builder = new RoboBuilder(); - builder.add(contextIS); - - final RoboContext system = builder.build(); - final RoboApplication roboApp = new RoboApplication(); - roboApp.launchNoExit(system, 3, TimeUnit.SECONDS); - - assertEquals(LifecycleState.SHUTDOWN, system.getState()); - } - - /** - * Build and shutdown the system - * - * @throws RoboBuilderException - * unexpected - */ - @Test - void roboApplicationLifeCycleTestWithExit() throws RoboBuilderException { - final InputStream contextIS = Thread.currentThread().getContextClassLoader().getResourceAsStream("test.xml"); - final RoboBuilder builder = new RoboBuilder(); - builder.add(contextIS); - - final RoboContext system = builder.build(); - final RoboApplication roboApp = new RoboApplication(); - roboApp.launchWithExit(system, 3, TimeUnit.SECONDS); - - System.setSecurityManager(new SecurityManager() { - @Override - public void checkExit(int status) { - assertEquals(Integer.valueOf(0), Integer.valueOf(status)); - } - }); - } - - @Disabled("individual test") - @Test - void roboApplicationLifeCycle() throws RoboBuilderException { - final InputStream contextIS = Thread.currentThread().getContextClassLoader().getResourceAsStream("test.xml"); - final RoboBuilder builder = new RoboBuilder(); - builder.add(contextIS); - - final RoboContext system = builder.build(); - final RoboApplication roboApp = new RoboApplication(); - roboApp.launch(system); - } -} diff --git a/robo4j-core/src/test/java/com/robo4j/RoboBuilderTests.java b/robo4j-core/src/test/java/com/robo4j/RoboBuilderTests.java index 920fa60f..09bf6a12 100644 --- a/robo4j-core/src/test/java/com/robo4j/RoboBuilderTests.java +++ b/robo4j-core/src/test/java/com/robo4j/RoboBuilderTests.java @@ -22,14 +22,18 @@ import com.robo4j.units.StringProducer; import com.robo4j.util.SystemUtil; import org.junit.jupiter.api.Test; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; import java.util.concurrent.CountDownLatch; import java.util.concurrent.ExecutionException; import java.util.concurrent.TimeUnit; import java.util.concurrent.TimeoutException; -import static com.robo4j.RoboUnitTestUtils.getAttributeOrTimeout; -import static org.junit.jupiter.api.Assertions.*; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertNotNull; +import static org.junit.jupiter.api.Assertions.assertSame; +import static org.junit.jupiter.api.Assertions.assertTrue; /** * Test(s) for the builder. @@ -38,8 +42,9 @@ * @author Miroslav Wengner (@miragemiko) */ public class RoboBuilderTests { + private static final Logger LOGGER = LoggerFactory.getLogger(RoboBuilderTests.class); private static final int MESSAGES = 10; - private static final int TIMEOUT = 100; + private static final int TIMEOUT_MIN = 2; private static final String SYSTEM_CONFIG_NAME = "mySystem"; private static final String PRODUCER_UNIT_NAME = "producer"; private static final String CONSUMER_UNIT_NAME = "consumer"; @@ -49,24 +54,24 @@ public class RoboBuilderTests { void testParsingFileWithSystemConfigAndInitiate() throws RoboBuilderException { var fileSystemAndUnitsConfigName = "testsystem.xml"; var contextLoader = Thread.currentThread().getContextClassLoader(); - RoboBuilder builder = new RoboBuilder( + var builder = new RoboBuilder( contextLoader.getResourceAsStream(fileSystemAndUnitsConfigName)); builder.add(contextLoader.getResourceAsStream(fileSystemAndUnitsConfigName)); - RoboContext system = builder.build(); + var system = builder.build(); assertEquals(SYSTEM_CONFIG_NAME, system.getId()); - assertEquals(system.getState(), LifecycleState.INITIALIZED); + assertEquals(LifecycleState.INITIALIZED, system.getState()); } @Test void testParsingFileWithSystemConfigAndStart() throws RoboBuilderException { var fileSystemAndUnitsConfigName = "testsystem.xml"; var contextLoader = Thread.currentThread().getContextClassLoader(); - RoboBuilder builder = new RoboBuilder( + var builder = new RoboBuilder( contextLoader.getResourceAsStream(fileSystemAndUnitsConfigName)); builder.add(contextLoader.getResourceAsStream(fileSystemAndUnitsConfigName)); - RoboContext system = builder.build(); + var system = builder.build(); system.start(); - assertSame(system.getState(), LifecycleState.STARTED); + assertSame(LifecycleState.STARTED, system.getState()); } @@ -89,12 +94,12 @@ void testParsingFileWithSystemConfig() for (int i = 0; i < MESSAGES; i++) { producer.sendMessage("sendRandomMessage"); } - var messagesProduced = producerLatch.await(TIMEOUT, TimeUnit.MINUTES); + var messagesProduced = producerLatch.await(TIMEOUT_MIN, TimeUnit.MINUTES); var totalProducedMessages = getAttributeOrTimeout(producer, StringProducer.DESCRIPTOR_TOTAL_MESSAGES); RoboReference consumer = system.getReference(CONSUMER_UNIT_NAME); CountDownLatch countDownLatchConsumer = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); - var messageReceived = countDownLatchConsumer.await(TIMEOUT, TimeUnit.MINUTES); + var messageReceived = countDownLatchConsumer.await(TIMEOUT_MIN, TimeUnit.MINUTES); var totalReceivedMessages = consumer.getAttribute(StringConsumer.DESCRIPTOR_TOTAL_MESSAGES).get(); system.stop(); @@ -124,8 +129,8 @@ void testParsingFile() RoboReference consumer = system.getReference(CONSUMER_UNIT_NAME); - CountDownLatch countDownLatchConsumer = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); - var receivedMessages = countDownLatchConsumer.await(TIMEOUT, TimeUnit.MINUTES); + var countDownLatchConsumer = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); + var receivedMessages = countDownLatchConsumer.await(TIMEOUT_MIN, TimeUnit.MINUTES); var totalReceivedMessages = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_TOTAL_MESSAGES); system.stop(); @@ -152,13 +157,13 @@ void testSeparateSystemUnitsSystemConfig() for (int i = 0; i < MESSAGES; i++) { producer.sendMessage("sendRandomMessage"); } - var messagesProduced = producerLatch.await(TIMEOUT, TimeUnit.MINUTES); + var messagesProduced = producerLatch.await(TIMEOUT_MIN, TimeUnit.MINUTES); var totalProducedMessages = producer.getAttribute(StringProducer.DESCRIPTOR_TOTAL_MESSAGES).get(); RoboReference consumer = system.getReference(CONSUMER_UNIT_NAME); CountDownLatch countDownLatchConsumer = getAttributeOrTimeout(consumer, StringProducer.DESCRIPTOR_COUNT_DOWN_LATCH); - var receivedMessages = countDownLatchConsumer.await(TIMEOUT, TimeUnit.MINUTES); + var receivedMessages = countDownLatchConsumer.await(TIMEOUT_MIN, TimeUnit.MINUTES); var totalReceivedMessages = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_TOTAL_MESSAGES); system.stop(); @@ -202,7 +207,7 @@ void testComplexConfiguration() throws RoboBuilderException { } @Test - void testProgrammaticConfiguration() throws RoboBuilderException, InterruptedException, ExecutionException, TimeoutException { + void programmaticConfigurationTest() throws RoboBuilderException, InterruptedException, ExecutionException, TimeoutException { ConfigurationBuilder systemConfigBuilder = new ConfigurationBuilder() .addInteger(RoboBuilder.KEY_SCHEDULER_POOL_SIZE, 11).addInteger(RoboBuilder.KEY_WORKER_POOL_SIZE, 5) .addInteger(RoboBuilder.KEY_BLOCKING_POOL_SIZE, 13); @@ -224,14 +229,14 @@ void testProgrammaticConfiguration() throws RoboBuilderException, InterruptedExc for (int i = 0; i < MESSAGES; i++) { producer.sendMessage(StringProducer.PROPERTY_SEND_RANDOM_MESSAGE); } - var producedMessage = producerLatch.await(TIMEOUT, TimeUnit.MINUTES); + var producedMessage = producerLatch.await(TIMEOUT_MIN, TimeUnit.MINUTES); var totalProducedMessages = producer.getAttribute(StringProducer.DESCRIPTOR_TOTAL_MESSAGES).get(); RoboReference consumer = system.getReference(CONSUMER_UNIT_NAME); // We need to fix these tests so that we can get a callback. CountDownLatch countDownLatchConsumer = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); - var messageReceived = countDownLatchConsumer.await(TIMEOUT, TimeUnit.MINUTES); + var messageReceived = countDownLatchConsumer.await(TIMEOUT_MIN, TimeUnit.MINUTES); int totalReceivedMessages = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_TOTAL_MESSAGES); @@ -247,4 +252,13 @@ void testProgrammaticConfiguration() throws RoboBuilderException, InterruptedExc system.shutdown(); } + private static R getAttributeOrTimeout(RoboReference roboReference, AttributeDescriptor attributeDescriptor) throws InterruptedException, ExecutionException, TimeoutException { + var attribute = roboReference.getAttribute(attributeDescriptor).get(TIMEOUT_MIN, TimeUnit.MINUTES); + if (attribute == null) { + attribute = roboReference.getAttribute(attributeDescriptor).get(TIMEOUT_MIN, TimeUnit.MINUTES); + LOGGER.error("roboReference:{}, no attribute:{}", roboReference.id(), attributeDescriptor.attributeName()); + } + return attribute; + } + } diff --git a/robo4j-core/src/test/java/com/robo4j/RoboSchedulerTests.java b/robo4j-core/src/test/java/com/robo4j/RoboSchedulerTests.java index 65eeb7c2..2d50996d 100644 --- a/robo4j-core/src/test/java/com/robo4j/RoboSchedulerTests.java +++ b/robo4j-core/src/test/java/com/robo4j/RoboSchedulerTests.java @@ -19,14 +19,18 @@ import com.robo4j.configuration.Configuration; import com.robo4j.configuration.ConfigurationBuilder; import com.robo4j.scheduler.FinalInvocationListener; -import com.robo4j.scheduler.Scheduler; import com.robo4j.units.StringConsumer; import com.robo4j.units.StringProducer; import com.robo4j.units.StringScheduledEmitter; import org.junit.jupiter.api.Test; -import java.util.concurrent.*; +import java.util.concurrent.CancellationException; +import java.util.concurrent.ExecutionException; +import java.util.concurrent.TimeUnit; +import java.util.concurrent.TimeoutException; +import static com.robo4j.RoboUnitTestUtils.futureGetSafe; +import static com.robo4j.RoboUnitTestUtils.getAttributeOrTimeout; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertTrue; @@ -47,31 +51,42 @@ public void onFinalInvocation(RoboContext context) { } @Test - void testScheduler() throws InterruptedException, ExecutionException { - // FIXME: 20.08.17 (miro,marcus): when notification implemented, correct the test - RoboSystem system = new RoboSystem(); - StringConsumer consumer = new StringConsumer(system, "consumer"); - system.addUnits(consumer); - consumer.setState(LifecycleState.STARTED); - - Scheduler scheduler = system.getScheduler(); - RoboReference reference = system.getReference("consumer"); - SchedulerListener listener = new SchedulerListener(); - ScheduledFuture schedule = scheduler.schedule(reference, "Lalalala", 1, 4, TimeUnit.SECONDS, 3, listener); - try { - schedule.get(); - } catch (CancellationException e) { - // Expected - using this to wait for completion. - } + void schedulerCycleTest() throws InterruptedException, ExecutionException, TimeoutException, RoboBuilderException, CancellationException { + final var usedTimeUnitMills = TimeUnit.MILLISECONDS; + final var maxDelayMills = 2; + final var initSystemDelayMills = 1; + final var scheduledMessageRepeatExclusive = 4; + final var usedScheduledMessage = "Lalalala"; + final int expectedMessagesMax = 3; + final var expectedConsumerName = "consumer"; + final Configuration consumerConf = new ConfigurationBuilder() + .addInteger(StringConsumer.PROP_TOTAL_MESSAGES, expectedMessagesMax).build(); + + var roboSystemBuilder = new RoboBuilder(); + roboSystemBuilder.add(StringConsumer.class, consumerConf, expectedConsumerName); + var system = (RoboSystem) roboSystemBuilder.build(); + system.start(); + + var consumerRef = system.getReference(expectedConsumerName); + assert consumerRef != null; + var scheduler = system.getScheduler(); + var consumerReference = system.getReference(expectedConsumerName); + var countDownLatchConsumer = getAttributeOrTimeout(consumerRef, StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); + var listener = new SchedulerListener(); + var schedule = scheduler.schedule(consumerReference, usedScheduledMessage, initSystemDelayMills, scheduledMessageRepeatExclusive, usedTimeUnitMills, expectedMessagesMax, listener); + futureGetSafe(schedule); - Thread.sleep(1000); - assertEquals(3, consumer.getReceivedMessages().size()); + var receivedMessages = countDownLatchConsumer.await(maxDelayMills, usedTimeUnitMills); + var totalReceivedMessages = getAttributeOrTimeout(consumerRef, StringConsumer.DESCRIPTOR_TOTAL_MESSAGES); + + assertTrue(receivedMessages); + assertEquals(expectedMessagesMax, totalReceivedMessages); assertTrue(listener.wasFinalCalled); system.shutdown(); } @Test - void testProducerWithSchedulerConsumer() throws ConfigurationException, InterruptedException { + void producerWithSchedulerConsumerTest() throws ConfigurationException, InterruptedException, ExecutionException, TimeoutException { int totalMessages = 10; int consideredTimeoutMills = 10; int totalTestTimeoutMills = consideredTimeoutMills * totalMessages + consideredTimeoutMills; @@ -80,62 +95,71 @@ void testProducerWithSchedulerConsumer() throws ConfigurationException, Interrup var producerConfig = new ConfigurationBuilder().addString(StringProducer.PROP_TARGET, StringScheduledEmitter.DEFAULT_UNIT_NAME) .addInteger(StringProducer.PROP_TOTAL_MESSAGES, totalMessages).build(); producer.initialize(producerConfig); - var producerCountDownLatch = producer.onGetAttribute(StringProducer.DESCRIPTOR_COUNT_DOWN_LATCH); var scheduledEmitter = new StringScheduledEmitter(system, StringScheduledEmitter.DEFAULT_UNIT_NAME); var scheduledEmitterConfig = new ConfigurationBuilder().addString(StringScheduledEmitter.PROP_TARGET, StringConsumer.DEFAULT_UNIT_NAME) .build(); scheduledEmitter.initialize(scheduledEmitterConfig); - var consumer = new StringConsumer(system, StringConsumer.DEFAULT_UNIT_NAME); var consumerConfig = new ConfigurationBuilder().addInteger(StringConsumer.PROP_TOTAL_MESSAGES, totalMessages).build(); consumer.initialize(consumerConfig); - var consumerCountDownLatch = consumer.onGetAttribute(StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); system.addUnits(producer, scheduledEmitter, consumer); + system.setState(LifecycleState.INITIALIZED); system.start(); + var producerCountDownLatch = getAttributeOrTimeout(producer, StringProducer.DESCRIPTOR_COUNT_DOWN_LATCH); + var countDownLatchConsumer = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); + for (int i = 0; i < totalMessages; i++) { producer.onMessage(StringProducer.PROPERTY_SEND_RANDOM_MESSAGE); - TimeUnit.MILLISECONDS.sleep(10); } var producerSentMessages = producerCountDownLatch.await(totalTestTimeoutMills, TimeUnit.MILLISECONDS); - var consumerReceivedMessages = consumerCountDownLatch.await(totalTestTimeoutMills, TimeUnit.MILLISECONDS); - var producerTotalMessagesCount = producer.onGetAttribute(StringProducer.DESCRIPTOR_TOTAL_MESSAGES); + var consumerReceivedMessages = countDownLatchConsumer.await(totalTestTimeoutMills, TimeUnit.MILLISECONDS); + var producerTotalMessagesCount = getAttributeOrTimeout(producer, StringProducer.DESCRIPTOR_TOTAL_MESSAGES); + var totalReceivedMessages = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_TOTAL_MESSAGES); system.shutdown(); assertTrue(producerSentMessages); assertEquals(totalMessages, producerTotalMessagesCount); assertTrue(consumerReceivedMessages); - assert(totalMessages <= consumer.getReceivedMessages().size()); + assertEquals(totalMessages, totalReceivedMessages); } @Test - void testSchedulerWithPressureAndMultipleTasks() throws InterruptedException, ExecutionException { - RoboSystem system = new RoboSystem(); - StringConsumer consumer = new StringConsumer(system, "consumer"); + void schedulerWithPressureAndMultipleTasksTest() throws InterruptedException, ExecutionException, TimeoutException, ConfigurationException { + var totalTestTimeoutMills = 10; + var consideredTimeUnit = TimeUnit.MILLISECONDS; + var expectedTotalInvocation = 3000; + var splitTotalInvocations = expectedTotalInvocation / 2; + var system = new RoboSystem(); + var consumer = new StringConsumer(system, "consumer"); + var consumerConfig = new ConfigurationBuilder().addInteger(StringConsumer.PROP_TOTAL_MESSAGES, expectedTotalInvocation).build(); + consumer.initialize(consumerConfig); + + system.addUnits(consumer); + system.setState(LifecycleState.INITIALIZED); + system.start(); - SchedulerListener listener = new SchedulerListener(); - ScheduledFuture f1 = system.getScheduler().schedule(consumer, "Lalalala", 0, 2, TimeUnit.MILLISECONDS, 1500, + var countDownLatchConsumer = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); + var listener = new SchedulerListener(); + var f1 = system.getScheduler().schedule(consumer, "Lalalala", 0, 2, consideredTimeUnit, splitTotalInvocations, listener); - ScheduledFuture f2 = system.getScheduler().schedule(consumer, "bläblä", 1, 2, TimeUnit.MILLISECONDS, 1500); + var f2 = system.getScheduler().schedule(consumer, "bläblä", 1, 2, consideredTimeUnit, splitTotalInvocations); + futureGetSafe(f1); + futureGetSafe(f2); - get(f1); - get(f2); + var consumerReceivedMessages = countDownLatchConsumer.await(totalTestTimeoutMills, consideredTimeUnit); + var totalReceivedMessages = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_TOTAL_MESSAGES); - assertEquals(3000, consumer.getReceivedMessages().size()); + assertTrue(consumerReceivedMessages); + assertEquals(expectedTotalInvocation, totalReceivedMessages); assertTrue(listener.wasFinalCalled); system.shutdown(); } - private void get(ScheduledFuture f) throws InterruptedException, ExecutionException { - try { - f.get(); - } catch (Throwable e) { - // Expected - using this to wait for completion. - } - } + } diff --git a/robo4j-core/src/test/java/com/robo4j/RoboUnitTestUtils.java b/robo4j-core/src/test/java/com/robo4j/RoboUnitTestUtils.java index 4d325e14..ffa4caf9 100644 --- a/robo4j-core/src/test/java/com/robo4j/RoboUnitTestUtils.java +++ b/robo4j-core/src/test/java/com/robo4j/RoboUnitTestUtils.java @@ -17,15 +17,28 @@ package com.robo4j; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + import java.util.concurrent.ExecutionException; +import java.util.concurrent.ScheduledFuture; import java.util.concurrent.TimeUnit; import java.util.concurrent.TimeoutException; final public class RoboUnitTestUtils { + private static final Logger LOGGER = LoggerFactory.getLogger(RoboUnitTestUtils.class); private static final int TIMEOUT = 5; public static R getAttributeOrTimeout(RoboReference roboReference, AttributeDescriptor attributeDescriptor) throws InterruptedException, ExecutionException, TimeoutException { return roboReference.getAttribute(attributeDescriptor).get(TIMEOUT, TimeUnit.MINUTES); } + public static void futureGetSafe(ScheduledFuture f) { + try { + f.get(); + } catch (Throwable e) { + LOGGER.warn("error:{}", e.getMessage(), e); + } + } + } diff --git a/robo4j-core/src/test/java/com/robo4j/RoboUnitTests.java b/robo4j-core/src/test/java/com/robo4j/RoboUnitTests.java index a95730b8..f1bf1d53 100644 --- a/robo4j-core/src/test/java/com/robo4j/RoboUnitTests.java +++ b/robo4j-core/src/test/java/com/robo4j/RoboUnitTests.java @@ -16,60 +16,104 @@ */ package com.robo4j; -import com.robo4j.configuration.Configuration; import com.robo4j.configuration.ConfigurationBuilder; import com.robo4j.units.StringConsumer; import com.robo4j.units.StringProducer; import org.junit.jupiter.api.Test; +import java.util.concurrent.TimeUnit; + +import static com.robo4j.RoboUnitTestUtils.getAttributeOrTimeout; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertTrue; /** * Test(s) for the RoboUnits. - * + * * @author Marcus Hirt (@hirt) * @author Miroslav Wengner (@miragemiko) */ class RoboUnitTests { - @Test - void testSystem() throws Exception { - int totalMessages = 10; - RoboSystem system = new RoboSystem(); - assertEquals(system.getState(), LifecycleState.UNINITIALIZED); - StringProducer producer = new StringProducer(system, "producer"); - Configuration config = new ConfigurationBuilder().addString(StringProducer.PROP_TARGET, "consumer") - .addInteger(StringProducer.PROP_TOTAL_MESSAGES, totalMessages).build(); - producer.initialize(config); - StringConsumer consumer = new StringConsumer(system, "consumer"); - system.addUnits(producer, consumer); - system.start(); - assertEquals(system.getState(), LifecycleState.STARTED); - assertTrue(system.getState() == LifecycleState.STARTING || system.getState() == LifecycleState.STARTED); - for (int i = 0; i < totalMessages; i++) { - producer.sendRandomMessage(); - } - system.shutdown(); - assertEquals(totalMessages, consumer.getReceivedMessages().size()); - } - - @Test - void testReferences() throws Exception { - RoboSystem system = new RoboSystem(); - assertEquals(system.getState(), LifecycleState.UNINITIALIZED); - StringConsumer consumer = new StringConsumer(system, "consumer"); - system.addUnits(consumer); - assertEquals(system.getState(), LifecycleState.UNINITIALIZED); - system.setState(LifecycleState.INITIALIZED); - system.start(); - - assertTrue(system.getState() == LifecycleState.STARTING || system.getState() == LifecycleState.STARTED); - - RoboReference ref = system.getReference(consumer.getId()); - consumer.sendMessage("Lalalala"); - ref.sendMessage("Lalala"); - system.shutdown(); - assertEquals(2, consumer.getReceivedMessages().size()); - } + @Test + void systemUninitializedTest() { + RoboSystem system = new RoboSystem(); + assertEquals(system.getState(), LifecycleState.UNINITIALIZED); + } + + @Test + void systemInitializedTest() { + var system = new RoboSystem(); + var consumer = new StringConsumer(system, "consumer"); + system.addUnits(consumer); + system.setState(LifecycleState.INITIALIZED); + system.start(); + + assertEquals(LifecycleState.STARTED, system.getState()); + system.shutdown(); + } + + @Test + void systemStartTest() throws Exception { + var consideredTimeUnit = TimeUnit.MILLISECONDS; + var totalTestTimeoutMills = 10; + int expectedTotalMessages = 10; + var system = new RoboSystem(); + var producer = new StringProducer(system, "producer"); + var producerConfig = new ConfigurationBuilder().addString(StringProducer.PROP_TARGET, "consumer") + .addInteger(StringProducer.PROP_TOTAL_MESSAGES, expectedTotalMessages) + .build(); + producer.initialize(producerConfig); + var consumer = new StringConsumer(system, "consumer"); + var consumerConfig = new ConfigurationBuilder().addInteger(StringConsumer.PROP_TOTAL_MESSAGES, expectedTotalMessages).build(); + consumer.initialize(consumerConfig); + + system.addUnits(producer, consumer); + system.setState(LifecycleState.INITIALIZED); + system.start(); + + var countDownLatchConsumer = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); + + for (int i = 0; i < expectedTotalMessages; i++) { + producer.sendRandomMessage(); + } + var consumerReceivedMessages = countDownLatchConsumer.await(totalTestTimeoutMills, consideredTimeUnit); + var totalReceivedMessages = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_TOTAL_MESSAGES); + + assertTrue(consumerReceivedMessages); + assertEquals(system.getState(), LifecycleState.STARTED); + assertEquals(expectedTotalMessages, totalReceivedMessages); + system.shutdown(); + + } + + @Test + void systemStartedReferenceMessagesTest() throws Exception { + var consideredTimeUnit = TimeUnit.MILLISECONDS; + var totalTestTimeoutMills = 10; + var randomMessage = "Lalalala"; + var expectedTotalMessages = 2; + var system = new RoboSystem(); + var consumer = new StringConsumer(system, "consumer"); + var consumerConfig = new ConfigurationBuilder().addInteger(StringConsumer.PROP_TOTAL_MESSAGES, expectedTotalMessages).build(); + consumer.initialize(consumerConfig); + system.addUnits(consumer); + system.setState(LifecycleState.INITIALIZED); + system.start(); + + var consumerRef = system.getReference(consumer.id()); + assert consumerRef != null; + + var countDownLatchConsumer = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_COUNT_DOWN_LATCH); + consumer.sendMessage(randomMessage); + consumerRef.sendMessage(randomMessage); + + + var consumerReceivedMessages = countDownLatchConsumer.await(totalTestTimeoutMills, consideredTimeUnit); + var totalReceivedMessages = getAttributeOrTimeout(consumer, StringConsumer.DESCRIPTOR_TOTAL_MESSAGES); + system.shutdown(); + + assertTrue(consumerReceivedMessages); + assertEquals(expectedTotalMessages, totalReceivedMessages); + } } diff --git a/robo4j-core/src/test/java/com/robo4j/RunnableProcessCounterUnitTests.java b/robo4j-core/src/test/java/com/robo4j/RunnableProcessCounterUnitTests.java new file mode 100644 index 00000000..3269c34d --- /dev/null +++ b/robo4j-core/src/test/java/com/robo4j/RunnableProcessCounterUnitTests.java @@ -0,0 +1,146 @@ +/* + * Copyright (c) 2014, 2024, Marcus Hirt, Miroslav Wengner + * + * Robo4J is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Robo4J is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Robo4J. If not, see . + */ +package com.robo4j; + +import com.robo4j.configuration.Configuration; +import com.robo4j.configuration.ConfigurationBuilder; +import com.robo4j.units.CounterCommand; +import com.robo4j.units.CounterUnit; +import com.robo4j.units.IntegerConsumer; +import org.junit.jupiter.api.Test; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +import java.util.ArrayList; +import java.util.concurrent.ExecutionException; +import java.util.concurrent.TimeUnit; +import java.util.concurrent.TimeoutException; + +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; + +/** + * Test for the CounterUnit. + * + * @author Marcus Hirt (@hirt) + * @author Miroslav Wengner (@miragemiko) + */ +class RunnableProcessCounterUnitTests { + private static final Logger LOGGER = LoggerFactory.getLogger(RunnableProcessCounterUnitTests.class); + private static final int TIMEOUT_MIN = 2; + private static final String COUNTER_PRODUCER_ID = "counter"; + private static final String CONSUMER_ID = "consumer"; + private static final AttributeDescriptor NUMBER_OF_MESSAGES = new DefaultAttributeDescriptor<>(Integer.class, + "NumberOfReceivedMessages"); + private static final AttributeDescriptor COUNTER = new DefaultAttributeDescriptor<>(Integer.class, CounterUnit.ATTR_COUNTER); + + @SuppressWarnings({"unchecked"}) + private static final AttributeDescriptor> MESSAGES = new DefaultAttributeDescriptor<>( + (Class>) new ArrayList().getClass(), + "ReceivedMessages"); + + @Test + void runnableProcessStartTest() throws RoboBuilderException { + RoboBuilder builder = new RoboBuilder(); + builder.add(IntegerConsumer.class, CONSUMER_ID); + builder.add(CounterUnit.class, getCounterConfiguration(CONSUMER_ID, 1000), COUNTER_PRODUCER_ID); + RoboContext context = builder.build(); + + context.start(); + + assertEquals(LifecycleState.STARTED, context.getState()); + } + + @Test + void runnableGetProcessReferenceTest() throws RoboBuilderException, ExecutionException, InterruptedException, TimeoutException { + var counterMessageProducerInterval = 1000; + RoboBuilder builder = new RoboBuilder(); + builder.add(IntegerConsumer.class, CONSUMER_ID); + builder.add(CounterUnit.class, getCounterConfiguration(CONSUMER_ID, counterMessageProducerInterval), COUNTER_PRODUCER_ID); + RoboContext context = builder.build(); + context.start(); + + RoboReference messageProducer = context.getReference(COUNTER_PRODUCER_ID); + messageProducer.sendMessage(CounterCommand.START); + var latchCreatedMessagesInInterval = getAttributeOrTimeout(messageProducer, CounterUnit.DESCRIPTOR_REPORT_RECEIVED_MESSAGES_LATCH); + var createdMessages = latchCreatedMessagesInInterval.await(TIMEOUT_MIN, TimeUnit.MINUTES); + + RoboReference consumer = context.getReference(CONSUMER_ID); + + var receivedMessages = getAttributeOrTimeout(consumer, NUMBER_OF_MESSAGES); + + assertTrue(createdMessages); + assertEquals(CounterUnit.DEFAULT_RECEIVED_MESSAGE, receivedMessages); + } + + @Test + void runnableGetStoppedProcessReferenceTest() throws RoboBuilderException, ExecutionException, InterruptedException, TimeoutException { + var updatedMessageOffsetAfterStop = CounterUnit.DEFAULT_RECEIVED_MESSAGE + 2; + var counterMessageProducerInterval = 1000; + RoboBuilder builder = new RoboBuilder(); + builder.add(IntegerConsumer.class, CONSUMER_ID); + builder.add(CounterUnit.class, getCounterConfiguration(CONSUMER_ID, counterMessageProducerInterval), COUNTER_PRODUCER_ID); + RoboContext context = builder.build(); + context.start(); + + RoboReference messageProducer = context.getReference(COUNTER_PRODUCER_ID); + messageProducer.sendMessage(CounterCommand.START); + var latchCreatedMessagesInInterval = getAttributeOrTimeout(messageProducer, CounterUnit.DESCRIPTOR_REPORT_RECEIVED_MESSAGES_LATCH); + var unitActiveInternalProcessDone = getAttributeOrTimeout(messageProducer, CounterUnit.DESCRIPTOR_PROCESS_DONE); + var createdMessagesAfterStart = latchCreatedMessagesInInterval.await(TIMEOUT_MIN, TimeUnit.MINUTES); + messageProducer.sendMessage(CounterCommand.STOP); + messageProducer.sendMessage(CounterCommand.COUNTER_INC); + messageProducer.sendMessage(CounterCommand.COUNTER_INC); + messageProducer.sendMessage(CounterCommand.RESET); + var latchCreatedMessagesAfterStop = getAttributeOrTimeout(messageProducer, CounterUnit.DESCRIPTOR_REPORT_RECEIVED_MESSAGES_LATCH); + + var activeAfterStopLatch = latchCreatedMessagesAfterStop.await(TIMEOUT_MIN, TimeUnit.MINUTES); + var updatedReceivedMessageOffset = getAttributeOrTimeout(messageProducer, CounterUnit.DESCRIPTOR_RECEIVED_MESSAGE_OFFSET); + var internalProcessDone = getAttributeOrTimeout(messageProducer, CounterUnit.DESCRIPTOR_PROCESS_DONE); + + RoboReference consumer = context.getReference(CONSUMER_ID); + var receivedMessages = getAttributeOrTimeout(consumer, NUMBER_OF_MESSAGES); + + + assertFalse(unitActiveInternalProcessDone); + assertTrue(createdMessagesAfterStart); + assertEquals(LifecycleState.STARTED, context.getState()); + assertTrue(activeAfterStopLatch); + assertTrue(internalProcessDone); + assertEquals(CounterUnit.DEFAULT_RECEIVED_MESSAGE, receivedMessages); + assertEquals(updatedMessageOffsetAfterStop, updatedReceivedMessageOffset); + } + + + private Configuration getCounterConfiguration(String target, int interval) { + return new ConfigurationBuilder().addString(CounterUnit.KEY_TARGET, target) + .addInteger(CounterUnit.KEY_INTERVAL, interval) + .addInteger(CounterUnit.KEY_RECEIVED_MESSAGE, CounterUnit.DEFAULT_RECEIVED_MESSAGE) + .build(); + } + + private static R getAttributeOrTimeout(RoboReference roboReference, AttributeDescriptor attributeDescriptor) throws InterruptedException, ExecutionException, TimeoutException { + var attribute = roboReference.getAttribute(attributeDescriptor).get(TIMEOUT_MIN, TimeUnit.MINUTES); + if (attribute == null) { + attribute = roboReference.getAttribute(attributeDescriptor).get(TIMEOUT_MIN, TimeUnit.MINUTES); + LOGGER.error("roboReference:{}, no attribute:{}", roboReference.id(), attributeDescriptor.attributeName()); + } + return attribute; + } + +} diff --git a/robo4j-core/src/test/java/com/robo4j/net/AckingStringConsumer.java b/robo4j-core/src/test/java/com/robo4j/net/AckingStringConsumer.java index 68d6e6ef..3a7a0ac4 100644 --- a/robo4j-core/src/test/java/com/robo4j/net/AckingStringConsumer.java +++ b/robo4j-core/src/test/java/com/robo4j/net/AckingStringConsumer.java @@ -48,13 +48,13 @@ public class AckingStringConsumer extends RoboUnit { public static final DefaultAttributeDescriptor DESCRIPTOR_TOTAL_RECEIVED_MESSAGES = DefaultAttributeDescriptor .create(Integer.class, ATTR_TOTAL_RECEIVED_MESSAGES); public static final String ATTR_ACKNOWLEDGE = "acknowledge"; - private volatile AtomicInteger counter; + private final AtomicInteger counter; private CountDownLatch acknowledgeLatch; - private List receivedMessages = new ArrayList<>(); + private final List receivedMessages = new ArrayList<>(); /** - * @param context - * @param id + * @param context system context + * @param id system id */ public AckingStringConsumer(RoboContext context, String id) { super(TestMessageType.class, context, id); @@ -87,15 +87,15 @@ protected void onInitialization(Configuration configuration) throws Configuratio @SuppressWarnings("unchecked") @Override public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals(ATTR_TOTAL_RECEIVED_MESSAGES) - && attribute.getAttributeType() == Integer.class) { + if (attribute.attributeName().equals(ATTR_TOTAL_RECEIVED_MESSAGES) + && attribute.attributeType() == Integer.class) { return (R) (Integer) counter.get(); } - if (attribute.getAttributeName().equals(ATTR_RECEIVED_MESSAGES) && attribute.getAttributeType() == List.class) { + if (attribute.attributeName().equals(ATTR_RECEIVED_MESSAGES) && attribute.attributeType() == List.class) { return (R) receivedMessages; } - if (attribute.getAttributeName().equals(ATTR_ACK_LATCH) - && attribute.getAttributeType() == CountDownLatch.class) { + if (attribute.attributeName().equals(ATTR_ACK_LATCH) + && attribute.attributeType() == CountDownLatch.class) { return (R) acknowledgeLatch; } return null; diff --git a/robo4j-core/src/test/java/com/robo4j/net/LookupServiceTests.java b/robo4j-core/src/test/java/com/robo4j/net/LookupServiceTests.java index b8f2a031..377cbc31 100644 --- a/robo4j-core/src/test/java/com/robo4j/net/LookupServiceTests.java +++ b/robo4j-core/src/test/java/com/robo4j/net/LookupServiceTests.java @@ -16,7 +16,6 @@ */ package com.robo4j.net; -import com.robo4j.RoboContext; import org.junit.jupiter.api.Test; import org.slf4j.Logger; import org.slf4j.LoggerFactory; @@ -54,15 +53,14 @@ static LookupService getLookupService(LocalLookupServiceImpl localLookupService) } @Test - void testEncodeDecode() throws IOException { - Map metadata = new HashMap<>(); - String id = "MyID"; - int heartBeatInterval = 1234; - metadata.put("name", "Pretty Human Readable Name"); - metadata.put("uri", "robo4j://localhost:12345"); - RoboContextDescriptor descriptor = new RoboContextDescriptor(id, heartBeatInterval, metadata); - byte[] encodedDescriptor = HearbeatMessageCodec.encode(descriptor); - RoboContextDescriptor decodedDescriptor = HearbeatMessageCodec.decode(encodedDescriptor); + void encodeDecodeTest() { + var metadata = Map.of("name", "Pretty Human Readable Name", "uri", "robo4j://localhost:12345"); + var id = "MyID"; + var heartBeatInterval = 1234; + + var descriptor = new RoboContextDescriptor(id, heartBeatInterval, metadata); + var encodedDescriptor = HearbeatMessageCodec.encode(descriptor); + var decodedDescriptor = HearbeatMessageCodec.decode(encodedDescriptor); assertEquals(descriptor.getId(), decodedDescriptor.getId()); assertEquals(descriptor.getHeartBeatInterval(), decodedDescriptor.getHeartBeatInterval()); @@ -70,33 +68,36 @@ void testEncodeDecode() throws IOException { } @Test - void testLookup() throws IOException, InterruptedException { - final LookupService service = getLookupService(new LocalLookupServiceImpl()); - service.start(); - RoboContextDescriptor descriptor = createRoboContextDescriptor(); - ContextEmitter emitter = new ContextEmitter(descriptor, InetAddress.getByName(LookupServiceProvider.DEFAULT_MULTICAST_ADDRESS), - LookupServiceProvider.DEFAULT_PORT, 250); + void lookupEmitterTest() throws IOException, InterruptedException { + final var expectedDiscoveredContexts = 1; + final var service = getLookupService(new LocalLookupServiceImpl()); + final var descriptor = createRoboContextDescriptor(); + final var heartBeatIntervalMills = 1; + final var emittedMessagesHearBeatInterval = 1; + final var emitter = new ContextEmitter(descriptor, InetAddress.getByName(LookupServiceProvider.DEFAULT_MULTICAST_ADDRESS), + LookupServiceProvider.DEFAULT_PORT, heartBeatIntervalMills); + service.start(); // TODO : review sleep usage - for (int i = 0; i < 10; i++) { + for (int i = 0; i < emittedMessagesHearBeatInterval; i++) { emitter.emit(); - Thread.sleep(250); + Thread.sleep(heartBeatIntervalMills); } - Map discoveredContexts = service.getDiscoveredContexts(); - RoboContext context = service.getContext(descriptor.getId()); - ClientRemoteRoboContext remoteContext = (ClientRemoteRoboContext) context; + var discoveredContexts = service.getDiscoveredContexts(); + var context = service.getContext(descriptor.getId()); + var remoteContext = (ClientRemoteRoboContext) context; LOGGER.info("discoveredContexts:{}", discoveredContexts); LOGGER.info("Address:{}", remoteContext.getAddress()); assertNotNull(context); assertNotNull(remoteContext.getAddress()); - assertEquals(1, discoveredContexts.size()); + assertEquals(expectedDiscoveredContexts, discoveredContexts.size()); } private static RoboContextDescriptor createRoboContextDescriptor() { - Map metadata = new HashMap<>(); - String id = "MyID"; + var metadata = new HashMap(); + var id = "MyID"; int heartBeatInterval = 1234; metadata.put("name", "Pretty Human Readable Name"); metadata.put(RoboContextDescriptor.KEY_URI, "robo4j://localhost:12345"); diff --git a/robo4j-core/src/test/java/com/robo4j/net/MessageServerTest.java b/robo4j-core/src/test/java/com/robo4j/net/MessageServerTest.java index 0839826f..805c3f6e 100644 --- a/robo4j-core/src/test/java/com/robo4j/net/MessageServerTest.java +++ b/robo4j-core/src/test/java/com/robo4j/net/MessageServerTest.java @@ -32,68 +32,77 @@ import java.util.stream.Collectors; import java.util.stream.Stream; -import static org.junit.jupiter.api.Assertions.*; +import static org.junit.jupiter.api.Assertions.assertArrayEquals; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertTrue; +import static org.junit.jupiter.api.Assertions.fail; /** * @author Marcus Hirt (@hirt) * @author Miroslav Wengner (@miragemiko) */ -// TODO : remove thread sleep public class MessageServerTest { private static final Logger LOGGER = LoggerFactory.getLogger(MessageServerTest.class); - private static final String CONST_MYUUID = "myuuid"; + private static final int TIMEOUT_SEC = 30; + private static final String CONST_MY_UUID = "myuuid"; private static final String PROPERTY_SERVER_NAME = "ServerName"; + private static final int SERVER_LISTEN_DELAY_MILLIS = 250; + private static final String LOCALHOST_VALUE = "localhost"; + private static final String MESSAGE_SERVER_NAME = "Server Name"; private volatile Exception exception = null; @Test - void testClientServerMessagePassing() throws Exception { - final List messages = new ArrayList<>(); - final CountDownLatch messageLatch = new CountDownLatch(3); + void clientServerMessagePassingTest() throws Exception { - Configuration serverConfig = new ConfigurationBuilder().addString(PROPERTY_SERVER_NAME, "Server Name") - .addString(MessageServer.KEY_HOST_NAME, "localhost").build(); - MessageServer server = new MessageServer((uuid, id, message) -> { + final var messageCache = new ArrayList<>(); + final var messagesLatch = new CountDownLatch(3); + + var messageServerConfig = new ConfigurationBuilder() + .addString(PROPERTY_SERVER_NAME, MESSAGE_SERVER_NAME) + .addString(MessageServer.KEY_HOST_NAME, LOCALHOST_VALUE) + .build(); + var messageServer = new MessageServer((uuid, id, message) -> { printInfo(uuid, id, message); - messages.add(String.valueOf(message)); - messageLatch.countDown(); - }, serverConfig); + messageCache.add(String.valueOf(message)); + messagesLatch.countDown(); + }, messageServerConfig); - Thread t = new Thread(() -> { + var serverListenerThread = new Thread(() -> { try { - server.start(); + messageServer.start(); } catch (IOException e) { exception = e; fail(e.getMessage()); } }, "Server Listener"); - t.setDaemon(true); - t.start(); + serverListenerThread.setDaemon(true); + serverListenerThread.start(); for (int i = 0; i < 10; i++) { - if (server.getListeningPort() == 0) { - Thread.sleep(250); + if (messageServer.getListeningPort() == 0) { + Thread.sleep(SERVER_LISTEN_DELAY_MILLIS); } else { break; } } - Configuration clientConfig = ConfigurationFactory.createEmptyConfiguration(); - MessageClient client = new MessageClient(server.getListeningURI(), CONST_MYUUID, clientConfig); + var messageReceiverConfig = ConfigurationFactory.createEmptyConfiguration(); + var messageReceiver = new MessageClient(messageServer.getListeningURI(), CONST_MY_UUID, messageReceiverConfig); if (exception != null) { throw exception; } List testMessage = getOrderedTestMessage("My First Little Message!", "My Second Little Message!", "My Third Little Message!"); - client.connect(); + messageReceiver.connect(); for (String message : testMessage) { - client.sendMessage("test", message); + messageReceiver.sendMessage("test", message); } - var receivedMessages = messageLatch.await(2, TimeUnit.SECONDS); + var receivedMessages = messagesLatch.await(TIMEOUT_SEC, TimeUnit.SECONDS); assertTrue(receivedMessages); - assertEquals(testMessage.size(), messages.size()); - assertArrayEquals(testMessage.toArray(), messages.toArray()); + assertEquals(testMessage.size(), messageCache.size()); + assertArrayEquals(testMessage.toArray(), messageCache.toArray()); } private List getOrderedTestMessage(String... messages) { @@ -110,9 +119,11 @@ void testMessageTypes() throws Exception { final List messages = new ArrayList<>(messagesNumber); final CountDownLatch messageLatch = new CountDownLatch(messagesNumber); - Configuration serverConfig = new ConfigurationBuilder().addString(PROPERTY_SERVER_NAME, "Server Name") - .addString(MessageServer.KEY_HOST_NAME, "localhost").build(); - MessageServer server = new MessageServer((uuid, id, message) -> { + final var serverConfig = new ConfigurationBuilder() + .addString(PROPERTY_SERVER_NAME, MESSAGE_SERVER_NAME) + .addString(MessageServer.KEY_HOST_NAME, LOCALHOST_VALUE) + .build(); + var messageServer = new MessageServer((uuid, id, message) -> { printInfo(uuid, id, message); messages.add(message); messageLatch.countDown(); @@ -120,7 +131,7 @@ void testMessageTypes() throws Exception { Thread t = new Thread(() -> { try { - server.start(); + messageServer.start(); } catch (IOException e) { exception = e; fail(e.getMessage()); @@ -129,7 +140,7 @@ void testMessageTypes() throws Exception { t.setDaemon(true); t.start(); for (int i = 0; i < 10; i++) { - if (server.getListeningPort() == 0) { + if (messageServer.getListeningPort() == 0) { Thread.sleep(250); } else { break; @@ -137,22 +148,22 @@ void testMessageTypes() throws Exception { } Configuration clientConfig = ConfigurationFactory.createEmptyConfiguration(); - MessageClient client = new MessageClient(server.getListeningURI(), CONST_MYUUID, clientConfig); + MessageClient client = new MessageClient(messageServer.getListeningURI(), CONST_MY_UUID, clientConfig); if (exception != null) { throw exception; } client.connect(); // TODO : review boxing - client.sendMessage("test1", Byte.valueOf((byte) 1)); - client.sendMessage("test2", Short.valueOf((short) 2)); + client.sendMessage("test1", (byte) 1); + client.sendMessage("test2", (short) 2); client.sendMessage("test3", Character.valueOf((char) 3)); - client.sendMessage("test4", Integer.valueOf(4)); - client.sendMessage("test5", Float.valueOf(5.0f)); - client.sendMessage("test6", Long.valueOf(6)); - client.sendMessage("test7", Double.valueOf(7)); + client.sendMessage("test4", 4); + client.sendMessage("test5", 5.0f); + client.sendMessage("test6", 6L); + client.sendMessage("test7", 7d); client.sendMessage("test8", new TestMessageType(8, messageText, null)); - messageLatch.await(24, TimeUnit.HOURS); + messageLatch.await(TIMEOUT_SEC, TimeUnit.SECONDS); assertEquals(messagesNumber, messages.size()); if (messages.get(0) instanceof Byte) { diff --git a/robo4j-core/src/test/java/com/robo4j/net/RemoteContextTests.java b/robo4j-core/src/test/java/com/robo4j/net/RemoteContextTests.java index c05eacd6..7219bece 100644 --- a/robo4j-core/src/test/java/com/robo4j/net/RemoteContextTests.java +++ b/robo4j-core/src/test/java/com/robo4j/net/RemoteContextTests.java @@ -16,7 +16,11 @@ */ package com.robo4j.net; -import com.robo4j.*; +import com.robo4j.ConfigurationException; +import com.robo4j.RoboBuilder; +import com.robo4j.RoboBuilderException; +import com.robo4j.RoboContext; +import com.robo4j.RoboReference; import com.robo4j.configuration.Configuration; import com.robo4j.configuration.ConfigurationBuilder; import com.robo4j.units.StringConsumer; @@ -30,8 +34,12 @@ import java.io.IOException; import java.util.List; import java.util.concurrent.CountDownLatch; +import java.util.concurrent.TimeUnit; -import static org.junit.jupiter.api.Assertions.*; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertNotNull; +import static org.junit.jupiter.api.Assertions.assertTrue; /** * Note that on Mac OS X, it seems the easiest way to get this test to run is to @@ -43,6 +51,8 @@ class RemoteContextTests { private static final Logger LOGGER = LoggerFactory.getLogger(RemoteContextTests.class); + private static final int TIMEOUT_SEC = 30; + private static final int LOOKUP_DELAY_MILLIS = 100; private static final String ACK_CONSUMER = "ackConsumer"; private static final String REMOTE_UNIT_EMITTER = "remoteEmitter"; private static final int NUMBER_ITERATIONS = 10; @@ -52,6 +62,9 @@ class RemoteContextTests { @Test void discoveryOfDiscoveryEnabledRoboContextTest() throws RoboBuilderException, IOException { + var expectedMetaDataName = "Caprica"; + var expectedMetaDataClass = "Cylon"; + RoboBuilder builder = new RoboBuilder(SystemUtil.getInputStreamByResourceName("testDiscoverableSystem.xml")); RoboContext ctx = builder.build(); ctx.start(); @@ -60,13 +73,13 @@ void discoveryOfDiscoveryEnabledRoboContextTest() throws RoboBuilderException, I service.start(); for (int i = 0; i < NUMBER_ITERATIONS && (service.getDescriptor("6") == null); i++) { - SystemUtil.sleep(200); + SystemUtil.sleep(LOOKUP_DELAY_MILLIS); } RoboContextDescriptor descriptor = service.getDescriptor("6"); assertFalse(service.getDiscoveredContexts().isEmpty()); - assertEquals(descriptor.getMetadata().get("name"), "Caprica"); - assertEquals(descriptor.getMetadata().get("class"), "Cylon"); + assertEquals(expectedMetaDataName, descriptor.getMetadata().get("name")); + assertEquals(expectedMetaDataClass, descriptor.getMetadata().get("class")); ctx.shutdown(); } @@ -90,7 +103,7 @@ void messageToDiscoveredContextTest() throws RoboBuilderException, IOException, service.start(); for (int i = 0; i < NUMBER_ITERATIONS && (service.getDescriptor("7") == null); i++) { - SystemUtil.sleep(200); + SystemUtil.sleep(LOOKUP_DELAY_MILLIS); } assertFalse(service.getDiscoveredContexts().isEmpty()); RoboContextDescriptor descriptor = service.getDescriptor("7"); @@ -108,7 +121,7 @@ void messageToDiscoveredContextTest() throws RoboBuilderException, IOException, remoteStringProducer.sendMessage("sendRandomMessage"); for (int i = 0; i < NUMBER_ITERATIONS && consumer.getReceivedMessages().isEmpty(); i++) { - SystemUtil.sleep(200); + SystemUtil.sleep(LOOKUP_DELAY_MILLIS); } printMessagesInfo(consumer.getReceivedMessages()); @@ -134,7 +147,7 @@ void messageIncludingReferenceToDiscoveredContextTest() service.start(); for (int i = 0; i < NUMBER_ITERATIONS && (service.getDescriptor("9") == null); i++) { - SystemUtil.sleep(200); + SystemUtil.sleep(LOOKUP_DELAY_MILLIS); } assertFalse(service.getDiscoveredContexts().isEmpty()); RoboContextDescriptor descriptor = service.getDescriptor("9"); @@ -193,7 +206,7 @@ void messageToDiscoveredContextAndReferenceToDiscoveredContextTest() throws Exce remoteTestMessageProducer.sendMessage(RemoteTestMessageProducer.ATTR_SEND_MESSAGE); CountDownLatch ackConsumerCountDownLatch = ackConsumer .getAttribute(AckingStringConsumer.DESCRIPTOR_ACK_LATCH).get(); - ackConsumerCountDownLatch.await(); + var ackConsumerLatch = ackConsumerCountDownLatch.await(TIMEOUT_SEC, TimeUnit.SECONDS); List receivedMessages = (List) ackConsumer .getAttribute(AckingStringConsumer.DESCRIPTOR_MESSAGES).get(); @@ -201,13 +214,16 @@ void messageToDiscoveredContextAndReferenceToDiscoveredContextTest() throws Exce CountDownLatch producerCountDownLatch = remoteTestMessageProducer .getAttribute(RemoteTestMessageProducer.DESCRIPTOR_COUNT_DOWN_LATCH).get(); - producerCountDownLatch.await(); + var producedMessagesLatch = producerCountDownLatch.await(TIMEOUT_SEC, TimeUnit.SECONDS); CountDownLatch producerAckLatch = remoteTestMessageProducer .getAttribute(RemoteTestMessageProducer.DESCRIPTOR_ACK_LATCH).get(); - producerAckLatch.await(); + var producedMessagesAckLatch = producerAckLatch.await(TIMEOUT_SEC, TimeUnit.SECONDS); Integer producerAcknowledge = remoteTestMessageProducer .getAttribute(RemoteTestMessageProducer.DESCRIPTOR_TOTAL_ACK).get(); assertTrue(producerAcknowledge > 0); + assertTrue(ackConsumerLatch); + assertTrue(producedMessagesLatch); + assertTrue(producedMessagesAckLatch); } @Disabled("for individual testing") @@ -223,38 +239,6 @@ void startRemoteReceiverTest() throws Exception { System.in.read(); } - @Disabled("for individual testing") - @Test - void startRemoteSenderTest() throws Exception { - // Note that all this cludging about with local lookup service - // implementations etc would normally not be needed. - // This is just to isolate this test from other tests. - final LocalLookupServiceImpl localLookup = new LocalLookupServiceImpl(); - final LookupService service = LookupServiceTests.getLookupService(localLookup); - - LookupServiceProvider.setDefaultLookupService(service); - service.start(); - - // context has been discovered - RoboContextDescriptor descriptor = getRoboContextDescriptor(service, CONTEXT_ID_REMOTE_RECEIVER); - assertFalse(service.getDiscoveredContexts().isEmpty()); - assertNotNull(descriptor); - - // build the producer system - RoboContext producerEmitterSystem = buildEmitterContext(String.class, UNIT_STRING_CONSUMER, - REMOTE_UNIT_EMITTER); - localLookup.addContext(producerEmitterSystem); - - producerEmitterSystem.start(); - RoboReference remoteTestMessageProducer = producerEmitterSystem.getReference(REMOTE_UNIT_EMITTER); - - for (int i = 0; i < 10; i++) { - remoteTestMessageProducer.sendMessage("REMOTE MESSAGE :" + i); - } - - System.in.read(); - } - private RoboContext buildEmitterContext(Class clazz, String target, String unitName) throws Exception { RoboBuilder builder = new RoboBuilder( SystemUtil.getInputStreamByResourceName("testMessageEmitterSystem_8.xml")); diff --git a/robo4j-core/src/test/java/com/robo4j/net/RemoteStringProducer.java b/robo4j-core/src/test/java/com/robo4j/net/RemoteStringProducer.java index 74ed3957..41a9748e 100644 --- a/robo4j-core/src/test/java/com/robo4j/net/RemoteStringProducer.java +++ b/robo4j-core/src/test/java/com/robo4j/net/RemoteStringProducer.java @@ -60,13 +60,10 @@ public void onMessage(String message) { counter.incrementAndGet(); String[] input = message.split("::"); String messageType = input[0]; - switch (messageType) { - case "sendRandomMessage": - sendRandomMessage(); - break; - default: - LOGGER.info("don't understand message: {}", message); - + if (messageType.equals("sendRandomMessage")) { + sendRandomMessage(); + } else { + LOGGER.info("don't understand message: {}", message); } } } @@ -74,7 +71,7 @@ public void onMessage(String message) { @SuppressWarnings("unchecked") @Override public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals("getNumberOfSentMessages") && attribute.getAttributeType() == Integer.class) { + if (attribute.attributeName().equals("getNumberOfSentMessages") && attribute.attributeType() == Integer.class) { return (R) (Integer) counter.get(); } return null; diff --git a/robo4j-core/src/test/java/com/robo4j/net/RemoteTestMessageProducer.java b/robo4j-core/src/test/java/com/robo4j/net/RemoteTestMessageProducer.java index b010a6df..5e04f316 100644 --- a/robo4j-core/src/test/java/com/robo4j/net/RemoteTestMessageProducer.java +++ b/robo4j-core/src/test/java/com/robo4j/net/RemoteTestMessageProducer.java @@ -111,18 +111,18 @@ public void onMessage(String message) { @SuppressWarnings("unchecked") @Override public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals(ATTR_TOTAL_MESSAGES) && attribute.getAttributeType() == Integer.class) { + if (attribute.attributeName().equals(ATTR_TOTAL_MESSAGES) && attribute.attributeType() == Integer.class) { return (R) (Integer) totalCounter.get(); } - if (attribute.getAttributeName().equals(ATTR_COUNT_DOWN_LATCH) - && attribute.getAttributeType() == CountDownLatch.class) { + if (attribute.attributeName().equals(ATTR_COUNT_DOWN_LATCH) + && attribute.attributeType() == CountDownLatch.class) { return (R) countDownLatch; } - if (attribute.getAttributeName().equals(ATTR_ACK_LATCH) - && attribute.getAttributeType() == CountDownLatch.class) { + if (attribute.attributeName().equals(ATTR_ACK_LATCH) + && attribute.attributeType() == CountDownLatch.class) { return (R) ackLatch; } - if (attribute.getAttributeName().equals(ATTR_ACK) && attribute.getAttributeType() == Integer.class) { + if (attribute.attributeName().equals(ATTR_ACK) && attribute.attributeType() == Integer.class) { return (R) Integer.valueOf(ackCounter.get()); } return null; @@ -133,7 +133,7 @@ public void sendRandomMessage() { final String text = StringToolkit.getRandomMessage(10); // We're sending a reference to ourself for getting the acks... - final TestMessageType message = new TestMessageType(number, text, getContext().getReference(getId())); + final TestMessageType message = new TestMessageType(number, text, getContext().getReference(id())); RoboContext ctx = LookupServiceProvider.getDefaultLookupService().getContext(targetContext); ctx.getReference(target).sendMessage(message); } diff --git a/robo4j-core/src/test/java/com/robo4j/net/RoboTestContext.java b/robo4j-core/src/test/java/com/robo4j/net/RoboTestContext.java index f58a56fd..4268e271 100644 --- a/robo4j-core/src/test/java/com/robo4j/net/RoboTestContext.java +++ b/robo4j-core/src/test/java/com/robo4j/net/RoboTestContext.java @@ -93,7 +93,7 @@ public Configuration getConfiguration() { } public void addRef(RoboTestReference roboTestReference) { - referenceMap.put(roboTestReference.getId(), roboTestReference); + referenceMap.put(roboTestReference.id(), roboTestReference); } } diff --git a/robo4j-core/src/test/java/com/robo4j/net/RoboTestReference.java b/robo4j-core/src/test/java/com/robo4j/net/RoboTestReference.java index 910b14b5..41ed1371 100644 --- a/robo4j-core/src/test/java/com/robo4j/net/RoboTestReference.java +++ b/robo4j-core/src/test/java/com/robo4j/net/RoboTestReference.java @@ -44,7 +44,7 @@ public RoboTestReference(String id, Configuration configuration) { } @Override - public String getId() { + public String id() { return id; } diff --git a/robo4j-core/src/test/java/com/robo4j/units/ConfigurationConsumer.java b/robo4j-core/src/test/java/com/robo4j/units/ConfigurationConsumer.java index ded57836..cec3f5a9 100644 --- a/robo4j-core/src/test/java/com/robo4j/units/ConfigurationConsumer.java +++ b/robo4j-core/src/test/java/com/robo4j/units/ConfigurationConsumer.java @@ -65,11 +65,11 @@ protected void onInitialization(Configuration configuration) throws Configuratio @SuppressWarnings("unchecked") @Override public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals("getNumberOfSentMessages") && attribute.getAttributeType() == Integer.class) { + if (attribute.attributeName().equals("getNumberOfSentMessages") && attribute.attributeType() == Integer.class) { return (R) (Integer) counter.get(); } - if (attribute.getAttributeName().equals("getReceivedMessages") - && attribute.getAttributeType() == ArrayList.class) { + if (attribute.attributeName().equals("getReceivedMessages") + && attribute.attributeType() == ArrayList.class) { return (R) receivedMessages; } return null; diff --git a/robo4j-core/src/main/java/com/robo4j/units/CounterCommand.java b/robo4j-core/src/test/java/com/robo4j/units/CounterCommand.java similarity index 96% rename from robo4j-core/src/main/java/com/robo4j/units/CounterCommand.java rename to robo4j-core/src/test/java/com/robo4j/units/CounterCommand.java index fd586ec9..7e7e6e42 100644 --- a/robo4j-core/src/main/java/com/robo4j/units/CounterCommand.java +++ b/robo4j-core/src/test/java/com/robo4j/units/CounterCommand.java @@ -23,5 +23,5 @@ * @author Miro Wengner (@miragemiko) */ public enum CounterCommand { - START, STOP, RESET + START, STOP, RESET, COUNTER_INC } diff --git a/robo4j-core/src/test/java/com/robo4j/units/CounterUnit.java b/robo4j-core/src/test/java/com/robo4j/units/CounterUnit.java new file mode 100644 index 00000000..7d0eec17 --- /dev/null +++ b/robo4j-core/src/test/java/com/robo4j/units/CounterUnit.java @@ -0,0 +1,196 @@ +/* + * Copyright (c) 2014, 2024, Marcus Hirt, Miroslav Wengner + * + * Robo4J is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Robo4J is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Robo4J. If not, see . + */ +package com.robo4j.units; + +import com.robo4j.AttributeDescriptor; +import com.robo4j.ConfigurationException; +import com.robo4j.DefaultAttributeDescriptor; +import com.robo4j.RoboContext; +import com.robo4j.RoboReference; +import com.robo4j.RoboUnit; +import com.robo4j.configuration.Configuration; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +import java.util.concurrent.CountDownLatch; +import java.util.concurrent.ScheduledFuture; +import java.util.concurrent.TimeUnit; +import java.util.concurrent.atomic.AtomicInteger; + +/** + * A simple unit which will count upwards from zero. Useful, for example, as a + * heart beat generator. + * + * @author Marcus Hirt (@hirt) + * @author Miro Wengner (@miragemiko) + */ +public class CounterUnit extends RoboUnit { + private final class CounterRunner implements Runnable { + private final RoboReference target; + private final CountDownLatch latchReportMessages; + + private CounterRunner(RoboReference target, CountDownLatch latchReportMessages) { + this.target = target; + this.latchReportMessages = latchReportMessages; + } + + @Override + public void run() { + if (target != null) { + LOGGER.debug("send message:{} to unit:{}", counter.get(), target); + target.sendMessage(counter.getAndIncrement()); + latchReportMessages.countDown(); + } else { + LOGGER.error("The target {} for the CounterUnit does not exist! Could not send count!", target); + } + } + } + + private static final Logger LOGGER = LoggerFactory.getLogger(CounterUnit.class); + + private final AtomicInteger counter = new AtomicInteger(0); + private int interval; + private int receivedMessagesOffset; + + + public static final String ATTR_RECEIVED_MESSAGES_OFFSET = "receivedMessagesOffset"; + public static final String ATTR_COUNTER = "Counter"; + public static final String ATTR_REPORT_RECEIVED_MESSAGES_LATCH = "reportMessagesLatch"; + public static final String ATTR_PROCESS_ACTIVE = "processActive"; + + public static final DefaultAttributeDescriptor DESCRIPTOR_REPORT_RECEIVED_MESSAGES_LATCH = DefaultAttributeDescriptor + .create(CountDownLatch.class, ATTR_REPORT_RECEIVED_MESSAGES_LATCH); + public static final DefaultAttributeDescriptor DESCRIPTOR_RECEIVED_MESSAGE_OFFSET = DefaultAttributeDescriptor + .create(Integer.class, ATTR_RECEIVED_MESSAGES_OFFSET); + public static final DefaultAttributeDescriptor DESCRIPTOR_PROCESS_DONE = DefaultAttributeDescriptor + .create(Boolean.class, ATTR_PROCESS_ACTIVE); + + /** + * This configuration key controls the interval between the updates, in ms. + */ + public static final String KEY_INTERVAL = "interval"; + + public static final String KEY_RECEIVED_MESSAGE = "reportMessages"; + + /** + * The default period, if no period is configured. + */ + public static final int DEFAULT_INTERVAL = 1000; + + /** + * The report latch when requested number of message is received + */ + public static final int DEFAULT_RECEIVED_MESSAGE = 2; + + /** + * This configuration key controls the target of the counter updates. This + * configuration key is mandatory. Also, the target must exist when the + * counter unit is started, and any change whilst running will be ignored. + */ + public static final String KEY_TARGET = "target"; + + /** + * latch helps to identify the STOP state, + */ + private CountDownLatch unitLatch = new CountDownLatch(1); + + /** + * latch for reporting specific number of messages are received, by default it signal that any message was received + */ + private CountDownLatch latchReportReceivedMessages = new CountDownLatch(1); + + /* + * The currently running timer updater. + */ + private ScheduledFuture scheduledFuture; + + /* + * The id of the target. + */ + private String targetId; + + + /** + * Constructor. + * + * @param context the RoboContext. + * @param id the id of the RoboUnit. + */ + public CounterUnit(RoboContext context, String id) { + super(CounterCommand.class, context, id); + } + + @Override + protected void onInitialization(Configuration configuration) throws ConfigurationException { + interval = configuration.getInteger(KEY_INTERVAL, DEFAULT_INTERVAL); + receivedMessagesOffset = configuration.getInteger(KEY_RECEIVED_MESSAGE, DEFAULT_RECEIVED_MESSAGE); + latchReportReceivedMessages = new CountDownLatch(receivedMessagesOffset); + targetId = configuration.getString(KEY_TARGET, null); + if (targetId == null) { + throw ConfigurationException.createMissingConfigNameException(KEY_TARGET); + } + } + + @Override + public void onMessage(CounterCommand message) { + synchronized (this) { + super.onMessage(message); + switch (message) { + case START -> { + var counterUnitAction = new CounterRunner(getContext().getReference(targetId), latchReportReceivedMessages); + scheduledFuture = getContext().getScheduler().scheduleAtFixedRate( + counterUnitAction, 0, interval, TimeUnit.MILLISECONDS); + } + + case STOP -> { + if (scheduledFuture.cancel(false)) { + unitLatch.countDown(); + } else { + scheduledFuture.cancel(true); + LOGGER.error("scheduled feature could not be properly cancelled!"); + } + } + case RESET -> { + counter.set(0); + } + case COUNTER_INC -> receivedMessagesOffset++; + + } + } + } + + @SuppressWarnings("unchecked") + @Override + public synchronized R onGetAttribute(AttributeDescriptor attribute) { + if (attribute.attributeName().equals(ATTR_RECEIVED_MESSAGES_OFFSET) && attribute.attributeType() == Integer.class) { + return (R) (Integer) receivedMessagesOffset; + } + if (attribute.attributeName().equals(ATTR_COUNTER) && attribute.attributeType() == Integer.class) { + return (R) (Integer) counter.get(); + } + if (attribute.attributeName().equals(ATTR_REPORT_RECEIVED_MESSAGES_LATCH) + && attribute.attributeType() == CountDownLatch.class) { + return (R) latchReportReceivedMessages; + } + if (attribute.attributeName().equals(ATTR_PROCESS_ACTIVE) + && attribute.attributeType() == Boolean.class) { + return (R) (Boolean) scheduledFuture.isDone(); + } + return null; + } + +} diff --git a/robo4j-core/src/test/java/com/robo4j/units/IntegerConsumer.java b/robo4j-core/src/test/java/com/robo4j/units/IntegerConsumer.java index bcdf1bcb..b330241b 100644 --- a/robo4j-core/src/test/java/com/robo4j/units/IntegerConsumer.java +++ b/robo4j-core/src/test/java/com/robo4j/units/IntegerConsumer.java @@ -16,14 +16,12 @@ */ package com.robo4j.units; -import java.util.ArrayList; -import java.util.List; - import com.robo4j.AttributeDescriptor; -import com.robo4j.ConfigurationException; import com.robo4j.RoboContext; import com.robo4j.RoboUnit; -import com.robo4j.configuration.Configuration; + +import java.util.ArrayList; +import java.util.List; /** * @@ -31,11 +29,11 @@ * @author Miroslav Wengner (@miragemiko) */ public class IntegerConsumer extends RoboUnit { - private List receivedMessages = new ArrayList<>(); + private final List receivedMessages = new ArrayList<>(); /** - * @param context - * @param id + * @param context robo-context + * @param id unit id */ public IntegerConsumer(RoboContext context, String id) { super(Integer.class, context, id); @@ -50,18 +48,13 @@ public synchronized void onMessage(Integer message) { receivedMessages.add(message); } - @Override - protected void onInitialization(Configuration configuration) throws ConfigurationException { - - } - - @SuppressWarnings("unchecked") + @SuppressWarnings("unchecked") @Override public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals("NumberOfReceivedMessages") && attribute.getAttributeType() == Integer.class) { + if (attribute.attributeName().equals("NumberOfReceivedMessages") && attribute.attributeType() == Integer.class) { return (R) (Integer) receivedMessages.size(); } - if (attribute.getAttributeName().equals("ReceivedMessages") && attribute.getAttributeType() == ArrayList.class) { + if (attribute.attributeName().equals("ReceivedMessages") && attribute.attributeType() == ArrayList.class) { return (R) receivedMessages; } return null; diff --git a/robo4j-core/src/test/java/com/robo4j/units/StringConsumer.java b/robo4j-core/src/test/java/com/robo4j/units/StringConsumer.java index 05e8ef1f..febeb941 100644 --- a/robo4j-core/src/test/java/com/robo4j/units/StringConsumer.java +++ b/robo4j-core/src/test/java/com/robo4j/units/StringConsumer.java @@ -79,16 +79,16 @@ protected void onInitialization(Configuration configuration) throws Configuratio @SuppressWarnings("unchecked") @Override public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals(ATTR_TOTAL_SENT_MESSAGES) - && attribute.getAttributeType() == Integer.class) { + if (attribute.attributeName().equals(ATTR_TOTAL_SENT_MESSAGES) + && attribute.attributeType() == Integer.class) { return (R) (Integer) counter.get(); } - if (attribute.getAttributeName().equals(ATTR_GET_RECEIVED_MESSAGES) - && attribute.getAttributeType() == List.class) { + if (attribute.attributeName().equals(ATTR_GET_RECEIVED_MESSAGES) + && attribute.attributeType() == List.class) { return (R) receivedMessages; } - if (attribute.getAttributeName().equals(ATTR_COUNT_DOWN_LATCH) - && attribute.getAttributeType() == CountDownLatch.class) { + if (attribute.attributeName().equals(ATTR_COUNT_DOWN_LATCH) + && attribute.attributeType() == CountDownLatch.class) { return (R) countDownLatch; } return null; diff --git a/robo4j-core/src/test/java/com/robo4j/units/StringConsumerWorker.java b/robo4j-core/src/test/java/com/robo4j/units/StringConsumerWorker.java index ae6f0a33..d0aa316a 100644 --- a/robo4j-core/src/test/java/com/robo4j/units/StringConsumerWorker.java +++ b/robo4j-core/src/test/java/com/robo4j/units/StringConsumerWorker.java @@ -16,8 +16,10 @@ */ package com.robo4j.units; -import com.robo4j.*; -import com.robo4j.configuration.Configuration; +import com.robo4j.AttributeDescriptor; +import com.robo4j.RoboContext; +import com.robo4j.RoboUnit; +import com.robo4j.WorkTrait; import java.util.ArrayList; import java.util.List; @@ -25,52 +27,47 @@ /** * This one should schedule everything on the Worker pool. - * + * * @author Marcus Hirt (@hirt) * @author Miroslav Wengner (@miragemiko) */ @WorkTrait public class StringConsumerWorker extends RoboUnit { - private static final int DEFAULT = 0; - private AtomicInteger counter; - private List receivedMessages = new ArrayList<>(); - - /** - * @param context - * @param id - */ - public StringConsumerWorker(RoboContext context, String id) { - super(String.class, context, id); - this.counter = new AtomicInteger(DEFAULT); - } - - public synchronized List getReceivedMessages() { - return receivedMessages; - } + private static final int DEFAULT = 0; + private final AtomicInteger counter; + private final List receivedMessages = new ArrayList<>(); - @Override - public synchronized void onMessage(String message) { - counter.incrementAndGet(); - receivedMessages.add(message); - } + /** + * @param context roboContext + * @param id RoboId + */ + public StringConsumerWorker(RoboContext context, String id) { + super(String.class, context, id); + this.counter = new AtomicInteger(DEFAULT); + } - @Override - protected void onInitialization(Configuration configuration) throws ConfigurationException { + public synchronized List getReceivedMessages() { + return receivedMessages; + } - } + @Override + public synchronized void onMessage(String message) { + counter.incrementAndGet(); + receivedMessages.add(message); + } - @SuppressWarnings("unchecked") - @Override - public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals("getNumberOfSentMessages") - && attribute.getAttributeType() == Integer.class) { - return (R) (Integer) counter.get(); - } - if (attribute.getAttributeName().equals("getReceivedMessages") - && attribute.getAttributeType() == ArrayList.class) { - return (R) receivedMessages; - } - return null; - } + @SuppressWarnings("unchecked") + @Override + public synchronized R onGetAttribute(AttributeDescriptor attribute) { + if (attribute.attributeName().equals("getNumberOfSentMessages") + && attribute.attributeType() == Integer.class) { + return (R) (Integer) counter.get(); + } + if (attribute.attributeName().equals("getReceivedMessages") + && attribute.attributeType() == ArrayList.class) { + return (R) receivedMessages; + } + return null; + } } diff --git a/robo4j-core/src/test/java/com/robo4j/units/StringProducer.java b/robo4j-core/src/test/java/com/robo4j/units/StringProducer.java index cc64d2fe..018ba9ec 100644 --- a/robo4j-core/src/test/java/com/robo4j/units/StringProducer.java +++ b/robo4j-core/src/test/java/com/robo4j/units/StringProducer.java @@ -91,10 +91,10 @@ public void onMessage(String message) { @SuppressWarnings("unchecked") @Override public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals(ATTR_GET_NUMBER_OF_SENT_MESSAGES) && attribute.getAttributeType() == Integer.class) { + if (attribute.attributeName().equals(ATTR_GET_NUMBER_OF_SENT_MESSAGES) && attribute.attributeType() == Integer.class) { return (R) (Integer) counter.get(); } - if (attribute.getAttributeName().equals(ATTR_COUNT_DOWN_LATCH) && attribute.getAttributeType() == CountDownLatch.class) { + if (attribute.attributeName().equals(ATTR_COUNT_DOWN_LATCH) && attribute.attributeType() == CountDownLatch.class) { return (R) latch; } return null; diff --git a/robo4j-core/src/test/java/com/robo4j/units/StringScheduledEmitter.java b/robo4j-core/src/test/java/com/robo4j/units/StringScheduledEmitter.java index 7b6b9b32..8a3c6b7b 100644 --- a/robo4j-core/src/test/java/com/robo4j/units/StringScheduledEmitter.java +++ b/robo4j-core/src/test/java/com/robo4j/units/StringScheduledEmitter.java @@ -93,10 +93,10 @@ public void onMessage(String message) { @SuppressWarnings("unchecked") @Override public synchronized R onGetAttribute(AttributeDescriptor attribute) { - if (attribute.getAttributeName().equals(ATTR_GET_NUMBER_OF_SENT_MESSAGES) && attribute.getAttributeType() == Integer.class) { + if (attribute.attributeName().equals(ATTR_GET_NUMBER_OF_SENT_MESSAGES) && attribute.attributeType() == Integer.class) { return (R) (Integer) counter.get(); } - if (attribute.getAttributeName().equals(ATTR_COUNT_DOWN_LATCH) && attribute.getAttributeType() == CountDownLatch.class) { + if (attribute.attributeName().equals(ATTR_COUNT_DOWN_LATCH) && attribute.attributeType() == CountDownLatch.class) { return (R) latch; } return null; diff --git a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/adafruitoled/SSD1306DeviceTest.java b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/adafruitoled/SSD1306DeviceTest.java index 585683eb..9dff0655 100644 --- a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/adafruitoled/SSD1306DeviceTest.java +++ b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/adafruitoled/SSD1306DeviceTest.java @@ -24,6 +24,8 @@ import java.awt.*; import java.io.IOException; +import static com.robo4j.hw.rpi.lcd.StringUtils.STRING_SPACE; + /** * Example which prints Hello World and draws a little. It also shows the image * in a JFrame, so that it is easy to know what to expect. @@ -57,7 +59,7 @@ public static void main(String[] args) throws IOException { LOGGER.info("If the number of lines do not match your device,"); LOGGER.info("please add the number of lines as the first argument!"); - String text = args.length > 0 ? String.join(" ", args) : "Hello Maxi!"; + String text = args.length > 0 ? String.join(STRING_SPACE, args) : "Hello Maxi!"; Graphics2D gc = oled.getGraphicsContext(); gc.setColor(Color.white); gc.setBackground(Color.black); diff --git a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/magnetometer/CalibratedMagnetometerExample.java b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/magnetometer/CalibratedMagnetometerExample.java index acd7f71a..eb786024 100644 --- a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/magnetometer/CalibratedMagnetometerExample.java +++ b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/magnetometer/CalibratedMagnetometerExample.java @@ -37,6 +37,7 @@ */ public class CalibratedMagnetometerExample { private static final Logger LOGGER = LoggerFactory.getLogger(CalibratedMagnetometerExample.class); + private static final int TIMEOUT_SEC = 1; private final static ScheduledExecutorService EXECUTOR = Executors.newScheduledThreadPool(1); private static class MagnetometerPoller implements Runnable { @@ -71,7 +72,11 @@ public static void main(String[] args) throws IOException, InterruptedException EXECUTOR.scheduleAtFixedRate(new MagnetometerPoller(magnetometer), 100, 500, TimeUnit.MILLISECONDS); System.in.read(); EXECUTOR.shutdown(); - EXECUTOR.awaitTermination(1, TimeUnit.SECONDS); + var terminated = EXECUTOR.awaitTermination(TIMEOUT_SEC, TimeUnit.SECONDS); + if(!terminated){ + LOGGER.warn("example not terminated properly."); + EXECUTOR.shutdownNow(); + } LOGGER.info("Goodbye!"); } } diff --git a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/magnetometer/MagnetometerLSM303Example.java b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/magnetometer/MagnetometerLSM303Example.java index 95732def..1220f788 100644 --- a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/magnetometer/MagnetometerLSM303Example.java +++ b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/magnetometer/MagnetometerLSM303Example.java @@ -41,6 +41,7 @@ */ public class MagnetometerLSM303Example { private static final Logger LOGGER = LoggerFactory.getLogger(MagnetometerLSM303Example.class); + private static final int TIMEOUT_SEC = 1; private final static ScheduledExecutorService EXECUTOR_SERVICE = Executors.newSingleThreadScheduledExecutor(); enum PrintStyle { @@ -126,7 +127,11 @@ public static void main(String[] args) throws IOException, InterruptedException EXECUTOR_SERVICE.scheduleAtFixedRate(dg, 0, period, TimeUnit.MILLISECONDS); System.in.read(); EXECUTOR_SERVICE.shutdown(); - EXECUTOR_SERVICE.awaitTermination(1, TimeUnit.SECONDS); + var terminated = EXECUTOR_SERVICE.awaitTermination(TIMEOUT_SEC, TimeUnit.SECONDS); + if (!terminated) { + LOGGER.warn("note terminated properly"); + EXECUTOR_SERVICE.shutdownNow(); + } printMessage(printStyle, "Collected " + dg.getCount() + " values!"); } diff --git a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/pwm/ServoTester.java b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/pwm/ServoTester.java index 6c0f2a7d..82fbc303 100644 --- a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/pwm/ServoTester.java +++ b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/i2c/pwm/ServoTester.java @@ -23,6 +23,8 @@ import java.io.IOException; import java.util.Scanner; +import static com.robo4j.hw.rpi.lcd.StringUtils.STRING_SPACE; + /** * This is a simple example allowing you to try out the servos connected to a * PCA9685. @@ -50,7 +52,7 @@ public static void main(String[] args) throws IOException, InterruptedException printPrompt(); while (!"q".equals(lastCommand = scanner.nextLine())) { lastCommand = lastCommand.trim(); - String[] split = lastCommand.split(" "); + String[] split = lastCommand.split(STRING_SPACE); if (split.length != 2) { LOGGER.debug("Could not parse {}. Please try again!", lastCommand); continue; diff --git a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/imu/Bno055Example.java b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/imu/Bno055Example.java index 578ecea5..6c43fd17 100644 --- a/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/imu/Bno055Example.java +++ b/robo4j-hw-rpi/src/examples/java/com/robo4j/hw/rpi/imu/Bno055Example.java @@ -38,6 +38,7 @@ */ public class Bno055Example { private static final Logger LOGGER = LoggerFactory.getLogger(Bno055Example.class); + private static final int TIMEOUT_SEC = 1; private final static ScheduledExecutorService EXECUTOR = Executors.newScheduledThreadPool(1); private final static class BNOPrinter implements Runnable { @@ -105,7 +106,11 @@ public static void main(String[] args) throws IOException, InterruptedException EXECUTOR.scheduleAtFixedRate(new BNOPrinter(bno), 40, 500, TimeUnit.MILLISECONDS); System.in.read(); EXECUTOR.shutdown(); - EXECUTOR.awaitTermination(1000, TimeUnit.MILLISECONDS); + var terminated = EXECUTOR.awaitTermination(TIMEOUT_SEC, TimeUnit.SECONDS); + if (!terminated) { + LOGGER.warn("not terminated properly"); + EXECUTOR.shutdownNow(); + } LOGGER.info("Bye, bye!"); bno.shutdown(); } diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/camera/CameraClientException.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/camera/CameraClientException.java index e39a693e..e70e8c4d 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/camera/CameraClientException.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/camera/CameraClientException.java @@ -16,11 +16,14 @@ */ package com.robo4j.hw.rpi.camera; +import java.io.Serial; + /** * @author Marcus Hirt (@hirt) * @author Miro Wengner (@miragemiko) */ public class CameraClientException extends RuntimeException { + @Serial private static final long serialVersionUID = 1L; public CameraClientException(String message, Throwable cause) { diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/camera/RaspiDevice.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/camera/RaspiDevice.java index 4c78eba5..0033a6a1 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/camera/RaspiDevice.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/camera/RaspiDevice.java @@ -43,6 +43,7 @@ public RaspiDevice() { public byte[] executeCommandRaspistill(String command) { final Runtime runtime = Runtime.getRuntime(); try (final ByteArrayOutputStream baos = new ByteArrayOutputStream()) { + // TODO: solve deprecated Process process = runtime.exec(command); InputStream imageArray = process.getInputStream(); diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/gps/Location.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/gps/Location.java index 90ab087a..686b8bce 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/gps/Location.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/gps/Location.java @@ -18,63 +18,67 @@ /** * A 2D location on earth. - * + * * @author Marcus Hirt (@hirt) * @author Miro Wengner (@miragemiko) */ public final class Location { - private static final String STR_DEGREE = "\u00B0"; - private static final String STR_MINUTE = "'"; // "\u2032"; - private static final String STR_SECOND = "\""; // \u2033"; + private static final String STR_DEGREE = "\u00B0"; + private static final String STR_MINUTE = "'"; // "\u2032"; + private static final String STR_SECOND = "\""; // \u2033"; + public static final int DEGREE_MINS = 60; + public static final int DEGREE_SECONDS = 3600; + + private final float latitude; + private final float longitude; - private final float latitude; - private final float longitude; + /** + * Creates a new location. + * + * @param latitude the latitude in decimal degrees. + * @param longitude the longitude in decimal degrees. + */ + public Location(float latitude, float longitude) { + this.latitude = latitude; + this.longitude = longitude; + } - /** - * Creates a new location. - * - * @param latitude - * the latitude in decimal degrees. - * @param longitude - * the longitude in decimal degrees. - */ - public Location(float latitude, float longitude) { - this.latitude = latitude; - this.longitude = longitude; - } + /** + * @return the decimal degree for the latitude. + */ + public float getLatitude() { + return latitude; + } - /** - * @return the decimal degree for the latitude. - */ - public float getLatitude() { - return latitude; - } + /** + * @return the decimal degree for the longitude. + */ + public float getLongitude() { + return longitude; + } - /** - * @return the decimal degree for the longitude. - */ - public float getLongitude() { - return longitude; - } + /** + * Returns the coordinates as a String in degrees, minutes and seconds format. + * + * @return the coordinates as a String in degrees, minutes and seconds format. + */ + public String asDMS() { + return String.format("%s%s %s%s", toDMS(latitude), latitude > 0 ? "N" : "S", toDMS(longitude), longitude > 0 ? "E" : "W"); + } - /** - * Returns the coordinates as a String in degrees, minutes and seconds format. - * - * @return the coordinates as a String in degrees, minutes and seconds format. - */ - public String asDMS() { - return String.format("%s%s %s%s", toDMS(latitude), latitude > 0 ? "N" : "S", toDMS(longitude), longitude > 0 ? "E" : "W"); - } + private Object toDMS(float coordinateInDegree) { + int degreesIntAbs = Math.abs((int) coordinateInDegree); + int minute = convertDegreesByConversionType(degreesIntAbs, DEGREE_MINS); + int second = convertDegreesByConversionType(degreesIntAbs, DEGREE_SECONDS); + return String.format("%d%s%d%s%d%s", degreesIntAbs, STR_DEGREE, minute, STR_MINUTE, second, STR_SECOND); + } - private Object toDMS(float coordinate) { - int deg = Math.abs((int) coordinate); - int minute = Math.abs((int) (coordinate * 60) % 60); - int second = Math.abs((int) (coordinate * 3600) % 60); - return String.format("%d%s%d%s%d%s", deg, STR_DEGREE, minute, STR_MINUTE, second, STR_SECOND); - } + @Override + public String toString() { + return asDMS(); + } - @Override - public String toString() { - return asDMS(); - } + private int convertDegreesByConversionType(int degree, int multiplier) { + return (degree * multiplier) % DEGREE_MINS; + } } diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/gps/NmeaUtils.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/gps/NmeaUtils.java index 77a4b86a..235ca718 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/gps/NmeaUtils.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/gps/NmeaUtils.java @@ -18,71 +18,75 @@ /** * Utilities to help with Nmea messages. - * + * * @author Marcus Hirt (@hirt) * @author Miro Wengner (@miragemiko) */ public final class NmeaUtils { - /** - * Checks the NEMA line checksum. - * - * @param data - * a line of NEMA data. - * @return true if the checksum is valid. - */ - public final static boolean hasValidCheckSum(String data) { - if (!data.startsWith("$")) { - return false; - } - try { - int indexOfStar = data.indexOf('*'); - if (indexOfStar <= 0 || indexOfStar >= data.length()) { - return false; - } - String chk = data.substring(1, indexOfStar); - String checksumStr = data.substring(indexOfStar + 1); - int valid = Integer.parseInt(checksumStr.trim(), 16); - int checksum = 0; - for (int i = 0; i < chk.length(); i++) { - checksum = checksum ^ chk.charAt(i); - } - return checksum == valid; - } catch (Exception e) { - return false; - } - } - public static int getInt(String string) { - if (string == null || "".equals(string)) { - return -1; - } - return Integer.parseInt(string); - } + private NmeaUtils() { + } + + /** + * Checks the NEMA line checksum. + * + * @param data a line of NEMA data. + * @return true if the checksum is valid. + */ + public static boolean hasValidCheckSum(String data) { + if (!data.startsWith("$")) { + return false; + } + try { + int indexOfStar = data.indexOf('*'); + // TODO review the statement + if (indexOfStar <= 0 || indexOfStar >= data.length()) { + return false; + } + String chk = data.substring(1, indexOfStar); + String checksumStr = data.substring(indexOfStar + 1); + int valid = Integer.parseInt(checksumStr.trim(), 16); + int checksum = 0; + for (int i = 0; i < chk.length(); i++) { + checksum = checksum ^ chk.charAt(i); + } + return checksum == valid; + } catch (Exception e) { + return false; + } + } + + public static int getInt(String string) { + if (string == null || string.isEmpty()) { + return -1; + } + return Integer.parseInt(string); + } - public static float getFloat(String string) { - if (string == null || "".equals(string)) { - return Float.NaN; - } - return Float.parseFloat(string); - } + public static float getFloat(String string) { + if (string == null || string.isEmpty()) { + return Float.NaN; + } + return Float.parseFloat(string); + } - public static float parseNmeaFormatCoordinate(String string) { - int index = string.indexOf('.'); - if (index < 0) { - return Float.NaN; - } - float minutes = Float.parseFloat(string.substring(index - 2)); - float degrees = Integer.parseInt(string.substring(0, index - 2)); - return degrees + minutes / 60.0f; - } + public static float parseNmeaFormatCoordinate(String string) { + int index = string.indexOf('.'); + if (index < 0) { + return Float.NaN; + } + float minutes = Float.parseFloat(string.substring(index - 2)); + float degrees = Integer.parseInt(string.substring(0, index - 2)); + return degrees + minutes / 60.0f; + } - public static String cleanLine(String dataLine) { - // We only attempt to recover the first part, and only if it looks - // like it could be an ok string. - if (dataLine.startsWith("$")) { - return dataLine.substring(0, Math.min(dataLine.indexOf('*') + 3, dataLine.length())); - } - return dataLine; - } + public static String cleanLine(String dataLine) { + // We only attempt to recover the first part, and only if it looks + // like it could be an ok string. + if (dataLine.startsWith("$")) { + return dataLine.substring(0, Math.min(dataLine.indexOf('*') + 3, dataLine.length())); + } + return dataLine; + } } diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/accelerometer/AccelerometerLSM303Device.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/accelerometer/AccelerometerLSM303Device.java index bac90ce2..8e11ac8d 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/accelerometer/AccelerometerLSM303Device.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/accelerometer/AccelerometerLSM303Device.java @@ -55,7 +55,7 @@ public enum DataRate { POWER_DOWN(0x0), HZ_1(0x10), HZ_10(0x20), HZ_25(0x30), HZ_50(0x40), HZ_100(0x50), HZ_200(0x60), HZ_400( 0x70), HZ_LP_1620(0x80), HZ_N_1354_LP_5376(0x81); - private int ctrlCode; + private final int ctrlCode; DataRate(int ctrlCode) { this.ctrlCode = ctrlCode; @@ -69,7 +69,7 @@ public int getCtrlCode() { public enum PowerMode { NORMAL(0x0), LOW_POWER(0x8); - private int ctrlCode; + private final int ctrlCode; PowerMode(int ctrlCode) { this.ctrlCode = ctrlCode; @@ -83,8 +83,8 @@ public int getCtrlCode() { public enum FullScale { G_2(0x0, 1), G_4(0x10, 1), G_8(0x20, 4), G_16(0x30, 12); - private int ctrlCode; - private int sensitivity; + private final int ctrlCode; + private final int sensitivity; FullScale(int ctrlCode, int sensitivity) { this.ctrlCode = ctrlCode; diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/AbstractBackpack.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/AbstractBackpack.java index 1e14d227..c6d646a9 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/AbstractBackpack.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/AbstractBackpack.java @@ -23,6 +23,7 @@ import org.slf4j.LoggerFactory; import java.io.IOException; +import java.util.Arrays; /** * AbstractBackpack is the abstraction for all Adafruit Backpack devices @@ -80,28 +81,24 @@ short intToShort(int value) { */ void setColorByMatrixToBuffer(short x, short y, BiColor color) { switch (color) { - case RED: + case RED -> { // Turn on red LED. buffer[y] |= _BV(intToShort(x + 8)); // Turn off green LED. - buffer[y] &= ~_BV(x); - break; - case YELLOW: + buffer[y] &= (short) ~_BV(x); + } + case YELLOW -> { // Turn on green and red LED. - buffer[y] |= _BV(intToShort(x + 8)) | _BV(x); - break; - case GREEN: + buffer[y] |= (short) (_BV(intToShort(x + 8)) | _BV(x)); + } + case GREEN -> { // Turn on green LED. buffer[y] |= _BV(x); // Turn off red LED. - buffer[y] &= ~_BV(intToShort(x + 8)); - break; - case OFF: - buffer[y] &= ~_BV(x) & ~_BV(intToShort(x + 8)); - break; - default: - LOGGER.warn("setColorByMatrixToBuffer: {}", color); - break; + buffer[y] &= (short) ~_BV(intToShort(x + 8)); + } + case OFF -> buffer[y] &= (short) (~_BV(x) & ~_BV(intToShort(x + 8))); + default -> LOGGER.warn("setColorByMatrixToBuffer: {}", color); } } @@ -133,36 +130,31 @@ void setValue(int n, short v, boolean dp) { */ void setColorToBarBuffer(short a, short c, BiColor color) { switch (color) { - case RED: + case RED -> { // Turn on red LED. buffer[c] |= _BV(a); // Turn off green LED. - buffer[c] &= ~_BV(intToShort(a + 8)); - break; - case YELLOW: + buffer[c] &= (short) ~_BV(intToShort(a + 8)); + } + case YELLOW -> { // Turn on red and green LED. - buffer[c] |= _BV(a) | _BV(intToShort(a + 8)); - break; - case GREEN: + buffer[c] |= (short) (_BV(a) | _BV(intToShort(a + 8))); + } + case GREEN -> { // Turn on green LED. buffer[c] |= _BV(intToShort(a + 8)); // Turn off red LED. - buffer[c] &= ~_BV(a); - break; - case OFF: + buffer[c] &= (short) ~_BV(a); + } + case OFF -> { // Turn off red and green LED. - buffer[c] &= ~_BV(a) & ~_BV(intToShort(a + 8)); - break; - default: - LOGGER.warn("setColorToBarBuffer: {}", color); - break; + buffer[c] &= (short) (~_BV(a) & ~_BV(intToShort(a + 8))); + } + default -> LOGGER.warn("setColorToBarBuffer: {}", color); } } private void initiate(int brightness) throws IOException { -// i2CConfig.write((byte) (OSCILLATOR_TURN_ON)); // Turn on oscilator -// i2CConfig.write(blinkRate(HT16K33_BLINK_OFF)); -// i2CConfig.write(setBrightness(brightness)); writeByte((byte) (OSCILLATOR_TURN_ON)); // Turn on oscilator writeByte(blinkRate(HT16K33_BLINK_OFF)); writeByte(setBrightness(brightness)); @@ -170,18 +162,14 @@ private void initiate(int brightness) throws IOException { private void writeDisplay() throws IOException { int address = 0; - for (int i = 0; i < buffer.length; i++) { -// i2CConfig.write(address++, (byte) (buffer[i] & 0xFF)); -// i2CConfig.write(address++, (byte) (buffer[i] >> 8)); - writeByte(address++, (byte) (buffer[i] & 0xFF)); - writeByte(address++, (byte) (buffer[i] >> 8)); + for (short value : buffer) { + writeByte(address++, (byte) (value & 0xFF)); + writeByte(address++, (byte) (value >> 8)); } } private void clearBuffer() throws IOException { - for (int i = 0; i < buffer.length; i++) { - buffer[i] = 0; - } + Arrays.fill(buffer, (short) 0); } private short _BV(short i) { diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/AlphanumericDevice.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/AlphanumericDevice.java index 153f8924..8d89aca0 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/AlphanumericDevice.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/AlphanumericDevice.java @@ -39,7 +39,7 @@ public class AlphanumericDevice extends AbstractBackpack { public static final int POSITION_START = 0; public static final int POSITION_MAX = 3; - private static int[] FONTS = { 0b0000000000000001, 0b0000000000000010, 0b0000000000000100, 0b0000000000001000, 0b0000000000010000, + private static final int[] FONTS = { 0b0000000000000001, 0b0000000000000010, 0b0000000000000100, 0b0000000000001000, 0b0000000000010000, 0b0000000000100000, 0b0000000001000000, 0b0000000010000000, 0b0000000100000000, 0b0000001000000000, 0b0000010000000000, 0b0000100000000000, 0b0001000000000000, 0b0010000000000000, 0b0100000000000000, 0b1000000000000000, 0b0000000000000000, 0b0000000000000000, 0b0000000000000000, 0b0000000000000000, 0b0000000000000000, 0b0000000000000000, 0b0000000000000000, diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/BiColor8x8MatrixDevice.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/BiColor8x8MatrixDevice.java index e2bba390..901b05d6 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/BiColor8x8MatrixDevice.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/BiColor8x8MatrixDevice.java @@ -65,6 +65,7 @@ public void drawPixel(short x, short y, BiColor color) { throw new IllegalArgumentException("x and/or y out of bounds. x=" + x + " y=" + y); } + // TODO : correct switch switch (rotation) { case DEFAULT_X_Y: break; diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/LedBackpackFactory.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/LedBackpackFactory.java index 02ce90f6..73599128 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/LedBackpackFactory.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/LedBackpackFactory.java @@ -29,17 +29,12 @@ */ public final class LedBackpackFactory { - public static AbstractBackpack createDevice(I2cBus bus, int address, LedBackpackType type, int brightness) - throws IOException { - switch (type) { - case BI_COLOR_BAR_24: - return new BiColor24BarDevice(bus, address, brightness); - case BI_COLOR_MATRIX_8x8: - return new BiColor8x8MatrixDevice(bus, address, brightness); - case ALPHANUMERIC: - return new AlphanumericDevice(bus, address, brightness); - default: - throw new IllegalStateException("not available backpack: " + type); - } - } + public static AbstractBackpack createDevice(I2cBus bus, int address, LedBackpackType type, int brightness) + throws IOException { + return switch (type) { + case BI_COLOR_BAR_24 -> new BiColor24BarDevice(bus, address, brightness); + case BI_COLOR_MATRIX_8x8 -> new BiColor8x8MatrixDevice(bus, address, brightness); + case ALPHANUMERIC -> new AlphanumericDevice(bus, address, brightness); + }; + } } diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/MatrixRotation.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/MatrixRotation.java index db95041d..7af38e92 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/MatrixRotation.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitbackpack/MatrixRotation.java @@ -24,7 +24,7 @@ * @author Miroslav Wengner (@miragemiko) */ public enum MatrixRotation { - //@formatter:off + //@formatter:off NONE (0, "none"), DEFAULT_X_Y (1,"default setup to pins"), RIGHT_90 (2, "90d to default, right"), @@ -36,24 +36,24 @@ public enum MatrixRotation { LEFT_270 (8, "270d to default, left"); //@formatter:on - private int id; - private final String note; + private final int id; + private final String note; - MatrixRotation(int id, String note) { - this.id = id; - this.note = note; - } + MatrixRotation(int id, String note) { + this.id = id; + this.note = note; + } - public String getNote() { - return note; - } + public String getNote() { + return note; + } - public static MatrixRotation getById(int code) { - for (MatrixRotation r : values()) { - if (code == r.id) { - return r; - } - } - return NONE; - } + public static MatrixRotation getById(int code) { + for (MatrixRotation r : values()) { + if (code == r.id) { + return r; + } + } + return NONE; + } } diff --git a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitlcd/Button.java b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitlcd/Button.java index b138d077..d9aa3b5b 100644 --- a/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitlcd/Button.java +++ b/robo4j-hw-rpi/src/main/java/com/robo4j/hw/rpi/i2c/adafruitlcd/Button.java @@ -16,20 +16,20 @@ */ package com.robo4j.hw.rpi.i2c.adafruitlcd; +import com.robo4j.hw.rpi.i2c.adafruitlcd.impl.AdafruitLcdImpl; + import java.util.HashSet; import java.util.Set; -import com.robo4j.hw.rpi.i2c.adafruitlcd.impl.AdafruitLcdImpl; - /** * Enumeration of the Buttons on the LCD shield. - * + * * @author Marcus Hirt (@hirt) * @author Miro Wengner (@miragemiko) */ public enum Button { - // @formatter:off + // @formatter:off SELECT (0), RIGHT (1), DOWN (2), @@ -37,52 +37,48 @@ public enum Button { LEFT (4); // @formatter:on - // Port expander input pin definition - private final int pin; + // Port expander input pin definition + private final int pin; - Button(int pin) { - this.pin = pin; - } + Button(int pin) { + this.pin = pin; + } - /** - * The pin corresponding to the button. - * - * @return the pin of the button. - */ - public int getPin() { - return pin; - } + /** + * The pin corresponding to the button. + * + * @return the pin of the button. + */ + public int getPin() { + return pin; + } - /** - * Checks if a button is pressed, given an input mask. - * - * @param mask - * the input mask. - * @return true if the button is pressed, false otherwise. - * - * @see AdafruitLcdImpl#buttonsPressedBitmask() - */ - public boolean isButtonPressed(int mask) { - return ((mask >> getPin()) & 1) > 0; - } + /** + * Checks if a button is pressed, given an input mask. + * + * @param mask the input mask. + * @return true if the button is pressed, false otherwise. + * @see AdafruitLcdImpl#buttonsPressedBitmask() + */ + public boolean isButtonPressed(int mask) { + return ((mask >> getPin()) & 1) > 0; + } - /** - * Returns a set of the buttons that are pressed, according to the input - * mask. - * - * @param mask - * the input mask. - * @return a set of the buttons pressed. - * - * @see AdafruitLcdImpl#buttonsPressedBitmask() - */ - public static Set