diff --git a/pom.xml b/pom.xml index f3502dffce..f2c0b00300 100644 --- a/pom.xml +++ b/pom.xml @@ -1603,6 +1603,34 @@ + + + io.vertx + vertx-core + 4.3.3 + provided + + + io.netty + * + + + + + io.vertx + vertx-web + 4.3.3 + provided + + + io.netty + * + + + + + + diff --git a/src/main/java/org/myrobotlab/service/Ads1115.java b/src/main/java/org/myrobotlab/service/Ads1115.java index 1594f287bd..8856f1e186 100644 --- a/src/main/java/org/myrobotlab/service/Ads1115.java +++ b/src/main/java/org/myrobotlab/service/Ads1115.java @@ -8,12 +8,14 @@ import java.util.Map; import java.util.Set; +import org.myrobotlab.codec.CodecUtils; import org.myrobotlab.framework.Registration; import org.myrobotlab.framework.Service; import org.myrobotlab.framework.interfaces.Attachable; import org.myrobotlab.logging.LoggerFactory; import org.myrobotlab.logging.Logging; import org.myrobotlab.logging.LoggingFactory; +import org.myrobotlab.service.abstracts.AbstractMicrocontroller.PinListenerFilter; import org.myrobotlab.service.config.Ads1115Config; import org.myrobotlab.service.config.ServiceConfig; import org.myrobotlab.service.data.PinData; @@ -446,46 +448,12 @@ public void attachPinArrayListener(PinArrayListener listener) { } - @Override - public void attachPinListener(PinListener listener, int pinAddress) { - attach(listener, String.format("%d", pinAddress)); - } - - @Override - public void attach(PinListener listener, String pin) { - String name = listener.getName(); - - if (listener.isLocal()) { - List list = null; - if (pinListeners.containsKey(pin)) { - list = pinListeners.get(pin); - } else { - list = new ArrayList(); - } - list.add(listener); - pinListeners.put(pin, list); - - } else { - // setup for pub sub - // FIXME - there is an architectual problem here - // locally it works - but remotely - outbox would need to know - // specifics of - // the data its sending - addListener("publishPin", name, "onPin"); - } - - } - // This section contains all the new attach logic @Override public void attach(String service) throws Exception { attach(Runtime.getService(service)); } - public void attach(String listener, int pinAddress) { - attachPinListener((PinListener) Runtime.getService(listener), pinAddress); - } - public void attach(String controllerName, String deviceBus, String deviceAddress) { attach((I2CController) Runtime.getService(controllerName), deviceBus, deviceAddress); } @@ -589,7 +557,7 @@ public void disablePins() { } } - @Override + @Deprecated /* use enablePin(String pin) */ public void enablePin(int address) { if (controller == null) { error("must be connected to enable pins"); @@ -608,8 +576,7 @@ public void enablePin(int address) { } } - @Override - // TODO Implement individula sample rates per pin + @Deprecated /* sue enablePin(String, int) */ public void enablePin(int address, int rate) { setSampleRate(rate); enablePin(address); @@ -697,7 +664,7 @@ public int getLastConversionResults() { } } - @Override + @Deprecated /* use getPin(String) */ public PinDefinition getPin(int address) { if (pinIndex.containsKey(address)) { return pinIndex.get(address); @@ -769,7 +736,7 @@ public void onRegistered(Registration s) { } - @Override + @Deprecated /* use pinMode(String, String */ public void pinMode(int address, String mode) { if (mode != null && mode.equalsIgnoreCase("INPUT")) { } else { @@ -780,7 +747,10 @@ public void pinMode(int address, String mode) { @Override public void pinMode(String pin, String mode) { - pinMode(getPin(pin).getAddress(), mode); + if (mode != null && mode.equalsIgnoreCase("INPUT")) { + } else { + log.error("Ads1115 only supports INPUT mode"); + } } public Integer pinNameToAddress(String pinName) { @@ -817,7 +787,7 @@ public PinDefinition publishPinDefinition(PinDefinition pinDef) { return pinDef; } - @Override + @Deprecated /* use read(String) */ public int read(int address) { pinIndex.get(address).setValue(readADC_SingleEnded(address)); return pinIndex.get(address).getValue(); @@ -1110,7 +1080,7 @@ public void startComparator_SingleEnded(int channel, int threshold) { writeRegister(ADS1015_REG_POINTER_CONFIG, config); } - @Override + @Deprecated /* use write(String, int value) */ public void write(int address, int value) { log.error("Ads1115 only supports read, not write"); @@ -1185,5 +1155,19 @@ public Ads1115Config apply(Ads1115Config c) { return c; } + @Override + public void attachPinListener(PinListener listener) { + String name = listener.getName(); + addListener("publishPin", name); + PinListenerFilter filter = new PinListenerFilter(listener); + outbox.addFilter(name, CodecUtils.getCallbackTopicName("publishPin"), filter); + } + + @Override + public void detachPinListener(PinListener listener) { + String name = listener.getName(); + removeListener("publishPin", name); + outbox.removeFilter(name, CodecUtils.getCallbackTopicName("publishPin")); + } } diff --git a/src/main/java/org/myrobotlab/service/Arduino.java b/src/main/java/org/myrobotlab/service/Arduino.java index 89e407c18d..113fb5ae23 100644 --- a/src/main/java/org/myrobotlab/service/Arduino.java +++ b/src/main/java/org/myrobotlab/service/Arduino.java @@ -9,7 +9,6 @@ import java.util.ArrayList; import java.util.Arrays; import java.util.Enumeration; -import java.util.HashMap; import java.util.HashSet; import java.util.List; import java.util.Map; @@ -233,13 +232,20 @@ DeviceSummary[] arrayToDeviceSummary(int[] deviceSummary) { /** * Routing Attach - routes ServiceInterface.attach(service) to appropriate * methods for this class + * + * FIXME - each one of these typed functions could simply provide the name of the + * interface that desires to attach. Then routing would be done easily by + * invoke("attach" + InterfaceName, name) + * + * If further refactored, the interface might be able to provide the implementation of + * setting up pub/sub/listeners + * */ @Override public void attach(String name) throws Exception { ServiceInterface service = Runtime.getService(name); if (ServoControl.class.isAssignableFrom(service.getClass())) { attachServoControl((ServoControl) service); - ((ServoControl) service).attach(this); return; } else if (MotorControl.class.isAssignableFrom(service.getClass())) { attachMotorControl((MotorControl) service); @@ -266,20 +272,6 @@ public void attach(ServoControl servo, int pin) throws Exception { attachServoControl(servo); } - /** - * String interface - this allows you to easily use url api requests like - * /attach/nameOfListener/3 - * - * @param listener - * the listener - * @param address - * the address - */ - @Deprecated /* using single attach parameter attach(String) */ - public void attach(String listener, int address) { - attachPinListener((PinListener) Runtime.getService(listener), address); - } - @Override public void attach(UltrasonicSensorControl sensor, Integer triggerPin, Integer echoPin) throws Exception { // refer to @@ -448,7 +440,9 @@ public void attachServoControl(ServoControl servo) { msg.servoAttach(dm.getId(), pin, uS, (int) speed, servo.getName()); msg.servoAttachPin(dm.getId(), pin); } - servo.attach(this); + if (!servo.isAttached(getName())) { + send(servo.getName(), "attach", getName()); + } } /** @@ -677,6 +671,7 @@ public void detach() { // > deviceDetach/deviceId @Override public void detach(Attachable device) { + super.detach(device); if (device == null) { return; } @@ -688,13 +683,6 @@ public void detach(Attachable device) { return; } - // when a Servo detaches it wants to send a "disable()" - // so the Servo needs to detach first - and send that disable, - // before we detach it from this arduino - if (device instanceof ServoControl && device.isAttached(this)) { - device.detach(this); - } - log.info("detaching device {}", device.getName()); Integer id = getDeviceId(device); if (id != null && msg != null) { @@ -786,7 +774,7 @@ public void disablePin(String pinName) { warn("pin definition %s does not exist", pinName); return; } - + pinDef.setEnabled(false); msg.disablePin(pinDef.getAddress()); } @@ -866,19 +854,24 @@ public void enableBoardInfo(Boolean enabled) { boardInfoEnabled = enabled; } + public void enablePin(String pin) { + PinDefinition pinDef = getPin(pin); + enablePin(pinDef.getPin(), 10); + } + @Override + @Deprecated /* use enablePin(String) */ public void enablePin(int address) { - enablePin(address, 0); + PinDefinition pinDef = getPin(address); + enablePin(pinDef.getPin(), 1); } // > enablePin/address/type/b16 rate @Override + @Deprecated /* use enablePin(String, int) */ public void enablePin(int address, int rate) { PinDefinition pinDef = getPin(address); - msg.enablePin(address, getMrlPinType(pinDef), rate); - pinDef.setEnabled(true); - pinDef.setPollRate(rate); - invoke("publishPinDefinition", pinDef); // broadcast pin change + enablePin(pinDef.getPin(), rate); } /** @@ -888,7 +881,10 @@ public void enablePin(int address, int rate) { public void enablePin(String pin, int rate) { if (isConnected()) { PinDefinition pinDef = getPin(pin); - enablePin(pinDef.getAddress(), rate); + msg.enablePin(pinDef.getAddress(), getMrlPinType(pinDef), rate); + pinDef.setEnabled(true); + pinDef.setPollRate(rate); + invoke("publishPinDefinition", pinDef); // broadcast pin change } } @@ -1535,10 +1531,10 @@ public byte[] getZippedMrlComm() { return null; } - @Override /** * // > pinMode/pin/mode */ + @Deprecated /* use pinMode(String, String */ public void pinMode(int address, String modeStr) { if (modeStr.equalsIgnoreCase("OUTPUT")) { pinMode(address, Arduino.OUTPUT); @@ -1752,42 +1748,7 @@ public PinData[] publishPinArray(int[] data) { // update def with last value pinDef.setValue(value); pinArray[i] = pinData; - - // handle individual pins - broadcast("publishPin", pinData); - - } - - // TODO: improve this logic so it doesn't something more effecient. - HashMap pinDataMap = new HashMap(); - for (int i = 0; i < pinArray.length; i++) { - if (pinArray[i] != null && pinArray[i].pin != null) { - pinDataMap.put(pinArray[i].pin, pinArray[i]); - } - } - - // FIXME !!! - simple pub/sub with broadcast like PinListener - - for (String name : pinArrayListeners.keySet()) { - // put the pin data into a map for quick lookup - PinArrayListener pal = pinArrayListeners.get(name); - if (pal.getActivePins() != null && pal.getActivePins().length > 0) { - int numActive = pal.getActivePins().length; - PinData[] subArray = new PinData[numActive]; - for (int i = 0; i < numActive; i++) { - String key = pal.getActivePins()[i]; - if (pinDataMap.containsKey(key)) { - subArray[i] = pinDataMap.get(key); - } else { - subArray[i] = null; - } - } - // only the values that the listener is asking for. - pal.onPinArray(subArray); - } else { - // the full array - pal.onPinArray(pinArray); - } + invoke("publishPin", pinData); } return pinArray; } @@ -2338,7 +2299,7 @@ public ArduinoConfig apply(ArduinoConfig c) { serial = (Serial) startPeer("serial"); if (serial == null) { log.error("serial is null"); - } + } msg.setSerial(serial); serial.addByteListener(this); } else { @@ -2370,11 +2331,11 @@ public static void main(String[] args) { LoggingFactory.init(Level.INFO); - Runtime runtime = Runtime.getInstance(); - runtime.saveAllDefaults(); - Runtime.start("arduino", "Arduino"); - Runtime.start("webgui", "WebGui"); + Runtime.start("python", "Python"); + WebGui webgui = (WebGui) Runtime.create("webgui", "WebGui"); + webgui.autoStartBrowser(false); + webgui.startService(); boolean isDone = true; diff --git a/src/main/java/org/myrobotlab/service/Bno055.java b/src/main/java/org/myrobotlab/service/Bno055.java index 1086f749fc..f662a7a6dc 100644 --- a/src/main/java/org/myrobotlab/service/Bno055.java +++ b/src/main/java/org/myrobotlab/service/Bno055.java @@ -1497,7 +1497,7 @@ public void showSystemError() { public void attachInterruptPin(PinArrayControl control, int pin) { pinControl = control; this.pin = String.format("%d", pin); - control.attachPinListener(this, pin); + control.attachPinListener(this); } @Override diff --git a/src/main/java/org/myrobotlab/service/Clock.java b/src/main/java/org/myrobotlab/service/Clock.java index 14fd02b2f3..8e14001551 100644 --- a/src/main/java/org/myrobotlab/service/Clock.java +++ b/src/main/java/org/myrobotlab/service/Clock.java @@ -160,7 +160,7 @@ public void setInterval(Integer milliseconds) { broadcastState(); } - @Deprecated /* use startClock skipFirst is default behavior */ + @Deprecated /* use start skipFirst is default behavior */ public void startClock(boolean skipFirst) { startClock(); } @@ -168,9 +168,24 @@ public void startClock(boolean skipFirst) { /** * start the clock */ + @Deprecated /* use start */ public void startClock() { myClock.start(); } + + /** + * start the clock + */ + public void start() { + myClock.start(); + } + + /** + * stop the clock + */ + public void stop() { + myClock.stop(); + } /** * see if the clock is running @@ -183,6 +198,7 @@ public boolean isClockRunning() { /** * stop a clock */ + @Deprecated /* use stop */ public void stopClock() { myClock.stop(); } diff --git a/src/main/java/org/myrobotlab/service/Hd44780.java b/src/main/java/org/myrobotlab/service/Hd44780.java index 9294fee992..cc3f68ce9a 100644 --- a/src/main/java/org/myrobotlab/service/Hd44780.java +++ b/src/main/java/org/myrobotlab/service/Hd44780.java @@ -187,7 +187,7 @@ public void attachPcf8574(Pcf8574 pcf8574) { * */ public void display(String string, int line) { - log.info("display({},{})", string, line); + log.debug("display({},{})", string, line); if (!initialized) { init(); } diff --git a/src/main/java/org/myrobotlab/service/InMoov2.java b/src/main/java/org/myrobotlab/service/InMoov2.java index 51dac5ae44..07a3d49a8f 100644 --- a/src/main/java/org/myrobotlab/service/InMoov2.java +++ b/src/main/java/org/myrobotlab/service/InMoov2.java @@ -3,6 +3,7 @@ import java.io.File; import java.io.FilenameFilter; import java.io.IOException; +import java.util.ArrayList; import java.util.HashMap; import java.util.LinkedHashMap; import java.util.List; @@ -17,6 +18,7 @@ import org.myrobotlab.framework.Registration; import org.myrobotlab.framework.Service; import org.myrobotlab.framework.Status; +import org.myrobotlab.framework.TimeoutException; import org.myrobotlab.framework.interfaces.ServiceInterface; import org.myrobotlab.io.FileIO; import org.myrobotlab.logging.Level; @@ -28,10 +30,12 @@ import org.myrobotlab.service.abstracts.AbstractSpeechRecognizer; import org.myrobotlab.service.abstracts.AbstractSpeechSynthesis; import org.myrobotlab.service.config.InMoov2Config; +import org.myrobotlab.service.config.ProgramABConfig; import org.myrobotlab.service.config.ServiceConfig; import org.myrobotlab.service.data.JoystickData; import org.myrobotlab.service.data.LedDisplayData; import org.myrobotlab.service.data.Locale; +import org.myrobotlab.service.data.TopicChange; import org.myrobotlab.service.interfaces.IKJointAngleListener; import org.myrobotlab.service.interfaces.JoystickListener; import org.myrobotlab.service.interfaces.LocaleProvider; @@ -46,14 +50,20 @@ public class InMoov2 extends Service implements ServiceLifeCycleListener, TextListener, TextPublisher, JoystickListener, LocaleProvider, IKJointAngleListener { + public static class Health { + double batteryLevel = 0; + List errors = new ArrayList<>(); + } + public final static Logger log = LoggerFactory.getLogger(InMoov2.class); public static LinkedHashMap lpVars = new LinkedHashMap(); private static final long serialVersionUID = 1L; - + static String speechRecognizer = "WebkitSpeechRecognition"; + /** * This method will load a python file into the python interpreter. * @@ -93,7 +103,15 @@ public static boolean loadFile(String file) { return true; } - protected transient ProgramAB chatBot; + + + /** + * Health pojo for health checking and reporting + */ + final protected Health health = new Health(); + + @Deprecated /* avoid direct references */ + transient ProgramAB chatBot; protected List configList; @@ -101,27 +119,39 @@ public static boolean loadFile(String file) { * Configuration from runtime has started. This is when runtime starts * processing a configuration set for the first time since inmoov was started */ - protected boolean configStarted = false; + boolean configStarted = false; String currentConfigurationName = "default"; - protected transient SpeechRecognizer ear; + @Deprecated /* avoid direct references */ + transient SpeechRecognizer ear; + @Deprecated /* avoid direct references */ + transient Tracking eyesTracking; // waiting controable threaded gestures we warn user protected boolean gestureAlreadyStarted = false; protected Set gestures = new TreeSet(); - protected transient HtmlFilter htmlFilter; + @Deprecated /* avoid direct references */ + transient Tracking headTracking; - protected transient ImageDisplay imageDisplay; + @Deprecated /* avoid direct references */ + transient HtmlFilter htmlFilter; - protected String lastGestureExecuted; + @Deprecated /* avoid direct references */ + transient ImageDisplay imageDisplay; protected Long lastPirActivityTime; - protected LedDisplayData led = new LedDisplayData(); + LedDisplayData ledBoot = new LedDisplayData(0, 220, 0); + + LedDisplayData ledPir = new LedDisplayData(); + + LedDisplayData ledHeartBeat = new LedDisplayData(); + + LedDisplayData ledError = new LedDisplayData(220, 0, 0); /** * supported locales @@ -129,20 +159,43 @@ public static boolean loadFile(String file) { protected Map locales = null; protected int maxInactivityTimeSeconds = 120; - + protected transient SpeechSynthesis mouth; - protected boolean mute = false; + // transient JMonkeyEngine simulator; - protected transient OpenCV opencv; + boolean mute = false; - protected transient Python python; + @Deprecated /* avoid direct references */ + transient OpenCV opencv; + + @Deprecated /* avoid direct references */ + transient Pir pir; + + @Deprecated /* avoid direct references */ + transient Python python; + + @Deprecated /* avoid direct references */ + transient ServoMixer servoMixer; + + @Deprecated /* avoid direct references */ + transient UltrasonicSensor ultrasonicLeft; + + @Deprecated /* avoid direct references */ + transient UltrasonicSensor ultrasonicRight; protected String voiceSelected; + @Deprecated /* avoid direct references */ + transient WebGui webgui; + + private boolean pythonLibsInitialized = false; + + protected String lastGestureExecuted; public InMoov2(String n, String id) { super(n, id); + Runtime.getInstance().attachServiceLifeCycleListener(getName()); } public void addTextListener(TextListener service) { @@ -163,7 +216,9 @@ public InMoov2Config apply(InMoov2Config c) { setLocale(getSupportedLocale(Runtime.getInstance().getLocale().toString())); } - loadInitScripts(); + if (config.loadInitScripts) { + loadInitScripts(); + } if (c.loadGestures) { loadGestures(); @@ -178,10 +233,11 @@ public InMoov2Config apply(InMoov2Config c) { } catch (Exception e) { error(e); } - return c; - } + invoke("publishConfig", c); + return c; + } @Override public void attachTextListener(String name) { @@ -321,6 +377,19 @@ public void closeAllImages() { imageDisplay.closeAll(); } + public void closeHands() { + invoke("publishMoveLeftHand", 180.0, 180.0, 180.0, 180.0, 180.0, null); + invoke("publishMoveRightHand", 180.0, 180.0, 180.0, 180.0, 180.0, null); + } + + public void closeLeftHand() { + invoke("publishMoveLeftHand", 180, 180, 180, 180, 180, null); + } + + public void closeRightHand() { + invoke("publishMoveRightHand", 180, 180, 180, 180, 180, null); + } + public void cycleGestures() { // if not loaded load - // FIXME - this needs alot of "help" :P @@ -343,7 +412,7 @@ public void cycleGestures() { } } } - + public void disable() { sendToPeer("head", "disable"); sendToPeer("rightHand", "disable"); @@ -352,7 +421,7 @@ public void disable() { sendToPeer("leftArm", "disable"); sendToPeer("torso", "disable"); } - + public void displayFullScreen(String src) { try { if (imageDisplay == null) { @@ -373,6 +442,7 @@ public void enable() { sendToPeer("leftArm", "enable"); sendToPeer("torso", "enable"); } + /** * Single place for InMoov2 service to execute arbitrary code - needed @@ -405,7 +475,7 @@ public String execGesture(String gesture) { subscribe("python", "publishStatus", this.getName(), "onGestureStatus"); startedGesture(gesture); lastGestureExecuted = gesture; - Python python = (Python)Runtime.getService("python"); + Python python = (Python) Runtime.getService("python"); if (python == null) { error("python service not started"); return null; @@ -453,7 +523,7 @@ public void finishedGesture(String nameOfGesture) { // FIXME - this isn't the callback for fsm - why is it needed here ? public void fire(String event) { - invoke("publishEvent", event); + invoke("publishSystemEvent", event); } public void fullSpeed() { @@ -494,6 +564,11 @@ public InMoov2Head getHead() { return (InMoov2Head) getPeer("head"); } + public Health getHealth() { + health.batteryLevel = Runtime.getBatteryLevel(); + return health; + } + /** * finds most recent activity * @@ -615,15 +690,6 @@ public void halfSpeed() { sendToPeer("torso", "setSpeed", 20.0, 20.0, 20.0); } - /** - * execute python scripts in the init directory on startup of the service - * - * @throws IOException - */ - public void loadInitScripts() throws IOException { - loadScripts(getResourceDir() + fs + "init"); - } - public boolean isCameraOn() { if (opencv != null) { if (opencv.isCapturing()) { @@ -651,7 +717,7 @@ public void loadGestures() { * @return true/false */ public boolean loadGestures(String directory) { - invoke("publishEvent", "LOAD GESTURES"); + invoke("publishSystemEvent", "LOAD GESTURES"); // iterate over each of the python files in the directory // and load them into the python interpreter. @@ -687,6 +753,17 @@ public boolean loadGestures(String directory) { return true; } + /** + * execute python scripts in the init directory on startup of the service + * + * @throws IOException + */ + public void loadInitScripts() throws IOException { + // FIXME !!! THIS SHOULD BE DATADIR !!!! + loadScripts(getResourceDir() + fs + "init"); + loadScripts(getDataDir() + fs + "init"); + } + /** * Generalized directory python script loading method * @@ -697,7 +774,7 @@ public void loadScripts(String directory) throws IOException { File dir = new File(directory); if (!dir.exists() || !dir.isDirectory()) { - invoke("publishEvent", "LOAD SCRIPTS ERROR"); + invoke("publishSystemEvent", "LOAD SCRIPTS ERROR"); return; } @@ -818,7 +895,7 @@ public void moveTorsoBlocking(Double topStom, Double midStom, Double lowStom) { public PredicateEvent onChangePredicate(PredicateEvent event) { log.error("onChangePredicate {}", event); if (event.name.equals("topic")) { - invoke("publishEvent", String.format("TOPIC CHANGED TO %s", event.value)); + invoke("publishSystemEvent", String.format("TOPIC CHANGED TO %s", event.value)); } // depending on configuration .... // call python ? @@ -845,7 +922,7 @@ public void onCreated(String fullname) { public void onFinishedConfig(String configName) { log.info("onFinishedConfig"); - // invoke("publishEvent", "configFinished"); + // invoke("publishSystemEvent", "configFinished"); invoke("publishFinishedConfig", configName); } @@ -853,8 +930,9 @@ public void onGestureStatus(Status status) { if (!status.equals(Status.success()) && !status.equals(Status.warn("Python process killed !"))) { error("I cannot execute %s, please check logs", lastGestureExecuted); } - finishedGesture(lastGestureExecuted); + finishedGesture(lastGestureExecuted); + unsubscribe("python", "publishStatus", this.getName(), "onGestureStatus"); } @@ -875,7 +953,7 @@ public void onJointAngles(Map angleMap) { public void onJoystickInput(JoystickData input) throws Exception { // TODO timer ? to test and not send an event // switches to manual control ? - invoke("publishEvent", "joystick"); + invoke("publishSystemEvent", "joystick"); } public String onNewState(String state) { @@ -905,16 +983,14 @@ public OpenCVData onOpenCVData(OpenCVData data) { * onPirOn flash neopixel */ public void onPirOn() { - led.action = "flash"; - led.red = 50; - led.green = 100; - led.blue = 150; - led.count = 5; - led.interval = 500; - // FIXME flash on config.flashOnBoot - invoke("publishFlash"); + invoke("publishFlash", new LedDisplayData(0, 0, 220)); // pirOn event vs wake event - invoke("publishEvent", "WAKE"); + ProgramAB chatBot = (ProgramAB)getPeer("chatBot"); + chatBot.getTopic(); + String topic = chatBot.getPredicate("topic"); + if (!"WAKE".equals(topic)) { + invoke("publishSystemEvent", "WAKE"); + } } // GOOD GOOD GOOD - LOOPBACK - flexible and replacable by python @@ -948,9 +1024,9 @@ public boolean onSense(boolean b) { // setEvent("pir-sense-on" .. also sets it in config ? // config.handledEvents["pir-sense-on"] if (b) { - invoke("publishEvent", "PIR ON"); + invoke("publishSystemEvent", "PIR ON"); } else { - invoke("publishEvent", "PIR OFF"); + invoke("publishSystemEvent", "PIR OFF"); } return b; } @@ -982,10 +1058,10 @@ public void onStarted(String name) { Runtime runtime = Runtime.getInstance(); log.info("onStarted {}", name); -// BAD IDEA - better to ask for a system report or an error report -// if (runtime.isProcessingConfig()) { -// invoke("publishEvent", "CONFIG STARTED"); -// } + // BAD IDEA - better to ask for a system report or an error report + // if (runtime.isProcessingConfig()) { + // invoke("publishSystemEvent", "CONFIG STARTED"); + // } String peerKey = getPeerKey(name); if (peerKey == null) { @@ -994,19 +1070,32 @@ public void onStarted(String name) { } if (runtime.isProcessingConfig() && !configStarted) { - invoke("publishEvent", "CONFIG STARTED " + runtime.getConfigName()); + invoke("publishSystemEvent", "CONFIG STARTED " + runtime.getConfigName()); configStarted = true; } - invoke("publishEvent", "STARTED " + peerKey); + if (peerKey != null) { + // if not 1st level peer don't bother publishing a system event + invoke("publishSystemEvent", "STARTED " + peerKey); + } switch (peerKey) { case "audioPlayer": break; case "chatBot": ProgramAB chatBot = (ProgramAB) Runtime.getService(name); - chatBot.attachTextListener(getPeerName("htmlFilter")); - startPeer("htmlFilter"); + ProgramABConfig cfg = (ProgramABConfig) chatBot.getConfig(); + if (cfg.currentBotName == null || cfg.currentBotName.isEmpty()) { + String locale = getLocale().getTag(); + if (locale != null) { + cfg.currentBotName = locale; + } + } + + // initial load via subscription into chatbot cfg_ + // send to self - not using invoke, because want this to be in our + // inbox after start + send(getName(), "getConfig"); break; case "controller3": break; @@ -1037,18 +1126,16 @@ public void onStarted(String name) { break; case "left": break; - case "leftArm": + case "leftArm": // FIXME - put in config addListener("publishMoveLeftArm", name, "onMoveArm"); break; - case "leftHand": + case "leftHand": // FIXME - put in config addListener("publishMoveLeftHand", name, "onMoveHand"); break; case "mouth": mouth = (AbstractSpeechSynthesis) Runtime.getService(name); mouth.attachSpeechListener(getPeerName("ear")); break; - case "mouthControl": - break; case "neoPixel": break; case "opencv": @@ -1113,10 +1200,60 @@ public void onText(String text) { // different sources // some might be coming from the ear - some from the mouth ... - there has // to be a distinction - log.info("onText - {}", text); + log.info("onText({})", text); invoke("publishText", text); } + /** + * FIXME - this is wrong .. it should be "in python" + * + * Callback from the chatbot which in turn are relayed to a publishPython + * method that python will subscribe to, in order to process user code in + * state callbacks + * + * @param topic + * @return + */ + public TopicChange onTopic(TopicChange topic) { + log.info("onTopic({})", topic); + String callback = "on" + topic.newTopic.substring(0, 1).toUpperCase() + topic.newTopic.substring(1) + "(runtime.getService('" + getName() + "'))"; + +// if (!pythonLibsInitialized) { +// StringBuilder init_myrobotlab = new StringBuilder("import myrobotlab\n"); +// init_myrobotlab.append("myrobotlab.connect()\n"); +// invoke("publishPython", init_myrobotlab.toString()); +// +// StringBuilder init_inmoov2 = new StringBuilder("import inmoov2\n"); +// init_inmoov2.append("inmoov2.start('" + getName() + "')\n"); +// invoke("publishPython", init_inmoov2.toString()); +// +// pythonLibsInitialized = false; +// } + + // not sure about publishPython ... + // do want an onState( name + // StateChange publishState( getName(), topic, ....) + // public MrlJson ( getName(), Message msg) ??? sender + + invoke("publishPython", callback); + // changes of topic from the chatbot are relayed to callbacks in python + + return topic; + } + + public void openHands() { + invoke("publishMoveLeftHand", 0.0, 0.0, 0.0, 0.0, 0.0, null); + invoke("publishMoveRightHand", 0.0, 0.0, 0.0, 0.0, 0.0, null); + } + + public void openLeftHand() { + invoke("publishMoveLeftHand", 0.0, 0.0, 0.0, 0.0, 0.0, null); + } + + public void openRightHand() { + invoke("publishMoveRightHand", 0.0, 0.0, 0.0, 0.0, 0.0, null); + } + // TODO FIX/CHECK this, migrate from python land public void powerDown() { @@ -1161,17 +1298,8 @@ public void publish(String name, String method, Object... data) { invoke("publishMessage", msg); } - public String publishStartConfig(String configName) { - info("config %s started", configName); - invoke("publishEvent", "CONFIG STARTED " + configName); - return configName; - } - - public String publishFinishedConfig(String configName) { - info("config %s finished", configName); - invoke("publishEvent", "CONFIG LOADED " + configName); - - return configName; + public InMoov2Config publishConfig() { + return (InMoov2Config) config; } /** @@ -1184,15 +1312,11 @@ public List publishConfigList() { return configList; } - /** - * event publisher for the fsm - although other services potentially can - * consume and filter this event channel - * - * @param event - * @return - */ - public String publishEvent(String event) { - return String.format("SYSTEM_EVENT %s", event); + public String publishFinishedConfig(String configName) { + info("config %s finished", configName); + invoke("publishEvent", "CONFIG LOADED " + configName); + + return configName; } /** @@ -1201,24 +1325,19 @@ public String publishEvent(String event) { * * @return */ - public LedDisplayData publishFlash() { + public LedDisplayData publishFlash(LedDisplayData led) { return led; } + public String publishHeartbeat() { - led.action = "flash"; - led.red = 180; - led.green = 10; - led.blue = 30; - led.count = 1; - led.interval = 50; - invoke("publishFlash"); + invoke("publishFlash", new LedDisplayData(150, 0, 0)); return getName(); } /** - * A more extensible interface point than publishEvent - * FIXME - create interface for this + * A more extensible interface point than publishSystemEvent FIXME - create + * interface for this * * @param msg * @return @@ -1316,6 +1435,86 @@ public HashMap publishMoveTorso(Double topStom, Double midStom, map.put("lowStom", lowStom); return map; } + + /** + * Play an audio resource - the only difference between this method + * and publishPlayAudioFile is this function adds the resource prefix to it. + * So, if the resource dir is changed to ../InMoov/resource .. + * then publishPlayAudioFile will be ../InMoov/resource/notifications/startupsound.mp3 + * @param resource - resource to play + * @return + */ + public String publishPlay(String resource) { + String ret = getResourceDir() + fs + resource; + invoke("publishPlayAudioFile", ret); + return ret; + } + + /** + * publishing point for desired sounds to be played. + * Full "relative" path of file relative to cwd + * + * @param filepath - relative path file to play + * @return + */ + public String publishPlayAudioFile(String filepath) { + return filepath; + } + + /** + * + * @param resource + * @return + */ + public String publishPlayRandom(String resource) { + String ret = getResourceDir() + fs + resource; + invoke("publishPlayRandomAudioFile", ret); + return ret; + } + + /** + * plays random file on certain notifications + * + * @param dirpath + * @return + */ + public String publishPlayRandomAudioFile(String dirpath) { + return dirpath; + } + + public String publishPython(String code) { + log.info("publishPython({})", code); + return code; + } + + public String publishStartConfig(String configName) { + info("config %s started", configName); + invoke("publishSystemEvent", "CONFIG STARTED " + configName); + return configName; + } + + @Override + public Status publishStatus(Status status) { + if (status.isError()) { + health.errors.add(status); + } + return status; + } + + /** + * event publisher for the fsm - although other services potentially can + * consume and filter this event channel + * + * @param event + * @return + */ + public String publishSystemEvent(String event) { + InMoov2Config c = (InMoov2Config) config; + if (c.customSound) { + invoke("publishPlayRandomAudioFile", getResourceDir() + fs + "system" + fs + "sounds" + fs + "Notifications"); + } + return String.format("SYSTEMEVENT %s", event); + } /** * all published text from InMoov2 - including ProgramAB @@ -1329,7 +1528,7 @@ public String publishText(String text) { public void releasePeer(String peerKey) { super.releasePeer(peerKey); if (peerKey != null) { - invoke("publishEvent", "STOPPED " + peerKey); + invoke("publishSystemEvent", "STOPPED " + peerKey); } } @@ -1554,6 +1753,11 @@ public void setTorsoVelocity(Double topStom, Double midStom, Double lowStom) { setTorsoSpeed(topStom, midStom, lowStom); } + // ----------------------------------------------------------------------------- + // These are methods added that were in InMoov1 that we no longer had in + // InMoov2. + // From original InMoov1 so we don't loose the + public void setVoice(String name) { if (mouth != null) { mouth.setVoice(name); @@ -1562,11 +1766,6 @@ public void setVoice(String name) { } } - // ----------------------------------------------------------------------------- - // These are methods added that were in InMoov1 that we no longer had in - // InMoov2. - // From original InMoov1 so we don't loose the - public void sleeping() { log.error("sleeping"); } @@ -1613,13 +1812,85 @@ public void speakBlocking(String format, Object... args) { } } + @Deprecated /* use config to start appropriate components */ public void startAll() throws Exception { startAll(null, null); } + // public void startBrain() { + // startChatBot(); + // } + + // public ProgramAB startChatBot() { + // + // try { + // chatBot = (ProgramAB) startPeer("chatBot"); + // + // if (locale != null) { + // chatBot.setCurrentBotName(locale.getTag()); + // } + // + // // FIXME remove get en.properties stuff + // speakBlocking(get("CHATBOTACTIVATED")); + // + // chatBot.attachTextPublisher(ear); + // + // // this.attach(chatBot); FIXME - attach as a TextPublisher - then + // // re-publish + // // FIXME - deal with language + // // speakBlocking(get("CHATBOTACTIVATED")); + // chatBot.repetitionCount(10); + // // chatBot.setPath(getResourceDir() + fs + "chatbot"); + // // chatBot.setPath(getDataDir() + "ProgramAB"); + // chatBot.startSession("default", locale.getTag()); + // // reset some parameters to default... + // chatBot.setPredicate("topic", "default"); + // chatBot.setPredicate("questionfirstinit", ""); + // chatBot.setPredicate("tmpname", ""); + // chatBot.setPredicate("null", ""); + // // load last user session + // if (!chatBot.getPredicate("name").isEmpty()) { + // if (chatBot.getPredicate("lastUsername").isEmpty() || + // chatBot.getPredicate("lastUsername").equals("unknown") || + // chatBot.getPredicate("lastUsername").equals("default")) { + // chatBot.setPredicate("lastUsername", chatBot.getPredicate("name")); + // } + // } + // chatBot.setPredicate("parameterHowDoYouDo", ""); + // chatBot.savePredicates(); + // htmlFilter = (HtmlFilter) startPeer("htmlFilter");// + // Runtime.start("htmlFilter", + // // "HtmlFilter"); + // chatBot.attachTextListener(htmlFilter); + // htmlFilter.attachTextListener((TextListener) getPeer("mouth")); + // chatBot.attachTextListener(this); + // // start session based on last recognized person + // // if (!chatBot.getPredicate("default", "lastUsername").isEmpty() && + // // !chatBot.getPredicate("default", "lastUsername").equals("unknown")) { + // // chatBot.startSession(chatBot.getPredicate("lastUsername")); + // // } + // if (chatBot.getPredicate("default", "firstinit").isEmpty() || + // chatBot.getPredicate("default", "firstinit").equals("unknown") + // || chatBot.getPredicate("default", "firstinit").equals("started")) { + // chatBot.startSession(chatBot.getPredicate("default", "lastUsername")); + // invoke("publishSystemEvent", "FIRST INIT"); + // } else { + // chatBot.startSession(chatBot.getPredicate("default", "lastUsername")); + // invoke("publishSystemEvent", "WAKE UP"); + // } + // } catch (Exception e) { + // speak("could not load chatBot"); + // error(e.getMessage()); + // speak(e.getMessage()); + // } + // broadcastState(); + // return chatBot; + // } + + @Deprecated /* use config to start appropriate components */ public void startAll(String leftPort, String rightPort) throws Exception { startMouth(); - startChatBot(); + // startChatBot(); // startHeadTracking(); // startEyesTracking(); @@ -1632,72 +1903,6 @@ public void startAll(String leftPort, String rightPort) throws Exception { speakBlocking(get("STARTINGSEQUENCE")); } - public void startBrain() { - startChatBot(); - } - - public ProgramAB startChatBot() { - - try { - chatBot = (ProgramAB) startPeer("chatBot"); - - if (locale != null) { - chatBot.setCurrentBotName(locale.getTag()); - } - - // FIXME remove get en.properties stuff - speakBlocking(get("CHATBOTACTIVATED")); - - chatBot.attachTextPublisher(ear); - - // this.attach(chatBot); FIXME - attach as a TextPublisher - then - // re-publish - // FIXME - deal with language - // speakBlocking(get("CHATBOTACTIVATED")); - chatBot.repetitionCount(10); - // chatBot.setPath(getResourceDir() + fs + "chatbot"); - // chatBot.setPath(getDataDir() + "ProgramAB"); - chatBot.startSession("default", locale.getTag()); - // reset some parameters to default... - chatBot.setPredicate("topic", "default"); - chatBot.setPredicate("questionfirstinit", ""); - chatBot.setPredicate("tmpname", ""); - chatBot.setPredicate("null", ""); - // load last user session - if (!chatBot.getPredicate("name").isEmpty()) { - if (chatBot.getPredicate("lastUsername").isEmpty() || chatBot.getPredicate("lastUsername").equals("unknown") || chatBot.getPredicate("lastUsername").equals("default")) { - chatBot.setPredicate("lastUsername", chatBot.getPredicate("name")); - } - } - chatBot.setPredicate("parameterHowDoYouDo", ""); - chatBot.savePredicates(); - htmlFilter = (HtmlFilter) startPeer("htmlFilter");// Runtime.start("htmlFilter", - // "HtmlFilter"); - chatBot.attachTextListener(htmlFilter); - htmlFilter.attachTextListener((TextListener) getPeer("mouth")); - chatBot.attachTextListener(this); - // start session based on last recognized person - // if (!chatBot.getPredicate("default", "lastUsername").isEmpty() && - // !chatBot.getPredicate("default", "lastUsername").equals("unknown")) { - // chatBot.startSession(chatBot.getPredicate("lastUsername")); - // } - if (chatBot.getPredicate("default", "firstinit").isEmpty() || chatBot.getPredicate("default", "firstinit").equals("unknown") - || chatBot.getPredicate("default", "firstinit").equals("started")) { - chatBot.startSession(chatBot.getPredicate("default", "lastUsername")); - invoke("publishEvent", "FIRST INIT"); - } else { - chatBot.startSession(chatBot.getPredicate("default", "lastUsername")); - invoke("publishEvent", "WAKE UP"); - } - } catch (Exception e) { - speak("could not load chatBot"); - error(e.getMessage()); - speak(e.getMessage()); - } - broadcastState(); - return chatBot; - } - public SpeechRecognizer startEar() { ear = (SpeechRecognizer) startPeer("ear"); @@ -1721,6 +1926,11 @@ public void startedGesture(String nameOfGesture) { } } + public void startHealthCheck() { + InMoov2Config c = (InMoov2Config) config; + addTask(c.healthCheckTimerMs, "getHealth"); + } + public void startHeartbeat() { addTask(1000, "publishHeartbeat"); } @@ -1775,12 +1985,6 @@ public OpenCV startOpenCV() { return opencv; } - @Override - public ServiceInterface startPeer(String peer) { - ServiceInterface si = super.startPeer(peer); - return si; - } - @Override public void startService() { super.startService(); @@ -1791,6 +1995,8 @@ public void startService() { // get service start and release life cycle events runtime.attachServiceLifeCycleListener(getName()); + // all existing servo service are automatically autoDisabled = true + // TODO should be in config InMoov2Config.servoAutoDisable:true List services = Runtime.getServices(); for (ServiceInterface si : services) { if ("Servo".equals(si.getSimpleName())) { @@ -1798,18 +2004,24 @@ public void startService() { } } + // FIXME - these should be handled by the StateMachine // get events of new services and shutdown subscribe("runtime", "shutdown"); // power up loopback subscription addListener(getName(), "powerUp"); - - + + // sad, but this is for the InMoov2 UI and the desire to put + // runtime related things there :( subscribe("runtime", "publishConfigList"); if (runtime.isProcessingConfig()) { - invoke("publishEvent", "configStarted"); + invoke("publishSystemEvent", "configStarted"); } - subscribe("runtime", "publishStartConfig"); - subscribe("runtime", "publishFinishedConfig"); + + // chatbot getresponse attached to publishSystemEvent + addListener("publishSystemEvent", getPeerName("chatBot"), "getResponse"); + + // chatbot getresponse attached to publishEvent + addListener("publishEvent", getPeerName("chatBot"), "getResponse"); // chatbot getresponse attached to publishEvent addListener("publishEvent", getPeerName("chatBot"), "getResponse"); @@ -1837,6 +2049,22 @@ public void startService() { } runtime.invoke("publishConfigList"); + + if (c.bootUpSound) { + invoke("publishPlayAudioFile", getResourceDir() + fs + "system" + fs + "sounds" + fs + "startupsound.mp3"); + } + + invoke("publishFlash"); + + // process all currently running services + // since registering for them to start won't process + // them + for (String service : Runtime.getServiceNames()) { + onStarted(service); + } + + invoke("publishSystemEvent", "BootUpCompleted"); + } public void startServos() { @@ -1868,6 +2096,10 @@ public void stopGesture() { p.stop(); } + public void stopHealthCheck() { + purgeTask("getHealth"); + } + public void stopHeartbeat() { purgeTask("publishHeartbeat"); } @@ -1876,6 +2108,10 @@ public void stopNeopixelAnimation() { sendToPeer("neopixel", "clear"); } + public void syncConfigToPredicates() { + + } + public void systemCheck() { log.error("systemCheck()"); Runtime runtime = Runtime.getInstance(); @@ -1896,7 +2132,7 @@ public void systemCheck() { Platform platform = Runtime.getPlatform(); setPredicate("system version", platform.getVersion()); // ERROR buffer !!! - invoke("publishEvent", "systemCheckFinished"); + invoke("publishSystemEvent", "systemCheckFinished"); } // FIXME - if this is really desired it will drive local references for all @@ -1910,8 +2146,7 @@ public void waitTargetPos() { sendToPeer("leftArm", "waitTargetPos"); sendToPeer("torso", "waitTargetPos"); } - - + public static void main(String[] args) { try { @@ -1921,14 +2156,10 @@ public static void main(String[] args) { // Runtime.start("intro", "Intro"); // Runtime.startConfig("pr-1213-1"); - - Runtime.main(new String[] {"--log-level", "info", "-s", "webgui", "WebGui", "intro", "Intro", "python", "Python"}); - - boolean done = true; - if (done) { - return; - } + Runtime.main(new String[] { "--log-level", "info", "-s", "intro", "Intro", "python", "Python" }); + + // Runtime.start("bot","ProgramAB"); WebGui webgui = (WebGui) Runtime.create("webgui", "WebGui"); // webgui.setSsl(true); @@ -1936,6 +2167,11 @@ public static void main(String[] args) { // webgui.setPort(8888); webgui.startService(); + boolean done = true; + if (done) { + return; + } + Runtime.start("python", "Python"); // Runtime.start("ros", "Ros"); Runtime.start("intro", "Intro"); @@ -1947,7 +2183,6 @@ public static void main(String[] args) { // Polly polly = (Polly)Runtime.start("i01.mouth", "Polly"); // i01 = (InMoov2) Runtime.start("i01", "InMoov2"); - // polly.speakBlocking("Hi, to be or not to be that is the question, // wheather to take arms against a see of trouble, and by aposing them end // them, to sleep, to die"); @@ -1987,14 +2222,13 @@ public static void main(String[] args) { random.save(); -// i01.startChatBot(); -// -// i01.startAll("COM3", "COM4"); + // i01.startChatBot(); + // + // i01.startAll("COM3", "COM4"); Runtime.start("python", "Python"); } catch (Exception e) { log.error("main threw", e); } - } - + } } diff --git a/src/main/java/org/myrobotlab/service/Mpr121.java b/src/main/java/org/myrobotlab/service/Mpr121.java index d71ca4da60..d81c62a17e 100644 --- a/src/main/java/org/myrobotlab/service/Mpr121.java +++ b/src/main/java/org/myrobotlab/service/Mpr121.java @@ -8,12 +8,14 @@ import java.util.Map; import java.util.Set; +import org.myrobotlab.codec.CodecUtils; import org.myrobotlab.framework.Registration; import org.myrobotlab.framework.Service; import org.myrobotlab.framework.interfaces.Attachable; import org.myrobotlab.logging.LoggerFactory; import org.myrobotlab.logging.Logging; import org.myrobotlab.logging.LoggingFactory; +import org.myrobotlab.service.abstracts.AbstractMicrocontroller.PinListenerFilter; import org.myrobotlab.service.config.Mpr121Config; import org.myrobotlab.service.config.ServiceConfig; import org.myrobotlab.service.data.PinData; @@ -534,7 +536,7 @@ public List getPinList() { return list; } - @Override + @Deprecated public int read(int address) { return pinIndex.get(address).getValue(); } @@ -544,7 +546,7 @@ public int read(String pinName) { return read(pinNameToAddress(pinName)); } - @Override + @Deprecated /* use pinMode(String, String */ public void pinMode(int address, String mode) { if (mode != null && mode.equalsIgnoreCase("INPUT")) { } else { @@ -566,58 +568,15 @@ public PinData[] publishPinArray(PinData[] pinData) { return pinData; } - public void attach(String listener, int pinAddress) { - attachPinListener((PinListener) Runtime.getService(listener), pinAddress); - } - - @Override - public void attachPinListener(PinListener listener, int pinAddress) { - String name = listener.getName(); - - if (listener.isLocal()) { - List list = null; - if (pinListeners.containsKey(pinAddress)) { - list = pinListeners.get(pinAddress); - } else { - list = new ArrayList(); - } - list.add(listener); - pinListeners.put(pinAddress, list); - - } else { - // setup for pub sub - // FIXME - there is an architectual problem here - // locally it works - but remotely - outbox would need to know - // specifics of - // the data its sending - addListener("publishPin", name, "onPin"); - } - - } - @Override public void attachPinArrayListener(PinArrayListener listener) { pinArrayListeners.put(listener.getName(), listener); } - @Override + @Deprecated /* use enablePin(String pin) */ public void enablePin(int address) { - if (controller == null) { - error("must be connected to enable pins"); - return; - } - - log.info("enablePin {}", address); - PinDefinition pin = pinIndex.get(address); - pin.setEnabled(true); - invoke("publishPinDefinition", pin); - - if (!isPublishing) { - log.info("Starting a new publisher instance"); - publisher = new Publisher(getName()); - publisher.start(); - } + enablePin(address + "", 1); } @Override @@ -700,11 +659,9 @@ public PinDefinition publishPinDefinition(PinDefinition pinDef) { return pinDef; } - @Override - // TODO Implement individula sample rates per pin + @Deprecated public void enablePin(int address, int rate) { - setSampleRate(rate); - enablePin(address); + enablePin(address + "", rate); } // This section contains all the new attach logic @@ -820,7 +777,7 @@ public PinDefinition getPin(String pinName) { return null; } - @Override + @Deprecated public PinDefinition getPin(int address) { if (pinIndex.containsKey(address)) { return pinIndex.get(address); @@ -829,8 +786,18 @@ public PinDefinition getPin(int address) { } @Override - public void attach(PinListener listener, String pin) { - attachPinListener(listener, getPin(pin).getAddress()); + public void attachPinListener(PinListener listener) { + String name = listener.getName(); + addListener("publishPin", name); + PinListenerFilter filter = new PinListenerFilter(listener); + outbox.addFilter(name, CodecUtils.getCallbackTopicName("publishPin"), filter); + } + + @Override + public void detachPinListener(PinListener listener) { + String name = listener.getName(); + removeListener("publishPin", name); + outbox.removeFilter(name, CodecUtils.getCallbackTopicName("publishPin")); } @Override @@ -845,7 +812,23 @@ public void enablePin(String pin) { @Override public void enablePin(String pin, int rate) { - enablePin(getPin(pin).getAddress(), rate); + setSampleRate(rate); + + if (controller == null) { + error("must be connected to enable pins"); + return; + } + + log.info("enablePin {}", pin); + PinDefinition pinDef = pinMap.get(pin); + pinDef.setEnabled(true); + invoke("publishPinDefinition", pinDef); + + if (!isPublishing) { + log.info("Starting a new publisher instance"); + publisher = new Publisher(getName()); + publisher.start(); + } } @Override @@ -858,7 +841,7 @@ public void write(String pin, int value) { write(getPin(pin).getAddress(), value); } - @Override + @Deprecated /* use write(String, int value) */ public void write(int address, int value) { log.error("Mpr121 does not support writing"); } diff --git a/src/main/java/org/myrobotlab/service/Mpu6050.java b/src/main/java/org/myrobotlab/service/Mpu6050.java index ac33ec9907..9cf4786b2e 100644 --- a/src/main/java/org/myrobotlab/service/Mpu6050.java +++ b/src/main/java/org/myrobotlab/service/Mpu6050.java @@ -49,7 +49,7 @@ public class Mpu6050 extends Service implements I2CControl, Orien protected transient HashSet listeners = new HashSet(); - final protected OrientationPublisher publisher = new OrientationPublisher(); + transient final protected OrientationPublisher publisher = new OrientationPublisher(); protected transient I2CController controller; @@ -67,21 +67,22 @@ public class Mpu6050 extends Service implements I2CControl, Orien protected String controllerName; + protected boolean isPublishing = false; + /** * frequency */ protected Double sampleRateHz = 3.0; protected class OrientationPublisher implements Runnable { - protected boolean isRunning = false; private transient Thread thread = null; @Override public void run() { try { - isRunning = true; + isPublishing = true; dmpInitialize(); // TODO check initialize() switch use dmp? - while (isRunning) { + while (isPublishing) { refresh(); invoke("publishOrientation", data.orientation); invoke("publishMpu6050Data", data); @@ -92,11 +93,11 @@ public void run() { log.error("publisher threw", e); error("publisher error %s", e.getMessage()); } - isRunning = false; + isPublishing = false; } public synchronized void start() { - if (isRunning) { + if (isPublishing) { return; } thread = new Thread(this, String.format("%s-publisher", getName())); @@ -105,7 +106,7 @@ public synchronized void start() { } public synchronized void stop() { - isRunning = false; + isPublishing = false; broadcastState(); } } @@ -4438,7 +4439,7 @@ public boolean isAttached(Attachable instance) { public Mpu6050Config getConfig() { super.getConfig(); // FIXME remove local fields in favor or config - config.start = publisher.isRunning; + config.start = isPublishing; config.sampleRate = sampleRateHz; config.bus = deviceBus; config.address = deviceAddress; @@ -4449,10 +4450,7 @@ public Mpu6050Config getConfig() { @Override public Mpu6050Config apply(Mpu6050Config c) { Mpu6050Config config = (Mpu6050Config) super.apply(c); - // FIXME remove local fields in favor or config - if (config.start) { - publisher.start(); - } + if (config.sampleRate != null) { setSampleRate(config.sampleRate); } @@ -4466,10 +4464,16 @@ public Mpu6050Config apply(Mpu6050Config c) { if (config.controller != null) { try { attach(config.controller); + + if (config.start) { + publisher.start(); + } + } catch (Exception e) { log.error("attach threw", e); } } + return c; } @@ -4485,7 +4489,7 @@ public void setSampleRate(double rateHz) { public static void main(String[] args) { try { - Runtime.main(new String[] { "--id", "admin"}); + Runtime.main(new String[] { "--id", "admin" }); LoggingFactory.init(Level.INFO); // Runtime.setAllVirtual(true); diff --git a/src/main/java/org/myrobotlab/service/Mqtt.java b/src/main/java/org/myrobotlab/service/Mqtt.java index 8466016039..599786f657 100644 --- a/src/main/java/org/myrobotlab/service/Mqtt.java +++ b/src/main/java/org/myrobotlab/service/Mqtt.java @@ -59,13 +59,13 @@ * information is updated from each connection since an instance can determine where * the incoming message came from by the topic * - * The recv topic between two instances c1 and c2 are - * mrl/gw/c1/rx<-c2 for c1 - * mrl/gw/c2/rx<-c1 for c2 + * The recv topic between two instances id1 and id2 are + * mrl/gw/id1/rx<-id2 for id1 + * mrl/gw/id2/rx<-id1 for id2 * * a general recv topic exist - * mrl/gw/c1/rx for c1 - * mrl/gw/c2/rx for c2 + * mrl/gw/id1/rx for id1 + * mrl/gw/id2/rx for id2 * * @author kmcgerald and GroG * @@ -481,7 +481,7 @@ public void messageArrived(String topic, MqttMessage message) throws MqttExcepti message.getQos(), message.getId()); /* * if (logMsg. - * equals("mqtt <--rx-- mrl/gw/c1/rx<-w1 (runtime@c1.onDescribe <--invoke-- runtime@w1.describe) qos 1 id 3" + * equals("mqtt <--rx-- mrl/gw/id1/rx<-w1 (runtime@id1.onDescribe <--invoke-- runtime@w1.describe) qos 1 id 3" * )) { log.info("here"); } */ log.warn(logMsg); @@ -846,7 +846,8 @@ String tokenToString(IMqttToken token) { public static void main(String[] args) { try { LoggingFactory.init("info"); - Runtime.main(new String[] { "--id", "m1"}); + Runtime.main(new String[] { "--id", "id1"}); + // Runtime.main(new String[] { "--id", "id2"}); /* * WebGui webgui = (WebGui) Runtime.create("webgui", "WebGui"); * webgui.setPort(8888); webgui.autoStartBrowser(false); @@ -856,18 +857,24 @@ public static void main(String[] args) { */ // Runtime.start("python", "Python"); // Runtime.start("audio", "AudioFile"); - Mqtt mqtt01 = (Mqtt) Runtime.start("mqtt01", "Mqtt"); + //Mqtt mqtt01 = (Mqtt) Runtime.start("mqtt01", "Mqtt"); + Mqtt mqtt02 = (Mqtt) Runtime.start("mqtt01", "Mqtt"); // mqtt01.connect("mqtt://localhost:1884"); // mqtt01.connect(fs, fs, fs, fs); // mqtt.inquire("r1") - // mqtt.inquire("mqtt02@c2") + // mqtt.inquire("mqtt02@id2") // MqttBroker broker = (MqttBroker) Runtime.start("broker", "MqttBroker"); // broker.start(); - mqtt01.setCert("certs/home-client/rootCA.pem", "certs/home-client/cert.pem.crt", "certs/home-client/private.key"); - mqtt01.connect("mqtts://a22mowsnlyfeb6-ats.iot.us-west-2.amazonaws.com:8883"); + // mqtt01.setCert("certs/home-client/rootCA.pem", "certs/home-client/cert.pem.crt", "certs/home-client/private.key"); + // mqtt01.connect("mqtts://a22mowsnlyfeb6-ats.iot.us-west-2.amazonaws.com:8883"); // mqtt01.connect("mqtt://broker.emqx.io:1883"); - // mqtt01.connect("tcp://iot.eclipse.org:1883"); + + // TO TEST ============= BEGIN ================ + // go to https://www.hivemq.com/demos/websocket-client/ + mqtt02.connect("mqtt://broker.hivemq.com:1883"); + + // mqtt01.connect("tcp://broker.hivemq.com:1883"); // mqtt01.connect("mqtt://127.0.0.1:1883"); // mqtt01.connect("mqtt://127.0.0.1:1883", "client", diff --git a/src/main/java/org/myrobotlab/service/Pcf8574.java b/src/main/java/org/myrobotlab/service/Pcf8574.java index 4e7410d0d2..65740f2ba9 100644 --- a/src/main/java/org/myrobotlab/service/Pcf8574.java +++ b/src/main/java/org/myrobotlab/service/Pcf8574.java @@ -9,12 +9,14 @@ import java.util.Set; import java.util.TreeMap; +import org.myrobotlab.codec.CodecUtils; import org.myrobotlab.framework.Registration; import org.myrobotlab.framework.Service; import org.myrobotlab.framework.interfaces.Attachable; import org.myrobotlab.framework.interfaces.ServiceInterface; import org.myrobotlab.logging.LoggerFactory; import org.myrobotlab.logging.LoggingFactory; +import org.myrobotlab.service.abstracts.AbstractMicrocontroller.PinListenerFilter; import org.myrobotlab.service.config.Pcf8574Config; import org.myrobotlab.service.data.PinData; import org.myrobotlab.service.interfaces.I2CControl; @@ -196,33 +198,23 @@ public void attachPinArrayListener(PinArrayListener listener) { } @Override - public void attachPinListener(PinListener listener, int address) { - attach(listener, String.format("%d", address)); + public void attachPinListener(PinListener listener) { + String name = listener.getName(); + addListener("publishPin", name); + PinListenerFilter filter = new PinListenerFilter(listener); + outbox.addFilter(name, CodecUtils.getCallbackTopicName("publishPin"), filter); } - + @Override - public void attach(PinListener listener, String pin) { + public void detachPinListener(PinListener listener) { String name = listener.getName(); + removeListener("publishPin", name); + outbox.removeFilter(name, CodecUtils.getCallbackTopicName("publishPin")); + } - if (listener.isLocal()) { - List list = null; - if (pinListeners.containsKey(pin)) { - list = pinListeners.get(pin); - } else { - list = new ArrayList(); - } - list.add(listener); - pinListeners.put(pin, list); - - } else { - // setup for pub sub - // FIXME - there is an architectual problem here - // locally it works - but remotely - outbox would need to know - // specifics of - // the data its sending - addListener("publishPin", name, "onPin"); - } + public void attach(PinListener listener) { + attachPinListener(listener); } // This section contains all the new attach logic @@ -237,11 +229,6 @@ public void attach(String name) throws Exception { } } - @Deprecated /* use attach(String) */ - public void attach(String listener, int pinAddress) { - attachPinListener((PinListener) Runtime.getService(listener), pinAddress); - } - @Deprecated /* use attach(String) */ public void attach(String controllerName, String deviceBus, String deviceAddress) { attach((I2CController) Runtime.getService(controllerName), deviceBus, deviceAddress); @@ -354,7 +341,7 @@ public void disablePins() { } } - @Override + @Deprecated /* use enablePin(String pin) */ public void enablePin(int address) { if (controller == null) { error("must be connected to enable pins"); @@ -368,7 +355,7 @@ public void enablePin(int address) { broadcastState(); } - @Override + @Deprecated /* use enablePin(String, int) */ public void enablePin(int address, int rate) { setSampleRate(rate); enablePin(address); @@ -444,7 +431,7 @@ public String getDeviceBus() { return c.bus; } - @Override + @Deprecated /* use getPin(String) */ public PinDefinition getPin(int address) { if (pinIndex.containsKey(address)) { return pinIndex.get(address); @@ -503,7 +490,7 @@ public void pinMode(int address, int mode) { invoke("publishPinDefinition", pinDef); } - @Override + @Deprecated /* use pinMode(String, String */ public void pinMode(int address, String mode) { PinDefinition pinDef = getPin(address); // There is no direction register in the PCF8574 it is always BIDRECTIONAL. @@ -541,7 +528,7 @@ public PinDefinition publishPinDefinition(PinDefinition pinDef) { return pinDef; } - @Override + @Deprecated /* use read(String) */ public int read(int address) { readRegister(); return getPin(address).getValue(); @@ -646,7 +633,7 @@ public double setSampleRate(double rate) { return rate; } - @Override + @Deprecated /* use write(String, int value) */ public void write(int address, int value) { log.info("Write Pin int {} with {}", address, value); // PinDefinition pinDef = getPin(address); // this doesn't get used at all diff --git a/src/main/java/org/myrobotlab/service/ProgramAB.java b/src/main/java/org/myrobotlab/service/ProgramAB.java index 171f67feae..2ff5e97e04 100644 --- a/src/main/java/org/myrobotlab/service/ProgramAB.java +++ b/src/main/java/org/myrobotlab/service/ProgramAB.java @@ -792,7 +792,7 @@ public String addBotPath(String path) { broadcastState(); } else { - error("invalid bot path - a bot must be a directory with a subdirectory named \"aiml\""); + error("invalid bot path %s - a bot must be a directory with a subdirectory named \"aiml\"", path); return null; } return path; diff --git a/src/main/java/org/myrobotlab/service/Vertx.java b/src/main/java/org/myrobotlab/service/Vertx.java new file mode 100644 index 0000000000..f87e9b9e4c --- /dev/null +++ b/src/main/java/org/myrobotlab/service/Vertx.java @@ -0,0 +1,135 @@ +package org.myrobotlab.service; + +import java.util.HashMap; +import java.util.Set; + +import org.myrobotlab.framework.Service; +import org.myrobotlab.logging.Level; +import org.myrobotlab.logging.LoggerFactory; +import org.myrobotlab.logging.LoggingFactory; +import org.myrobotlab.vertx.ApiVerticle; +import org.slf4j.Logger; + +import io.vertx.core.VertxOptions; + +/** + * Vertx gateway - used to support a http and websocket gateway for myrobotlab. + * Write business logic in Verticles. Also, try not to write any logic besides initialization inside start() method. + * + * It currently does not utilize the Vertx event bus - which is pretty much the most important part of Vertx. + * TODO: take advantage of publishing on the event bus + * + * @see https://medium.com/@pvub/https-medium-com-pvub-vert-x-workers-6a8df9b2b9ee + * + * @author greg + * + */ +public class Vertx extends Service { + + private static final long serialVersionUID = 1L; + + private transient io.vertx.core.Vertx vertx = null; + + public final static Logger log = LoggerFactory.getLogger(Vertx.class); + + public Vertx(String n, String id) { + super(n, id); + } + + /** + * deploys a http and websocket verticle on a secure TLS channel with self signed certificate + */ + public void start() { + log.info("starting driver"); + + /** + * FIXME - might have to revisit this This is a block comment, but takes + * advantage of javadoc pre non-formatting in ide to preserve the code + * formatting + * + *
+     * 
+     * final Vertx that = this;
+     * 
+     * java.lang.Runtime.getRuntime().addShutdownHook(new Thread() {
+     *   public void run() {
+     *     System.out.println("Running Shutdown Hook");
+     *     that.stop();
+     *   }
+     * });
+     * 
+     * 
+ */ + + vertx = io.vertx.core.Vertx.vertx(new VertxOptions().setBlockedThreadCheckInterval(100000)); + vertx.deployVerticle(new ApiVerticle(this)); + + } + + @Override + public void startService() { + super.startService(); + start(); + } + + @Override + public void stopService() { + super.stopService(); + stop(); + } + + + /** + * + */ + public void stop() { + log.info("stopping driver"); + Set ids = vertx.deploymentIDs(); + for (String id : ids) { + vertx.undeploy(id, (result) -> { + if (result.succeeded()) { + log.info("succeeded"); + } else { + log.error("failed"); + } + }); + } + } + + public static class Matrix { + public String name; + public HashMap matrix; + + public Matrix() { + }; + } + + public Matrix publishMatrix(Matrix data) { + // log.info("publishMatrix {}", data.name); + return data; + } + + public static void main(String[] args) { + try { + + LoggingFactory.init(Level.INFO); + + Vertx vertx = (Vertx) Runtime.start("vertx", "Vertx"); + vertx.start(); + + InMoov2 i01 = (InMoov2)Runtime.start("i01", "InMoov2"); + // i01.startSimulator(); + JMonkeyEngine jme = (JMonkeyEngine)i01.startPeer("simulator"); +// Runtime.start("python", "Python"); +// + WebGui webgui = (WebGui) Runtime.create("webgui", "WebGui"); + // webgui.setSsl(true); + webgui.autoStartBrowser(false); + webgui.setPort(8888); + webgui.startService(); + + } catch (Exception e) { + log.error("main threw", e); + } + } +} diff --git a/src/main/java/org/myrobotlab/service/WebXR.java b/src/main/java/org/myrobotlab/service/WebXR.java new file mode 100644 index 0000000000..8bd99e9cfe --- /dev/null +++ b/src/main/java/org/myrobotlab/service/WebXR.java @@ -0,0 +1,90 @@ +package org.myrobotlab.service; + +import java.util.HashMap; +import java.util.Map; + +import org.myrobotlab.framework.Service; +import org.myrobotlab.logging.Level; +import org.myrobotlab.logging.LoggerFactory; +import org.myrobotlab.logging.LoggingFactory; +import org.myrobotlab.math.MapperSimple; +import org.myrobotlab.service.config.WebXRConfig; +import org.myrobotlab.service.data.Pose; +import org.slf4j.Logger; + +public class WebXR extends Service { + + private static final long serialVersionUID = 1L; + + public final static Logger log = LoggerFactory.getLogger(WebXR.class); + + public WebXR(String n, String id) { + super(n, id); + } + + public Pose publishPose(Pose pose) { + log.warn("publishPose {}", pose); + System.out.println(pose.toString()); + + // process mappings config into joint angles + Map map = new HashMap<>(); + + WebXRConfig c = (WebXRConfig)config; + String path = String.format("%s.orientation.roll", pose.name); + if (c.mappings.containsKey(path)) { + Map mapper = c.mappings.get(path); + for (String name: mapper.keySet()) { + map.put(name, mapper.get(name).calcOutput(pose.orientation.roll)); + } + } + + path = String.format("%s.orientation.pitch", pose.name); + if (c.mappings.containsKey(path)) { + Map mapper = c.mappings.get(path); + for (String name: mapper.keySet()) { + map.put(name, mapper.get(name).calcOutput(pose.orientation.pitch)); + } + } + + path = String.format("%s.orientation.yaw", pose.name); + if (c.mappings.containsKey(path)) { + Map mapper = c.mappings.get(path); + for (String name: mapper.keySet()) { + map.put(name, mapper.get(name).calcOutput(pose.orientation.yaw)); + } + } + + invoke("publishJointAngles", map); + + // TODO - publishQuaternion + // invoke("publishQuaternion", map); + + return pose; + } + + + public Map publishJointAngles(Map map){ + return map; + } + + public static void main(String[] args) { + try { + + LoggingFactory.init(Level.INFO); + + Runtime.start("webxr", "WebXr"); + WebGui webgui = (WebGui) Runtime.create("webgui", "WebGui"); + // webgui.setSsl(true); + + webgui.autoStartBrowser(false); + webgui.startService(); + Runtime.start("vertx", "Vertx"); + InMoov2 i01 = (InMoov2)Runtime.start("i01", "InMoov2"); + i01.startPeer("simulator"); + + + } catch (Exception e) { + log.error("main threw", e); + } + } +} diff --git a/src/main/java/org/myrobotlab/service/abstracts/AbstractMicrocontroller.java b/src/main/java/org/myrobotlab/service/abstracts/AbstractMicrocontroller.java index 2beafb2958..8e37b6643b 100644 --- a/src/main/java/org/myrobotlab/service/abstracts/AbstractMicrocontroller.java +++ b/src/main/java/org/myrobotlab/service/abstracts/AbstractMicrocontroller.java @@ -8,6 +8,9 @@ import org.myrobotlab.arduino.BoardInfo; import org.myrobotlab.arduino.BoardType; +import org.myrobotlab.codec.CodecUtils; +import org.myrobotlab.framework.Message; +import org.myrobotlab.framework.Outbox; import org.myrobotlab.framework.Service; import org.myrobotlab.service.config.ServiceConfig; import org.myrobotlab.service.data.PinData; @@ -19,6 +22,33 @@ public abstract class AbstractMicrocontroller extends Service implements Microcontroller { private static final long serialVersionUID = 1L; + + /** + * A filter class. This class is used to provide a filter on a common publishing point. In this case + * "publishPin". The challenge with publishPin is all pins get published to all PinListeners, yet a + * PinListener typically only wants to listen to a single pin. What this filter provides is a filter + * for that specific pin before the message gets enqueued on the outbox. The filter is added when + * the subscription is processed, and its done in a general way that "any" filter could be provided to a subscription. + * This is a generalized and simple way to provide filtering on subscriptions. + * + * @author GroG + * + */ + public static class PinListenerFilter implements Outbox.FilterInterface{ + PinListener listener = null; + + public PinListenerFilter(PinListener listener) { + this.listener = listener; + } + + @Override + public boolean filter(Message msg) { + if ("onPin".equals(msg.method) && msg.data != null && msg.data.length > 0 && ((PinData)msg.data[0]).pin.equals(listener.getPin())) { + return false; + } + return true; + } + } /** * board type - UNO Mega etc.. @@ -52,6 +82,7 @@ public abstract class AbstractMicrocontroller extends S * whatever its documented to people e.g. "A5" or "D7", it comes down to a * unique address */ + @Deprecated /* use pinIndex only */ protected Map addressIndex = new TreeMap<>(); /** @@ -89,28 +120,17 @@ public void attachPinArrayListener(PinArrayListener listener) { } @Override - @Deprecated /* - * use attachPinListener(PinListener listener) GET RID OF THIS ! - */ - public void attachPinListener(PinListener listener, int address) { - PinDefinition pin = getPin(address); - listener.setPin(pin.getPinName()); - attachPinListener(listener); - } - - /** - * attach a pin listener who listens to a specific pin - */ public void attachPinListener(PinListener listener) { String name = listener.getName(); addListener("publishPin", name); + PinListenerFilter filter = new PinListenerFilter(listener); + outbox.addFilter(name, CodecUtils.getCallbackTopicName("publishPin"), filter); } - - @Override - @Deprecated /* set pin then call attach(listener) */ - public void attach(PinListener listener, String pin) { - PinDefinition pinDef = getPin(pin); - attachPinListener(listener, pinDef.getAddress()); + + public void detachPinListener(PinListener listener) { + String name = listener.getName(); + removeListener("publishPin", name); + outbox.removeFilter(name, CodecUtils.getCallbackTopicName("publishPin")); } @Override @@ -119,6 +139,7 @@ public void disablePin(String pin) { } @Override + @Deprecated /* use disablePin(String pin) */ abstract public void disablePin(int address); @Override @@ -133,7 +154,7 @@ public void enablePin(String pin) { enablePin(getPin(pin).getAddress()); } - @Override + @Deprecated /*use enablePin(String)*/ abstract public void enablePin(int address); @Override @@ -141,18 +162,19 @@ public void enablePin(String pin, int rate) { enablePin(getPin(pin).getAddress(), rate); } - @Override + @Deprecated /* use enablePin(String, int) */ abstract public void enablePin(int address, int rate); @Override - public PinDefinition getPin(String pinName) { - if (pinIndex.containsKey(pinName)) { - return pinIndex.get(pinName); + public PinDefinition getPin(String pin) { + if (pinIndex.containsKey(pin)) { + return pinIndex.get(pin); } // another attempt - if user used address instead of pin + // FIXME - remove this try { - int address = Integer.parseInt(pinName); + int address = Integer.parseInt(pin); return addressIndex.get(address); } catch (Exception e) { } @@ -161,7 +183,7 @@ public PinDefinition getPin(String pinName) { return null; } - @Override + @Deprecated /* use getPin(String pin) */ public PinDefinition getPin(int address) { if (addressIndex.containsKey(address)) { return addressIndex.get(address); @@ -172,13 +194,13 @@ public PinDefinition getPin(int address) { @Override abstract public List getPinList(); - + @Override public void pinMode(String pin, String mode) { pinMode(getPin(pin).getAddress(), mode); } - @Override + abstract public void pinMode(int address, String mode); @Override @@ -202,7 +224,7 @@ public PinDefinition publishPinDefinition(PinDefinition pinDef) { return pinDef; } - @Override + @Deprecated /* use read(String pin) */ public int read(int address) { // FIXME - this would be "last" read return addressIndex.get(address).getValue(); @@ -223,8 +245,10 @@ public void write(String pin, int value) { write(pinDef.getAddress(), value); } - @Override - abstract public void write(int address, int value); + @Deprecated /* don't expose the complexity of address to the user, use only "pin" write(String, int) */ + public void write(int address, int value) { + log.error("do not use write(int address, int value) use write(String pin, int)"); + } /** * Identifier of "board type" from the possible set in boardTypes diff --git a/src/main/java/org/myrobotlab/service/abstracts/AbstractServo.java b/src/main/java/org/myrobotlab/service/abstracts/AbstractServo.java index 5c57cef155..f278a5de49 100644 --- a/src/main/java/org/myrobotlab/service/abstracts/AbstractServo.java +++ b/src/main/java/org/myrobotlab/service/abstracts/AbstractServo.java @@ -369,8 +369,7 @@ public void attachServoController(String service) { disable(); addTaskOneShot(idleTimeout, "disable"); } - - broadcastState(); + } /** diff --git a/src/main/java/org/myrobotlab/service/config/InMoov2Config.java b/src/main/java/org/myrobotlab/service/config/InMoov2Config.java index ecb2d59c4e..83ac568c97 100644 --- a/src/main/java/org/myrobotlab/service/config/InMoov2Config.java +++ b/src/main/java/org/myrobotlab/service/config/InMoov2Config.java @@ -12,80 +12,95 @@ public class InMoov2Config extends ServiceConfig { + @Deprecated /* no implementation */ public int analogPinFromSoundCard = 53; - + + @Deprecated /* no implementation */ public int audioPollsBySeconds = 2; - - public boolean audioSignalProcessing=false; - + + @Deprecated /* no implementation */ + public boolean audioSignalProcessing = false; + public boolean batteryInSystem = false; + + /** + * start sound for when service starts + */ + public boolean bootUpSound = true; + + /** + * produces random sound on wake and other events + * TODO - make this not random + */ + public boolean customSound = false; - public boolean customSound=false; - + /** + * sound for when the topic/state switches + */ + public boolean topicSound = false; + public boolean forceMicroOnIfSleeping = true; - + public boolean healthCheckActivated = false; - + public int healthCheckTimerMs = 60000; - + public boolean heartbeat = false; - /** * idle time measures the time the fsm is in an idle state */ public boolean idleTimer = true; - public boolean loadGestures = true; + public boolean loadGestures = false; + + public boolean loadInitScripts = false; /** * default to null - allow the OS to set it, unless explicilty set */ public String locale = null; // = "en-US"; - public boolean neoPixelBootGreen=true; + public boolean neoPixelBootGreen = true; public boolean neoPixelDownloadBlue = true; public boolean neoPixelErrorRed = true; - + public boolean neoPixelFlashWhenSpeaking = true; - - public boolean openCVFaceRecognizerActivated=true; - - public boolean openCVFlipPicture=false; - + + public boolean openCVFaceRecognizerActivated = true; + + public boolean openCVFlipPicture = false; + public boolean pirEnableTracking = false; - + /** - * play pir sounds when pir switching states - * sound located in data/InMoov2/sounds/pir-activated.mp3 - * sound located in data/InMoov2/sounds/pir-deactivated.mp3 + * play pir sounds when pir switching states sound located in + * data/InMoov2/sounds/pir-activated.mp3 sound located in + * data/InMoov2/sounds/pir-deactivated.mp3 */ public boolean pirPlaySounds = true; - + public boolean pirWakeUp = true; - + public boolean robotCanMoveHeadWhileSpeaking = true; - - + /** * startup and shutdown will pause inmoov - set the speed to this value then * attempt to move to rest */ public double shutdownStartupSpeed = 50; - + /** - * Sleep 5 minutes after last presence detected + * Sleep 5 minutes after last presence detected */ public int sleepTimeoutMs=300000; public boolean startupSound = true; - public int trackingTimeoutMs=10000; - public String unlockInsult = "forgive me"; - + public boolean virtual = false; public InMoov2Config() { @@ -95,9 +110,13 @@ public InMoov2Config() { public Plan getDefault(Plan plan, String name) { super.getDefault(plan, name); - // peers FIXME global opencv + // peers which autostart by default addDefaultPeerConfig(plan, name, "audioPlayer", "AudioFile", true); + addDefaultPeerConfig(plan, name, "htmlFilter", "HtmlFilter", true); + addDefaultPeerConfig(plan, name, "mouth", "MarySpeech", false); + addDefaultPeerConfig(plan, name, "chatBot", "ProgramAB", true); + addDefaultPeerConfig(plan, name, "controller3", "Arduino", false); addDefaultPeerConfig(plan, name, "controller4", "Arduino", false); addDefaultPeerConfig(plan, name, "ear", "WebkitSpeechRecognition", false); @@ -112,7 +131,6 @@ public Plan getDefault(Plan plan, String name) { addDefaultPeerConfig(plan, name, "left", "Arduino", false); addDefaultPeerConfig(plan, name, "leftArm", "InMoov2Arm", false); addDefaultPeerConfig(plan, name, "leftHand", "InMoov2Hand", false); - addDefaultPeerConfig(plan, name, "mouth", "MarySpeech", false); addDefaultPeerConfig(plan, name, "mouthControl", "MouthControl", false); addDefaultPeerConfig(plan, name, "neoPixel", "NeoPixel", false); addDefaultPeerConfig(plan, name, "opencv", "OpenCV", false); @@ -131,16 +149,13 @@ public Plan getDefault(Plan plan, String name) { addDefaultPeerConfig(plan, name, "ultrasonicLeft", "UltrasonicSensor", false); MouthControlConfig mouthControl = (MouthControlConfig) plan.get(getPeerName("mouthControl")); + + // setup name references to different services mouthControl.jaw = name + ".head.jaw"; - String i01Name = name; - int index = name.indexOf("."); - if (index > 0) { - i01Name = name.substring(0, name.indexOf(".")); - } + mouthControl.mouth = name + ".mouth"; - mouthControl.mouth = i01Name + ".mouth"; ProgramABConfig chatBot = (ProgramABConfig) plan.get(getPeerName("chatBot")); Runtime runtime = Runtime.getInstance(); @@ -174,6 +189,8 @@ public Plan getDefault(Plan plan, String name) { // onStarted // == Peer - mouth ============================= // setup name references to different services + // LocalSpeechConfig mouth = (LocalSpeechConfig) + // plan.get(getPeerName("mouth")); MarySpeechConfig mouth = (MarySpeechConfig) plan.get(getPeerName("mouth")); mouth.voice = "Mark"; mouth.speechRecognizers = new String[] { name + ".ear" }; @@ -186,6 +203,12 @@ public Plan getDefault(Plan plan, String name) { ear.listening = true; // remove, should only need ServiceConfig.listeners ear.textListeners = new String[]{name + ".chatBot"}; + + // for servo mixer speech + ServoMixerConfig servoMixer = (ServoMixerConfig) plan.get(getPeerName("servoMixer")); + servoMixer.listeners = new ArrayList<>(); + servoMixer.listeners.add(new Listener("publishText", name + ".mouth", "onText")); + JMonkeyEngineConfig simulator = (JMonkeyEngineConfig) plan.get(getPeerName("simulator")); @@ -252,9 +275,14 @@ public Plan getDefault(Plan plan, String name) { simulator.nodes.put(name + ".rightHand.pinky2", new UserDataConfig(new MapperLinear(0.0, 180.0, 70.0, -10.0, true, false), "x")); simulator.nodes.put(name + ".rightHand.pinky3", new UserDataConfig(new MapperLinear(0.0, 180.0, 60.0, -10.0, true, false), "x")); simulator.cameraLookAt = name + ".torso.lowStom"; + + simulator.listeners = new ArrayList<>(); + simulator.listeners.add(new Listener("getSelectedPath", name + ".servoMixer", "onSelected")); + FiniteStateMachineConfig fsm = (FiniteStateMachineConfig) plan.get(getPeerName("fsm")); - // TODO - events easily gotten from InMoov data ?? auto callbacks in python if exists ? + // TODO - events easily gotten from InMoov data ?? auto callbacks in python + // if exists ? fsm.current = "boot"; fsm.transitions.add(new Transition("boot", "configStarted", "applyingConfig")); fsm.transitions.add(new Transition("applyingConfig", "getUserInfo", "getUserInfo")); @@ -264,14 +292,12 @@ public Plan getDefault(Plan plan, String name) { fsm.transitions.add(new Transition("systemCheck", "systemCheckFinished", "awake")); fsm.transitions.add(new Transition("awake", "sleep", "sleeping")); - - PirConfig pir = (PirConfig) plan.get(getPeerName("pir")); - pir.pin = "23"; + pir.pin = "D23"; pir.controller = name + ".left"; pir.listeners = new ArrayList<>(); pir.listeners.add(new Listener("publishPirOn", name, "onPirOn")); - + // == Peer - random ============================= RandomConfig random = (RandomConfig) plan.get(getPeerName("random")); random.enabled = false; @@ -380,17 +406,31 @@ public Plan getDefault(Plan plan, String name) { plan.remove(name + ".eyeTracking.controller"); plan.remove(name + ".eyeTracking.controller.serial"); plan.remove(name + ".eyeTracking.cv"); - + // inmoov2 default listeners listeners = new ArrayList<>(); // FIXME - should be getPeerName("neoPixel") listeners.add(new Listener("publishFlash", name + ".neoPixel", "onLedDisplay")); listeners.add(new Listener("publishEvent", name + ".fsm")); - + + listeners.add(new Listener("publishPython", "python")); + + listeners.add(new Listener("publishPlayAudioFile", name + ".audioPlayer")); + listeners.add(new Listener("publishPlayRandomAudioFile", name + ".audioPlayer")); + + + listeners.add(new Listener("setConfig", name + ".chatBot")); + listeners.add(new Listener("getConfig", name + ".chatBot")); + listeners.add(new Listener("setConfigValue", name + ".chatBot", "onConfig")); + + + // listeners.add(new Listener("publishLeftAr", name + ".audioPlayer")); + + // remove the auto-added starts in the plan's runtime RuntimConfig.registry plan.removeStartsWith(name + "."); - + // rtConfig.add(name); // <-- adding i01 / not needed return plan; diff --git a/src/main/java/org/myrobotlab/service/config/Mpu6050Config.java b/src/main/java/org/myrobotlab/service/config/Mpu6050Config.java index 3ce4fee638..6e5e6bd707 100644 --- a/src/main/java/org/myrobotlab/service/config/Mpu6050Config.java +++ b/src/main/java/org/myrobotlab/service/config/Mpu6050Config.java @@ -5,12 +5,12 @@ public class Mpu6050Config extends ServiceConfig { /** * bus for this device String to support writing to hex */ - public String bus; + public String bus = "1"; /** * address for this device String to support writing to hex */ - public String address; + public String address = "0x68"; /** * auto start mpu 6050 @@ -20,7 +20,7 @@ public class Mpu6050Config extends ServiceConfig { /** * orientation sample rate in hz */ - public Double sampleRate; + public Double sampleRate = 1.0; /** * I2C Controller diff --git a/src/main/java/org/myrobotlab/service/config/VertxConfig.java b/src/main/java/org/myrobotlab/service/config/VertxConfig.java new file mode 100644 index 0000000000..f2119d8ddd --- /dev/null +++ b/src/main/java/org/myrobotlab/service/config/VertxConfig.java @@ -0,0 +1,9 @@ +package org.myrobotlab.service.config; + +public class VertxConfig extends ServiceConfig { + + public Integer port = 8443; + public Integer workerCount = 1; + public boolean ssl = true; + +} diff --git a/src/main/java/org/myrobotlab/service/config/WebXRConfig.java b/src/main/java/org/myrobotlab/service/config/WebXRConfig.java new file mode 100644 index 0000000000..897a30eba6 --- /dev/null +++ b/src/main/java/org/myrobotlab/service/config/WebXRConfig.java @@ -0,0 +1,16 @@ +package org.myrobotlab.service.config; + +import java.util.HashMap; +import java.util.Map; + +import org.myrobotlab.math.MapperSimple; + +public class WebXRConfig extends ServiceConfig { + + /** + * Mapping to handle differences in rotation or position of data from + * sensor + */ + public Map> mappings = new HashMap<>(); + +} diff --git a/src/main/java/org/myrobotlab/service/data/LedDisplayData.java b/src/main/java/org/myrobotlab/service/data/LedDisplayData.java index 92ce88ba38..9971f322b7 100644 --- a/src/main/java/org/myrobotlab/service/data/LedDisplayData.java +++ b/src/main/java/org/myrobotlab/service/data/LedDisplayData.java @@ -9,7 +9,7 @@ */ public class LedDisplayData { - public String action; // fill | flash | play animation | stop | clear + public String action = "flash"; // fill | flash | play animation | stop | clear public int red; public int green; public int blue; @@ -25,4 +25,14 @@ public class LedDisplayData { public long interval = 500; + public LedDisplayData() {}; + + public LedDisplayData(int red, int green, int blue) { + this.red = red; + this.green = green; + this.blue = blue; + + }; + + } diff --git a/src/main/java/org/myrobotlab/service/data/Orientation.java b/src/main/java/org/myrobotlab/service/data/Orientation.java index b2d5d5658e..b7df4102dc 100644 --- a/src/main/java/org/myrobotlab/service/data/Orientation.java +++ b/src/main/java/org/myrobotlab/service/data/Orientation.java @@ -11,6 +11,7 @@ public class Orientation { public Double roll = null; public Double pitch = null; public Double yaw = null; + public String src = null; // default constructor (values will be null until set) public Orientation() { diff --git a/src/main/java/org/myrobotlab/service/data/Pose.java b/src/main/java/org/myrobotlab/service/data/Pose.java new file mode 100644 index 0000000000..767d9be81d --- /dev/null +++ b/src/main/java/org/myrobotlab/service/data/Pose.java @@ -0,0 +1,22 @@ +package org.myrobotlab.service.data; + +public class Pose { + public String name = null; + public Long ts = null; + public Position position = null; + public Orientation orientation = null; + + public String toString() { + StringBuilder sb = new StringBuilder(); + sb.append(String.format("name:%s", name)); + if (position != null) { + sb.append(String.format(" x:%.2f y:%.2f z:%.2f", position.x, position.y, position.z)); + } + if (orientation != null) { + sb.append(String.format(" roll:%.2f pitch:%.2f yaw:%.2f", orientation.roll, orientation.pitch, orientation.yaw)); + } + return sb.toString(); + } + + +} diff --git a/src/main/java/org/myrobotlab/service/data/Position.java b/src/main/java/org/myrobotlab/service/data/Position.java new file mode 100644 index 0000000000..83fe574a44 --- /dev/null +++ b/src/main/java/org/myrobotlab/service/data/Position.java @@ -0,0 +1,43 @@ +package org.myrobotlab.service.data; + +public class Position { + + public Double x; + public Double y; + public Double z; + public String src; + + public Position(double x, double y, double z) { + this.x = x; + this.y = y; + this.z = z; + } + + public Position(double x, double y) { + this.x = x; + this.y = y; + } + + public Position(int x, int y, int z) { + this.x = (double) x; + this.y = (double) y; + this.z = (double) z; + } + + public Position(int x, int y) { + this.x = (double) x; + this.y = (double) y; + } + + public Position(float x, float y, float z) { + this.x = (double) x; + this.y = (double) y; + this.z = (double) z; + } + + public Position(float x, float y) { + this.x = (double) x; + this.y = (double) y; + } + +} diff --git a/src/main/java/org/myrobotlab/service/data/TopicChange.java b/src/main/java/org/myrobotlab/service/data/TopicChange.java index af25c05f06..7b43522089 100644 --- a/src/main/java/org/myrobotlab/service/data/TopicChange.java +++ b/src/main/java/org/myrobotlab/service/data/TopicChange.java @@ -40,5 +40,8 @@ public TopicChange(String userName, String botName, String newTopic, String oldT this.oldTopic = oldTopic; } + public String toString() { + return String.format("newTopic: %s oldTopic: %s botName %s userName: %s", newTopic, oldTopic, botName, userName); + } } diff --git a/src/main/java/org/myrobotlab/service/interfaces/ButtonDefinition.java b/src/main/java/org/myrobotlab/service/interfaces/ButtonDefinition.java index 94e6074335..e18a8f0354 100644 --- a/src/main/java/org/myrobotlab/service/interfaces/ButtonDefinition.java +++ b/src/main/java/org/myrobotlab/service/interfaces/ButtonDefinition.java @@ -5,10 +5,12 @@ public class ButtonDefinition implements Serializable { private static final long serialVersionUID = 1L; - String axisName; - Double value; + public String axisName; + public Double value; + public String serviceName; public ButtonDefinition(String serviceName, String axisName) { + this.serviceName = serviceName; this.axisName = axisName; } } diff --git a/src/main/java/org/myrobotlab/service/interfaces/PinArrayControl.java b/src/main/java/org/myrobotlab/service/interfaces/PinArrayControl.java index 245b605d65..02b6061100 100644 --- a/src/main/java/org/myrobotlab/service/interfaces/PinArrayControl.java +++ b/src/main/java/org/myrobotlab/service/interfaces/PinArrayControl.java @@ -11,36 +11,27 @@ */ public interface PinArrayControl extends PinArrayPublisher { - @Deprecated /* use attach(String) or attachPinListener(PinListener) */ - public void attachPinListener(PinListener listener, int address); + public void attachPinListener(PinListener listener); - @Deprecated /* use attach(String) */ - public void attach(PinListener listener, String pin); + public void detachPinListener(PinListener listener); public void disablePin(String pin); + @Deprecated /* use disablePin(String pin) */ public void disablePin(int address); public void disablePins(); public void enablePin(String pin); - public void enablePin(int address); - public void enablePin(String pin, int rate); - public void enablePin(int address, int rate); - public PinDefinition getPin(String pin); - public PinDefinition getPin(int address); - public List getPinList(); public void pinMode(String pin, String mode); - public void pinMode(int address, String mode); - public PinData publishPin(PinData pinData); public PinDefinition publishPinDefinition(PinDefinition pinDef); @@ -52,12 +43,6 @@ public interface PinArrayControl extends PinArrayPublisher { */ public int read(String pin); - /** - * read the address location a = read(20) - * @param address - * @return - */ - public int read(int address); /** * write to the pin e.g. write("P0", 1) @@ -71,7 +56,7 @@ public interface PinArrayControl extends PinArrayPublisher { * @param address * @param state */ - public void write(int address, int state); + // public void write(int address, int state); Integer getAddress(String pin); diff --git a/src/main/java/org/myrobotlab/service/interfaces/PinArrayListener.java b/src/main/java/org/myrobotlab/service/interfaces/PinArrayListener.java index e7d1d5aa2f..376f9436e0 100644 --- a/src/main/java/org/myrobotlab/service/interfaces/PinArrayListener.java +++ b/src/main/java/org/myrobotlab/service/interfaces/PinArrayListener.java @@ -6,6 +6,6 @@ public interface PinArrayListener extends Listener { public void onPinArray(PinData[] pindata); - public String[] getActivePins(); + public String[] getActivePins(); } diff --git a/src/main/java/org/myrobotlab/service/meta/WebXRMeta.java b/src/main/java/org/myrobotlab/service/meta/WebXRMeta.java new file mode 100644 index 0000000000..171959fbf5 --- /dev/null +++ b/src/main/java/org/myrobotlab/service/meta/WebXRMeta.java @@ -0,0 +1,33 @@ +package org.myrobotlab.service.meta; + +import org.myrobotlab.logging.LoggerFactory; +import org.myrobotlab.service.meta.abstracts.MetaData; +import org.slf4j.Logger; + +public class WebXRMeta extends MetaData { + private static final long serialVersionUID = 1L; + public final static Logger log = LoggerFactory.getLogger(WebXRMeta.class); + + /** + * This class is contains all the meta data details of a service. It's peers, + * dependencies, and all other meta data related to the service. + * + */ + public WebXRMeta() { + + // add a cool description + addDescription("WebXr allows hmi devices to add input and get data back from mrl"); + + // false will prevent it being seen in the ui + setAvailable(true); + + // add it to one or many categories + addCategory("remote","control"); + + // add a sponsor to this service + // the person who will do maintenance + // setSponsor("GroG"); + + } + +} diff --git a/src/main/java/org/myrobotlab/vertx/ApiVerticle.java b/src/main/java/org/myrobotlab/vertx/ApiVerticle.java new file mode 100644 index 0000000000..6b3ca595c7 --- /dev/null +++ b/src/main/java/org/myrobotlab/vertx/ApiVerticle.java @@ -0,0 +1,105 @@ +package org.myrobotlab.vertx; + +import java.lang.reflect.Method; + +import org.myrobotlab.codec.CodecUtils; +import org.myrobotlab.framework.MethodCache; +import org.myrobotlab.framework.interfaces.ServiceInterface; +import org.myrobotlab.service.Runtime; +import org.myrobotlab.service.config.VertxConfig; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +import io.vertx.core.AbstractVerticle; +import io.vertx.core.Handler; +import io.vertx.core.http.HttpMethod; +import io.vertx.core.http.HttpServer; +import io.vertx.core.http.HttpServerOptions; +import io.vertx.core.http.ServerWebSocket; +import io.vertx.core.net.SelfSignedCertificate; +import io.vertx.ext.web.Router; +import io.vertx.ext.web.handler.CorsHandler; +import io.vertx.ext.web.handler.StaticHandler; + +/** + * verticle to handle api requests + * + * @author GroG + */ +public class ApiVerticle extends AbstractVerticle { + + public final static Logger log = LoggerFactory.getLogger(ApiVerticle.class); + + private Router router; + + transient private org.myrobotlab.service.Vertx service; + + public ApiVerticle(org.myrobotlab.service.Vertx service) { + super(); + this.service = service; + } + + @Override + public void start() throws Exception { + // process configuration and create handlers + log.info("starting api verticle"); + VertxConfig config = (VertxConfig) service.getConfig(); + + // create a router + router = Router.router(vertx); + + // handle cors requests + router.route().handler(CorsHandler.create("*").allowedMethod(HttpMethod.GET).allowedMethod(HttpMethod.OPTIONS).allowedHeader("Accept").allowedHeader("Authorization") + .allowedHeader("Content-Type")); + + // static file routing + + //StaticHandler root = StaticHandler.create("src/main/resources/resource/Vertx/app"); + // StaticHandler root = StaticHandler.create("src/main/resources/resource/Vertx/app"); + StaticHandler root = StaticHandler.create("../robotlab-x-app/build/"); + root.setCachingEnabled(false); + root.setDirectoryListing(true); + root.setIndexPage("index.html"); + // root.setAllowRootFileSystemAccess(true); + // root.setWebRoot(null); + router.route("/*").handler(root); + + + // router.get("/health").handler(this::generateHealth); + // router.get("/api/transaction/:customer/:tid").handler(this::handleTransaction); + + // create the HTTP server and pass the + // "accept" method to the request handler + HttpServerOptions httpOptions = new HttpServerOptions(); + + if (config.ssl) { + SelfSignedCertificate certificate = SelfSignedCertificate.create(); + httpOptions.setSsl(true); + httpOptions.setKeyCertOptions(certificate.keyCertOptions()); + httpOptions.setTrustOptions(certificate.trustOptions()); + } + httpOptions.setPort(config.port); + + + HttpServer server = vertx.createHttpServer(httpOptions); + // TODO - this is where multiple workers would be defined + // .createHttpServer() + + // WebSocketHandler webSocketHandler = new WebSocketHandler(service); + // server.webSocketHandler(webSocketHandler); + + // FIXME - don't do "long" or "common" processing in the start() + // FIXME - how to do this -> server.webSocketHandler(this::handleWebSocket); + server.webSocketHandler(new WebSocketHandler(service)); + server.requestHandler(router); + // start servers + server.listen(); + } + + + @Override + public void stop() throws Exception { + log.info("stopping api verticle"); + } + +} diff --git a/src/main/java/org/myrobotlab/vertx/WebSocketHandler.java b/src/main/java/org/myrobotlab/vertx/WebSocketHandler.java new file mode 100644 index 0000000000..76d0fb8c1f --- /dev/null +++ b/src/main/java/org/myrobotlab/vertx/WebSocketHandler.java @@ -0,0 +1,93 @@ +package org.myrobotlab.vertx; + +import java.lang.reflect.Method; + +import org.myrobotlab.codec.CodecUtils; +import org.myrobotlab.framework.MethodCache; +import org.myrobotlab.framework.interfaces.ServiceInterface; +import org.myrobotlab.logging.LoggerFactory; +import org.myrobotlab.service.Runtime; +import org.slf4j.Logger; + +import io.vertx.core.Handler; +import io.vertx.core.http.ServerWebSocket; + +/** + * + * TODO - what else besides text messages - websocket binary streams ??? text stream ? + * + * @author GroG + * + */ +public class WebSocketHandler implements Handler { + + public final static Logger log = LoggerFactory.getLogger(WebSocketHandler.class); + + transient private org.myrobotlab.service.Vertx service = null; + TextMessageHandler textMessageHandler = null; + + public static class TextMessageHandler implements Handler { + + org.myrobotlab.service.Vertx service = null; + + public TextMessageHandler(org.myrobotlab.service.Vertx service) { + this.service = service; + } + + @Override + public void handle(String json) { + log.info("handling {}", json); + + Method method; + try { + + org.myrobotlab.framework.Message msg = CodecUtils.fromJson(json, org.myrobotlab.framework.Message.class); + + Class clazz = Runtime.getClass(msg.name); + if (clazz == null) { + log.error("cannot derive local type from service {}", msg.name); + return; + } + + MethodCache cache = MethodCache.getInstance(); + Object[] params = cache.getDecodedJsonParameters(clazz, msg.method, msg.data); + + method = cache.getMethod(clazz, msg.method, params); + if (method == null) { + service.error("method cache could not find %s.%s(%s)", clazz.getSimpleName(), msg.method, msg.data); + return; + } + + ServiceInterface si = Runtime.getService(msg.name); + Object ret = method.invoke(si, params); + + // put msg on mrl msg bus :) + // service.in(msg); <- NOT DECODE PARAMS !! + + // if ((new Random()).nextInt(100) == 0) { + // ctx.close(); - will close the websocket !!! + // } else { + // ctx.writeTextMessage("ping"); Useful is writing back + // } + + } catch (Exception e) { + service.error(e); + } + } + } + + public WebSocketHandler(org.myrobotlab.service.Vertx service) { + this.service = service; + this.textMessageHandler = new TextMessageHandler(service); + } + + @Override + public void handle(ServerWebSocket event) { + + // ctx.writeTextMessage("ping"); FIXME - query ? + // FIXME - thread-safe ? how many connections mapped to objects ? + event.textMessageHandler(new TextMessageHandler(service)); + + } + +}