From: Mart Lubbers Date: Thu, 10 Dec 2015 14:31:06 +0000 (+0100) Subject: push X-Git-Url: https://git.martlubbers.net/?a=commitdiff_plain;h=08b6c73b2092b16b5dc1c0f2884d2e9c49c445af;p=des2015.git push --- diff --git a/dsl/runtime/specs/spec1.tdsl b/dsl/runtime/specs/spec1.tdsl index 197784a..ce35b55 100644 --- a/dsl/runtime/specs/spec1.tdsl +++ b/dsl/runtime/specs/spec1.tdsl @@ -1,4 +1,4 @@ -Acceleration 1000 +-Acceleration 1000 Speed 200 Behaviour Wander take control: diff --git a/dsl/runtime/specs/wander.tdsl b/dsl/runtime/specs/wander.tdsl new file mode 100644 index 0000000..5100e52 --- /dev/null +++ b/dsl/runtime/specs/wander.tdsl @@ -0,0 +1,33 @@ +Acceleration 1000 +Speed 250 +Behaviour Wander + take control: + action: + left motor forward + right motor forward + wait forever + +Behaviour StayInFieldBoth + take control: (&& Light on left Light on right) + action: + left motor backward with speed 1000 acceleration 10000 + right motor backward with speed 250 acceleration 10000 + wait 1000 ms +Behaviour StayInFieldL + take control: Light on left + action: + right motor backward with speed 250 acceleration 10000 + left motor forward with speed 250 acceleration 10000 + wait 750 ms +Behaviour StayInFieldR + take control: Light on right + action: + right motor forward with speed 250 acceleration 10000 + left motor backward with speed 250 acceleration 10000 + wait 750 ms +Behaviour StayInFieldB + take control: Distance dangerous at back + action: + wait 750 ms + +Mission stayinfield using Wander StayInFieldL StayInFieldR StayInFieldB StayInFieldBoth and stops when Color is Cyan \ No newline at end of file diff --git a/dsl/runtime/src/nl/ru/des/BasicBehaviour.java b/dsl/runtime/src/nl/ru/des/BasicBehaviour.java index d67f83b..1d79edd 100644 --- a/dsl/runtime/src/nl/ru/des/BasicBehaviour.java +++ b/dsl/runtime/src/nl/ru/des/BasicBehaviour.java @@ -35,6 +35,14 @@ public abstract class BasicBehaviour implements Behavior{ } + protected void rightTurn(int angle){ + + } + + protected void leftTurn(int angle){ + + } + @Override public void action() { suppressed = false; diff --git a/dsl/runtime/src/nl/ru/des/Marster.java b/dsl/runtime/src/nl/ru/des/Marster.java index 6353904..ad31306 100644 --- a/dsl/runtime/src/nl/ru/des/Marster.java +++ b/dsl/runtime/src/nl/ru/des/Marster.java @@ -1,6 +1,7 @@ package nl.ru.des; -import lejos.hardware.Button; +import java.util.LinkedList; + import lejos.hardware.ev3.EV3; import lejos.hardware.ev3.LocalEV3; import lejos.hardware.lcd.Font; @@ -59,12 +60,12 @@ public class Marster { RegulatedMotor rightMotor = new EV3LargeRegulatedMotor(MotorPort.A); RegulatedMotor leftMotor = new EV3LargeRegulatedMotor(MotorPort.B); RegulatedMotor measMotor = new EV3MediumRegulatedMotor(MotorPort.C); -// leftMotor.setSpeed(Constants.speed); -// rightMotor.setSpeed(Constants.speed); -// measMotor.setSpeed(100); -// rightMotor.setAcceleration(Constants.acceleration); -// leftMotor.setAcceleration(Constants.acceleration); -// measMotor.setAcceleration(100); + leftMotor.setSpeed(Constants.speed); + rightMotor.setSpeed(Constants.speed); + measMotor.setSpeed(100); + rightMotor.setAcceleration(Constants.acceleration); + leftMotor.setAcceleration(Constants.acceleration); + measMotor.setAcceleration(100); LCDPrinter.print("Loading touch sensors..."); SampleProvider leftLight = new NXTLightSensor(brick.getPort("S1")).getRedMode(); @@ -76,16 +77,15 @@ public class Marster { LCDPrinter.print("Loading gyro sensor..."); SampleProvider gyro = new EV3GyroSensor(brick.getPort("S4")).getAngleAndRateMode(); - BTController.startMaster(slave, new SensorCollector(backUltra, leftLight, rightLight, gyro)); + SensorCollector sc = new SensorCollector(backUltra, leftLight, rightLight, gyro); + BTController.startMaster(slave, sc); LCDPrinter.print("Finished loading"); - Button.waitForAnyPress(); -// Arbitrator a; -// LinkedList missions = Missions.getMissions(sensors, rightMotor, leftMotor, colorMemory); -// for(Mission m : missions){ -// LCDPrinter.print("Start " + m.name + " mission..."); -// a = new Arbitrator(m.behaviours); -// a.start(); -// } + LinkedList missions = Missions.getMissions(sc, rightMotor, leftMotor, measMotor); + for(Mission m : missions){ + LCDPrinter.print("Start " + m.name + " mission..."); + arb = new Arbitrator(m.behaviours); + arb.start(); + } } } } \ No newline at end of file diff --git a/dsl/runtime/src/nl/ru/des/ShutdownBehaviour.java b/dsl/runtime/src/nl/ru/des/ShutdownBehaviour.java index ae75647..7993fe0 100644 --- a/dsl/runtime/src/nl/ru/des/ShutdownBehaviour.java +++ b/dsl/runtime/src/nl/ru/des/ShutdownBehaviour.java @@ -1,16 +1,12 @@ package nl.ru.des; -import lejos.hardware.motor.EV3LargeRegulatedMotor; -import nl.ru.des.sensors.SensorCollector; +import lejos.robotics.subsumption.Behavior; -public class ShutdownBehaviour extends BasicBehaviour{ - public ShutdownBehaviour(SensorCollector sensors, EV3LargeRegulatedMotor leftMotor, - EV3LargeRegulatedMotor rightMotor, EV3LargeRegulatedMotor measMotor) { - super(sensors, leftMotor, rightMotor, measMotor); - } - +public abstract class ShutdownBehaviour implements Behavior{ @Override public void action(){ LCDPrinter.print("Terminate mission"); Marster.arb.stop(); } + + @Override public void suppress(){} } diff --git a/dsl/runtime/src/nl/ru/des/sensors/RemoteSensors.java b/dsl/runtime/src/nl/ru/des/sensors/RemoteSensors.java index 2075512..65bc067 100644 --- a/dsl/runtime/src/nl/ru/des/sensors/RemoteSensors.java +++ b/dsl/runtime/src/nl/ru/des/sensors/RemoteSensors.java @@ -7,7 +7,7 @@ import lejos.utility.Delay; import nl.ru.des.LCDPrinter; public class RemoteSensors{ - public static final int DELAY = 250; + public static final int DELAY = 100; private SampleProvider left, right, ultra, color; private float[] leftSamples, rightSamples, ultraSamples, colorSamples; private float leftLatest, rightLatest, ultraLatest, colorLatest; diff --git a/dsl/runtime/src/nl/ru/des/sensors/SensorCollector.java b/dsl/runtime/src/nl/ru/des/sensors/SensorCollector.java index 60652d8..29433c1 100644 --- a/dsl/runtime/src/nl/ru/des/sensors/SensorCollector.java +++ b/dsl/runtime/src/nl/ru/des/sensors/SensorCollector.java @@ -1,10 +1,15 @@ package nl.ru.des.sensors; +import lejos.hardware.lcd.LCD; import lejos.robotics.SampleProvider; -import nl.ru.des.LCDPrinter; +import lejos.utility.Delay; public class SensorCollector implements MessageHandler{ - public static final int DELAY = 300; + public static final int DELAY = 100; + + private static final float DANGER_DISTANCE_FRONT = 0.15f; + private static final float DANGER_DISTANCE_BACK = 0.035f; + private static final float DANGER_LIGHT = 0.45f; //Local sensors private SampleProvider ultra, leftLight, rightLight, gyro; @@ -34,13 +39,30 @@ public class SensorCollector implements MessageHandler{ gyroTime = System.currentTimeMillis(); } + public void debug(){ + new Thread(){ + @Override public void run(){ + while(true){ + ultra.fetchSample(ultraSamples, 0); + leftLight.fetchSample(leftLightSamples, 0); + rightLight.fetchSample(rightLightSamples, 0); + LCD.drawString("back: " + Float.toString(ultraSamples[0]), 0, 1); + LCD.drawString("front: " + Float.toString(frontUltra), 0, 2); + LCD.drawString("left: " + Float.toString(leftLightSamples[0]), 0, 3); + LCD.drawString("right: " + Float.toString(rightLightSamples[0]), 0, 4); + Delay.msDelay(250); + } + } + }.run(); + } + //Local sensors - public float backDistance(){ + public boolean backDistance(){ if(System.currentTimeMillis()-ultraTime>DELAY){ ultra.fetchSample(ultraSamples, 0); ultraTime = System.currentTimeMillis(); } - return ultraSamples[0]; + return ultraSamples[0]>DANGER_DISTANCE_BACK; } public boolean leftLight(){ @@ -48,7 +70,7 @@ public class SensorCollector implements MessageHandler{ leftLight.fetchSample(leftLightSamples, 0); leftLightTime = System.currentTimeMillis(); } - return leftLightSamples[0]>0.5; + return leftLightSamples[0]>DANGER_LIGHT; } public boolean rightLight(){ @@ -56,7 +78,7 @@ public class SensorCollector implements MessageHandler{ rightLight.fetchSample(rightLightSamples, 0); rightLightTime = System.currentTimeMillis(); } - return rightLightSamples[0]>0.5; + return rightLightSamples[0]>DANGER_LIGHT; } public float gyro(){ @@ -68,6 +90,10 @@ public class SensorCollector implements MessageHandler{ } //Remote sensors + public boolean collected(int[] colors){ + return false; + } + public int color(){ return color; } @@ -80,13 +106,12 @@ public class SensorCollector implements MessageHandler{ return rightTouch; } - public float frontDistance(){ - return frontUltra; + public boolean frontDistance(){ + return frontUltra list)''' + def CharSequence makeMissions(EList mission)''' package nl.ru.des; import java.util.LinkedList; -import lejos.hardware.motor.EV3LargeRegulatedMotor; import lejos.robotics.subsumption.Behavior; -import nl.ru.des.Behaviours; +import lejos.robotics.RegulatedMotor; + +import nl.ru.des.sensors.SensorCollector; public class Missions{ - public static LinkedList getMissions(SensorCollector sensors, EV3LargeRegulatedMotor rightMotor, - EV3LargeRegulatedMotor leftMotor, ColorMemory colors){ + public static LinkedList getMissions(final SensorCollector sensors, RegulatedMotor rightMotor, + RegulatedMotor leftMotor, RegulatedMotor measMotor){ LinkedList missions = new LinkedList(); - «FOR m : list» + «FOR m : mission» missions.add(new Mission("«m.name»", new Behavior[]{ - «FOR b : m.behaviours SEPARATOR ","» - new Behaviours.«b.name»Behaviour(sensors, rightMotor, leftMotor, colors) - «ENDFOR», - new ShutdownBehaviour(sensors, rightMotor, leftMotor, colors){ + «FOR b : m.behaviours SEPARATOR "," AFTER ","»new «b.name»Behaviour(sensors, rightMotor, leftMotor, measMotor) + «ENDFOR» + new ShutdownBehaviour(){ @Override public boolean takeControl(){ - return »; + return «printExpression(m.se)»; } }} «ENDFOR»)); @@ -73,8 +73,8 @@ public class «b.name»Behaviour extends BasicBehaviour { } «IF b.tc != null» @Override public boolean takeControl(){ - return «printExpression(b.tc)»; - } + return !suppressed || «printExpression(b.tc)»; + } «ENDIF» @Override public void action(){ @@ -88,6 +88,8 @@ public class «b.name»Behaviour extends BasicBehaviour { «a.whichMotor.d.toString()»Motor.«a.moveDir.d.toString()»(); «ELSEIF a.measureWhat != null» «a.measureWhat.d.toString()»Measure(); + «ELSEIF a.turnDir != null» + «a.turnDir.d.toString()»Turn(«a.degrees»); «ELSE» time = System.currentTimeMillis(); while(!suppressed«IF a.time.time > 0» && System.currentTimeMillis()-time>«a.time.time»«ENDIF»){ @@ -114,8 +116,10 @@ public class Constants{ sensors.collected(new int[]{«FOR c : e.scond.colors SEPARATOR ","»«c.d.ordinal»«ENDFOR»}) «ELSEIF e.scond.touch != null» sensors.«e.scond.touch.d.toString()»Touch() + «ELSEIF e.scond.light != null» + sensors.«e.scond.light.d.toString()»Light() «ELSEIF e.scond.dist != null» - sensors.distance() «e.scond.dist.d.toString()» «e.scond.dist» + sensors.«e.scond.dist.d.toString()»Distance() «ELSEIF e.scond.color != null» sensors.color() == «e.scond.color.d.ordinal» «ENDIF» @@ -123,8 +127,7 @@ public class Constants{ «IF e.op.d.equals(OperatorE.AND)» «FOR ex : e.s BEFORE "(" SEPARATOR "&&" AFTER ")"»«printExpression(ex)»«ENDFOR» «ELSE» - «FOR ex : e.s BEFORE "(" SEPARATOR "&&" AFTER ")"»«printExpression(ex)»«ENDFOR» + «FOR ex : e.s BEFORE "(" SEPARATOR "||" AFTER ")"»«printExpression(ex)»«ENDFOR» «ENDIF» - «ENDIF» - ''' + «ENDIF»''' } \ No newline at end of file