();
- }
- 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));
+
+ }
+
+}