From d5b3f49c495e5f2eada6ea4322dad370dbcb3ee6 Mon Sep 17 00:00:00 2001 From: GroG Date: Sat, 11 Nov 2023 20:17:08 -0800 Subject: [PATCH 1/5] misc fixes (#1354) --- .../java/org/myrobotlab/service/Arduino.java | 2 +- .../org/myrobotlab/service/AudioFile.java | 2 +- src/main/java/org/myrobotlab/service/Pir.java | 68 ++++++++----------- 3 files changed, 29 insertions(+), 43 deletions(-) diff --git a/src/main/java/org/myrobotlab/service/Arduino.java b/src/main/java/org/myrobotlab/service/Arduino.java index 89e407c18d..bff3e027ac 100644 --- a/src/main/java/org/myrobotlab/service/Arduino.java +++ b/src/main/java/org/myrobotlab/service/Arduino.java @@ -929,7 +929,7 @@ public List getBoardTypes() { List boardTypes = new ArrayList(); try { - String b = FileIO.resourceToString("Arduino" + File.separator + "boards.txt"); + String b = FileIO.toString(FileIO.gluePaths(getResourceDir(), "boards.txt")); Properties boardProps = new Properties(); boardProps.load(new ByteArrayInputStream(b.getBytes())); diff --git a/src/main/java/org/myrobotlab/service/AudioFile.java b/src/main/java/org/myrobotlab/service/AudioFile.java index 8b5a3cb828..6a4dc76221 100644 --- a/src/main/java/org/myrobotlab/service/AudioFile.java +++ b/src/main/java/org/myrobotlab/service/AudioFile.java @@ -557,7 +557,7 @@ public AudioFileConfig apply(AudioFileConfig config) { } public double publishPeak(double peak) { - log.info("publishPeak {}", peak); + log.debug("publishPeak {}", peak); return peak; } diff --git a/src/main/java/org/myrobotlab/service/Pir.java b/src/main/java/org/myrobotlab/service/Pir.java index 5a2f0d750c..eea710f585 100644 --- a/src/main/java/org/myrobotlab/service/Pir.java +++ b/src/main/java/org/myrobotlab/service/Pir.java @@ -9,7 +9,6 @@ import org.myrobotlab.logging.LoggerFactory; import org.myrobotlab.logging.LoggingFactory; import org.myrobotlab.service.config.PirConfig; -import org.myrobotlab.service.config.ServiceConfig; import org.myrobotlab.service.data.PinData; import org.myrobotlab.service.interfaces.PinArrayControl; import org.myrobotlab.service.interfaces.PinDefinition; @@ -52,33 +51,31 @@ public void attach(String name) { } public void setPinArrayControl(String control) { - PirConfig c = (PirConfig) config; - c.controller = control; + config.controller = control; } public void attachPinArrayControl(String control) { - PirConfig c = (PirConfig) config; if (control == null) { error("controller cannot be null"); return; } - if (c.pin == null) { + if (config.pin == null) { error("pin should be set before attaching"); return; } - c.controller = CodecUtils.getShortName(control); + config.controller = CodecUtils.getShortName(control); // fire and forget - send(c.controller, "attach", getName()); + send(config.controller, "attach", getName()); // assume worky isAttached = true; // enable if configured - if (c.enable) { - send(c.controller, "enablePin", c.pin, c.rate); + if (config.enable) { + send(config.controller, "enablePin", config.pin, config.rate); } broadcastState(); @@ -95,16 +92,15 @@ public void detach(String name) { * @param control */ public void detachPinArrayControl(String control) { - PirConfig c = (PirConfig) config; if (control == null) { log.info("detaching null"); return; } - if (c.controller != null) { - if (!c.controller.equals(control)) { - log.warn("attempting to detach {} but this pir is attached to {}", control, c.controller); + if (config.controller != null) { + if (!config.controller.equals(control)) { + log.warn("attempting to detach {} but this pir is attached to {}", control, config.controller); return; } } @@ -112,8 +108,8 @@ public void detachPinArrayControl(String control) { // disable disable(); - send(c.controller, "detach", getName()); - // c.controller = null; left as configuration .. "last controller" + send(config.controller, "detach", getName()); + // config.controller = null; left as configuration .. "last controller" // detached isAttached = false; @@ -128,13 +124,12 @@ public void detachPinArrayControl(String control) { * */ public void disable() { - PirConfig c = (PirConfig) config; - if (c.controller != null && c.pin != null) { - send(c.controller, "disablePin", c.pin); + if (config.controller != null && config.pin != null) { + send(config.controller, "disablePin", config.pin); } - c.enable = false; + config.enable = false; active = null; broadcastState(); } @@ -143,8 +138,7 @@ public void disable() { * Enables polling at the preset poll rate. */ public void enable() { - PirConfig c = (PirConfig) config; - enable(c.rate); + enable(config.rate); } /** @@ -154,14 +148,13 @@ public void enable() { * */ public void enable(int rateHz) { - PirConfig c = (PirConfig) config; - if (c.controller == null) { + if (config.controller == null) { error("pin control not set"); return; } - if (c.pin == null) { + if (config.pin == null) { error("pin not set"); return; } @@ -171,17 +164,16 @@ public void enable(int rateHz) { return; } - c.rate = rateHz; + config.rate = rateHz; /* PinArrayControl.enablePin */ - send(c.controller, "enablePin", c.pin, rateHz); - c.enable = true; + send(config.controller, "enablePin", config.pin, rateHz); + config.enable = true; broadcastState(); } @Override public String getPin() { - PirConfig c = (PirConfig) config; - return c.pin; + return config.pin; } /** @@ -190,8 +182,7 @@ public String getPin() { * @return Hz */ public int getRate() { - PirConfig c = (PirConfig) config; - return c.rate; + return config.rate; } /** @@ -211,8 +202,7 @@ public boolean isActive() { * @return true = Enabled. false = Disabled. */ public boolean isEnabled() { - PirConfig c = (PirConfig) config; - return c.enable; + return config.enable; } @Override @@ -247,13 +237,12 @@ public PirConfig getConfig() { @Override public void onPin(PinData pindata) { - PirConfig c = (PirConfig) config; log.debug("onPin {}", pindata); boolean sense = (pindata.value != 0); // sparse publishing only on state change - if (active == null || active != sense && c.enable) { + if (active == null || active != sense && config.enable) { // state change invoke("publishSense", sense); active = sense; @@ -286,14 +275,12 @@ public void publishPirOff() { */ @Override public void setPin(String pin) { - PirConfig c = (PirConfig) config; - c.pin = pin; + config.pin = pin; } @Deprecated /* use attach(String) */ public void setPinArrayControl(PinArrayControl pinControl) { - PirConfig c = (PirConfig) config; - c.controller = pinControl.getName(); + config.controller = pinControl.getName(); } /** @@ -306,8 +293,7 @@ public void setRate(int rateHz) { error("invalid poll rate - default is 1 Hz valid value is > 0"); return; } - PirConfig c = (PirConfig) config; - c.rate = rateHz; + config.rate = rateHz; } /** From 43416e0a676e418d5db970893db720ec7a51c962 Mon Sep 17 00:00:00 2001 From: GroG Date: Sun, 12 Nov 2023 08:25:06 -0800 Subject: [PATCH 2/5] fixed setting speech type (#1362) --- .../java/org/myrobotlab/service/InMoov2.java | 72 +++++++++++++++---- 1 file changed, 60 insertions(+), 12 deletions(-) diff --git a/src/main/java/org/myrobotlab/service/InMoov2.java b/src/main/java/org/myrobotlab/service/InMoov2.java index bd794195b8..50ba4d3a8a 100644 --- a/src/main/java/org/myrobotlab/service/InMoov2.java +++ b/src/main/java/org/myrobotlab/service/InMoov2.java @@ -30,7 +30,7 @@ import org.myrobotlab.service.abstracts.AbstractSpeechSynthesis; import org.myrobotlab.service.config.InMoov2Config; import org.myrobotlab.service.config.OpenCVConfig; -import org.myrobotlab.service.config.ServiceConfig; +import org.myrobotlab.service.config.SpeechSynthesisConfig; import org.myrobotlab.service.data.JoystickData; import org.myrobotlab.service.data.LedDisplayData; import org.myrobotlab.service.data.Locale; @@ -913,6 +913,19 @@ public OpenCVData onOpenCVData(OpenCVData data) { // FIXME - publish event with or without data ? String file reference return data; } + + /** + * onPeak volume callback TODO - maybe make it variable with volume ? + * + * @param volume + */ + public void onPeak(double volume) { + if (config.neoPixelFlashWhenSpeaking && !configStarted) { + if (volume > 0.5) { + invoke("publishSpeakingFlash", "speaking"); + } + } + } /** * initial callback for Pir sensor Default behavior will be: send fsm event @@ -1555,11 +1568,6 @@ public void setRightHandSpeed(Integer thumb, Integer index, Integer majeure, Int setHandSpeed("right", (double) thumb, (double) index, (double) majeure, (double) ringFinger, (double) pinky, (double) wrist); } - public String setSpeechType(String speechType) { - updatePeerType("mouth" /* getPeerName("mouth") */, speechType); - return speechType; - } - public void setTorsoSpeed(Double topStom, Double midStom, Double lowStom) { sendToPeer("torso", "setSpeed", topStom, midStom, lowStom); } @@ -1928,6 +1936,44 @@ public void waitTargetPos() { sendToPeer("leftArm", "waitTargetPos"); sendToPeer("torso", "waitTargetPos"); } + + public boolean setSpeechType(String speechType) { + + if (speechType == null) { + error("cannot change speech type to null"); + return false; + } + + if (!speechType.contains(".")) { + speechType = "org.myrobotlab.service." + speechType; + } + + Runtime runtime = Runtime.getInstance(); + String peerName = getName() + ".mouth"; + Plan plan = runtime.getDefault(peerName, speechType); + try { + SpeechSynthesisConfig mouth = (SpeechSynthesisConfig)plan.get(peerName); + mouth.speechRecognizers = new String[] { getName() + ".ear" }; + + savePeerConfig("mouth", plan.get(peerName)); + + if (isPeerStarted("mouth")) { + // restart + releasePeer("mouth"); + startPeer("mouth"); + } + + } catch(Exception e) { + error("could not create config for %s", speechType); + return false; + } + + return true; + + // updatePeerType("mouth" /* getPeerName("mouth") */, speechType); + // return speechType; + } + public static void main(String[] args) { try { @@ -1937,15 +1983,21 @@ public static void main(String[] args) { // Runtime.start("s01", "Servo"); // Runtime.start("intro", "Intro"); - // Runtime.startConfig("pr-1213-1"); + Runtime.startConfig("dev"); WebGui webgui = (WebGui) Runtime.create("webgui", "WebGui"); // webgui.setSsl(true); webgui.autoStartBrowser(false); // webgui.setPort(8888); webgui.startService(); - InMoov2 i01 = (InMoov2)Runtime.start("i01","InMoov2"); + + boolean done = true; + if (done) { + return; + } + + OpenCVConfig ocvConfig = i01.getPeerConfig("opencv", new StaticType<>() {}); ocvConfig.flip = true; i01.setPeerConfigValue("opencv", "flip", true); @@ -1955,10 +2007,6 @@ public static void main(String[] args) { // Runtime.main(new String[] { "--log-level", "info", "-s", "webgui", "WebGui", "intro", "Intro", "python", "Python" }); - boolean done = true; - if (done) { - return; - } Runtime.start("python", "Python"); From b7909ca96d8935f312175b523ff4b18ab1ac0814 Mon Sep 17 00:00:00 2001 From: GroG Date: Sun, 12 Nov 2023 10:38:24 -0800 Subject: [PATCH 3/5] random service update (#1361) --- .../org/myrobotlab/service/JMonkeyEngine.java | 2 +- .../java/org/myrobotlab/service/Random.java | 262 ++++++++++-------- .../myrobotlab/service/meta/RandomMeta.java | 5 +- src/main/resources/resource/Random/Random.py | 54 +++- .../WebGui/app/service/views/RandomGui.html | 12 +- .../org/myrobotlab/service/RandomTest.java | 18 +- 6 files changed, 212 insertions(+), 141 deletions(-) diff --git a/src/main/java/org/myrobotlab/service/JMonkeyEngine.java b/src/main/java/org/myrobotlab/service/JMonkeyEngine.java index fbc5ef5e99..a22156778e 100644 --- a/src/main/java/org/myrobotlab/service/JMonkeyEngine.java +++ b/src/main/java/org/myrobotlab/service/JMonkeyEngine.java @@ -2157,7 +2157,7 @@ public void simpleInitApp() { new File(getDataDir()).mkdirs(); new File(getResourceDir()).mkdirs(); - // assetManager.registerLocator("./", FileLocator.class); + assetManager.registerLocator("./", FileLocator.class); assetManager.registerLocator(getDataDir(), FileLocator.class); assetManager.registerLocator(assetsDir, FileLocator.class); assetManager.registerLocator(modelsDir, FileLocator.class); diff --git a/src/main/java/org/myrobotlab/service/Random.java b/src/main/java/org/myrobotlab/service/Random.java index dca027aa3a..71ca99616f 100644 --- a/src/main/java/org/myrobotlab/service/Random.java +++ b/src/main/java/org/myrobotlab/service/Random.java @@ -32,6 +32,10 @@ public class Random extends Service { public final static Logger log = LoggerFactory.getLogger(Random.class); + transient private RandomProcessor processor = null; + + transient private final Object lock = new Object(); + /** * * RandomMessage is used to contain the ranges of values and intervals for @@ -39,14 +43,15 @@ public class Random extends Service { * */ static public class RandomMessage { + public String taskName; public String name; public String method; public Range[] data; public boolean enabled = true; public long minIntervalMs; public long maxIntervalMs; - public long interval; public boolean oneShot = false; + public transient long nextProcessTimeTs = 0; public RandomMessage() { } @@ -103,6 +108,23 @@ public double getRandom(double min, double max) { return min + (Math.random() * (max - min)); } + public void addRandom(String taskName, long minIntervalMs, long maxIntervalMs, String name, String method, Integer... values) { + addRandom(taskName, minIntervalMs, maxIntervalMs, name, method, toRanges((Object[]) values)); + } + + public void addRandom(String taskName, long minIntervalMs, long maxIntervalMs, String name, String method, Double... values) { + addRandom(taskName, minIntervalMs, maxIntervalMs, name, method, toRanges((Object[]) values)); + } + + // FIXME - test this + public void addRandom(String taskName, long minIntervalMs, long maxIntervalMs, String name, String method) { + addRandom(taskName, minIntervalMs, maxIntervalMs, name, method, toRanges((Object[]) null)); + } + + public void addRandom(String taskName, long minIntervalMs, long maxIntervalMs, String name, String method, String... params) { + addRandom(taskName, minIntervalMs, maxIntervalMs, name, method, setRange((Object[]) params)); + } + public void addRandom(long minIntervalMs, long maxIntervalMs, String name, String method, Integer... values) { addRandom(minIntervalMs, maxIntervalMs, name, method, toRanges((Object[]) values)); } @@ -170,74 +192,105 @@ public void removeAll() { } public void addRandom(long minIntervalMs, long maxIntervalMs, String name, String method, Range... ranges) { + String taskName = String.format("%s.%s", name, method); + addRandom(taskName, minIntervalMs, maxIntervalMs, name, method, ranges); + } - RandomMessage msg = new RandomMessage(); - msg.name = name; - msg.method = method; - msg.minIntervalMs = minIntervalMs; - msg.maxIntervalMs = maxIntervalMs; - msg.data = ranges; - - String key = String.format("%s.%s", name, method); - randomData.put(key, msg); - - msg.interval = getRandom(minIntervalMs, maxIntervalMs); - log.info("add random message {} in {} ms", key, msg.interval); - if (enabled) { - // only if global enabled is enabled do we start the task - addTask(key, 0, msg.interval, "process", key); - } + public void addRandom(String taskName, long minIntervalMs, long maxIntervalMs, String name, String method, Range... ranges) { + + RandomMessage data = new RandomMessage(); + data.name = name; + data.method = method; + data.minIntervalMs = minIntervalMs; + data.maxIntervalMs = maxIntervalMs; + data.data = ranges; + data.enabled = true; + + randomData.put(taskName, data); + + log.info("add random message {} in {} to {} ms", taskName, data.minIntervalMs, data.maxIntervalMs); broadcastState(); } - public void process(String key) { - // if (!enabled) { - // return; - // } + private class RandomProcessor extends Thread { - RandomMessage msg = randomData.get(key); - if (msg == null || !msg.enabled) { - return; + public RandomProcessor(String name) { + super(name); } - Message m = Message.createMessage(getName(), msg.name, msg.method, null); - if (msg.data != null) { - List data = new ArrayList<>(); - - for (int i = 0; i < msg.data.length; ++i) { - Object o = msg.data[i]; - if (o instanceof Range) { - Range range = (Range) o; - Object param = null; - - if (range.set != null) { - int rand = getRandom(0, range.set.size() - 1); - param = range.set.get(rand); - } else if (range.min instanceof Double) { - param = getRandom((Double) range.min, (Double) range.max); - } else if (range.min instanceof Long) { - param = getRandom((Long) range.min, (Long) range.max); - } else if (range.min instanceof Integer) { - param = getRandom((Integer) range.min, (Integer) range.max); + public void run() { + while (enabled) { + try { + // minimal interval time for processor to check + // and see if any random event needs processing + + sleep(200); + for (String key : randomData.keySet()) { + + long now = System.currentTimeMillis(); + + RandomMessage randomEntry = randomData.get(key); + if (!randomEntry.enabled) { + continue; + } + + // first time set + if (randomEntry.nextProcessTimeTs == 0) { + randomEntry.nextProcessTimeTs = now + getRandom((Long) randomEntry.minIntervalMs, (Long) randomEntry.maxIntervalMs); + } + + if (now < randomEntry.nextProcessTimeTs) { + // this entry isn't ready + continue; + } + + Message m = Message.createMessage(getName(), randomEntry.name, randomEntry.method, null); + if (randomEntry.data != null) { + List data = new ArrayList<>(); + + for (int i = 0; i < randomEntry.data.length; ++i) { + Object o = randomEntry.data[i]; + if (o instanceof Range) { + Range range = (Range) o; + Object param = null; + + if (range.set != null) { + int rand = getRandom(0, range.set.size() - 1); + param = range.set.get(rand); + } else if (range.min instanceof Double) { + param = getRandom((Double) range.min, (Double) range.max); + } else if (range.min instanceof Long) { + param = getRandom((Long) range.min, (Long) range.max); + } else if (range.min instanceof Integer) { + param = getRandom((Integer) range.min, (Integer) range.max); + } + + data.add(param); + } + } + m.data = data.toArray(); + } + m.sendingMethod = "process"; + log.debug("random msg @ {} ms {}", now - randomEntry.nextProcessTimeTs, m); + out(m); + + // auto-disable oneshot + if (randomEntry.oneShot) { + randomEntry.enabled = false; + } + + // reset next processing time + randomEntry.nextProcessTimeTs = now + getRandom((Long) randomEntry.minIntervalMs, (Long) randomEntry.maxIntervalMs); + } - data.add(param); + } catch (Exception e) { + error(e); } - } - m.data = data.toArray(); - } - m.sendingMethod = "process"; - log.info("random msg @ {} ms {}", msg.interval, m); - out(m); - - purgeTask(key); - if (!msg.oneShot) { - msg.interval = getRandom(msg.minIntervalMs, msg.maxIntervalMs); - // must re-schedule unless one shot - if (enabled) { - // only if global enabled is enabled do we start the task - addTask(key, 0, msg.interval, "process", key); - } + + } // while (enabled) { + + log.info("Random {}-processor terminating", getName()); } } @@ -280,12 +333,12 @@ public RandomConfig apply(RandomConfig c) { return c; } + @Deprecated /* use remove(String key) */ public RandomMessage remove(String name, String method) { return remove(String.format("%s.%s", name, method)); } public RandomMessage remove(String key) { - purgeTask(key); return randomData.remove(key); } @@ -294,79 +347,49 @@ public Set getKeySet() { } public void disable(String key) { - // exact match - if (key.contains(".")) { - RandomMessage msg = randomData.get(key); - if (msg == null) { - log.warn("cannot disable random event with key {}", key); - return; - } - randomData.get(key).enabled = false; - purgeTask(key); + + if (!randomData.containsKey(key)) { + error("disable cannot find key %s", key); return; } - // must be name - disable "all" for this service - for (RandomMessage msg : randomData.values()) { - if (msg.name.equals(key)) { - msg.enabled = false; - purgeTask(String.format("%s.%s", msg.name, msg.method)); - } - } + + randomData.get(key).enabled = false; } public void enable(String key) { - // exact match - if (key.contains(".")) { - RandomMessage msg = randomData.get(key); - if (msg == null) { - log.warn("cannot enable random event with key {}", key); - return; - } - randomData.get(key).enabled = true; - if (enabled) { - // only if global enabled is enabled do we start the task - addTask(key, 0, msg.interval, "process", key); - } + if (!randomData.containsKey(key)) { + error("disable cannot find key %s", key); return; } - // must be name - disable "all" for this service - String name = key; - for (RandomMessage msg : randomData.values()) { - if (msg.name.equals(name)) { - msg.enabled = true; - String fullKey = String.format("%s.%s", msg.name, msg.method); - if (enabled) { - // only if global enabled is enabled do we start the task - addTask(fullKey, 0, msg.interval, "process", fullKey); - } - } - } + randomData.get(key).enabled = true; } public void disable() { - // remove all timed attempts of processing random - // events - purgeTasks(); - enabled = false; - broadcastState(); + synchronized (lock) { + enabled = false; + processor = null; + broadcastState(); + } } public void enable() { - for (RandomMessage msg : randomData.values()) { - // re-enable tasks which were previously enabled - if (msg.enabled == true) { - String fullKey = String.format("%s.%s", msg.name, msg.method); - addTask(fullKey, 0, msg.interval, "process", fullKey); + synchronized (lock) { + enabled = true; + if (processor == null) { + processor = new RandomProcessor(String.format("%s-processor", getName())); + processor.start(); + // wait until thread starts + sleep(200); + } else { + info("%s already enabled"); } + broadcastState(); } - - enabled = true; - broadcastState(); } public void purge() { randomData.clear(); - purgeTasks(); + broadcastState(); } public Set getMethodsFromName(String serviceName) { @@ -395,13 +418,22 @@ public List methodQuery(String serviceName, String methodName) { } return MethodCache.getInstance().query(si.getClass().getCanonicalName(), methodName); } + + public Map getRandomEvents(){ + return randomData; + } + + public RandomMessage getRandomEvent(String key) { + return randomData.get(key); + } public static void main(String[] args) { try { LoggingFactory.init(Level.INFO); - + Runtime.setConfig("dev"); Runtime.start("c1", "Clock"); + Runtime.start("python", "Python"); Random random = (Random) Runtime.start("random", "Random"); diff --git a/src/main/java/org/myrobotlab/service/meta/RandomMeta.java b/src/main/java/org/myrobotlab/service/meta/RandomMeta.java index c18ebfa9a7..f7765982c2 100644 --- a/src/main/java/org/myrobotlab/service/meta/RandomMeta.java +++ b/src/main/java/org/myrobotlab/service/meta/RandomMeta.java @@ -17,13 +17,10 @@ public RandomMeta() { // add a cool description addDescription("provides a service for random message generation"); - // false will prevent it being seen in the ui - setAvailable(true); - // add dependencies if necessary // addDependency("com.twelvemonkeys.common", "common-lang", "3.1.1"); - setAvailable(false); + setAvailable(true); // add it to one or many categories addCategory("general"); diff --git a/src/main/resources/resource/Random/Random.py b/src/main/resources/resource/Random/Random.py index 7d5fa86f9b..84c79ab17a 100644 --- a/src/main/resources/resource/Random/Random.py +++ b/src/main/resources/resource/Random/Random.py @@ -7,34 +7,63 @@ ######################################### # start the service -python = runtime.start("python","Python") -random = runtime.start("random","Random") -clock = runtime.start("clock","Clock") +python = runtime.start("python", "Python") +random = runtime.start("random", "Random") +clock = runtime.start("clock", "Clock") + + +def happy(): + print("i am happy") + + +def sad(): + print("i am sad") + + +def angry(): + print("i am angry") + + +# add a named random task +random.addRandom("random emotion", 1000, 2000, "python", "exec", "happy()", "sad()", "angry()") + # enable random events random.enable() -# roll the dice every 1 to 2 seonds -random.addRandom(1000, 2000, "python", "roll_dice", random.intRange(1, 6)) + + def roll_dice(value): print("roll_dice " + str(value)) + +# roll the dice every 1 to 2 seonds +random.addRandom(1000, 2000, "python", "roll_dice", random.intRange(1, 6)) + + # add a complex dice -random.addRandom(1000, 2000, "python", "roll_complex_dice", random.doubleRange(1, 6)) def roll_complex_dice(value): print("roll_complex_dice " + str(value)) -# roll the dice every 1 to 2 seonds -random.addRandom(1000, 2000, "python", "random_color", random.setRange("red","green","blue","yellow")) +# roll the complex dice every 1 to 2 seonds +random.addRandom(1000, 2000, "python", "roll_complex_dice", random.doubleRange(1, 6)) + + def random_color(value): print("random_color " + str(value)) +# roll the dice every 1 to 2 seonds +random.addRandom(1000, 2000, "python", "random_color", random.setRange("red", "green", "blue", "yellow")) + + # do a complex multi parameter, multi-type method -random.addRandom(1000, 2000, "python", "kitchen_sink", random.intRange(1, 6), random.doubleRange(1, 6), random.setRange("red","green","blue","yellow"), random.setRange("bob","jane","fred","mary")) def kitchen_sink(dice, complex_dice, colors, names): print("kitchen_sink ", dice, complex_dice, colors, names) + +random.addRandom(1000, 2000, "python", "kitchen_sink", random.intRange(1, 6), random.doubleRange(1, 6), random.setRange("red","green","blue","yellow"), random.setRange("bob","jane","fred","mary")) + # set the interval on a clock between 1000 and 8000 # if you look in the UI you can see the clock interval changing random.addRandom(200, 500, "clock", "setInterval", random.intRange(1000, 8000)) @@ -43,13 +72,8 @@ def kitchen_sink(dice, complex_dice, colors, names): random.addRandom(200, 500, "clock", "startClock") random.addRandom(200, 500, "clock", "stopClock") - -# run it all for 8 seconds -sleep(8) - # disable single random event generator - must be explicit with name.method key random.disable("python.roll_dice") -sleep(8) # you know longer should see the python.roll_dice event firing - since it was explicitly disabled @@ -61,4 +85,4 @@ def kitchen_sink(dice, complex_dice, colors, names): # random.enable() # stop events and clear all random event ata -# random.purge() \ No newline at end of file +# random.purge() diff --git a/src/main/resources/resource/WebGui/app/service/views/RandomGui.html b/src/main/resources/resource/WebGui/app/service/views/RandomGui.html index 34c57ea2ca..b49a6365a0 100644 --- a/src/main/resources/resource/WebGui/app/service/views/RandomGui.html +++ b/src/main/resources/resource/WebGui/app/service/views/RandomGui.html @@ -12,10 +12,16 @@

( - + [ + {{param.min}} - {{param.max}} - {{item}} - + + + {{item}} + , + ] + , + ) every {{value.minIntervalMs}} ms to {{value.maxIntervalMs}} ms diff --git a/src/test/java/org/myrobotlab/service/RandomTest.java b/src/test/java/org/myrobotlab/service/RandomTest.java index 450ffa04da..cf0d85f94e 100644 --- a/src/test/java/org/myrobotlab/service/RandomTest.java +++ b/src/test/java/org/myrobotlab/service/RandomTest.java @@ -3,7 +3,10 @@ import static org.junit.Assert.assertEquals; import static org.junit.Assert.assertTrue; +import java.util.Map; + import org.myrobotlab.framework.Service; +import org.myrobotlab.service.Random.RandomMessage; public class RandomTest extends AbstractServiceTest { @@ -25,8 +28,9 @@ public void testService() throws Exception { assertTrue("set interval 1000 base value", 1000 == clock.getInterval()); random.addRandom(0, 200, "clock", "setInterval", 5000, 10000); + random.enable(); - sleep(200); + sleep(300); assertTrue("should have method", random.getKeySet().contains("clock.setInterval")); @@ -45,13 +49,13 @@ public void testService() throws Exception { assertTrue("clock should be started 1", clock.isClockRunning()); // disable all of a services random events - random.disable("clock"); + random.disable("clock.startClock"); clock.stopClock(); sleep(200); assertTrue("clock should not be started", !clock.isClockRunning()); // enable all of a service's random events - random.enable("clock"); + random.enable("clock.startClock"); sleep(200); assertTrue("clock should be started 2", clock.isClockRunning()); @@ -77,7 +81,15 @@ public void testService() throws Exception { assertTrue("clock should not be started", !clock.isClockRunning()); assertTrue(String.format("random method 3 should be %d => 5000 values", clock.getInterval()), 5000 <= clock.getInterval()); assertTrue(String.format("random method 3 should be %d <= 10000 values",clock.getInterval()) , clock.getInterval() <= 10000); + + clock.stopClock(); + random.purge(); + Map events = random.getRandomEvents(); + assertTrue(events.size() == 0); + + random.addRandom("named task", 200, 500, "clock", "setInterval", 100, 1000, 10); + clock.releaseService(); random.releaseService(); From 820d0c42827e255c9cf1455de5e7541b93906711 Mon Sep 17 00:00:00 2001 From: grog Date: Sun, 12 Nov 2023 18:50:16 -0800 Subject: [PATCH 4/5] Implemented peakDelayMs in AudioFile --- .../org/myrobotlab/audio/AudioProcessor.java | 22 ++++++++++++++++++- .../service/config/AudioFileConfig.java | 11 ++++++++-- 2 files changed, 30 insertions(+), 3 deletions(-) diff --git a/src/main/java/org/myrobotlab/audio/AudioProcessor.java b/src/main/java/org/myrobotlab/audio/AudioProcessor.java index 2ca8f7aa28..46bc11d136 100644 --- a/src/main/java/org/myrobotlab/audio/AudioProcessor.java +++ b/src/main/java/org/myrobotlab/audio/AudioProcessor.java @@ -5,6 +5,10 @@ import java.util.concurrent.BlockingQueue; import java.util.concurrent.LinkedBlockingQueue; +import java.util.concurrent.Executors; +import java.util.concurrent.ScheduledExecutorService; +import java.util.concurrent.TimeUnit; + import javax.sound.sampled.AudioFormat; import javax.sound.sampled.AudioInputStream; import javax.sound.sampled.AudioSystem; @@ -32,6 +36,8 @@ public class AudioProcessor extends Thread { // it seems to make sense - some how the file gets decoded enough - so that // a audio decoder can be slected from some // internal registry ... i think + + private final ScheduledExecutorService scheduler = Executors.newScheduledThreadPool(1); transient private final ScheduledExecutorService delayScheduler = Executors.newScheduledThreadPool(1); protected int currentTrackCount = 0; @@ -231,7 +237,14 @@ public AudioData play(AudioData data) { peak = abs; } } - audioFile.invoke("publishPeak", peak * (double) audioFile.getPeakMultiplier()); + + final double value = peak * (double) audioFile.getPeakMultiplier(); + + if (audioFile.getConfig().peakDelayMs == null) { + audioFile.invoke("publishPeak", value); + } else { + delayScheduler.schedule(() -> audioFile.invoke("publishPeak", value), audioFile.getConfig().peakDelayMs, TimeUnit.MILLISECONDS); + } } } // Stop @@ -247,6 +260,12 @@ public AudioData play(AudioData data) { // System.gc(); + if (audioFile.getConfig().peakDelayMs == null) { + audioFile.invoke("publishPeak", 0); + } else { + delayScheduler.schedule(() -> audioFile.invoke("publishPeak", 0), audioFile.getConfig().peakDelayMs, TimeUnit.MILLISECONDS); + } + audioFile.invoke("publishPeak", 0); audioFile.invoke("publishAudioEnd", data); @@ -313,6 +332,7 @@ public void run() { } // default waits on queued audio requests log.info("audio processor {} exiting", getName()); + delayScheduler.shutdown(); } public void setVolume(Double volume) { diff --git a/src/main/java/org/myrobotlab/service/config/AudioFileConfig.java b/src/main/java/org/myrobotlab/service/config/AudioFileConfig.java index caabbdb72b..391d175d55 100644 --- a/src/main/java/org/myrobotlab/service/config/AudioFileConfig.java +++ b/src/main/java/org/myrobotlab/service/config/AudioFileConfig.java @@ -10,13 +10,20 @@ public class AudioFileConfig extends ServiceConfig { public double volume = 1.0; public String currentPlaylist = "default"; public Map> playlists; - public double peakMultiplier = 100.0; + + @Deprecated /* use regular "listeners" from ServiceConfig parent */ public String[] audioListeners; - + + /** + * a multiplier to scale amplitude of output waveform + */ + public double peakMultiplier = 100.0; + /** * sample interval for peak */ public double peakSampleInterval = 15; + /** * delay to synchronize publishing of peak with actual sound in milliseconds */ From 8d33fc57a7d1c8b0cc548725fe51a516ec96d7d1 Mon Sep 17 00:00:00 2001 From: grog Date: Mon, 13 Nov 2023 17:35:42 -0800 Subject: [PATCH 5/5] a little closer to worky motors --- .../org/myrobotlab/service/AudioFile.java | 6 +- .../java/org/myrobotlab/service/I2cMux.java | 2 + .../java/org/myrobotlab/service/Motor.java | 12 ++ .../org/myrobotlab/service/MotorDualPwm.java | 43 +++--- .../org/myrobotlab/service/MotorHat4Pi.java | 12 ++ .../org/myrobotlab/service/MotorPort.java | 12 ++ .../java/org/myrobotlab/service/WebGui.java | 2 +- .../service/abstracts/AbstractMotor.java | 125 ++++++++---------- .../abstracts/AbstractSpeechSynthesis.java | 15 ++- .../service/interfaces/MotorControl.java | 56 +++++++- .../WebGui/app/service/js/MotorDualPwmGui.js | 22 ++- .../app/service/views/MotorDualPwmGui.html | 33 ++--- 12 files changed, 210 insertions(+), 130 deletions(-) diff --git a/src/main/java/org/myrobotlab/service/AudioFile.java b/src/main/java/org/myrobotlab/service/AudioFile.java index 6a4dc76221..104db4dce0 100644 --- a/src/main/java/org/myrobotlab/service/AudioFile.java +++ b/src/main/java/org/myrobotlab/service/AudioFile.java @@ -223,10 +223,10 @@ public AudioData play(String filename, boolean blocking, Integer repeat, String data.track = track; data.repeat = repeat; - return play(data); + return playAudioData(data); } - public AudioData play(AudioData data) { + public AudioData playAudioData(AudioData data) { // use File interface such that filename is preserved // but regardless of location (e.g. url, local, resource) // or type (mp3 wav) a stream is opened and the @@ -382,7 +382,7 @@ public AudioData repeat(String filename, Integer count) { // TODO Auto-generated method stub AudioData data = new AudioData(filename); data.repeat = count; - return play(data); + return playAudioData(data); } @Deprecated /* use setTrack() */ diff --git a/src/main/java/org/myrobotlab/service/I2cMux.java b/src/main/java/org/myrobotlab/service/I2cMux.java index ced3b15a46..62fdebb2fa 100644 --- a/src/main/java/org/myrobotlab/service/I2cMux.java +++ b/src/main/java/org/myrobotlab/service/I2cMux.java @@ -237,11 +237,13 @@ public void attach(Attachable service) throws Exception { } } + @Deprecated /* use attach(String) */ public void attach(String controllerName, String deviceBus, String deviceAddress) { attach((I2CController) Runtime.getService(controllerName), deviceBus, deviceAddress); } @Override + @Deprecated /*use attach(String) */ public void attach(I2CController controller, String deviceBus, String deviceAddress) { if (isAttached && this.controller != controller) { diff --git a/src/main/java/org/myrobotlab/service/Motor.java b/src/main/java/org/myrobotlab/service/Motor.java index 6b410e1f7d..e9e7a00004 100644 --- a/src/main/java/org/myrobotlab/service/Motor.java +++ b/src/main/java/org/myrobotlab/service/Motor.java @@ -196,4 +196,16 @@ public static void main(String[] args) { } + @Override + public void attachMotorController(String controller) throws Exception { + // TODO Auto-generated method stub + + } + + @Override + public void detachMotorController(String controller) { + // TODO Auto-generated method stub + + } + } diff --git a/src/main/java/org/myrobotlab/service/MotorDualPwm.java b/src/main/java/org/myrobotlab/service/MotorDualPwm.java index fe4764ae6d..e1746ca071 100644 --- a/src/main/java/org/myrobotlab/service/MotorDualPwm.java +++ b/src/main/java/org/myrobotlab/service/MotorDualPwm.java @@ -1,14 +1,13 @@ package org.myrobotlab.service; -import java.io.IOException; import java.util.Arrays; import java.util.List; +import org.myrobotlab.framework.Platform; import org.myrobotlab.logging.Level; import org.myrobotlab.logging.LoggingFactory; import org.myrobotlab.service.abstracts.AbstractMotor; import org.myrobotlab.service.config.MotorDualPwmConfig; -import org.myrobotlab.service.config.ServiceConfig; public class MotorDualPwm extends AbstractMotor { private static final long serialVersionUID = 1L; @@ -92,32 +91,34 @@ public MotorDualPwmConfig apply(MotorDualPwmConfig c) { return c; } - public static void main(String[] args) throws InterruptedException { - - LoggingFactory.init(Level.INFO); - String arduinoPort = "COM5"; - - VirtualArduino virtual = (VirtualArduino) Runtime.start("virtual", "VirtualArduino"); + public static void main(String[] args) { try { - virtual.connect(arduinoPort); - } catch (IOException e) { - // TODO Auto-generated catch block - e.printStackTrace(); - } - Runtime.start("gui", "SwingGui"); - Runtime.start("python", "Python"); + LoggingFactory.init(Level.INFO); + String arduinoPort = "COM5"; + + Platform.setVirtual(true); + Runtime.startConfig("dev"); + Runtime.start("webgui", "WebGui"); + MotorDualPwm motor = (MotorDualPwm) Runtime.start("motor", "MotorDualPwm"); + Arduino arduino = (Arduino) Runtime.start("arduino", "Arduino"); + arduino.connect(arduinoPort); + motor.setPwmPins(10, 11); - MotorDualPwm motor = (MotorDualPwm) Runtime.start("motor", "MotorDualPwm"); - Arduino arduino = (Arduino) Runtime.start("arduino", "Arduino"); - arduino.connect(arduinoPort); - motor.setPwmPins(10, 11); - try { motor.attach(arduino); } catch (Exception e) { - // TODO Auto-generated catch block e.printStackTrace(); } + } + @Override + public void attachMotorController(String controller) throws Exception { + // TODO Auto-generated method stub + } + @Override + public void detachMotorController(String controller) { + // TODO Auto-generated method stub + + } } diff --git a/src/main/java/org/myrobotlab/service/MotorHat4Pi.java b/src/main/java/org/myrobotlab/service/MotorHat4Pi.java index 1bc2bb6c1d..47256b98e5 100644 --- a/src/main/java/org/myrobotlab/service/MotorHat4Pi.java +++ b/src/main/java/org/myrobotlab/service/MotorHat4Pi.java @@ -113,4 +113,16 @@ public static void main(String[] args) { hat.attach(raspi, "1", "0x60"); } + @Override + public void attachMotorController(String controller) throws Exception { + // TODO Auto-generated method stub + + } + + @Override + public void detachMotorController(String controller) { + // TODO Auto-generated method stub + + } + } diff --git a/src/main/java/org/myrobotlab/service/MotorPort.java b/src/main/java/org/myrobotlab/service/MotorPort.java index d908d79e37..055209aeec 100644 --- a/src/main/java/org/myrobotlab/service/MotorPort.java +++ b/src/main/java/org/myrobotlab/service/MotorPort.java @@ -52,6 +52,18 @@ public static void main(String[] args) { log.error("main threw", e); } } + + @Override + public void attachMotorController(String controller) throws Exception { + // TODO Auto-generated method stub + + } + + @Override + public void detachMotorController(String controller) { + // TODO Auto-generated method stub + + } diff --git a/src/main/java/org/myrobotlab/service/WebGui.java b/src/main/java/org/myrobotlab/service/WebGui.java index dd2178bf8c..d007befe6e 100644 --- a/src/main/java/org/myrobotlab/service/WebGui.java +++ b/src/main/java/org/myrobotlab/service/WebGui.java @@ -1179,7 +1179,7 @@ public static void main(String[] args) { // Platform.setVirtual(true); - Runtime.startConfig("default"); + Runtime.startConfig("dev"); boolean done = true; if (done) { diff --git a/src/main/java/org/myrobotlab/service/abstracts/AbstractMotor.java b/src/main/java/org/myrobotlab/service/abstracts/AbstractMotor.java index eb496e0d35..9af8d6b32c 100644 --- a/src/main/java/org/myrobotlab/service/abstracts/AbstractMotor.java +++ b/src/main/java/org/myrobotlab/service/abstracts/AbstractMotor.java @@ -42,10 +42,8 @@ import org.myrobotlab.sensor.EncoderPublisher; import org.myrobotlab.service.Runtime; import org.myrobotlab.service.config.GeneralMotorConfig; -import org.myrobotlab.service.config.ServiceConfig; import org.myrobotlab.service.data.AnalogData; import org.myrobotlab.service.interfaces.AnalogPublisher; -import org.myrobotlab.service.interfaces.ButtonDefinition; import org.myrobotlab.service.interfaces.MotorControl; import org.myrobotlab.service.interfaces.MotorController; import org.slf4j.Logger; @@ -80,16 +78,6 @@ abstract public class AbstractMotor extends Servic */ protected boolean locked = false; - /** - * attached analog publishers to this service - functionally its a simple - * "lock" to avoid cyclic attach/detaches - works well - */ - // final protected Set analogPublishers = new HashSet<>(); - // bad idea publishers internally will need to know about subscribers - // but not the other way around ... could this be a general pattern for - // how to manage attach? ie publishers attach "always" needs to be called - // subscribers can just call publishers attach with their attach - /** * the power level requested - varies between -1.0 <--> 1.0 */ @@ -99,7 +87,11 @@ abstract public class AbstractMotor extends Servic protected Double positionCurrent; // aka currentPos - // private String axisName; + /** + * controller now is part of config, + * isAttached is if that controller is or is not attached + */ + protected boolean isAttached = false; public AbstractMotor(String n, String id) { super(n, id); @@ -135,8 +127,7 @@ public Set refreshControllers() { } public MotorController getController() { - GeneralMotorConfig c = config; - return (MotorController) Runtime.getService(c.controller); + return (MotorController) Runtime.getService(config.controller); } // FIXME - repair input/output @@ -147,14 +138,15 @@ public double getPowerLevel() { @Override public boolean isAttached(MotorController controller) { - GeneralMotorConfig c = config; - return controller.getName().equals(c.controller); + if (controller == null) { + return false; + } + return controller.getName().equals(config.controller); } @Override public boolean isInverted() { - GeneralMotorConfig c = config; - return c.mapper.maxIn < c.mapper.minOut; + return config.mapper.maxIn < config.mapper.minOut; } @Override @@ -169,18 +161,18 @@ public void move(double powerInput) { info("%s is locked - will not move"); return; } - GeneralMotorConfig c = config; + // FIXME make mapper.isInInputRange(x) - double min = Math.min(c.mapper.minIn, c.mapper.maxIn); - double max = Math.max(c.mapper.minIn, c.mapper.maxIn); + double min = Math.min(config.mapper.minIn, config.mapper.maxIn); + double max = Math.max(config.mapper.minIn, config.mapper.maxIn); if (powerInput < min) { - warn("requested power %.2f is under minimum %.2f", powerInput, c.mapper.minIn); + warn("requested power %.2f is under minimum %.2f", powerInput, config.mapper.minIn); return; } if (powerInput > max) { - warn("requested power %.2f is over maximum %.2f", powerInput, c.mapper.maxIn); + warn("requested power %.2f is over maximum %.2f", powerInput, config.mapper.maxIn); return; } @@ -189,47 +181,52 @@ public void move(double powerInput) { MotorController controller = getController(); if (controller != null) { invoke("publishPowerChange", powerInput); - invoke("publishPowerOutputChange", c.mapper.calcOutput(powerInput)); + invoke("publishPowerOutputChange", config.mapper.calcOutput(powerInput)); controller.motorMove(this); } - // broadcastState(); } @Override public double publishPowerChange(double powerInput) { return powerInput; } - + /** * the published output of this motor control */ public double publishPowerOutputChange(double output) { return output; } - @Override public void setInverted(boolean invert) { log.warn("setting {} inverted = {}", getName(), invert); - GeneralMotorConfig c = config; - double temp = c.mapper.minIn; - c.mapper.minIn = c.mapper.maxIn; - c.mapper.maxIn = temp; + + // FIXME - this is residue when mapper had inverted state - + // which it shouldn't, "inverted" is just values of the in/out params + + if (!invert) { + return; + } + + double temp = config.mapper.minIn; + config.mapper.minIn = config.mapper.maxIn; + config.mapper.maxIn = temp; broadcastState(); } @Override public void setMinMax(double min, double max) { - GeneralMotorConfig c = config; - c.mapper.minIn = min; - c.mapper.maxIn = max; + + config.mapper.minIn = min; + config.mapper.maxIn = max; info("updated min %.2f max %.2f", min, max); broadcastState(); } public void map(double minX, double maxX, double minY, double maxY) { - GeneralMotorConfig c = config; - c.mapper.map(minX, maxX, minY, maxY); + + config.mapper.map(minX, maxX, minY, maxY); broadcastState(); } @@ -304,10 +301,10 @@ public void setEncoder(EncoderPublisher encoder) { @Override public void detachMotorController(MotorController controller) { - GeneralMotorConfig c = config; + controller.detach(this); controller = null; - c.controller = null; + config.controller = null; broadcastState(); } @@ -350,8 +347,8 @@ public void attachMotorController(MotorController controller) throws Exception { } log.info("attachMotorController {}", controller.getName()); - GeneralMotorConfig c = config; - c.controller = controller.getName(); + + config.controller = controller.getName(); motorPorts = controller.getPorts(); // TODO: KW: set a reasonable mapper. for pwm motor it's probable -1 to 1 to // 0 to 255 ? not sure. @@ -371,8 +368,6 @@ public void attachMotorController(MotorController controller) throws Exception { * So, the controller gave sane defaults, but the motor control has all the necessary configuration * */ - Mapper defaultControllerMapper = controller.getDefaultMapper(); - c.mapper.map(c.mapper.minIn, c.mapper.maxIn, defaultControllerMapper.getMinY(), defaultControllerMapper.getMaxY()); broadcastState(); controller.attach(this); @@ -385,32 +380,22 @@ public boolean isAttached() { @Override public void detach() { - GeneralMotorConfig c = config; - c.controller = null; - // MAKE NOTE!: don't want to do this anymore for fear of infinit detach loop - // just detach this service -// if (controller != null) { -// detach(controller.getName()); -// } + detach(config.controller); } - // FIXME - clean up the attach/detach - // TODO - this could be Java 8 default interface implementation @Override public void detach(String name) { - GeneralMotorConfig c = config; MotorController controller = getController(); if (controller == null || !name.equals(controller.getName())) { return; } - // MAKE NOTE !: mutual detach - this is dangerous, because of potential - // cycliclal detaching for dependencies - // its safer only to detach this service from the other service, vs call its detach - // but i think currently motorcontroller just remove notifylists (equivalent of unsubscribe) - // however if any of those call this detach - it will go infinite loop :( - // controller.detach(this); - c.controller = null; + + String controllerName = config.controller; + config.controller = null; + if (controllerName != null) { + send(controllerName, "detach", getName()); + } broadcastState(); } @@ -432,34 +417,30 @@ public Set getAttached() { // FIXME promote to interface public Mapper getMapper() { - GeneralMotorConfig c = config; - return c.mapper; + return config.mapper; } // FIXME promote to interface public void setMapper(MapperSimple mapper) { - GeneralMotorConfig c = config; - c.mapper = mapper; + config.mapper = mapper; } // FIXME promote to interface @Override public double calcControllerOutput() { - GeneralMotorConfig c = config; - return c.mapper.calcOutput(getPowerLevel()); + + return config.mapper.calcOutput(getPowerLevel()); } @Override public void setAxis(String name) { - GeneralMotorConfig c = config; - c.axis = name; + config.axis = name; broadcastState(); } @Override public String getAxis() { - GeneralMotorConfig c = config; - return c.axis; + return config.axis; } @Override @@ -477,9 +458,9 @@ public C apply(C c) { // mapper.setClip(config.clip); // FIXME ?? future use only ServiceConfig.listeners ? - if (c.controller != null) { + if (config.controller != null) { try { - attach(c.controller); + attach(config.controller); } catch (Exception e) { error(e); } diff --git a/src/main/java/org/myrobotlab/service/abstracts/AbstractSpeechSynthesis.java b/src/main/java/org/myrobotlab/service/abstracts/AbstractSpeechSynthesis.java index 50bd64ccd0..f8cca2fa92 100644 --- a/src/main/java/org/myrobotlab/service/abstracts/AbstractSpeechSynthesis.java +++ b/src/main/java/org/myrobotlab/service/abstracts/AbstractSpeechSynthesis.java @@ -545,7 +545,7 @@ AudioData play(AudioData data, boolean block) { log.warn("{} audioFile is null", getName()); return data; } - return audioFile.play(data); + return audioFile.playAudioData(data); } /** @@ -571,6 +571,12 @@ public String publishSpeechRequested(String toSpeak) { * @return - list of audio data */ public List parse(String toSpeak) { + + // we generate a list of audio data to play to support + // synthesizing this speech + List playList = new ArrayList(); + + try { // TODO - not sure if we want to support this notation // but at the moment it seems useful @@ -596,10 +602,6 @@ public List parse(String toSpeak) { toSpeak = filterText(toSpeak); - // we generate a list of audio data to play to support - // synthesizing this speech - List playList = new ArrayList(); - for (String speak : spokenParts) { AudioData audioData = null; @@ -627,6 +629,9 @@ public List parse(String toSpeak) { // so starting speaking event is when the first audio is "started" // and finished speaking is when the last audio is finished + } catch(Exception e) { + error(e); + } return playList; } diff --git a/src/main/java/org/myrobotlab/service/interfaces/MotorControl.java b/src/main/java/org/myrobotlab/service/interfaces/MotorControl.java index 4f5c098b99..d965d847a3 100644 --- a/src/main/java/org/myrobotlab/service/interfaces/MotorControl.java +++ b/src/main/java/org/myrobotlab/service/interfaces/MotorControl.java @@ -26,13 +26,65 @@ package org.myrobotlab.service.interfaces; import org.myrobotlab.framework.interfaces.Attachable; +import org.myrobotlab.logging.LoggerFactory; import org.myrobotlab.sensor.EncoderPublisher; +import org.myrobotlab.service.abstracts.AbstractMotor; +import org.slf4j.Logger; public interface MotorControl extends RelativePositionControl, AnalogListener, Attachable { - void attachMotorController(MotorController controller) throws Exception; + public final static Logger log = LoggerFactory.getLogger(MotorControl.class); + + /** + * Attaching a motor controller with a reference is useful in Python or Java + * but final implementation should always be done with a named string parameter + * attachMotorController(String name) to support standardized messaging without + * the need of typed references + * + * @param controller + * @throws Exception + */ + default void attachMotorController(MotorController controller) throws Exception { + if (controller == null) { + log.error("cannot attach with null controller"); + return; + } + attachMotorController(controller.getName()); + } + + /** + * Implementation of attachMotorController + * @param controller + * @throws Exception + */ + void attachMotorController(String controller) throws Exception; + + + /** + * Detaching a motor controller with a reference is useful in Python or Java + * but final implementation should always be done with a named string parameter + * detachMotorController(String name) to support standardized messaging without + * the need of typed references + * + * @param controller + * @throws Exception + */ + default void detachMotorController(MotorController controller){ + if (controller == null) { + log.error("cannot detach with null controller"); + return; + } + detachMotorController(controller.getName()); + } + + + /** + * Implementation of detachMotorController + * @param controller + * @throws Exception + */ + void detachMotorController(String controller); - void detachMotorController(MotorController controller); /** * the raw non-computed input range is -1.0 <---> 1.0 diff --git a/src/main/resources/resource/WebGui/app/service/js/MotorDualPwmGui.js b/src/main/resources/resource/WebGui/app/service/js/MotorDualPwmGui.js index fc60b23983..c9c86d4041 100644 --- a/src/main/resources/resource/WebGui/app/service/js/MotorDualPwmGui.js +++ b/src/main/resources/resource/WebGui/app/service/js/MotorDualPwmGui.js @@ -6,6 +6,13 @@ angular.module('mrlapp.service.MotorDualPwmGui', []).controller('MotorDualPwmGui $scope.requestedPower = 0 $scope.powerOutput = 0 + $scope.options = { + interface: 'PinArrayControl', + attach: _self.selectController, + // isAttached: $scope.service.config.controller // callback: function... + // attachName: $scope.controllerName + } + $scope.powerSlider = { value: 0, @@ -14,12 +21,9 @@ angular.module('mrlapp.service.MotorDualPwmGui', []).controller('MotorDualPwmGui ceil: 100, minLimit: -100, maxLimit: 100, - // hideLimitLabels: true, onStart: function() {}, onChange: function() { - // if ($scope.sliderEnabled) { msg.send('move', $scope.requestedPower / 100) - //} }, onEnd: function() {} } @@ -35,8 +39,12 @@ angular.module('mrlapp.service.MotorDualPwmGui', []).controller('MotorDualPwmGui this.updateState = function(service) { $scope.service = service if (firstTime) { - $scope.requestedController = service.controllerName + $scope.requestedController = service.config.controller firstTime = false + + $scope.options.attachName = service.config.controller + $scope.options.isAttached = service.attached + $scope.options.interface = 'PinArrayControl' } } @@ -77,7 +85,7 @@ angular.module('mrlapp.service.MotorDualPwmGui', []).controller('MotorDualPwmGui $scope.update = function() { console.info('update') - msg.send('map', $scope.service.mapper.minX, $scope.service.mapper.maxX, $scope.service.mapper.minY, $scope.service.mapper.maxY) + msg.send('map', $scope.service.config.mapper.minIn, $scope.service.config.mapper.minIn, $scope.service.config.mapper.minOut, $scope.service.config.mapper.maxOut) } $scope.setController = function(c) { @@ -91,8 +99,8 @@ angular.module('mrlapp.service.MotorDualPwmGui', []).controller('MotorDualPwmGui } $scope.detach = function() { - console.info('detach', $scope.service.controllerName) - msg.send('detach', $scope.service.controllerName) + console.info('detach') + msg.send('detach') } $scope.moveTo = function() { diff --git a/src/main/resources/resource/WebGui/app/service/views/MotorDualPwmGui.html b/src/main/resources/resource/WebGui/app/service/views/MotorDualPwmGui.html index 8f3256870e..bb6ff3b3f4 100644 --- a/src/main/resources/resource/WebGui/app/service/views/MotorDualPwmGui.html +++ b/src/main/resources/resource/WebGui/app/service/views/MotorDualPwmGui.html @@ -40,18 +40,23 @@

- + min
+ - + max
+ - + min
+ - + max
+ +
@@ -61,7 +66,7 @@

invert -   +   @@ -73,19 +78,9 @@

-
- - - -
- - + + +
-