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 @@

-
- - - -
- - + + +
-