├── .gitignore
├── CODE_OF_CONDUCT.md
├── LICENSE
├── Leguino.cpp
├── Leguino.h
├── README.md
├── actor
├── Actor.cpp
├── Actor.h
├── Light.cpp
├── Light.h
├── Motor.cpp
├── Motor.h
├── Sequence.cpp
├── Sequence.h
├── SingleActor.cpp
├── SingleActor.h
├── Tread.cpp
└── Tread.h
├── core
├── LeguinoCore.cpp
├── LeguinoCore.h
├── LeguinoList.h
├── LeguinoPanic.h
└── LeguinoTypes.h
├── docs
├── Leguino-Kurzanleitung-DE.doc
├── Power-Functions-assignment.jpg
├── TQ2L25-bistable-relay-assignment.png
├── ideas
│ └── Robotik-für-Kinder.jpg
├── nano-shield.svg
├── overall-wiring.svg
├── parts.md
├── photos
│ ├── Leguino-Hardware-1.jpg
│ ├── Leguino-Hardware-10.jpg
│ ├── Leguino-Hardware-11.jpg
│ ├── Leguino-Hardware-12.jpg
│ ├── Leguino-Hardware-13.jpg
│ ├── Leguino-Hardware-14.jpg
│ ├── Leguino-Hardware-15.jpg
│ ├── Leguino-Hardware-16.jpg
│ ├── Leguino-Hardware-17.jpg
│ ├── Leguino-Hardware-18.jpg
│ ├── Leguino-Hardware-19.jpg
│ ├── Leguino-Hardware-2.jpg
│ ├── Leguino-Hardware-20.jpg
│ ├── Leguino-Hardware-21.jpg
│ ├── Leguino-Hardware-22.jpg
│ ├── Leguino-Hardware-23.jpg
│ ├── Leguino-Hardware-24.jpg
│ ├── Leguino-Hardware-25.jpg
│ ├── Leguino-Hardware-26.jpg
│ ├── Leguino-Hardware-27.jpg
│ ├── Leguino-Hardware-3.jpg
│ ├── Leguino-Hardware-4.jpg
│ ├── Leguino-Hardware-5.jpg
│ ├── Leguino-Hardware-6.jpg
│ ├── Leguino-Hardware-7.jpg
│ ├── Leguino-Hardware-8.jpg
│ └── Leguino-Hardware-9.jpg
└── uno-shield.svg
├── eagle
├── .gitignore
├── LeguinoUno-Gerber.zip
├── LeguinoUno.brd
├── LeguinoUno.sch
├── eagle.epf
└── sfe-gerb274x-JEB.cam
├── examples
├── LeguinoEmpty-de
│ └── LeguinoEmpty-de.ino
├── LeguinoEmpty
│ └── LeguinoEmpty.ino
└── LeguinoTester
│ └── LeguinoTester.ino
└── sensor
├── DistanceSensor.cpp
├── DistanceSensor.h
├── LightBarrier.cpp
├── LightBarrier.h
├── LightSensor.cpp
├── LightSensor.h
├── Sensor.cpp
├── Sensor.h
├── SingleSensor.cpp
├── SingleSensor.h
├── Switch.cpp
└── Switch.h
/.gitignore:
--------------------------------------------------------------------------------
1 | /.project
2 |
--------------------------------------------------------------------------------
/CODE_OF_CONDUCT.md:
--------------------------------------------------------------------------------
1 | # Contributor Covenant Code of Conduct
2 |
3 | ## Our Pledge
4 |
5 | In the interest of fostering an open and welcoming environment, we as contributors and maintainers pledge to making participation in our project and our community a harassment-free experience for everyone, regardless of age, body size, disability, ethnicity, gender identity and expression, level of experience, nationality, personal appearance, race, religion, or sexual identity and orientation.
6 |
7 | ## Our Standards
8 |
9 | Examples of behavior that contributes to creating a positive environment include:
10 |
11 | * Using welcoming and inclusive language
12 | * Being respectful of differing viewpoints and experiences
13 | * Gracefully accepting constructive criticism
14 | * Focusing on what is best for the community
15 | * Showing empathy towards other community members
16 |
17 | Examples of unacceptable behavior by participants include:
18 |
19 | * The use of sexualized language or imagery and unwelcome sexual attention or advances
20 | * Trolling, insulting/derogatory comments, and personal or political attacks
21 | * Public or private harassment
22 | * Publishing others' private information, such as a physical or electronic address, without explicit permission
23 | * Other conduct which could reasonably be considered inappropriate in a professional setting
24 |
25 | ## Our Responsibilities
26 |
27 | Project maintainers are responsible for clarifying the standards of acceptable behavior and are expected to take appropriate and fair corrective action in response to any instances of unacceptable behavior.
28 |
29 | Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful.
30 |
31 | ## Scope
32 |
33 | This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers.
34 |
35 | ## Enforcement
36 |
37 | Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at http://thomasjacob.de/footer/contact. The project team will review and investigate all complaints, and will respond in a way that it deems appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately.
38 |
39 | Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project's leadership.
40 |
41 | ## Attribution
42 |
43 | This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4, available at [http://contributor-covenant.org/version/1/4][version]
44 |
45 | [homepage]: http://contributor-covenant.org
46 | [version]: http://contributor-covenant.org/version/1/4/
47 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2017 SinnerSchrader Deutschland GmbH
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/Leguino.cpp:
--------------------------------------------------------------------------------
1 | #include "Leguino.h"
2 |
3 |
4 | #include "core/LeguinoCore.cpp"
5 |
6 | #include "sensor/Sensor.cpp"
7 | #include "sensor/SingleSensor.cpp"
8 | #include "sensor/DistanceSensor.cpp"
9 | #include "sensor/LightSensor.cpp"
10 | #include "sensor/LightBarrier.cpp"
11 | #include "sensor/Switch.cpp"
12 |
13 | #include "actor/Sequence.cpp"
14 |
15 | #include "actor/Actor.cpp"
16 | #include "actor/SingleActor.cpp"
17 | #include "actor/Light.cpp"
18 | #include "actor/Motor.cpp"
19 | #include "actor/Tread.cpp"
20 |
--------------------------------------------------------------------------------
/Leguino.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_H
2 | #define __LEGUINO_H
3 |
4 |
5 | class Actor;
6 | class SingleActor;
7 | class Light;
8 | class Motor;
9 | class Tread;
10 |
11 | class LeguinoCore;
12 |
13 | class Sensor;
14 | class SingleSensor;
15 | class Switch;
16 | class DistanceSensor;
17 | class LightSensor;
18 | class LightBarrier;
19 |
20 | class Sequence;
21 |
22 |
23 | #include "Arduino.h"
24 |
25 | #include "core/LeguinoList.h"
26 | #include "core/LeguinoPanic.h"
27 | #include "core/LeguinoTypes.h"
28 |
29 | #include "core/LeguinoCore.h"
30 |
31 | #include "sensor/Sensor.h"
32 | #include "sensor/SingleSensor.h"
33 | #include "sensor/Switch.h"
34 | #include "sensor/DistanceSensor.h"
35 | #include "sensor/LightSensor.h"
36 | #include "sensor/LightBarrier.h"
37 |
38 | #include "actor/Sequence.h"
39 |
40 | #include "actor/Actor.h"
41 | #include "actor/SingleActor.h"
42 | #include "actor/Light.h"
43 | #include "actor/Motor.h"
44 | #include "actor/Tread.h"
45 |
46 |
47 | #endif
48 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Disclaimer and warning
2 |
3 | The instructions, images, schematics, source codes, etc. may not be accurate nor complete.
4 | Use at your own risk.
5 |
6 | LEGO® is a trademark of the LEGO Group of companies which does not sponsor, authorize or endorse this site.
7 | LEGUINO™ is a trademark of Leguino Ltd., which is independent of this Leguino project.
8 |
9 | **Attention**: Please note that there are two projects with the name "Leguino" out there:
10 |
11 | 1. This open-source, free GitHub project, focussing on the creation of an Arduino shield to drive standard LEGO® Technic motors and lights. You can find more details on the history of the project in this readme, and at [Thomas Jacob's website](https://www.thomasjacob.de/kreativ/leguino-en). In this project, you take your existing LEGO® Technic models and bring them to life by programming against an Arduino API.
12 |
13 | 2. A commercial project, started as a Kickstarter campaign, focussing on the creation of proprietary hardware bricks compatible to the geometry of LEGO®, with Arduino and Raspberry Pi programming. You can find more details on that project at [Leguino.com](http://leguino.com).
14 |
15 | # Introduction
16 |
17 | [LEGO® Mindstorms](https://www.lego.com/de-de/mindstorms) is a wonderful platform to playfully get used to robotics and programming. Kids can complete their existing LEGO® collection with motors and sensors, and the graphical programming environment is easy to understand, but it also contains complex concepts like commands, iterations, branching, variables, and events.
18 |
19 | LEGO® Mindstorms is, on the other hand, not very cheap (especially for the inquisitive offspring). Though my son already had a rich collection of LEGO® Technic models with motors, lights, and switches, it lacks of sensors and even programming.
20 |
21 | But he was very much interested in that stuff.
22 |
23 | So I thought, let's try to fill the gap and build an open-source platform based on LEGO® Technic, that is cheap enough (goal <100€) and also easy to understand. To do so, [Arduino](https://www.arduino.cc/) is the perfect choice, for the following reasons:
24 |
25 | * An Arduino Nano costs less than 20€, sometimes even below 10€.
26 | * You can power it with a regular LEGO® Technic battery.
27 | * It starts up in less than a second (in contrast to the [Raspberry Pi](https://www.raspberrypi.org/) for instance), a circumstance that is important when building models with a switchable battery.
28 | * It has enough inputs/outputs for about 10 devices.
29 |
30 | I added a programming platform, an API that abstracts from sensors, actors, control sequences etc., so the offspring (and you) can focus on the actual project.
31 |
32 | If you want to learn more about how Leguino was invented, [visit my web site](http://www.thomasjacob.de/kreativ/leguino-en).
33 |
34 | # Getting started
35 |
36 | Leguino is both a custom Arduino shield and wiring, as well as a library for Arduino. To get started, you need to build the shield yourself (sorry, no orderable ready-made PCB as of today), and then install the Arduino IDE, and the Leguino library.
37 |
38 | ## Hardware
39 |
40 | First of all, you require an Arduino Uno or Nano. I recommend the latter, as it fulfills the Leguino requirements and it has much smaller dimensions.
41 |
42 | As there is no Leguino PCB design as of today (maybe you'd like to contribute?), you need to buy an Arduino shield and all electronics parts, and solder them manually.
43 |
44 | You also need to make LEGO® Technic wires and the case.
45 |
46 | You can find all parts in the [parts list](docs/parts.md), as well as wiring and board schematics in [schematics folder](docs/schematics). I also took [some pictures](docs/photos) while building the prototype. Maybe my [my web site](http://www.thomasjacob.de/kreativ/leguino-en) helps, too.
47 |
48 | ## Software
49 |
50 | To write your own Leguino program, you first need the Arduino IDE, which you can [download here].
51 |
52 | After installation, take this Leguino source folder, and put it into the libraries folder of your installation.
53 |
54 | Then, start your programs by using one of the example sketches found in [examples)(examples), and read the API of the [Leguino core](core/LeguinoCore.h), [its actors](actor/Actor.h), and [its sensors](sensor/Sensor.h).
55 |
56 | There is also a kids-friendly (but German) documentation available, [see here](docs/Leguino-Kurzanleitung-DE.doc).
57 |
58 | # Contribute
59 |
60 | Do you have suggestions, ideas, even code or PCB designs? Please contact me at http://thomasjacob.de/footer/contact.
61 |
--------------------------------------------------------------------------------
/actor/Actor.cpp:
--------------------------------------------------------------------------------
1 | Actor::Actor()
2 | {
3 | }
4 |
5 | Actor::~Actor()
6 | {
7 | }
8 |
--------------------------------------------------------------------------------
/actor/Actor.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_ACTOR_H
2 | #define __LEGUINO_ACTOR_H
3 |
4 |
5 | /**
6 | * Constant to refer to output A (use this in the actors' constructor.
7 | */
8 | #define OUT_A 'A'
9 |
10 | /**
11 | * Constant to refer to output B (use this in the actors' constructor.
12 | */
13 | #define OUT_B 'B'
14 |
15 | /**
16 | * Constant to refer to output C (use this in the actors' constructor.
17 | */
18 | #define OUT_C 'C'
19 |
20 | /**
21 | * Constant to refer to output D (use this in the actors' constructor.
22 | */
23 | #define OUT_D 'D'
24 |
25 | /**
26 | * Constant to refer to output E (use this in the actors' constructor.
27 | */
28 | #define OUT_E 'E'
29 |
30 |
31 | /**
32 | *
33 | * Actors represent active devices you attach to the Leguino board, like
34 | * LEGO© motors and lights. One actor usually requires one
35 | * output, but some actors may also represent a combination of outputs, like
36 | * the treads (two motors).
37 | *
38 | *
39 | *
40 | * Add actors to your program in the setup function, after initializing Leguino,
41 | * using the following example pattern:
42 | * leguino.add(drive = new Motor(OUT_A));
43 | * or
44 | * leguino.add(drive = new Tread(OUT_A, OUT_B));
45 | * or
46 | * leguino.add(frontLight = new Light(OUT_C));
47 | * where drive
and frontLight
are global variables.
48 | *
49 | *
50 | *
51 | * In the main loop, after the regular update call to the Leguino platform,
52 | * use the actor's methods to control the outputs, spontaneously or
53 | * time-controlled.
54 | *
55 | */
56 | class Actor
57 | {
58 | friend SingleActor;
59 |
60 | public:
61 |
62 | /**
63 | * Destroys the actor.
64 | * Don't call this method from your program.
65 | */
66 | virtual ~Actor();
67 |
68 | /**
69 | * Internal Leguino method to update the actor.
70 | * Don't call this method from your program.
71 | * @param msecs The number of milli-seconds since the last update.
72 | */
73 | virtual void update(uint16 timeStep) = NULL;
74 |
75 | protected:
76 |
77 | Actor();
78 | };
79 |
80 |
81 | #endif
82 |
--------------------------------------------------------------------------------
/actor/Light.cpp:
--------------------------------------------------------------------------------
1 | Light::Light(int8 output)
2 | : SingleActor(output)
3 | {
4 | }
5 |
--------------------------------------------------------------------------------
/actor/Light.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_LIGHT_H
2 | #define __LEGUINO_LIGHT_H
3 |
4 |
5 | /**
6 | * A Leguino single actor representing a LEGO© Technic light.
7 | *
8 | * @see Actor
9 | * @see SingleActor
10 | */
11 | class Light : public SingleActor
12 | {
13 | public:
14 |
15 | /**
16 | * Creates a new light.
17 | * @param output The output the light is connected to.
18 | * Use the constants OUT_A thru OUT_E.
19 | */
20 | Light(int8 output);
21 | };
22 |
23 |
24 | #endif
25 |
--------------------------------------------------------------------------------
/actor/Motor.cpp:
--------------------------------------------------------------------------------
1 | Motor::Motor(int8 output)
2 | : SingleActor(output)
3 | {
4 | }
5 |
6 | void Motor::reverse()
7 | {
8 | setValue(-100);
9 | }
10 |
11 | void Motor::reverse(uint16 msecs)
12 | {
13 | reverse();
14 | leguino.delay(msecs);
15 | off();
16 | }
17 |
--------------------------------------------------------------------------------
/actor/Motor.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_MOTOR_H
2 | #define __LEGUINO_MOTOR_H
3 |
4 |
5 | /**
6 | * A Leguino single actor representing a LEGO© Technic motor.
7 | *
8 | * @see Actor
9 | * @see SingleActor
10 | */
11 | class Motor : public SingleActor
12 | {
13 | public:
14 |
15 | /**
16 | * Creates a new motor.
17 | * @param output The output the motor is connected to.
18 | * Use the constants OUT_A thru OUT_E.
19 | */
20 | Motor(int8 output);
21 |
22 | /**
23 | * Turns on this actor (motor) in reverse, setting its output to -100,
24 | * and disabling any sequence.
25 | * @see on()
26 | * @see off()
27 | */
28 | void reverse();
29 |
30 | /**
31 | * Turns on this actor (motor) in reverse, setting its output to -100,
32 | * and disabling any sequence. Waits a given number of milli-seconds,
33 | * then turns it off.
34 | * Note: This method blocks until the delay is over. For
35 | * background value control, use sequences instead.
36 | * @param msecs The number of milli-seconds to wait before turning off
37 | * the motor.
38 | * @see on()
39 | * @see off()
40 | * @see Sequence
41 | */
42 | void reverse(uint16 msecs);
43 | };
44 |
45 |
46 | #endif
47 |
--------------------------------------------------------------------------------
/actor/Sequence.cpp:
--------------------------------------------------------------------------------
1 | Sequence::Sequence()
2 | {
3 | repeat = false;
4 | smooth = false;
5 | }
6 |
7 | void Sequence::addStep(int8 value, uint16 msecs)
8 | {
9 | values.append(value);
10 | durations.append(msecs);
11 | }
12 |
13 | uint16 Sequence::getDuration(int step)
14 | {
15 | return durations.get(step);
16 | }
17 |
18 | uint16 Sequence::getTotalDuration()
19 | {
20 | uint16 totalDuration = 0;
21 | for (int i=0; ismooth = smooth;
49 | }
50 |
51 | void Sequence::setRepeat(bool repeat)
52 | {
53 | this->repeat = repeat;
54 | }
55 |
--------------------------------------------------------------------------------
/actor/Sequence.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_SEQUENCE_H
2 | #define __LEGUINO_SEQUENCE_H
3 |
4 |
5 | /**
6 | *
7 | * A sequence of single-actor values (e.g. for motors, lights), which Leguino
8 | * will activate automatically and in background. Use this for e.g. for
9 | * flashing lights or any kind of temporary actor activation that requires
10 | * the main program to continue in the mean time.
11 | *
12 | *
13 | *
14 | * Use the following code to define and activate a sequence:
15 | * Sequence * sequence = new Sequence();
16 | * sequence->addStep(100, 500);
17 | * sequence->addStep(0, 500);
18 | * sequence->setRepeat(true);
19 | * light->setSequence(sequence);
20 | *
21 | */
22 | class Sequence
23 | {
24 | public:
25 |
26 | /**
27 | * Creates a new sequence. Use global variables or the new operator for
28 | * sequences, to ensure the memory is not freed while active in actors.
29 | */
30 | Sequence();
31 |
32 | /**
33 | * Adds a step to the sequence.
34 | * @param value The new value from -100 (full reverse), over 0 (off),
35 | * to 100 (full on).
36 | * @param msecs The number of milli-seconds to hold the value.
37 | */
38 | void addStep(int8 value, uint16 msecs);
39 |
40 | /**
41 | * Returns the duration of a given step.
42 | * @param step The 0-indexed step number.
43 | * @return The number of milli-seconds of the step.
44 | */
45 | uint16 getDuration(int step);
46 |
47 | /**
48 | * Returns the value of a given step.
49 | * @param step The 0-indexed step number.
50 | * @return The value of the step from -100 (full reverse), over 0 (off),
51 | * to 100 (full on).
52 | */
53 | int8 getValue(int step);
54 |
55 | /**
56 | * Returns the number of steps added to this sequence so far.
57 | * @return The number of steps.
58 | */
59 | int getSteps();
60 |
61 | /**
62 | * Returns the total duration of all steps.
63 | * @return The total duration of all steps.
64 | */
65 | uint16 getTotalDuration();
66 |
67 | /**
68 | * Returns whether the transition of the value of one step to the next
69 | * should be smooth.
70 | * @return Whether the sequence transitions are smooth.
71 | */
72 | bool isSmooth();
73 |
74 | /**
75 | * Returns whether the sequence should repeat infinitely.
76 | * @return Whether the sequence should repeat.
77 | */
78 | bool isRepeat();
79 |
80 | /**
81 | * Sets whether the transition of the value of one step to the next
82 | * should be smooth.
83 | * @param smooth Whether the sequence transitions are smooth.
84 | */
85 | void setSmooth(bool smooth);
86 |
87 | /**
88 | * Sets whether the sequence should repeat infinitely.
89 | * Unset the sequence in the actor (or call stop) to stop the repetition.
90 | * @param repeat Whether the sequence should repeat.
91 | */
92 | void setRepeat(bool repeat);
93 |
94 | protected:
95 |
96 | ValueList durations;
97 | bool repeat;
98 | bool smooth;
99 | ValueList values;
100 | };
101 |
102 |
103 | #endif
104 |
--------------------------------------------------------------------------------
/actor/SingleActor.cpp:
--------------------------------------------------------------------------------
1 | SingleActor::SingleActor(int8 output)
2 | {
3 | switch (output)
4 | {
5 | case OUT_A: powerPin = 3; forwardPin = 2; backwardPin = 7; break;
6 | case OUT_B: powerPin = 5; forwardPin = 2; backwardPin = 9; break;
7 | case OUT_C: powerPin = 6; forwardPin = 2; backwardPin = 8; break;
8 | case OUT_D: powerPin = 10; forwardPin = -1; backwardPin = -1; break;
9 | case OUT_E: powerPin = 11; forwardPin = -1; backwardPin = -1; break;
10 |
11 | default: powerPin = -1; forwardPin = -1; backwardPin = -1;
12 | }
13 |
14 | currentValue = 0;
15 | direction = 0;
16 | requestedValue = 0;
17 | sequence = NULL;
18 | sequenceStep = -1;
19 | sequenceStepDuration = 0;
20 | sequenceStepRemaining = 0;
21 | sequenceStepStartValue = 0;
22 | sequenceStepEndValue = 0;
23 | }
24 |
25 | uint16 SingleActor::getCurrentValue()
26 | {
27 | return currentValue;
28 | }
29 |
30 | Sequence * SingleActor::getSequence()
31 | {
32 | return sequence;
33 | }
34 |
35 | void SingleActor::off()
36 | {
37 | setValue(0);
38 | }
39 |
40 | void SingleActor::on()
41 | {
42 | setValue(100);
43 | }
44 |
45 | void SingleActor::on(uint16 msecs)
46 | {
47 | on();
48 | leguino.delay(msecs);
49 | off();
50 | }
51 |
52 | void SingleActor::setSequence(Sequence * sequence)
53 | {
54 | this->sequence = sequence;
55 | sequenceStep = -1;
56 | sequenceStepDuration = 0;
57 | sequenceStepRemaining = 0;
58 | sequenceStepStartValue = requestedValue;
59 | sequenceStepEndValue = requestedValue;
60 | }
61 |
62 | void SingleActor::setValue(int8 value)
63 | {
64 | requestedValue = value;
65 | sequence = NULL;
66 | }
67 |
68 | void SingleActor::setValue(int8 value, uint16 msecs)
69 | {
70 | setValue(value);
71 | leguino.delay(msecs);
72 | off();
73 | }
74 |
75 | void SingleActor::switchDirection(int8 value)
76 | {
77 | int8 offValue = value > 0 ? 1 : 0;
78 | digitalWrite(2, offValue);
79 | digitalWrite(7, offValue);
80 | digitalWrite(9, offValue);
81 | digitalWrite(8, offValue);
82 |
83 | if (value != 0 && backwardPin >= 0)
84 | digitalWrite(backwardPin, !offValue);
85 |
86 | if (value > 0) direction = 1;
87 | if (value < 0) direction = -1;
88 | }
89 |
90 | void SingleActor::update(uint16 timeStep)
91 | {
92 | updateSequence(timeStep);
93 | updateOutputPins(timeStep);
94 | }
95 |
96 | void SingleActor::updateSequence(uint16 timeStep)
97 | {
98 | if (sequence == NULL)
99 | return;
100 |
101 | while (true)
102 | {
103 | if (sequenceStepRemaining <= timeStep)
104 | {
105 | timeStep -= sequenceStepRemaining;
106 | sequenceStepStartValue = sequenceStep < 0 ? requestedValue : sequence->getValue(sequenceStep);
107 | sequenceStep++;
108 |
109 | if (sequenceStep >= sequence->getSteps())
110 | {
111 | if (sequence->isRepeat() && sequence->getSteps() > 0)
112 | {
113 | sequenceStep = 0;
114 | }
115 | else
116 | {
117 | sequence = NULL;
118 | break;
119 | }
120 | }
121 |
122 | sequenceStepEndValue = sequence->getValue(sequenceStep);
123 | if (!sequence->isSmooth())
124 | requestedValue = sequenceStepEndValue;
125 | sequenceStepDuration = sequence->getDuration(sequenceStep);
126 | sequenceStepRemaining = sequenceStepDuration;
127 | }
128 | else
129 | {
130 | sequenceStepRemaining -= timeStep;
131 | break;
132 | }
133 | }
134 |
135 | if (sequence == NULL)
136 | return;
137 |
138 | if (sequence->isSmooth() && sequenceStepDuration > 0)
139 | {
140 | requestedValue = (int8)
141 | (
142 | ((long) sequenceStepEndValue)
143 | -
144 | (
145 | ((long) sequenceStepEndValue - sequenceStepStartValue)
146 | * sequenceStepRemaining
147 | + (sequenceStepDuration / 2)
148 | )
149 | / sequenceStepDuration
150 | );
151 | }
152 | }
153 |
154 | void SingleActor::updateOutputPins(uint16 timeStep)
155 | {
156 | if (leguino.switchingActor == this)
157 | {
158 | if (leguino.remainingSwitchTime <= timeStep)
159 | {
160 | switchDirection(0);
161 | leguino.switchingActor = NULL;
162 | leguino.remainingSwitchTime = 0;
163 | }
164 | else
165 | {
166 | leguino.remainingSwitchTime -= timeStep;
167 | if (leguino.remainingSwitchTime <= _SWITCHTIME_LOW)
168 | switchDirection(0);
169 | }
170 | }
171 |
172 | if (currentValue == requestedValue)
173 | return;
174 |
175 | if (forwardPin >= 0 && backwardPin >= 0
176 | && (requestedValue > 0 && direction <= 0 || requestedValue < 0 && direction >= 0))
177 | {
178 | if (leguino.switchingActor != NULL)
179 | {
180 | digitalWrite(powerPin, 0);
181 | return;
182 | }
183 |
184 | switchDirection(requestedValue);
185 | leguino.switchingActor = this;
186 | leguino.remainingSwitchTime = _SWITCHTIME_LOW
187 | + _SWITCHTIME_HIGH_READY + _SWITCHTIME_HIGH_NOTREADY;
188 | }
189 |
190 | if (leguino.switchingActor == this
191 | && leguino.remainingSwitchTime > _SWITCHTIME_LOW + _SWITCHTIME_HIGH_READY)
192 | return;
193 |
194 | currentValue = requestedValue;
195 |
196 | if (powerPin >= 0)
197 | {
198 | int8 absoluteValue = currentValue < 0 ? -currentValue : currentValue;
199 |
200 | if (absoluteValue <= 0)
201 | digitalWrite(powerPin, 0);
202 | else if (absoluteValue >= 100)
203 | digitalWrite(powerPin, 1);
204 | else
205 | analogWrite(powerPin, (absoluteValue * 255 + 128) / 100);
206 | }
207 | }
208 |
--------------------------------------------------------------------------------
/actor/SingleActor.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_SINGLEACTOR_H
2 | #define __LEGUINO_SINGLEACTOR_H
3 |
4 |
5 | #define _SWITCHTIME_HIGH_NOTREADY 5
6 | #define _SWITCHTIME_HIGH_READY 50
7 | #define _SWITCHTIME_LOW 1
8 |
9 |
10 | /**
11 | * A Leguino actor that requires exactly one output jack (e.g. lights,
12 | * simple motors).
13 | *
14 | * @see Actor
15 | * @see Light
16 | * @see Motor
17 | */
18 | class SingleActor : public Actor
19 | {
20 | public:
21 |
22 | /**
23 | * Creates a new single actor.
24 | * @param output The output the actor is connected to.
25 | * Use the constants OUT_A thru OUT_E.
26 | */
27 | SingleActor(int8 output);
28 |
29 | /**
30 | * Returns the currently set value of the actor, considering instant and
31 | * sequence-controlled values.
32 | * @return The current value from -100 (full reverse), over 0 (off),
33 | * to 100 (full on).
34 | */
35 | uint16 getCurrentValue();
36 |
37 | /**
38 | * Returns the currently active sequence of this actor, if any.
39 | * See Sequence for more details.
40 | * @return The currently active sequence, or NULL, if no sequence is
41 | * active (which is usually the case, e.g. for instant values).
42 | * @see Sequence
43 | */
44 | Sequence * getSequence();
45 |
46 | /**
47 | * Turns off this actor, setting its output to 0, and disabling any
48 | * sequence.
49 | */
50 | void off();
51 |
52 | /**
53 | * Turns on this actor, setting its output to 100, and disabling any
54 | * sequence.
55 | */
56 | void on();
57 |
58 | /**
59 | * Turns on this actor for a given period of time, then turns it off.
60 | * Also, disables any active sequence.
61 | * Note: This method blocks until the delay is over. For
62 | * background value control, use sequences instead.
63 | * @param msecs The number of milli-seconds before turning off.
64 | * @see Sequence
65 | */
66 | void on(uint16 msecs);
67 |
68 | /**
69 | * Starts a sequence on this actor. Any previous sequence is
70 | * automatically disabled.
71 | * See Sequence for more details.
72 | * @param sequence The new sequence to set.
73 | * @see Sequence
74 | */
75 | void setSequence(Sequence * sequence);
76 |
77 | /**
78 | * Sets this actor to a given value and disables any active sequence.
79 | * @param value The new value from -100 (full reverse), over 0 (off),
80 | * to 100 (full on).
81 | */
82 | void setValue(int8 value);
83 |
84 | /**
85 | * Sets this actor to a given value, for a given period of time, then
86 | * turns it off. Also, disables any active sequence.
87 | * Note: This method blocks until the delay is over. For
88 | * background value control, use sequences instead.
89 | * @param value The new value from -100 (full reverse), over 0 (off),
90 | * to 100 (full on).
91 | * @param msecs The number of milli-seconds to hold the new value.
92 | * @see Sequence
93 | */
94 | void setValue(int8 value, uint16 msecs);
95 |
96 | /**
97 | * Internal Leguino method to update the actor.
98 | * Don't call this method from your program.
99 | * @param msecs The number of milli-seconds since the last update.
100 | */
101 | virtual void update(uint16 timeStep);
102 |
103 | protected:
104 |
105 | int8 backwardPin;
106 | int8 currentValue;
107 | int8 direction;
108 | int8 forwardPin;
109 | int8 powerPin;
110 | int8 requestedValue;
111 | Sequence * sequence;
112 | int sequenceStep;
113 | uint16 sequenceStepDuration;
114 | uint16 sequenceStepRemaining;
115 | int8 sequenceStepStartValue;
116 | int8 sequenceStepEndValue;
117 |
118 | void switchDirection(int8 value);
119 | void updateOutputPins(uint16 timeStep);
120 | void updateSequence(uint16 timeStep);
121 | };
122 |
123 |
124 | #endif
125 |
--------------------------------------------------------------------------------
/actor/Tread.cpp:
--------------------------------------------------------------------------------
1 | Tread::Tread(int8 leftOutput, int8 rightOutput)
2 | {
3 | left = new Motor(leftOutput);
4 | right = new Motor(rightOutput);
5 | }
6 |
7 | Tread::~Tread()
8 | {
9 | delete left;
10 | delete right;
11 | }
12 |
13 | uint16 Tread::getCurrentLeftValue()
14 | {
15 | return left->getCurrentValue();
16 | }
17 |
18 | uint16 Tread::getCurrentRightValue()
19 | {
20 | return right->getCurrentValue();
21 | }
22 |
23 | void Tread::move(int8 direction, int8 thrust)
24 | {
25 | if (direction > 0)
26 | {
27 | left->setValue(thrust);
28 | right->setValue((-thrust * (50 - direction) + 25) / 50);
29 | }
30 | else if (direction < 0)
31 | {
32 | left->setValue((thrust * (50 + direction) + 25) / 50);
33 | right->setValue(-thrust);
34 | }
35 | else
36 | {
37 | left->setValue(thrust);
38 | right->setValue(-thrust);
39 | }
40 | }
41 |
42 | void Tread::move(int8 direction, int8 thrust, uint16 msecs)
43 | {
44 | move(direction, thrust);
45 | leguino.delay(msecs);
46 | stop();
47 | }
48 |
49 | void Tread::moveLeft(int8 thrust)
50 | {
51 | move(-50, thrust);
52 | }
53 |
54 | void Tread::moveLeft(int8 thrust, uint16 msecs)
55 | {
56 | move(-50, thrust);
57 | leguino.delay(msecs);
58 | stop();
59 | }
60 |
61 | void Tread::moveRight(int8 thrust)
62 | {
63 | move(50, thrust);
64 | }
65 |
66 | void Tread::moveRight(int8 thrust, uint16 msecs)
67 | {
68 | move(50, thrust);
69 | leguino.delay(msecs);
70 | stop();
71 | }
72 |
73 | void Tread::moveStraight(int8 thrust)
74 | {
75 | move(0, thrust);
76 | }
77 |
78 | void Tread::moveStraight(int8 thrust, uint16 msecs)
79 | {
80 | move(0, thrust);
81 | leguino.delay(msecs);
82 | stop();
83 | }
84 |
85 | void Tread::stop()
86 | {
87 | left->off();
88 | right->off();
89 | }
90 |
91 | void Tread::turnAroundLeft(int8 thrust)
92 | {
93 | move(-100, thrust);
94 | }
95 |
96 | void Tread::turnAroundLeft(int8 thrust, uint16 msecs)
97 | {
98 | move(-100, thrust);
99 | leguino.delay(msecs);
100 | stop();
101 | }
102 |
103 | void Tread::turnAroundRight(int8 thrust)
104 | {
105 | move(100, thrust);
106 | }
107 |
108 | void Tread::turnAroundRight(int8 thrust, uint16 msecs)
109 | {
110 | move(100, thrust);
111 | leguino.delay(msecs);
112 | stop();
113 | }
114 |
115 | void Tread::update(uint16 timeStep)
116 | {
117 | left->update(timeStep);
118 | right->update(timeStep);
119 | }
120 |
--------------------------------------------------------------------------------
/actor/Tread.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_TREAD_H
2 | #define __LEGUINO_TREAD_H
3 |
4 |
5 | /**
6 | * A double-motor tread connected to two Leguino outputs.
7 | * Note that one motor must be attached reverse to the other.
8 | *
9 | * @see Actor
10 | */
11 | class Tread : public Actor
12 | {
13 | public:
14 |
15 | /**
16 | * Creates a new tread.
17 | * @param leftOutput The output the left motor is connected to.
18 | * Use the constants OUT_A thru OUT_E.
19 | * @param rightOutput The output the right motor is connected to.
20 | * Use the constants OUT_A thru OUT_E.
21 | */
22 | Tread(int8 leftOutput, int8 rightOutput);
23 |
24 | /**
25 | * Destroys the tread.
26 | * Don't call this method from your program.
27 | */
28 | virtual ~Tread();
29 |
30 | /**
31 | * Returns the currently set value of the left motor, considering instant
32 | * and sequence-controlled values.
33 | * @return The current value from -100 (full reverse), over 0 (off),
34 | * to 100 (full on).
35 | */
36 | uint16 getCurrentLeftValue();
37 |
38 | /**
39 | * Returns the currently set value of the right motor, considering instant
40 | * and sequence-controlled values.
41 | * @return The current value from -100 (full reverse), over 0 (off),
42 | * to 100 (full on).
43 | */
44 | uint16 getCurrentRightValue();
45 |
46 | /**
47 | * Sets the values of both motors so that the tread it moving towards
48 | * a given direction, using a given thrust.
49 | * @param direction The direction of the tread, from -100 (turn around
50 | * left at the spot), over -50 (left-turn), 0 (straight),
51 | * 50 (right-turn), to 100 (turn around right at the spot), and any
52 | * value in between.
53 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
54 | */
55 | void move(int8 direction, int8 thrust);
56 |
57 | /**
58 | * Sets the values of both motors so that the tread it moving towards
59 | * a given direction, using a given thrust. Then, after a given time,
60 | * stops the tread.
61 | * Note: This method blocks until the delay is over.
62 | * @param direction The direction of the tread, from -100 (turn around
63 | * left at the spot), over -50 (left-turn), 0 (straight),
64 | * 50 (right-turn), to 100 (turn around right at the spot), and any
65 | * value in between.
66 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
67 | * @param msecs The number of milli-seconds to drive before stopping.
68 | */
69 | void move(int8 direction, int8 thrust, uint16 msecs);
70 |
71 | /**
72 | * Sets the values of both motors so that the tread it turning left
73 | * (while still moving), using a given thrust.
74 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
75 | */
76 | void moveLeft(int8 thrust);
77 |
78 | /**
79 | * Sets the values of both motors so that the tread it turning left
80 | * (while still moving), using a given thrust.
81 | * Note: This method blocks until the delay is over.
82 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
83 | * @param msecs The number of milli-seconds to drive before stopping.
84 | */
85 | void moveLeft(int8 thrust, uint16 msecs);
86 |
87 | /**
88 | * Sets the values of both motors so that the tread it turning right
89 | * (while still moving), using a given thrust.
90 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
91 | */
92 | void moveRight(int8 thrust);
93 |
94 | /**
95 | * Sets the values of both motors so that the tread it turning right
96 | * (while still moving), using a given thrust.
97 | * Note: This method blocks until the delay is over.
98 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
99 | * @param msecs The number of milli-seconds to drive before stopping.
100 | */
101 | void moveRight(int8 thrust, uint16 msecs);
102 |
103 | /**
104 | * Sets the values of both motors so that the tread it turning straight,
105 | * using a given thrust.
106 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
107 | */
108 | void moveStraight(int8 thrust);
109 |
110 | /**
111 | * Sets the values of both motors so that the tread it turning straight,
112 | * using a given thrust.
113 | * Note: This method blocks until the delay is over.
114 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
115 | * @param msecs The number of milli-seconds to drive before stopping.
116 | */
117 | void moveStraight(int8 thrust, uint16 msecs);
118 |
119 | /**
120 | * Stops both motors of the tread.
121 | */
122 | void stop();
123 |
124 | /**
125 | * Sets the values of both motors so that the tread it turning around
126 | * left at the spot, using a given thrust.
127 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
128 | */
129 | void turnAroundLeft(int8 thrust);
130 |
131 | /**
132 | * Sets the values of both motors so that the tread it turning around
133 | * left at the spot, using a given thrust.
134 | * Note: This method blocks until the delay is over.
135 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
136 | * @param msecs The number of milli-seconds to drive before stopping.
137 | */
138 | void turnAroundLeft(int8 thrust, uint16 msecs);
139 |
140 | /**
141 | * Sets the values of both motors so that the tread it turning around
142 | * right at the spot, using a given thrust.
143 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
144 | */
145 | void turnAroundRight(int8 thrust);
146 |
147 | /**
148 | * Sets the values of both motors so that the tread it turning around
149 | * right at the spot, using a given thrust.
150 | * Note: This method blocks until the delay is over.
151 | * @param thrust Any value from 0 (stop) to 100 (full thrust).
152 | * @param msecs The number of milli-seconds to drive before stopping.
153 | */
154 | void turnAroundRight(int8 thrust, uint16 msecs);
155 |
156 | /**
157 | * Internal Leguino method to update the actor.
158 | * Don't call this method from your program.
159 | * @param msecs The number of milli-seconds since the last update.
160 | */
161 | virtual void update(uint16 timeStep);
162 |
163 | protected:
164 |
165 | Motor * left;
166 | Motor * right;
167 | };
168 |
169 |
170 | #endif
171 |
--------------------------------------------------------------------------------
/core/LeguinoCore.cpp:
--------------------------------------------------------------------------------
1 | LeguinoCore leguino;
2 |
3 | LeguinoCore::LeguinoCore()
4 | {
5 | switchingActor = NULL;
6 | remainingSwitchTime = 0;
7 | time = 0;
8 | }
9 |
10 | void LeguinoCore::add(Actor * actor)
11 | {
12 | actors.append(actor);
13 | }
14 |
15 | void LeguinoCore::add(Sensor * sensor)
16 | {
17 | sensors.append(sensor);
18 | }
19 |
20 | void LeguinoCore::delay(uint16 msecs)
21 | {
22 | uint32 start = millis();
23 | uint32 end = start + msecs;
24 | uint32 current = millis();
25 | while (current < end && current >= start)
26 | {
27 | update();
28 | current = millis();
29 | }
30 | }
31 |
32 | uint32 LeguinoCore::getTime()
33 | {
34 | return time;
35 | }
36 |
37 | void LeguinoCore::setup(bool waitForPlay)
38 | {
39 | Serial.begin(9600);
40 |
41 | time = millis();
42 |
43 | pinMode(_PIN_PLAY, INPUT);
44 | pinMode(_PIN_LED, OUTPUT);
45 | digitalWrite(_PIN_PLAY, 1);
46 |
47 | int8 pin;
48 | pin = 3; pinMode(pin, OUTPUT); digitalWrite(pin, 0);
49 | pin = 5; pinMode(pin, OUTPUT); digitalWrite(pin, 0);
50 | pin = 6; pinMode(pin, OUTPUT); digitalWrite(pin, 0);
51 | pin = 10; pinMode(pin, OUTPUT); digitalWrite(pin, 0);
52 | pin = 11; pinMode(pin, OUTPUT); digitalWrite(pin, 0);
53 | pin = 2; pinMode(pin, OUTPUT); digitalWrite(pin, 0);
54 | pin = 7; pinMode(pin, OUTPUT); digitalWrite(pin, 0);
55 | pin = 9; pinMode(pin, OUTPUT); digitalWrite(pin, 0);
56 | pin = 8; pinMode(pin, OUTPUT); digitalWrite(pin, 0);
57 |
58 | ::delay(250);
59 |
60 | if (!waitForPlay)
61 | return;
62 |
63 | bool playPressed = false;
64 | while (!playPressed)
65 | {
66 | uint32 start = millis();
67 | digitalWrite(_PIN_LED, HIGH);
68 | while (millis() < start + 50)
69 | if (digitalRead(_PIN_PLAY) == LOW)
70 | {
71 | playPressed = true;
72 | break;
73 | }
74 |
75 | start = millis();
76 | digitalWrite(_PIN_LED, LOW);
77 | while (millis() < start + 950)
78 | if (digitalRead(_PIN_PLAY) == LOW)
79 | {
80 | playPressed = true;
81 | break;
82 | }
83 | }
84 | digitalWrite(_PIN_LED, LOW);
85 |
86 | while (digitalRead(_PIN_PLAY) == LOW);
87 | ::delay(1000);
88 | }
89 |
90 | void LeguinoCore::update()
91 | {
92 | uint32 currentTime = millis();
93 | if (currentTime < time)
94 | time = currentTime;
95 |
96 | uint16 timeStep = currentTime < time ? 0 : (uint16) (currentTime - time);
97 | time = currentTime;
98 |
99 | if (timeStep <= 0)
100 | return;
101 |
102 | for (int i=0; iupdate(timeStep);
104 | for (int i=0; iupdate(timeStep);
106 | }
107 |
--------------------------------------------------------------------------------
/core/LeguinoCore.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_CORE_H
2 | #define __LEGUINO_CORE_H
3 |
4 |
5 | #define NO_WAIT 0
6 | #define WAIT_FOR_PLAY 1
7 |
8 | #define _PIN_PLAY 4
9 | #define _PIN_IR 12
10 | #define _PIN_LED 13
11 |
12 |
13 | extern LeguinoCore leguino;
14 |
15 |
16 | /**
17 | *
18 | * Main Leguino management class. Available as global 'leguino' object.
19 | *
20 | *
21 | *
22 | * Use this object to initialize Leguino in the program's setup function, and
23 | * then to add actors or sensors like this:
24 | * leguino.setup(WAIT_FOR_PLAY);
25 | * leguino.add(drive = new Motor(OUT_A));
26 | * leguino.add(frontLight = new Light(OUT_C));
27 | * where drive
and frontLight
are global variables.
28 | *
29 | */
30 | class LeguinoCore
31 | {
32 | friend SingleActor;
33 |
34 | public:
35 |
36 | /**
37 | * Creates the Leguino core.
38 | * Don't call this method from your program.
39 | */
40 | LeguinoCore();
41 |
42 | /**
43 | * Adds a new actor to Leguino. Call this method in your program's setup
44 | * function after calling #setup(). Store the actor in a global variable.
45 | */
46 | void add(Actor * actor);
47 |
48 | /**
49 | * Adds a new sensor to Leguino. Call this method in your program's setup
50 | * function after calling #setup(). Store the actor in a global variable.
51 | */
52 | void add(Sensor * sensor);
53 |
54 | /**
55 | * Pauses the main program for a given time, while still updating
56 | * sequences and other time-controlled functions.
57 | * @param msecs The number of milli-seconds to pause.
58 | */
59 | void delay(uint16 msecs);
60 |
61 | /**
62 | * Returns the number of milli-seconds since starting Leguino.
63 | * @return The number of milli-seconds since starting Leguino.
64 | */
65 | uint32 getTime();
66 |
67 | /**
68 | * Initializes Leguino. Call this method prior to any other Leguino
69 | * method call, in your setup function.
70 | * @param waitForPlay Whether the main program loop should wait for the
71 | * user pressing the play button. Otherwise, the program starts
72 | * instantly. Use WAIT_FOR_PLAY or NO_WAIT.
73 | */
74 | void setup(bool waitForPlay);
75 |
76 | /**
77 | * Updates Leguino. Call this method regularly (as first line of your
78 | * program's loop function).
79 | */
80 | void update();
81 |
82 | protected:
83 |
84 | ObjectList actors;
85 | ObjectList sensors;
86 | uint32 time;
87 | class Actor * switchingActor;
88 | uint16 remainingSwitchTime;
89 | };
90 |
91 |
92 | #endif
93 |
--------------------------------------------------------------------------------
/core/LeguinoList.h:
--------------------------------------------------------------------------------
1 | #ifndef __LIGHT_LIST_H
2 | #define __LIGHT_LIST_H
3 |
4 |
5 | #include "LeguinoPanic.h"
6 |
7 |
8 | template class ValueList
9 | {
10 | public:
11 |
12 | ValueList();
13 | virtual ~ValueList();
14 | void append(ELEMENTTYPE element);
15 | ELEMENTTYPE get(int no) const;
16 | inline int getCount() const;
17 | ELEMENTTYPE getFirst() const;
18 | ELEMENTTYPE getLast() const;
19 | void insert(int no, ELEMENTTYPE element);
20 | inline bool isEmpty() const;
21 | inline void prepend(ELEMENTTYPE element);
22 | ELEMENTTYPE set(int no, ELEMENTTYPE newElement);
23 | void unlinkAll();
24 | ELEMENTTYPE unlinkAt(int no);
25 | ELEMENTTYPE unlinkElement(ELEMENTTYPE element);
26 | bool unlinkRange(int from, int count);
27 | inline ELEMENTTYPE unlinkFirst();
28 | ELEMENTTYPE unlinkLast();
29 |
30 | protected:
31 |
32 | int count;
33 | ELEMENTTYPE * elements;
34 | int size;
35 |
36 | void checkSize(int newSize);
37 | };
38 |
39 | template class ObjectList : public ValueList
40 | {
41 | public:
42 |
43 | virtual ~ObjectList();
44 | void deleteAll();
45 | bool deleteAt(int no);
46 | bool deleteElement(ELEMENTTYPE element);
47 | inline bool deleteFirst();
48 | bool deleteLast();
49 | bool deleteRange(int from, int count);
50 | };
51 |
52 |
53 | template ValueList::ValueList()
54 | {
55 | count = 0;
56 | elements = NULL;
57 | size = 0;
58 |
59 | checkSize(1);
60 | }
61 |
62 | template ValueList::~ValueList()
63 | {
64 | unlinkAll();
65 | if (elements) {delete elements; elements = NULL;}
66 | }
67 |
68 | template void ValueList::append(ELEMENTTYPE element)
69 | {
70 | checkSize(count + 1);
71 | elements[count++] = element;
72 | }
73 |
74 | template void ValueList::checkSize(int newSize)
75 | {
76 | if (newSize <= size)
77 | return;
78 |
79 | size = newSize + 3;
80 |
81 | ELEMENTTYPE * newElements;
82 | if ((newElements = new ELEMENTTYPE[size]) == NULL)
83 | panic();
84 | memset(newElements, 0, sizeof(ELEMENTTYPE) * size);
85 |
86 | if (elements)
87 | {
88 | memmove(newElements, elements, sizeof(ELEMENTTYPE) * count);
89 | delete elements;
90 | }
91 |
92 | elements = newElements;
93 | }
94 |
95 | template ELEMENTTYPE ValueList::get(int no) const
96 | {
97 | if (no < 0 || no >= count)
98 | return NULL;
99 |
100 | return elements[no];
101 | }
102 |
103 | template inline int ValueList::getCount() const
104 | {
105 | return count;
106 | }
107 |
108 | template ELEMENTTYPE ValueList::getFirst() const
109 | {
110 | if (count <= 0)
111 | return NULL;
112 |
113 | return elements[0];
114 | }
115 |
116 | template ELEMENTTYPE ValueList::getLast() const
117 | {
118 | if (count <= 0)
119 | return NULL;
120 |
121 | return elements[count-1];
122 | }
123 |
124 | template void ValueList::insert(int no, ELEMENTTYPE element)
125 | {
126 | if (no < 0 || no > count)
127 | return;
128 |
129 | checkSize(count + 1);
130 |
131 | memmove(&elements[no+1], &elements[no], sizeof(ELEMENTTYPE) * (count - no));
132 | count++;
133 | elements[no] = element;
134 | }
135 |
136 | template inline bool ValueList::isEmpty() const
137 | {
138 | return count <= 0;
139 | }
140 |
141 | template inline void ValueList::prepend(ELEMENTTYPE element)
142 | {
143 | insert(element, 0);
144 | }
145 |
146 | template ELEMENTTYPE ValueList::set(int no, ELEMENTTYPE newElement)
147 | {
148 | if (no < 0)
149 | return NULL;
150 |
151 | checkSize(no + 1);
152 |
153 | ELEMENTTYPE oldElement = elements[no];
154 | elements[no] = newElement;
155 | return oldElement;
156 | }
157 |
158 | template void ValueList::unlinkAll()
159 | {
160 | checkSize(0);
161 | count = 0;
162 | }
163 |
164 | template ELEMENTTYPE ValueList::unlinkAt(int no)
165 | {
166 | if (no < 0 || no >= count)
167 | return NULL;
168 |
169 | ELEMENTTYPE oldElement = elements[no];
170 | memmove(&elements[no], &elements[no+1], sizeof(ELEMENTTYPE) * (count - no - 1));
171 |
172 | checkSize(count - 1);
173 | count--;
174 |
175 | return oldElement;
176 | }
177 |
178 | template ELEMENTTYPE ValueList::unlinkElement(ELEMENTTYPE element)
179 | {
180 | for (int i=0; i bool ValueList::unlinkRange(int from, int count)
188 | {
189 | if (from < 0 || count < 0 || from + count > this->count)
190 | return false;
191 |
192 | memmove(&elements[from], &elements[from + count], sizeof(ELEMENTTYPE) * (this->count - from - count));
193 |
194 | checkSize(this->count - count);
195 | this->count -= count;
196 |
197 | return true;
198 | }
199 |
200 | template inline ELEMENTTYPE ValueList::unlinkFirst()
201 | {
202 | return unlinkAt(0);
203 | }
204 |
205 | template ELEMENTTYPE ValueList::unlinkLast()
206 | {
207 | if (count <= 0)
208 | return NULL;
209 |
210 | ELEMENTTYPE oldElement = elements[count - 1];
211 |
212 | checkSize(count - 1);
213 | count--;
214 |
215 | return oldElement;
216 | }
217 |
218 |
219 | template ObjectList::~ObjectList()
220 | {
221 | deleteAll();
222 | }
223 |
224 | template void ObjectList::deleteAll()
225 | {
226 | for (int i=0; icount; i++)
227 | delete this->elements[i];
228 |
229 | this->checkSize(0);
230 | this->count = 0;
231 | }
232 |
233 | template bool ObjectList::deleteAt(int no)
234 | {
235 | ELEMENTTYPE deleteElement;
236 | if ((deleteElement = ValueList::unlinkAt(no)) != NULL)
237 | {
238 | delete (ELEMENTTYPE) deleteElement;
239 | return true;
240 | }
241 | else
242 | return false;
243 | }
244 |
245 | template bool ObjectList::deleteElement(ELEMENTTYPE element)
246 | {
247 | ELEMENTTYPE deleteElement;
248 | if ((deleteElement = ValueList::unlinkElement(element)) != NULL)
249 | {
250 | delete (ELEMENTTYPE) deleteElement;
251 | return true;
252 | }
253 | else
254 | return false;
255 | }
256 |
257 | template inline bool ObjectList::deleteFirst()
258 | {
259 | return deleteAt(0);
260 | }
261 |
262 | template bool ObjectList::deleteLast()
263 | {
264 | ELEMENTTYPE deleteElement;
265 |
266 | if ((deleteElement = this->unlinkLast()) != NULL)
267 | {
268 | delete (ELEMENTTYPE) deleteElement;
269 | return true;
270 | }
271 | else
272 | return false;
273 | }
274 |
275 | template bool ObjectList::deleteRange(int from, int count)
276 | {
277 | if (from < 0 || count < 0 || from + count > this->count)
278 | return false;
279 |
280 | for (int i=from; ielements[i];
282 |
283 | memmove(&this->elements[from], &this->elements[from + count],
284 | sizeof(ELEMENTTYPE) * (this->count - from - count));
285 | this->checkSize(this->count - count);
286 |
287 | this->count -= count;
288 |
289 | return true;
290 | }
291 |
292 |
293 | #endif
294 |
--------------------------------------------------------------------------------
/core/LeguinoPanic.h:
--------------------------------------------------------------------------------
1 | #ifndef __LIGHT_PANIC_H
2 | #define __LIGHT_PANIC_H
3 |
4 |
5 | inline void panic()
6 | {
7 | // Don't use any variables, we don't have any RAM anymore
8 |
9 | digitalWrite(2, 0);
10 | digitalWrite(3, 0);
11 | digitalWrite(4, 0);
12 | digitalWrite(5, 0);
13 | digitalWrite(6, 0);
14 | digitalWrite(7, 0);
15 | digitalWrite(8, 0);
16 | digitalWrite(9, 0);
17 | digitalWrite(10, 0);
18 | digitalWrite(11, 0);
19 | digitalWrite(12, 0);
20 |
21 | pinMode(13, OUTPUT);
22 | while (true)
23 | {
24 | digitalWrite(13, 1); delay(200); digitalWrite(13, 0); delay(200);
25 | digitalWrite(13, 1); delay(200); digitalWrite(13, 0); delay(200);
26 | digitalWrite(13, 1); delay(200); digitalWrite(13, 0); delay(200);
27 |
28 | delay(800);
29 | }
30 | }
31 |
32 |
33 | #endif
34 |
--------------------------------------------------------------------------------
/core/LeguinoTypes.h:
--------------------------------------------------------------------------------
1 | #ifndef __LIGHT_TYPES_H
2 | #define __LIGHT_TYPES_H
3 |
4 |
5 | typedef signed char int8;
6 | typedef unsigned char uint8;
7 | typedef signed short int int16;
8 | typedef unsigned short int uint16;
9 | typedef signed long int int32;
10 | typedef unsigned long int uint32;
11 |
12 | #define NULL 0
13 |
14 |
15 | #endif
16 |
--------------------------------------------------------------------------------
/docs/Leguino-Kurzanleitung-DE.doc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/Leguino-Kurzanleitung-DE.doc
--------------------------------------------------------------------------------
/docs/Power-Functions-assignment.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/Power-Functions-assignment.jpg
--------------------------------------------------------------------------------
/docs/TQ2L25-bistable-relay-assignment.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/TQ2L25-bistable-relay-assignment.png
--------------------------------------------------------------------------------
/docs/ideas/Robotik-für-Kinder.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/ideas/Robotik-für-Kinder.jpg
--------------------------------------------------------------------------------
/docs/parts.md:
--------------------------------------------------------------------------------
1 | # Electronic parts
2 |
3 | ## Leguino shield prototype
4 |
5 | * Prototype Shield
6 | * Header Pin set
7 | * 5x 100k resistor
8 | * 3x bistable Print relay TQ2L25, 1A, 2x switch UK Panasonic bistable 5V 2x switch, 1A 110V DC (125V AV) 30W (62,5 VA) ([Conrad #505062](http://www.conrad.de/ce/de/product/505062))
9 | * 5x FQP30N06L MOSFET N-Channel
10 | * Switching regulator, output 5V/1A, input 9V (e.g. [EzSBC PSU2-5](https://www.ezsbc.com/index.php/psu2-5.html) or [Conrad #167805, W78-5V0](http://www.conrad.de/ce/de/product/167805))
11 | * Diode 1N4001 ([Conrad #162213](http://www.conrad.de/ce/de/product/162213))
12 | * Play button MS-402/SW
13 | * Reset button MS-402/RT
14 | * 2x Black female railroad plug ([Conrad #731927](http://www.conrad.de/ce/de/product/731927))
15 | * 2x Red female railroad plug ([Conrad #731919](http://www.conrad.de/ce/de/product/731919))
16 | * 6x Yellow female railroad plug ([Conrad #731935](http://www.conrad.de/ce/de/product/731935))
17 | * Several black male railroad plugs ([Conrad #730572](http://www.conrad.de/ce/de/product/730572))
18 | * Several red male railroad plugs ([Conrad #730564](http://www.conrad.de/ce/de/product/730564))
19 | * Several yellow male railroad plugs ([Conrad #730580](http://www.conrad.de/ce/de/product/730580))
20 |
21 | ## Sensors
22 |
23 | * Proximity (distance) sensor ([Conrad #504591](http://www.conrad.de/ce/de/product/504591) or [Reichelt #GP2-1080](http://www.reichelt.de/Sensoren/GP2-1080/3/index.html?&ACTION=3&LA=446&ARTICLE=110602&GROUPID=3190&artnr=GP2-1080&SEARCH=GP2-1080))
24 |
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-1.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-1.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-10.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-10.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-11.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-11.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-12.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-12.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-13.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-13.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-14.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-14.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-15.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-15.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-16.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-16.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-17.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-17.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-18.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-18.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-19.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-19.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-2.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-2.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-20.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-20.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-21.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-21.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-22.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-22.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-23.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-23.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-24.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-24.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-25.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-25.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-26.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-26.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-27.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-27.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-3.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-3.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-4.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-4.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-5.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-5.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-6.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-6.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-7.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-7.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-8.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-8.jpg
--------------------------------------------------------------------------------
/docs/photos/Leguino-Hardware-9.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/docs/photos/Leguino-Hardware-9.jpg
--------------------------------------------------------------------------------
/eagle/.gitignore:
--------------------------------------------------------------------------------
1 | *.b#*
2 | *.s#*
3 | *.job
4 |
--------------------------------------------------------------------------------
/eagle/LeguinoUno-Gerber.zip:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/TheReincarnator/leguino/f4d38c7f46ef3e8fd44f3fd58eb1eeb8b4f6f690/eagle/LeguinoUno-Gerber.zip
--------------------------------------------------------------------------------
/eagle/eagle.epf:
--------------------------------------------------------------------------------
1 | [Eagle]
2 | Version="08 05 00"
3 | Platform="Windows"
4 | Globals="Globals"
5 | Desktop="Desktop"
6 |
7 | [Globals]
8 | AutoSaveProject=1
9 | UsedLibraryUrn="urn:adsk.eagle:library:79"
10 | UsedLibraryUrn="urn:adsk.eagle:library:88"
11 | UsedLibraryUrn="urn:adsk.eagle:library:178"
12 | UsedLibraryUrn="urn:adsk.eagle:library:179"
13 | UsedLibraryUrn="urn:adsk.eagle:library:180"
14 | UsedLibraryUrn="urn:adsk.eagle:library:181"
15 | UsedLibraryUrn="urn:adsk.eagle:library:182"
16 | UsedLibraryUrn="urn:adsk.eagle:library:183"
17 | UsedLibraryUrn="urn:adsk.eagle:library:184"
18 | UsedLibraryUrn="urn:adsk.eagle:library:185"
19 | UsedLibraryUrn="urn:adsk.eagle:library:186"
20 | UsedLibraryUrn="urn:adsk.eagle:library:187"
21 | UsedLibraryUrn="urn:adsk.eagle:library:89"
22 | UsedLibraryUrn="urn:adsk.eagle:library:188"
23 | UsedLibraryUrn="urn:adsk.eagle:library:189"
24 | UsedLibraryUrn="urn:adsk.eagle:library:190"
25 | UsedLibraryUrn="urn:adsk.eagle:library:191"
26 | UsedLibraryUrn="urn:adsk.eagle:library:192"
27 | UsedLibraryUrn="urn:adsk.eagle:library:193"
28 | UsedLibraryUrn="urn:adsk.eagle:library:194"
29 | UsedLibraryUrn="urn:adsk.eagle:library:195"
30 | UsedLibraryUrn="urn:adsk.eagle:library:196"
31 | UsedLibraryUrn="urn:adsk.eagle:library:197"
32 | UsedLibraryUrn="urn:adsk.eagle:library:90"
33 | UsedLibraryUrn="urn:adsk.eagle:library:198"
34 | UsedLibraryUrn="urn:adsk.eagle:library:199"
35 | UsedLibraryUrn="urn:adsk.eagle:library:200"
36 | UsedLibraryUrn="urn:adsk.eagle:library:201"
37 | UsedLibraryUrn="urn:adsk.eagle:library:202"
38 | UsedLibraryUrn="urn:adsk.eagle:library:203"
39 | UsedLibraryUrn="urn:adsk.eagle:library:204"
40 | UsedLibraryUrn="urn:adsk.eagle:library:205"
41 | UsedLibraryUrn="urn:adsk.eagle:library:206"
42 | UsedLibraryUrn="urn:adsk.eagle:library:207"
43 | UsedLibraryUrn="urn:adsk.eagle:library:91"
44 | UsedLibraryUrn="urn:adsk.eagle:library:208"
45 | UsedLibraryUrn="urn:adsk.eagle:library:209"
46 | UsedLibraryUrn="urn:adsk.eagle:library:210"
47 | UsedLibraryUrn="urn:adsk.eagle:library:211"
48 | UsedLibraryUrn="urn:adsk.eagle:library:212"
49 | UsedLibraryUrn="urn:adsk.eagle:library:213"
50 | UsedLibraryUrn="urn:adsk.eagle:library:214"
51 | UsedLibraryUrn="urn:adsk.eagle:library:215"
52 | UsedLibraryUrn="urn:adsk.eagle:library:216"
53 | UsedLibraryUrn="urn:adsk.eagle:library:217"
54 | UsedLibraryUrn="urn:adsk.eagle:library:92"
55 | UsedLibraryUrn="urn:adsk.eagle:library:218"
56 | UsedLibraryUrn="urn:adsk.eagle:library:219"
57 | UsedLibraryUrn="urn:adsk.eagle:library:220"
58 | UsedLibraryUrn="urn:adsk.eagle:library:221"
59 | UsedLibraryUrn="urn:adsk.eagle:library:222"
60 | UsedLibraryUrn="urn:adsk.eagle:library:223"
61 | UsedLibraryUrn="urn:adsk.eagle:library:224"
62 | UsedLibraryUrn="urn:adsk.eagle:library:225"
63 | UsedLibraryUrn="urn:adsk.eagle:library:226"
64 | UsedLibraryUrn="urn:adsk.eagle:library:227"
65 | UsedLibraryUrn="urn:adsk.eagle:library:93"
66 | UsedLibraryUrn="urn:adsk.eagle:library:228"
67 | UsedLibraryUrn="urn:adsk.eagle:library:229"
68 | UsedLibraryUrn="urn:adsk.eagle:library:230"
69 | UsedLibraryUrn="urn:adsk.eagle:library:231"
70 | UsedLibraryUrn="urn:adsk.eagle:library:232"
71 | UsedLibraryUrn="urn:adsk.eagle:library:233"
72 | UsedLibraryUrn="urn:adsk.eagle:library:234"
73 | UsedLibraryUrn="urn:adsk.eagle:library:235"
74 | UsedLibraryUrn="urn:adsk.eagle:library:236"
75 | UsedLibraryUrn="urn:adsk.eagle:library:237"
76 | UsedLibraryUrn="urn:adsk.eagle:library:94"
77 | UsedLibraryUrn="urn:adsk.eagle:library:238"
78 | UsedLibraryUrn="urn:adsk.eagle:library:239"
79 | UsedLibraryUrn="urn:adsk.eagle:library:240"
80 | UsedLibraryUrn="urn:adsk.eagle:library:241"
81 | UsedLibraryUrn="urn:adsk.eagle:library:242"
82 | UsedLibraryUrn="urn:adsk.eagle:library:243"
83 | UsedLibraryUrn="urn:adsk.eagle:library:244"
84 | UsedLibraryUrn="urn:adsk.eagle:library:245"
85 | UsedLibraryUrn="urn:adsk.eagle:library:246"
86 | UsedLibraryUrn="urn:adsk.eagle:library:247"
87 | UsedLibraryUrn="urn:adsk.eagle:library:95"
88 | UsedLibraryUrn="urn:adsk.eagle:library:248"
89 | UsedLibraryUrn="urn:adsk.eagle:library:249"
90 | UsedLibraryUrn="urn:adsk.eagle:library:250"
91 | UsedLibraryUrn="urn:adsk.eagle:library:251"
92 | UsedLibraryUrn="urn:adsk.eagle:library:252"
93 | UsedLibraryUrn="urn:adsk.eagle:library:253"
94 | UsedLibraryUrn="urn:adsk.eagle:library:254"
95 | UsedLibraryUrn="urn:adsk.eagle:library:255"
96 | UsedLibraryUrn="urn:adsk.eagle:library:256"
97 | UsedLibraryUrn="urn:adsk.eagle:library:257"
98 | UsedLibraryUrn="urn:adsk.eagle:library:96"
99 | UsedLibraryUrn="urn:adsk.eagle:library:258"
100 | UsedLibraryUrn="urn:adsk.eagle:library:259"
101 | UsedLibraryUrn="urn:adsk.eagle:library:260"
102 | UsedLibraryUrn="urn:adsk.eagle:library:261"
103 | UsedLibraryUrn="urn:adsk.eagle:library:262"
104 | UsedLibraryUrn="urn:adsk.eagle:library:263"
105 | UsedLibraryUrn="urn:adsk.eagle:library:264"
106 | UsedLibraryUrn="urn:adsk.eagle:library:265"
107 | UsedLibraryUrn="urn:adsk.eagle:library:266"
108 | UsedLibraryUrn="urn:adsk.eagle:library:267"
109 | UsedLibraryUrn="urn:adsk.eagle:library:97"
110 | UsedLibraryUrn="urn:adsk.eagle:library:268"
111 | UsedLibraryUrn="urn:adsk.eagle:library:269"
112 | UsedLibraryUrn="urn:adsk.eagle:library:270"
113 | UsedLibraryUrn="urn:adsk.eagle:library:271"
114 | UsedLibraryUrn="urn:adsk.eagle:library:272"
115 | UsedLibraryUrn="urn:adsk.eagle:library:273"
116 | UsedLibraryUrn="urn:adsk.eagle:library:274"
117 | UsedLibraryUrn="urn:adsk.eagle:library:275"
118 | UsedLibraryUrn="urn:adsk.eagle:library:276"
119 | UsedLibraryUrn="urn:adsk.eagle:library:277"
120 | UsedLibraryUrn="urn:adsk.eagle:library:80"
121 | UsedLibraryUrn="urn:adsk.eagle:library:98"
122 | UsedLibraryUrn="urn:adsk.eagle:library:278"
123 | UsedLibraryUrn="urn:adsk.eagle:library:279"
124 | UsedLibraryUrn="urn:adsk.eagle:library:280"
125 | UsedLibraryUrn="urn:adsk.eagle:library:281"
126 | UsedLibraryUrn="urn:adsk.eagle:library:282"
127 | UsedLibraryUrn="urn:adsk.eagle:library:283"
128 | UsedLibraryUrn="urn:adsk.eagle:library:284"
129 | UsedLibraryUrn="urn:adsk.eagle:library:285"
130 | UsedLibraryUrn="urn:adsk.eagle:library:286"
131 | UsedLibraryUrn="urn:adsk.eagle:library:287"
132 | UsedLibraryUrn="urn:adsk.eagle:library:99"
133 | UsedLibraryUrn="urn:adsk.eagle:library:288"
134 | UsedLibraryUrn="urn:adsk.eagle:library:289"
135 | UsedLibraryUrn="urn:adsk.eagle:library:290"
136 | UsedLibraryUrn="urn:adsk.eagle:library:291"
137 | UsedLibraryUrn="urn:adsk.eagle:library:292"
138 | UsedLibraryUrn="urn:adsk.eagle:library:293"
139 | UsedLibraryUrn="urn:adsk.eagle:library:294"
140 | UsedLibraryUrn="urn:adsk.eagle:library:295"
141 | UsedLibraryUrn="urn:adsk.eagle:library:296"
142 | UsedLibraryUrn="urn:adsk.eagle:library:297"
143 | UsedLibraryUrn="urn:adsk.eagle:library:100"
144 | UsedLibraryUrn="urn:adsk.eagle:library:298"
145 | UsedLibraryUrn="urn:adsk.eagle:library:299"
146 | UsedLibraryUrn="urn:adsk.eagle:library:300"
147 | UsedLibraryUrn="urn:adsk.eagle:library:301"
148 | UsedLibraryUrn="urn:adsk.eagle:library:302"
149 | UsedLibraryUrn="urn:adsk.eagle:library:303"
150 | UsedLibraryUrn="urn:adsk.eagle:library:304"
151 | UsedLibraryUrn="urn:adsk.eagle:library:305"
152 | UsedLibraryUrn="urn:adsk.eagle:library:306"
153 | UsedLibraryUrn="urn:adsk.eagle:library:307"
154 | UsedLibraryUrn="urn:adsk.eagle:library:101"
155 | UsedLibraryUrn="urn:adsk.eagle:library:308"
156 | UsedLibraryUrn="urn:adsk.eagle:library:309"
157 | UsedLibraryUrn="urn:adsk.eagle:library:310"
158 | UsedLibraryUrn="urn:adsk.eagle:library:311"
159 | UsedLibraryUrn="urn:adsk.eagle:library:312"
160 | UsedLibraryUrn="urn:adsk.eagle:library:313"
161 | UsedLibraryUrn="urn:adsk.eagle:library:314"
162 | UsedLibraryUrn="urn:adsk.eagle:library:315"
163 | UsedLibraryUrn="urn:adsk.eagle:library:316"
164 | UsedLibraryUrn="urn:adsk.eagle:library:317"
165 | UsedLibraryUrn="urn:adsk.eagle:library:102"
166 | UsedLibraryUrn="urn:adsk.eagle:library:318"
167 | UsedLibraryUrn="urn:adsk.eagle:library:319"
168 | UsedLibraryUrn="urn:adsk.eagle:library:320"
169 | UsedLibraryUrn="urn:adsk.eagle:library:321"
170 | UsedLibraryUrn="urn:adsk.eagle:library:322"
171 | UsedLibraryUrn="urn:adsk.eagle:library:323"
172 | UsedLibraryUrn="urn:adsk.eagle:library:324"
173 | UsedLibraryUrn="urn:adsk.eagle:library:325"
174 | UsedLibraryUrn="urn:adsk.eagle:library:326"
175 | UsedLibraryUrn="urn:adsk.eagle:library:327"
176 | UsedLibraryUrn="urn:adsk.eagle:library:103"
177 | UsedLibraryUrn="urn:adsk.eagle:library:328"
178 | UsedLibraryUrn="urn:adsk.eagle:library:329"
179 | UsedLibraryUrn="urn:adsk.eagle:library:330"
180 | UsedLibraryUrn="urn:adsk.eagle:library:331"
181 | UsedLibraryUrn="urn:adsk.eagle:library:332"
182 | UsedLibraryUrn="urn:adsk.eagle:library:333"
183 | UsedLibraryUrn="urn:adsk.eagle:library:334"
184 | UsedLibraryUrn="urn:adsk.eagle:library:335"
185 | UsedLibraryUrn="urn:adsk.eagle:library:336"
186 | UsedLibraryUrn="urn:adsk.eagle:library:337"
187 | UsedLibraryUrn="urn:adsk.eagle:library:104"
188 | UsedLibraryUrn="urn:adsk.eagle:library:338"
189 | UsedLibraryUrn="urn:adsk.eagle:library:339"
190 | UsedLibraryUrn="urn:adsk.eagle:library:340"
191 | UsedLibraryUrn="urn:adsk.eagle:library:341"
192 | UsedLibraryUrn="urn:adsk.eagle:library:342"
193 | UsedLibraryUrn="urn:adsk.eagle:library:343"
194 | UsedLibraryUrn="urn:adsk.eagle:library:344"
195 | UsedLibraryUrn="urn:adsk.eagle:library:345"
196 | UsedLibraryUrn="urn:adsk.eagle:library:346"
197 | UsedLibraryUrn="urn:adsk.eagle:library:347"
198 | UsedLibraryUrn="urn:adsk.eagle:library:105"
199 | UsedLibraryUrn="urn:adsk.eagle:library:348"
200 | UsedLibraryUrn="urn:adsk.eagle:library:349"
201 | UsedLibraryUrn="urn:adsk.eagle:library:350"
202 | UsedLibraryUrn="urn:adsk.eagle:library:351"
203 | UsedLibraryUrn="urn:adsk.eagle:library:352"
204 | UsedLibraryUrn="urn:adsk.eagle:library:353"
205 | UsedLibraryUrn="urn:adsk.eagle:library:354"
206 | UsedLibraryUrn="urn:adsk.eagle:library:355"
207 | UsedLibraryUrn="urn:adsk.eagle:library:356"
208 | UsedLibraryUrn="urn:adsk.eagle:library:357"
209 | UsedLibraryUrn="urn:adsk.eagle:library:106"
210 | UsedLibraryUrn="urn:adsk.eagle:library:358"
211 | UsedLibraryUrn="urn:adsk.eagle:library:359"
212 | UsedLibraryUrn="urn:adsk.eagle:library:360"
213 | UsedLibraryUrn="urn:adsk.eagle:library:361"
214 | UsedLibraryUrn="urn:adsk.eagle:library:362"
215 | UsedLibraryUrn="urn:adsk.eagle:library:363"
216 | UsedLibraryUrn="urn:adsk.eagle:library:364"
217 | UsedLibraryUrn="urn:adsk.eagle:library:365"
218 | UsedLibraryUrn="urn:adsk.eagle:library:366"
219 | UsedLibraryUrn="urn:adsk.eagle:library:367"
220 | UsedLibraryUrn="urn:adsk.eagle:library:107"
221 | UsedLibraryUrn="urn:adsk.eagle:library:368"
222 | UsedLibraryUrn="urn:adsk.eagle:library:369"
223 | UsedLibraryUrn="urn:adsk.eagle:library:370"
224 | UsedLibraryUrn="urn:adsk.eagle:library:371"
225 | UsedLibraryUrn="urn:adsk.eagle:library:372"
226 | UsedLibraryUrn="urn:adsk.eagle:library:373"
227 | UsedLibraryUrn="urn:adsk.eagle:library:374"
228 | UsedLibraryUrn="urn:adsk.eagle:library:375"
229 | UsedLibraryUrn="urn:adsk.eagle:library:376"
230 | UsedLibraryUrn="urn:adsk.eagle:library:377"
231 | UsedLibraryUrn="urn:adsk.eagle:library:81"
232 | UsedLibraryUrn="urn:adsk.eagle:library:108"
233 | UsedLibraryUrn="urn:adsk.eagle:library:378"
234 | UsedLibraryUrn="urn:adsk.eagle:library:379"
235 | UsedLibraryUrn="urn:adsk.eagle:library:380"
236 | UsedLibraryUrn="urn:adsk.eagle:library:381"
237 | UsedLibraryUrn="urn:adsk.eagle:library:382"
238 | UsedLibraryUrn="urn:adsk.eagle:library:383"
239 | UsedLibraryUrn="urn:adsk.eagle:library:384"
240 | UsedLibraryUrn="urn:adsk.eagle:library:385"
241 | UsedLibraryUrn="urn:adsk.eagle:library:386"
242 | UsedLibraryUrn="urn:adsk.eagle:library:387"
243 | UsedLibraryUrn="urn:adsk.eagle:library:109"
244 | UsedLibraryUrn="urn:adsk.eagle:library:388"
245 | UsedLibraryUrn="urn:adsk.eagle:library:389"
246 | UsedLibraryUrn="urn:adsk.eagle:library:390"
247 | UsedLibraryUrn="urn:adsk.eagle:library:391"
248 | UsedLibraryUrn="urn:adsk.eagle:library:392"
249 | UsedLibraryUrn="urn:adsk.eagle:library:393"
250 | UsedLibraryUrn="urn:adsk.eagle:library:394"
251 | UsedLibraryUrn="urn:adsk.eagle:library:395"
252 | UsedLibraryUrn="urn:adsk.eagle:library:396"
253 | UsedLibraryUrn="urn:adsk.eagle:library:397"
254 | UsedLibraryUrn="urn:adsk.eagle:library:110"
255 | UsedLibraryUrn="urn:adsk.eagle:library:398"
256 | UsedLibraryUrn="urn:adsk.eagle:library:399"
257 | UsedLibraryUrn="urn:adsk.eagle:library:400"
258 | UsedLibraryUrn="urn:adsk.eagle:library:401"
259 | UsedLibraryUrn="urn:adsk.eagle:library:402"
260 | UsedLibraryUrn="urn:adsk.eagle:library:403"
261 | UsedLibraryUrn="urn:adsk.eagle:library:404"
262 | UsedLibraryUrn="urn:adsk.eagle:library:405"
263 | UsedLibraryUrn="urn:adsk.eagle:library:406"
264 | UsedLibraryUrn="urn:adsk.eagle:library:407"
265 | UsedLibraryUrn="urn:adsk.eagle:library:111"
266 | UsedLibraryUrn="urn:adsk.eagle:library:408"
267 | UsedLibraryUrn="urn:adsk.eagle:library:409"
268 | UsedLibraryUrn="urn:adsk.eagle:library:410"
269 | UsedLibraryUrn="urn:adsk.eagle:library:411"
270 | UsedLibraryUrn="urn:adsk.eagle:library:412"
271 | UsedLibraryUrn="urn:adsk.eagle:library:413"
272 | UsedLibraryUrn="urn:adsk.eagle:library:414"
273 | UsedLibraryUrn="urn:adsk.eagle:library:415"
274 | UsedLibraryUrn="urn:adsk.eagle:library:416"
275 | UsedLibraryUrn="urn:adsk.eagle:library:417"
276 | UsedLibraryUrn="urn:adsk.eagle:library:112"
277 | UsedLibraryUrn="urn:adsk.eagle:library:418"
278 | UsedLibraryUrn="urn:adsk.eagle:library:419"
279 | UsedLibraryUrn="urn:adsk.eagle:library:527439"
280 | UsedLibraryUrn="urn:adsk.eagle:library:420"
281 | UsedLibraryUrn="urn:adsk.eagle:library:510"
282 | UsedLibraryUrn="urn:adsk.eagle:library:509"
283 | UsedLibraryUrn="urn:adsk.eagle:library:517"
284 | UsedLibraryUrn="urn:adsk.eagle:library:513"
285 | UsedLibraryUrn="urn:adsk.eagle:library:520"
286 | UsedLibraryUrn="urn:adsk.eagle:library:524"
287 | UsedLibraryUrn="urn:adsk.eagle:library:113"
288 | UsedLibraryUrn="urn:adsk.eagle:library:523"
289 | UsedLibraryUrn="urn:adsk.eagle:library:526"
290 | UsedLibraryUrn="urn:adsk.eagle:library:525"
291 | UsedLibraryUrn="urn:adsk.eagle:library:527"
292 | UsedLibraryUrn="urn:adsk.eagle:library:528"
293 | UsedLibraryUrn="urn:adsk.eagle:library:529"
294 | UsedLibraryUrn="urn:adsk.eagle:library:530"
295 | UsedLibraryUrn="urn:adsk.eagle:library:532"
296 | UsedLibraryUrn="urn:adsk.eagle:library:514"
297 | UsedLibraryUrn="urn:adsk.eagle:library:519"
298 | UsedLibraryUrn="urn:adsk.eagle:library:114"
299 | UsedLibraryUrn="urn:adsk.eagle:library:521"
300 | UsedLibraryUrn="urn:adsk.eagle:library:522"
301 | UsedLibraryUrn="urn:adsk.eagle:library:970892"
302 | UsedLibraryUrn="urn:adsk.eagle:library:220454"
303 | UsedLibraryUrn="urn:adsk.eagle:library:506"
304 | UsedLibraryUrn="urn:adsk.eagle:library:169009"
305 | UsedLibraryUrn="urn:adsk.eagle:library:464"
306 | UsedLibraryUrn="urn:adsk.eagle:library:478"
307 | UsedLibraryUrn="urn:adsk.eagle:library:466"
308 | UsedLibraryUrn="urn:adsk.eagle:library:467"
309 | UsedLibraryUrn="urn:adsk.eagle:library:115"
310 | UsedLibraryUrn="urn:adsk.eagle:library:468"
311 | UsedLibraryUrn="urn:adsk.eagle:library:469"
312 | UsedLibraryUrn="urn:adsk.eagle:library:470"
313 | UsedLibraryUrn="urn:adsk.eagle:library:471"
314 | UsedLibraryUrn="urn:adsk.eagle:library:472"
315 | UsedLibraryUrn="urn:adsk.eagle:library:473"
316 | UsedLibraryUrn="urn:adsk.eagle:library:474"
317 | UsedLibraryUrn="urn:adsk.eagle:library:475"
318 | UsedLibraryUrn="urn:adsk.eagle:library:476"
319 | UsedLibraryUrn="urn:adsk.eagle:library:477"
320 | UsedLibraryUrn="urn:adsk.eagle:library:116"
321 | UsedLibraryUrn="urn:adsk.eagle:library:507"
322 | UsedLibraryUrn="urn:adsk.eagle:library:508"
323 | UsedLibraryUrn="urn:adsk.eagle:library:511"
324 | UsedLibraryUrn="urn:adsk.eagle:library:512"
325 | UsedLibraryUrn="urn:adsk.eagle:library:515"
326 | UsedLibraryUrn="urn:adsk.eagle:library:516"
327 | UsedLibraryUrn="urn:adsk.eagle:library:518"
328 | UsedLibraryUrn="urn:adsk.eagle:library:533"
329 | UsedLibraryUrn="urn:adsk.eagle:library:531"
330 | UsedLibraryUrn="urn:adsk.eagle:library:534"
331 | UsedLibraryUrn="urn:adsk.eagle:library:117"
332 | UsedLibraryUrn="urn:adsk.eagle:library:535"
333 | UsedLibraryUrn="urn:adsk.eagle:library:536"
334 | UsedLibraryUrn="urn:adsk.eagle:library:488243"
335 | UsedLibraryUrn="urn:adsk.eagle:library:484"
336 | UsedLibraryUrn="urn:adsk.eagle:library:491"
337 | UsedLibraryUrn="urn:adsk.eagle:library:438"
338 | UsedLibraryUrn="urn:adsk.eagle:library:439"
339 | UsedLibraryUrn="urn:adsk.eagle:library:440"
340 | UsedLibraryUrn="urn:adsk.eagle:library:441"
341 | UsedLibraryUrn="urn:adsk.eagle:library:442"
342 | UsedLibraryUrn="urn:adsk.eagle:library:82"
343 | UsedLibraryUrn="urn:adsk.eagle:library:118"
344 | UsedLibraryUrn="urn:adsk.eagle:library:480"
345 | UsedLibraryUrn="urn:adsk.eagle:library:492"
346 | UsedLibraryUrn="urn:adsk.eagle:library:485"
347 | UsedLibraryUrn="urn:adsk.eagle:library:493"
348 | UsedLibraryUrn="urn:adsk.eagle:library:486"
349 | UsedLibraryUrn="urn:adsk.eagle:library:483"
350 | UsedLibraryUrn="urn:adsk.eagle:library:446"
351 | UsedLibraryUrn="urn:adsk.eagle:library:447"
352 | UsedLibraryUrn="urn:adsk.eagle:library:119"
353 | UsedLibraryUrn="urn:adsk.eagle:library:120"
354 | UsedLibraryUrn="urn:adsk.eagle:library:121"
355 | UsedLibraryUrn="urn:adsk.eagle:library:122"
356 | UsedLibraryUrn="urn:adsk.eagle:library:123"
357 | UsedLibraryUrn="urn:adsk.eagle:library:124"
358 | UsedLibraryUrn="urn:adsk.eagle:library:125"
359 | UsedLibraryUrn="urn:adsk.eagle:library:126"
360 | UsedLibraryUrn="urn:adsk.eagle:library:127"
361 | UsedLibraryUrn="urn:adsk.eagle:library:83"
362 | UsedLibraryUrn="urn:adsk.eagle:library:128"
363 | UsedLibraryUrn="urn:adsk.eagle:library:129"
364 | UsedLibraryUrn="urn:adsk.eagle:library:130"
365 | UsedLibraryUrn="urn:adsk.eagle:library:131"
366 | UsedLibraryUrn="urn:adsk.eagle:library:132"
367 | UsedLibraryUrn="urn:adsk.eagle:library:133"
368 | UsedLibraryUrn="urn:adsk.eagle:library:134"
369 | UsedLibraryUrn="urn:adsk.eagle:library:135"
370 | UsedLibraryUrn="urn:adsk.eagle:library:136"
371 | UsedLibraryUrn="urn:adsk.eagle:library:137"
372 | UsedLibraryUrn="urn:adsk.eagle:library:84"
373 | UsedLibraryUrn="urn:adsk.eagle:library:138"
374 | UsedLibraryUrn="urn:adsk.eagle:library:139"
375 | UsedLibraryUrn="urn:adsk.eagle:library:140"
376 | UsedLibraryUrn="urn:adsk.eagle:library:141"
377 | UsedLibraryUrn="urn:adsk.eagle:library:142"
378 | UsedLibraryUrn="urn:adsk.eagle:library:143"
379 | UsedLibraryUrn="urn:adsk.eagle:library:144"
380 | UsedLibraryUrn="urn:adsk.eagle:library:145"
381 | UsedLibraryUrn="urn:adsk.eagle:library:146"
382 | UsedLibraryUrn="urn:adsk.eagle:library:147"
383 | UsedLibraryUrn="urn:adsk.eagle:library:85"
384 | UsedLibraryUrn="urn:adsk.eagle:library:148"
385 | UsedLibraryUrn="urn:adsk.eagle:library:149"
386 | UsedLibraryUrn="urn:adsk.eagle:library:150"
387 | UsedLibraryUrn="urn:adsk.eagle:library:151"
388 | UsedLibraryUrn="urn:adsk.eagle:library:152"
389 | UsedLibraryUrn="urn:adsk.eagle:library:153"
390 | UsedLibraryUrn="urn:adsk.eagle:library:154"
391 | UsedLibraryUrn="urn:adsk.eagle:library:155"
392 | UsedLibraryUrn="urn:adsk.eagle:library:156"
393 | UsedLibraryUrn="urn:adsk.eagle:library:157"
394 | UsedLibraryUrn="urn:adsk.eagle:library:86"
395 | UsedLibraryUrn="urn:adsk.eagle:library:158"
396 | UsedLibraryUrn="urn:adsk.eagle:library:159"
397 | UsedLibraryUrn="urn:adsk.eagle:library:160"
398 | UsedLibraryUrn="urn:adsk.eagle:library:161"
399 | UsedLibraryUrn="urn:adsk.eagle:library:162"
400 | UsedLibraryUrn="urn:adsk.eagle:library:163"
401 | UsedLibraryUrn="urn:adsk.eagle:library:164"
402 | UsedLibraryUrn="urn:adsk.eagle:library:165"
403 | UsedLibraryUrn="urn:adsk.eagle:library:166"
404 | UsedLibraryUrn="urn:adsk.eagle:library:167"
405 | UsedLibraryUrn="urn:adsk.eagle:library:87"
406 | UsedLibraryUrn="urn:adsk.eagle:library:168"
407 | UsedLibraryUrn="urn:adsk.eagle:library:169"
408 | UsedLibraryUrn="urn:adsk.eagle:library:170"
409 | UsedLibraryUrn="urn:adsk.eagle:library:171"
410 | UsedLibraryUrn="urn:adsk.eagle:library:172"
411 | UsedLibraryUrn="urn:adsk.eagle:library:173"
412 | UsedLibraryUrn="urn:adsk.eagle:library:174"
413 | UsedLibraryUrn="urn:adsk.eagle:library:175"
414 | UsedLibraryUrn="urn:adsk.eagle:library:176"
415 | UsedLibraryUrn="urn:adsk.eagle:library:177"
416 |
417 | [Win_1]
418 | Type="Control Panel"
419 | Number=0
420 |
421 | [Desktop]
422 | Screen="1920 1080"
423 | Window="Win_1"
424 |
--------------------------------------------------------------------------------
/eagle/sfe-gerb274x-JEB.cam:
--------------------------------------------------------------------------------
1 | [CAM Processor Job]
2 | Description[en]="Generates Extended Gerber Format\nThis CAM job consists of five sections that generate data for a two layer board.
\nYou will get five gerber files that contain data for:
\ncomponent side *.cmp
\nsolder side *.sol
\nsilkscreen component side *.plc
\nsolder stop component side *.stc
\nsolder stop solder sid *.sts
"
3 | Section=Sec_1
4 | Section=Sec_2
5 | Section=Sec_3
6 | Section=Sec_4
7 | Section=Sec_5
8 | Section=Sec_6
9 |
10 | [Sec_1]
11 | Name[de]="Top Copper"
12 | Name[en]="Top Copper"
13 | Prompt=""
14 | Device="GERBER_RS274X"
15 | Wheel=""
16 | Rack=""
17 | Scale=1
18 | Output=".GTL"
19 | Flags="0 0 0 1 0 1 1"
20 | Emulate="0"
21 | Offset="0.0mil 0.0mil"
22 | Sheet=1
23 | Tolerance="0 0 0 0 0 0"
24 | Pen="0.0mil 0"
25 | Page="12000.0mil 8000.0mil"
26 | Layers=" 1 17 18 20"
27 | Colors=" 1 2 1 2 1 2 1 2 1 2 1 2 1 2 1 2 6 6 4 8 8 8 8 8 8 8 8 8 8 8 8 8 4 4 1 1 1 1 3 3 1 2 6 8 8 5 8 8 8 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 4 2 4 3 6 6 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0"
28 |
29 | [Sec_2]
30 | Name[de]="Bottom Copper"
31 | Name[en]="Bottom Copper"
32 | Prompt=""
33 | Device="GERBER_RS274X"
34 | Wheel=".whl"
35 | Rack=""
36 | Scale=1
37 | Output=".GBL"
38 | Flags="0 0 0 1 0 1 1"
39 | Emulate="0"
40 | Offset="0.0mil 0.0mil"
41 | Sheet=1
42 | Tolerance="0 0 0 0 0 0"
43 | Pen="0.0mil 0"
44 | Page="12000.0mil 8000.0mil"
45 | Layers=" 16 17 18 20"
46 | Colors=" 1 2 1 2 1 2 1 2 1 2 1 2 1 2 1 2 6 6 4 8 8 8 8 8 8 8 8 8 8 8 8 8 4 4 1 1 1 1 3 3 1 2 6 8 8 5 8 8 8 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 4 2 4 3 6 6 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0"
47 |
48 | [Sec_3]
49 | Name[de]="Top Silkscreen"
50 | Name[en]="Top Silkscreen"
51 | Prompt=""
52 | Device="GERBER_RS274X"
53 | Wheel=".whl"
54 | Rack=""
55 | Scale=1
56 | Output=".GTO"
57 | Flags="0 0 0 1 0 1 1"
58 | Emulate="0"
59 | Offset="0.0mil 0.0mil"
60 | Sheet=1
61 | Tolerance="0 0 0 0 0 0"
62 | Pen="0.0mil 0"
63 | Page="12000.0mil 8000.0mil"
64 | Layers=" 20 21 25 27"
65 | Colors=" 1 2 1 2 1 2 1 2 1 2 1 2 1 2 1 2 6 6 4 8 8 8 8 8 8 8 8 8 8 8 8 8 4 4 1 1 1 1 3 3 1 2 6 8 8 5 8 8 8 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 4 2 4 3 6 6 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0"
66 |
67 | [Sec_4]
68 | Name[de]="Top Soldermask"
69 | Name[en]="Top Soldermask"
70 | Prompt=""
71 | Device="GERBER_RS274X"
72 | Wheel=".whl"
73 | Rack=""
74 | Scale=1
75 | Output=".GTS"
76 | Flags="0 0 0 1 0 1 1"
77 | Emulate="0"
78 | Offset="0.0mil 0.0mil"
79 | Sheet=1
80 | Tolerance="0 0 0 0 0 0"
81 | Pen="0.0mil 0"
82 | Page="12000.0mil 8000.0mil"
83 | Layers=" 20 29"
84 | Colors=" 1 2 1 2 1 2 1 2 1 2 1 2 1 2 1 2 6 6 4 8 8 8 8 8 8 8 8 8 8 8 8 8 4 4 1 1 1 1 3 3 1 2 6 8 8 5 8 8 8 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 4 2 4 3 6 6 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0"
85 |
86 | [Sec_5]
87 | Name[de]="Bottom Soldermask"
88 | Name[en]="Bottom Soldermask"
89 | Prompt=""
90 | Device="GERBER_RS274X"
91 | Wheel=".whl"
92 | Rack=""
93 | Scale=1
94 | Output=".GBS"
95 | Flags="0 0 0 1 0 1 1"
96 | Emulate="0"
97 | Offset="0.0mil 0.0mil"
98 | Sheet=1
99 | Tolerance="0 0 0 0 0 0"
100 | Pen="0.0mil 0"
101 | Page="12000.0mil 8000.0mil"
102 | Layers=" 20 30"
103 | Colors=" 1 2 1 2 1 2 1 2 1 2 1 2 1 2 1 2 6 6 4 8 8 8 8 8 8 8 8 8 8 8 8 8 4 4 1 1 1 1 3 3 1 2 6 8 8 5 8 8 8 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 4 2 4 3 6 6 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0"
104 |
105 | [Sec_6]
106 | Name[de]="Drill File"
107 | Name[en]="Drill File"
108 | Prompt=""
109 | Device="EXCELLON"
110 | Wheel=""
111 | Rack=""
112 | Scale=1
113 | Output=".TXT"
114 | Flags="0 0 0 1 0 1 1"
115 | Emulate="0"
116 | Offset="0.0mil 0.0mil"
117 | Sheet=1
118 | Tolerance="0 0 0 0 0 0"
119 | Pen="0.0mil 0"
120 | Page="12000.0mil 8000.0mil"
121 | Layers=" 44 45"
122 | Colors=" 1 2 1 2 1 2 1 2 1 2 1 2 1 2 1 2 6 6 4 8 8 8 8 8 8 8 8 8 8 8 8 8 4 4 1 1 1 1 3 3 1 2 6 8 8 5 8 8 8 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 4 2 4 3 6 6 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0"
123 |
--------------------------------------------------------------------------------
/examples/LeguinoEmpty-de/LeguinoEmpty-de.ino:
--------------------------------------------------------------------------------
1 | #include
2 |
3 |
4 | // ==================
5 | // === Sensoren ===
6 | // ==================
7 |
8 | // Deklariere hier alle Sensoren (Anschluesse 1 bis 6)
9 |
10 | // Zum Beispiel wie folgt:
11 | //Switch * tasteRot;
12 | //Switch * tasteGelb;
13 | //LightSensor * helligkeit;
14 | //LightBarrier * muenzEinwurf;
15 | //DistanceSensor * entfernung;
16 | //SingleSensor * spannungsMessung;
17 |
18 |
19 | // =================
20 | // === Aktoren ===
21 | // =================
22 |
23 | // Deklariere hier alle Aktoren (LEGO-Technik-Anschluesse A bis E)
24 |
25 | // Zum Beispiel wie folgt:
26 | //Light * frontlicht;
27 | //Light * ruecklicht;
28 | //Tread * antrieb;
29 | //Motor * winde;
30 |
31 |
32 | // =======================
33 | // === Hauptprogramm ===
34 | // =======================
35 |
36 | void setup() {
37 | // Leguino starten (entweder mit WAIT_FOR_PLAY oder NO_WAIT).
38 | // Diese Zeile muss immer als erstes in dem setup stehen.
39 | leguino.setup(WAIT_FOR_PLAY);
40 |
41 | // -------------------------------------------------------------------------
42 | // Initialisierungen. Hier das Programmieren, was nur einmal passieren soll.
43 | // -------------------------------------------------------------------------
44 |
45 | // Sensoren anlegen und mit Anschluessen verbinden
46 | //leguino.add(tasteRot = new Switch(IN_1));
47 | //leguino.add(tasteGelb = new Switch(IN_2));
48 | //leguino.add(helligkeit = new LightSensor(IN_3));
49 | //leguino.add(muenzEinwurf = new LightBarrier(IN_4));
50 | //leguino.add(entfernung = new DistanceSensor(IN_5));
51 | //leguino.add(spannungsMessung = new SingleSensor(IN_6));
52 |
53 | // Aktoren anlegen und mit Anschluessen verbinden
54 | // Achtung: Motoren und Antriebe funktionieren nur an A, B und C
55 | //leguino.add(antrieb = new Tread(OUT_A, OUT_B));
56 | //leguino.add(winde = new Motor(OUT_C));
57 | //leguino.add(frontlicht = new Light(OUT_D));
58 | //leguino.add(ruecklicht = new Light(OUT_E));
59 |
60 | // Sensoren ggf. einstellen und Aktoren voreinstellen
61 | //muenzEinwurf->setThresholds(300, 600);
62 | //frontlicht->on();
63 | //ruecklicht->on();
64 | }
65 |
66 | void loop() {
67 | // Leguino aktualisieren. Diese Zeile muss immer als erstes in der loop stehen.
68 | leguino.update();
69 |
70 | // ----------------------------------------------------------
71 | // Endlosschleife. Hier Sensoren abfragen und Aktoren setzen.
72 | // ----------------------------------------------------------
73 |
74 | // Beispiel für Switch (Abfrage)
75 | //if (tasteRot->isOn())
76 | //{
77 | //...
78 | //tasteRot->waitOff();
79 | //}
80 |
81 | // Beispiel für Switch (Warten auf Einschalten)
82 | //tasteRot->waitOn();
83 | //...
84 | //tasteRot->waitOff();
85 |
86 | // Beispiel für LightSensor (Abfrage, Werte sind 0 bis 1023)
87 | //if (helligkeit->getBrightness() < 300)
88 | //frontlicht->on();
89 | //else
90 | //frontlicht->off();
91 |
92 | // Beispiel für LightSensor (Warten auf heller als 500, max. 2 Sekunden)
93 | //helligkeit->waitBrighter(500, 2000);
94 | //...
95 |
96 | // Beispiel für LightBarrier (Abfrage)
97 | //if (muenzEinwurf->isHit())
98 | //{
99 | //...
100 | //muenzEinwurf->waitClear();
101 | //}
102 |
103 | // Beispiel für LightBarrier (Warten auf Unterbrechung)
104 | //muenzEinwurf->waitHit();
105 | //...
106 | //muenzEinwurf->waitClear();
107 |
108 | // Beispiel für DistanceSensor (Abfrage in cm oder mm, Werte 5cm bis 200cm bzw. 50mm bis 2000mm)
109 | //if (entfernung->getDistanceCm() < 30)
110 | //{
111 | //...
112 | //}
113 |
114 | // Beispiel für DistanceSensor (Warten auf nahen Gegenstand <95mm, max. 5 Sekunden)
115 | //entfernung->waitNearerMm(95, 5000);
116 | //...
117 |
118 | // Beispiel für einen beliebigen Sensor wie Poti oder Messpunkt (Raw-Werte)
119 | // Hinweis: Raw-Werte und Spannungen funktionieren bei jedem Sensor
120 | //uint16 spannung = spannungsMessung->getMilliVolts();
121 |
122 | // Raw-Value bei einem beliebigen Sensor auf dem Monitor ausgeben
123 | //Serial.print("Wert der Lichtschranke: ");
124 | //Serial.print(muenzEinwurf->getRawValue());
125 | //Serial.println();
126 |
127 | // Einfache Beispiele für Light (Werte 0 bis 100)
128 | //frontlicht->on();
129 | //frontlicht->off();
130 | //frontlicht->setValue(50);
131 |
132 | // Light nur für bestimmte Zeit einschalten (msecs)
133 | //frontlicht->on(1000);
134 |
135 | // Hinweis: Serial.print oder Serial.println kann man auch für Status-Meldungen nutzen
136 | //Serial.println("Licht wird eingeschaltet");
137 | //frontlicht->on();
138 |
139 | // Beispiele für Motor (Werte -100 bis 100)
140 | //winde->on();
141 | //winde->on(1000);
142 | //winde->off();
143 | //winde->reverse();
144 | //winde->reverse(1000);
145 | //winde->setValue(50);
146 | //winde->setValue(50, 1000);
147 | //winde->setValue(-50);
148 | //winde->setValue(-50, 1000);
149 |
150 | // Einfache Beispiele für Tread (mit Schub von 0 bis 100 Prozent)
151 | //antrieb->moveStraight(100);
152 | //antrieb->moveLeft(80);
153 | //antrieb->moveRight(80);
154 | //antrieb->stop();
155 | //antrieb->turnAroundLeft(100);
156 | //antrieb->turnAroundRight(100);
157 |
158 | // Beliebige Richtungen von -100 (Drehung links), ueber 0 (geradeaus), bis 100 (Drehung rechts)
159 | //antrieb->move(-50, 100);
160 |
161 | // Alle zusaetzlich auch noch mit Dauer, wenn gewuenscht
162 | //antrieb->moveLeft(100, 1000);
163 |
164 | // Verwende die Leguino-Delay-Funktion, Wenn du einfach nur mal warten
165 | // möchtest, damit Hintergrund-Aufgabe wie Sequenzen weiterlaufen.
166 | //leguino.delay(1000);
167 | }
168 |
--------------------------------------------------------------------------------
/examples/LeguinoEmpty/LeguinoEmpty.ino:
--------------------------------------------------------------------------------
1 | #include
2 |
3 |
4 | // =================
5 | // === Sensors ===
6 | // =================
7 |
8 | // Declare all sensors here (jacks 1 to 6)
9 |
10 | // For example:
11 | //Switch * buttonRed;
12 | //Switch * buttonYellow;
13 | //LightSensor * brightness;
14 | //LightBarrier * coinSlot;
15 | //DistanceSensor * distance;
16 | //SingleSensor * voltageProbe;
17 |
18 |
19 | // ================
20 | // === Aktors ===
21 | // ================
22 |
23 | // Declare all actors here (jacks A to E)
24 |
25 | // For example:
26 | //Light * frontLight;
27 | //Light * backLight;
28 | //Tread * drive;
29 | //Motor * winch;
30 |
31 |
32 | // ======================
33 | // === Main program ===
34 | // ======================
35 |
36 | void setup() {
37 | // Start Leguino (either use WAIT_FOR_PLAY or NO_WAIT).
38 | // This line must always be the first in the setup function.
39 | leguino.setup(WAIT_FOR_PLAY);
40 |
41 | // -----------------------------------------------------------------------
42 | // Initializations. Add code here for things that should happen once only.
43 | // -----------------------------------------------------------------------
44 |
45 | // Sensoren anlegen und mit Anschluessen verbinden
46 | //leguino.add(buttonRed = new Switch(IN_1));
47 | //leguino.add(buttonYellow = new Switch(IN_2));
48 | //leguino.add(brightness = new LightSensor(IN_3));
49 | //leguino.add(coinSlot = new LightBarrier(IN_4));
50 | //leguino.add(distance = new DistanceSensor(IN_5));
51 | //leguino.add(voltageProbe = new SingleSensor(IN_6));
52 |
53 | // Aktoren anlegen und mit Anschluessen verbinden
54 | // Achtung: Motoren und Antriebe funktionieren nur an A, B und C
55 | //leguino.add(drive = new Tread(OUT_A, OUT_B));
56 | //leguino.add(winch = new Motor(OUT_C));
57 | //leguino.add(frontLight = new Light(OUT_D));
58 | //leguino.add(backLight = new Light(OUT_E));
59 |
60 | // Sensoren ggf. einstellen und Aktoren voreinstellen
61 | //coinSlot->setThresholds(300, 600);
62 | //frontLight->on();
63 | //backLight->on();
64 | }
65 |
66 | void loop() {
67 | // Update Leguino.
68 | // This line must always be the first in the loop function.
69 | leguino.update();
70 |
71 | // -------------------------------------------
72 | // Endless loop. Query sensors and set actors.
73 | // -------------------------------------------
74 |
75 | // Example for a switch (query)
76 | //if (buttonRed->isOn())
77 | //{
78 | //...
79 | //buttonRed->waitOff();
80 | //}
81 |
82 | // Example for a switch (for until turned on)
83 | //buttonRed->waitOn();
84 | //...
85 | //buttonRed->waitOff();
86 |
87 | // Example for a light sensor (query, values are 0 to 1023)
88 | //if (brightness->getBrightness() < 300)
89 | //frontLight->on();
90 | //else
91 | //frontLight->off();
92 |
93 | // Example for a light sensor (wait until brighter than 500, max. 2 seconds)
94 | //brightness->waitBrighter(500, 2000);
95 | //...
96 |
97 | // Example for a light barrier (query)
98 | //if (coinSlot->isHit())
99 | //{
100 | //...
101 | //coinSlot->waitClear();
102 | //}
103 |
104 | // Example for a light barrier (wait until hit)
105 | //coinSlot->waitHit();
106 | //...
107 | //coinSlot->waitClear();
108 |
109 | // Example for a distance sensor (query cm or mm, values are 20 cm to 200 cm
110 | // resp. 200 mm to 2000 mm)
111 | //if (distance->getDistanceCm() < 30)
112 | //{
113 | //...
114 | //}
115 |
116 | // Example for a distance sensor (wait for an obstacle to get closer than
117 | // 95 mm, max. 5 seconds)
118 | //distance->waitNearerMm(95, 5000);
119 | //...
120 |
121 | // Example for an arbitrary sensor like pots and probes (raw values)
122 | // Note: Raw values and voltages work with any sensor
123 | //uint16 voltage = voltageProbe->getVoltage();
124 |
125 | // Output raw value of an arbitrary sensor on the monitor
126 | //Serial.print("Value of the light barrier: ");
127 | //Serial.print(coinSlot->getRawValue());
128 | //Serial.println();
129 |
130 | // Simple example for light (value 0 to 100)
131 | //frontLight->on();
132 | //frontLight->off();
133 | //frontLight->setValue(50);
134 |
135 | // Turn on light for a given time (msecs)
136 | //frontLight->on(1000);
137 |
138 | // Note: You can use Serial.print or Serial.println for status messages
139 | //Serial.println("Light gets turned on");
140 | //frontLight->on();
141 |
142 | // Example for motors (values -100 to 100)
143 | //winch->on();
144 | //winch->on(1000);
145 | //winch->off();
146 | //winch->reverse();
147 | //winch->reverse(1000);
148 | //winch->setValue(50);
149 | //winch->setValue(50, 1000);
150 | //winch->setValue(-50);
151 | //winch->setValue(-50, 1000);
152 |
153 | // Simple tread examples (thrust from 0 to 100 percent)
154 | //drive->moveStraight(100);
155 | //drive->moveLeft(80);
156 | //drive->moveRight(80);
157 | //drive->stop();
158 | //drive->turnAroundLeft(100);
159 | //drive->turnAroundRight(100);
160 |
161 | // Arbitrary tread directions from -100 (turn around left on the spot),
162 | // over 0 (straight), to 100 (turn around right on the spot).
163 | //drive->move(-50, 100);
164 |
165 | // Add a duration to the tread move, if desired
166 | //drive->moveLeft(100, 1000);
167 |
168 | // To simply wait, use Leguino's delay function (keeps background tasks
169 | // like sequences active).
170 | //leguino.delay(1000);
171 | }
172 |
--------------------------------------------------------------------------------
/examples/LeguinoTester/LeguinoTester.ino:
--------------------------------------------------------------------------------
1 | #include
2 |
3 |
4 | // =================
5 | // === Sensors ===
6 | // =================
7 |
8 | // Declare all sensors here (jacks 1 to 6)
9 |
10 | // For example:
11 | //Switch * buttonRed;
12 | //Switch * buttonYellow;
13 | //LightSensor * brightness;
14 | //LightBarrier * coinSlot;
15 | //DistanceSensor * distance;
16 | //SingleSensor * voltageProbe;
17 |
18 |
19 | // ================
20 | // === Aktors ===
21 | // ================
22 |
23 | // Declare all actors here (jacks A to E)
24 |
25 | // For example:
26 | //Light * frontLight;
27 | //Light * backLight;
28 | //Tread * drive;
29 | //Motor * winch;
30 |
31 |
32 | // ======================
33 | // === Main program ===
34 | // ======================
35 |
36 | void setup() {
37 | // Start Leguino (either use WAIT_FOR_PLAY or NO_WAIT).
38 | // This line must always be the first in the setup function.
39 | leguino.setup(WAIT_FOR_PLAY);
40 |
41 | // -----------------------------------------------------------------------
42 | // Initializations. Add code here for things that should happen once only.
43 | // -----------------------------------------------------------------------
44 |
45 | // Sensoren anlegen und mit Anschluessen verbinden
46 | //leguino.add(buttonRed = new Switch(IN_1));
47 | //leguino.add(buttonYellow = new Switch(IN_2));
48 | //leguino.add(brightness = new LightSensor(IN_3));
49 | //leguino.add(coinSlot = new LightBarrier(IN_4));
50 | //leguino.add(distance = new DistanceSensor(IN_5));
51 | //leguino.add(voltageProbe = new SingleSensor(IN_6));
52 |
53 | // Aktoren anlegen und mit Anschluessen verbinden
54 | // Achtung: Motoren und Antriebe funktionieren nur an A, B und C
55 | //leguino.add(drive = new Tread(OUT_A, OUT_B));
56 | //leguino.add(winch = new Motor(OUT_C));
57 | //leguino.add(frontLight = new Light(OUT_D));
58 | //leguino.add(backLight = new Light(OUT_E));
59 |
60 | // Sensoren ggf. einstellen und Aktoren voreinstellen
61 | //coinSlot->setThresholds(300, 600);
62 | //frontLight->on();
63 | //backLight->on();
64 | }
65 |
66 | void loop() {
67 | // Update Leguino.
68 | // This line must always be the first in the loop function.
69 | leguino.update();
70 |
71 | // -------------------------------------------
72 | // Endless loop. Query sensors and set actors.
73 | // -------------------------------------------
74 |
75 | // Example for a switch (query)
76 | //if (buttonRed->isOn())
77 | //{
78 | //...
79 | //buttonRed->waitOff();
80 | //}
81 |
82 | // Example for a switch (for until turned on)
83 | //buttonRed->waitOn();
84 | //...
85 | //buttonRed->waitOff();
86 |
87 | // Example for a light sensor (query, values are 0 to 1023)
88 | //if (brightness->getBrightness() < 300)
89 | //frontLight->on();
90 | //else
91 | //frontLight->off();
92 |
93 | // Example for a light sensor (wait until brighter than 500, max. 2 seconds)
94 | //brightness->waitBrighter(500, 2000);
95 | //...
96 |
97 | // Example for a light barrier (query)
98 | //if (coinSlot->isHit())
99 | //{
100 | //...
101 | //coinSlot->waitClear();
102 | //}
103 |
104 | // Example for a light barrier (wait until hit)
105 | //coinSlot->waitHit();
106 | //...
107 | //coinSlot->waitClear();
108 |
109 | // Example for a distance sensor (query cm or mm, values are 20 cm to 200 cm
110 | // resp. 200 mm to 2000 mm)
111 | //if (distance->getDistanceCm() < 30)
112 | //{
113 | //...
114 | //}
115 |
116 | // Example for a distance sensor (wait for an obstacle to get closer than
117 | // 95 mm, max. 5 seconds)
118 | //distance->waitNearerMm(95, 5000);
119 | //...
120 |
121 | // Example for an arbitrary sensor like pots and probes (raw values)
122 | // Note: Raw values and voltages work with any sensor
123 | //uint16 voltage = voltageProbe->getVoltage();
124 |
125 | // Output raw value of an arbitrary sensor on the monitor
126 | //Serial.print("Value of the light barrier: ");
127 | //Serial.print(coinSlot->getRawValue());
128 | //Serial.println();
129 |
130 | // Simple example for light (value 0 to 100)
131 | //frontLight->on();
132 | //frontLight->off();
133 | //frontLight->setValue(50);
134 |
135 | // Turn on light for a given time (msecs)
136 | //frontLight->on(1000);
137 |
138 | // Note: You can use Serial.print or Serial.println for status messages
139 | //Serial.println("Light gets turned on");
140 | //frontLight->on();
141 |
142 | // Example for motors (values -100 to 100)
143 | //winch->on();
144 | //winch->on(1000);
145 | //winch->off();
146 | //winch->reverse();
147 | //winch->reverse(1000);
148 | //winch->setValue(50);
149 | //winch->setValue(50, 1000);
150 | //winch->setValue(-50);
151 | //winch->setValue(-50, 1000);
152 |
153 | // Simple tread examples (thrust from 0 to 100 percent)
154 | //drive->moveStraight(100);
155 | //drive->moveLeft(80);
156 | //drive->moveRight(80);
157 | //drive->stop();
158 | //drive->turnAroundLeft(100);
159 | //drive->turnAroundRight(100);
160 |
161 | // Arbitrary tread directions from -100 (turn around left on the spot),
162 | // over 0 (straight), to 100 (turn around right on the spot).
163 | //drive->move(-50, 100);
164 |
165 | // Add a duration to the tread move, if desired
166 | //drive->moveLeft(100, 1000);
167 |
168 | // To simply wait, use Leguino's delay function (keeps background tasks
169 | // like sequences active).
170 | //leguino.delay(1000);
171 | }
172 |
--------------------------------------------------------------------------------
/sensor/DistanceSensor.cpp:
--------------------------------------------------------------------------------
1 | DistanceSensor::DistanceSensor(int8 input)
2 | : SingleSensor(input)
3 | {
4 | minimumRawValue = 30;
5 | maximumRawValue = 1023;
6 | mmPerRawInverse = 59334U;
7 | mmOffset = -30;
8 | }
9 |
10 | void DistanceSensor::calibrate(uint16 minimumRawValue, uint16 maximumRawValue,
11 | uint16 mmPerRawInverse, int16 mmOffset)
12 | {
13 | this->minimumRawValue = minimumRawValue;
14 | this->maximumRawValue = maximumRawValue;
15 | this->mmPerRawInverse = mmPerRawInverse;
16 | this->mmOffset = mmOffset;
17 | }
18 |
19 | int16 DistanceSensor::getDistanceCm()
20 | {
21 | return (getDistanceMm() + 5) / 10;
22 | }
23 |
24 | int16 DistanceSensor::getDistanceMm()
25 | {
26 | uint16 rawValue = getRawValue();
27 | if (rawValue < minimumRawValue)
28 | rawValue = minimumRawValue;
29 | if (rawValue > maximumRawValue)
30 | rawValue = maximumRawValue;
31 |
32 | return (int16) (mmPerRawInverse / rawValue + mmOffset);
33 | }
34 |
35 | bool DistanceSensor::waitFartherCm(int16 cm, uint16 timeout)
36 | {
37 | return waitUntilMm('>', cm * 10, timeout);
38 | }
39 |
40 | bool DistanceSensor::waitFartherMm(int16 mm, uint16 timeout)
41 | {
42 | return waitUntilMm('>', mm, timeout);
43 | }
44 |
45 | bool DistanceSensor::waitNearerCm(int16 cm, uint16 timeout)
46 | {
47 | return waitUntilMm('<', cm * 10, timeout);
48 | }
49 |
50 | bool DistanceSensor::waitNearerMm(int16 mm, uint16 timeout)
51 | {
52 | return waitUntilMm('<', mm, timeout);
53 | }
54 |
55 | bool DistanceSensor::waitUntilMm(char comparator, int16 mm, uint16 timeout)
56 | {
57 | uint32 start = millis();
58 | uint32 end = start + timeout;
59 | uint32 current = millis();
60 | while (timeout == 0 || current < end && current >= start)
61 | {
62 | leguino.delay(20);
63 |
64 | if (comparator == '>' && getDistanceMm() > mm
65 | || comparator == '<' && getDistanceMm() < mm)
66 | return true;
67 |
68 | current = millis();
69 | }
70 |
71 | return false;
72 | }
73 |
--------------------------------------------------------------------------------
/sensor/DistanceSensor.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_DISTANCESENSOR_H
2 | #define __LEGUINO_DISTANCESENSOR_H
3 |
4 |
5 | /**
6 | * A distance sensor (e.g. infra-red type Sharp GP2Y0A21YK).
7 | * Connect the three pins to VCC (+), ground (-) and a Leguino input. The
8 | * GP2Y0A21YK does not need a pull-up resistor.
9 | *
10 | * @see Sensor
11 | * @see SingleSensor
12 | */
13 | class DistanceSensor : public SingleSensor
14 | {
15 | public:
16 |
17 | /**
18 | * Creates a new distance sensor.
19 | * @param input The input the sensor is connected to.
20 | * Use the constants IN_1 thru IN_6.
21 | */
22 | DistanceSensor(int8 input);
23 |
24 | /**
25 | * The distance-sensor object is calibrates to match Sharp GP2Y0A21YK.
26 | * Use this method to adapt to any other type of distance sensor.
27 | * @param minimumRawValue The minimum reliable raw value of the sensor.
28 | * All values below this threshold are considered that threshold.
29 | * @param maximumRawValue The maximum reliable raw value of the sensor.
30 | * All values above this threshold are considered that threshold.
31 | * @param mmPerRawInverse The number of milli-meters per raw-value
32 | * inverse. The large the value, the bigger the results.
33 | * @param mmOffset The number of milli-meters to add to the conversion
34 | * result. The large the value, the bigger the results.
35 | */
36 | void calibrate(uint16 minimumRawValue, uint16 maximumRawValue,
37 | uint16 mmPerRawInverse, int16 mmOffset);
38 |
39 | /**
40 | * Returns the distance of the nearest obstacle in front of the sensor.
41 | * @return The distance in centi-meters.
42 | */
43 | int16 getDistanceCm();
44 |
45 | /**
46 | * Returns the distance of the nearest obstacle in front of the sensor.
47 | * @return The distance in milli-meters.
48 | */
49 | int16 getDistanceMm();
50 |
51 | /**
52 | * Waits (blocks) until the nearest obstacle in front of the sensor is
53 | * farther away than a given threshold.
54 | * @param cm The threshold in centi-meters.
55 | * @param msecs The number of milli-seconds to wait before giving up,
56 | * or 0 (the default) to wait forever.
57 | * @return Whether the event actually happened. false indicates a
58 | * timeout.
59 | */
60 | bool waitFartherCm(int16 cm, uint16 timeout = 0);
61 |
62 | /**
63 | * Waits (blocks) until the nearest obstacle in front of the sensor is
64 | * farther away than a given threshold.
65 | * @param cm The threshold in milli-meters.
66 | * @param msecs The number of milli-seconds to wait before giving up,
67 | * or 0 (the default) to wait forever.
68 | * @return Whether the event actually happened. false indicates a
69 | * timeout.
70 | */
71 | bool waitFartherMm(int16 mm, uint16 timeout = 0);
72 |
73 | /**
74 | * Waits (blocks) until the nearest obstacle in front of the sensor is
75 | * nearer than a given threshold.
76 | * @param cm The threshold in centi-meters.
77 | * @param msecs The number of milli-seconds to wait before giving up,
78 | * or 0 (the default) to wait forever.
79 | * @return Whether the event actually happened. false indicates a
80 | * timeout.
81 | */
82 | bool waitNearerCm(int16 cm, uint16 timeout = 0);
83 |
84 | /**
85 | * Waits (blocks) until the nearest obstacle in front of the sensor is
86 | * nearer than a given threshold.
87 | * @param cm The threshold in milli-meters.
88 | * @param msecs The number of milli-seconds to wait before giving up,
89 | * or 0 (the default) to wait forever.
90 | * @return Whether the event actually happened. false indicates a
91 | * timeout.
92 | */
93 | bool waitNearerMm(int16 mm, uint16 timeout = 0);
94 |
95 | protected:
96 |
97 | uint16 maximumRawValue;
98 | uint16 minimumRawValue;
99 | int16 mmOffset;
100 | uint16 mmPerRawInverse;
101 |
102 | bool waitUntilMm(char comparator, int16 mm, uint16 timeout = 0);
103 | };
104 |
105 |
106 | #endif
107 |
--------------------------------------------------------------------------------
/sensor/LightBarrier.cpp:
--------------------------------------------------------------------------------
1 | LightBarrier::LightBarrier(int8 input)
2 | : SingleSensor(input)
3 | {
4 | hitThreshold = 600;
5 | clearThreshold = 300;
6 |
7 | hit = false;
8 | }
9 |
10 | bool LightBarrier::isClear()
11 | {
12 | return !isHit();
13 | }
14 |
15 | bool LightBarrier::isHit()
16 | {
17 | int16 rawValue = getRawValue();
18 | if (hit && rawValue <= clearThreshold) {
19 | hit = false;
20 | } else if (!hit && rawValue >= hitThreshold) {
21 | hit = true;
22 | }
23 |
24 | return hit;
25 | }
26 |
27 | void LightBarrier::setThresholds(int16 hitThreshold, int16 clearThreshold)
28 | {
29 | this->hitThreshold = hitThreshold;
30 | this->clearThreshold = clearThreshold;
31 | }
32 |
33 | bool LightBarrier::waitClear(uint16 timeout)
34 | {
35 | if (isClear())
36 | return true;
37 |
38 | bool success = waitUntilRaw('L', clearThreshold, timeout);
39 | if (success)
40 | hit = false;
41 |
42 | return success;
43 | }
44 |
45 | bool LightBarrier::waitHit(uint16 timeout)
46 | {
47 | if (isHit())
48 | return true;
49 |
50 | bool success = waitUntilRaw('G', hitThreshold, timeout);
51 | if (success)
52 | hit = true;
53 |
54 | return success;
55 | }
56 |
--------------------------------------------------------------------------------
/sensor/LightBarrier.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_LIGHTBARRIER_H
2 | #define __LEGUINO_LIGHTBARRIER_H
3 |
4 |
5 | /**
6 | * A light barrier (IR LED and photo resistor resp. photo diode).
7 | * Connect the IR LED (protected by a resistor) to VCC (+) and ground (-).
8 | * Connect the photo resistor or photo diode to a Leguino input and ground (-),
9 | * and use a pull-up resistor of 10k between the input and VCC (+).
10 | *
11 | * @see Sensor
12 | * @see SingleSensor
13 | */
14 | class LightBarrier : public SingleSensor
15 | {
16 | public:
17 |
18 | /**
19 | * Creates a new light barrier.
20 | * @param input The input the sensor is connected to.
21 | * Use the constants IN_1 thru IN_6.
22 | */
23 | LightBarrier(int8 input);
24 |
25 | /**
26 | * Returns whether the barrier is currently clear (no obstacle is in
27 | * between).
28 | * @return Whether the barrier is currently clear.
29 | */
30 | bool isClear();
31 |
32 | /**
33 | * Returns whether the barrier is currently hit (an obstacle is in
34 | * between).
35 | * @return Whether the barrier is currently hit.
36 | */
37 | bool isHit();
38 |
39 | /**
40 | * Sets the brightnesses that indicate a hit and a clearing.
41 | * Use a hit threshold bigger than the clear threshold. The bigger the
42 | * gap, the more stable the barrier switching (the sensor behaves as a
43 | * Schmitt trigger hysteresis). Defaults are 600 and 300.
44 | * @param hitThreshold The hit threshold. Brightness at the receiver
45 | * below this value is considered a hit.
46 | * @param clearThreshold The clear threshold. Brightness at the receiver
47 | * above this value is considered a clearing.
48 | */
49 | void setThresholds(int16 hitThreshold, int16 clearThreshold);
50 |
51 | /**
52 | * Waits until the barrier is clear (no obstacle is in between).
53 | * @param msecs The number of milli-seconds to wait before giving up,
54 | * or 0 (the default) to wait forever.
55 | * @return Whether the event actually happened. false indicates a
56 | * timeout.
57 | */
58 | bool waitClear(uint16 timeout = 0);
59 |
60 | /**
61 | * Waits until the barrier is hit (an obstacle is in between).
62 | * @param msecs The number of milli-seconds to wait before giving up,
63 | * or 0 (the default) to wait forever.
64 | * @return Whether the event actually happened. false indicates a
65 | * timeout.
66 | */
67 | bool waitHit(uint16 timeout = 0);
68 |
69 | protected:
70 |
71 | int16 clearThreshold;
72 | bool hit;
73 | int16 hitThreshold;
74 | };
75 |
76 |
77 | #endif
78 |
--------------------------------------------------------------------------------
/sensor/LightSensor.cpp:
--------------------------------------------------------------------------------
1 | LightSensor::LightSensor(int8 input)
2 | : SingleSensor(input)
3 | {
4 | }
5 |
6 | int16 LightSensor::getBrightness()
7 | {
8 | return 1023 - getRawValue();
9 | }
10 |
11 | bool LightSensor::waitBrighter(int16 value, uint16 timeout)
12 | {
13 | return waitUntilRaw('<', 1023 - value, timeout);
14 | }
15 |
16 | bool LightSensor::waitDarker(int16 value, uint16 timeout)
17 | {
18 | return waitUntilRaw('>', 1023 - value, timeout);
19 | }
20 |
--------------------------------------------------------------------------------
/sensor/LightSensor.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_LIGHTSENSOR_H
2 | #define __LEGUINO_LIGHTSENSOR_H
3 |
4 |
5 | /**
6 | * A light sensor (photo resistor or photo diode) connected to a Leguino input
7 | * and ground (-). Use a pull-up resistor of 10k between the input and VCC (+).
8 | *
9 | * @see Sensor
10 | * @see SingleSensor
11 | */
12 | class LightSensor : public SingleSensor
13 | {
14 | public:
15 |
16 | /**
17 | * Creates a new light sensor.
18 | * @param input The input the sensor is connected to.
19 | * Use the constants IN_1 thru IN_6.
20 | */
21 | LightSensor(int8 input);
22 |
23 | /**
24 | * Returns the current brightness.
25 | * @return The current brightness from 0 (dark) to 1023 (light).
26 | */
27 | int16 getBrightness();
28 |
29 | /**
30 | * Waits (blocks) until the light is brighter than a given value.
31 | * @param value The threshold value.
32 | * @param msecs The number of milli-seconds to wait before giving up,
33 | * or 0 (the default) to wait forever.
34 | * @return Whether the event actually happened. false indicates a
35 | * timeout.
36 | */
37 | bool waitBrighter(int16 value, uint16 timeout = 0);
38 |
39 | /**
40 | * Waits (blocks) until the light is darker than a given value.
41 | * @param value The threshold value.
42 | * @param msecs The number of milli-seconds to wait before giving up,
43 | * or 0 (the default) to wait forever.
44 | * @return Whether the event actually happened. false indicates a
45 | * timeout.
46 | */
47 | bool waitDarker(int16 value, uint16 timeout = 0);
48 | };
49 |
50 |
51 | #endif
52 |
--------------------------------------------------------------------------------
/sensor/Sensor.cpp:
--------------------------------------------------------------------------------
1 | Sensor::Sensor()
2 | {
3 | }
4 |
5 | Sensor::~Sensor()
6 | {
7 | }
8 |
--------------------------------------------------------------------------------
/sensor/Sensor.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_SENSOR_H
2 | #define __LEGUINO_SENSOR_H
3 |
4 |
5 | /**
6 | * Constant to refer to input 1 (use this in the sensors' constructor.
7 | */
8 | #define IN_1 1
9 |
10 | /**
11 | * Constant to refer to input 2 (use this in the sensors' constructor.
12 | */
13 | #define IN_2 2
14 |
15 | /**
16 | * Constant to refer to input 3 (use this in the sensors' constructor.
17 | */
18 | #define IN_3 3
19 |
20 | /**
21 | * Constant to refer to input 4 (use this in the sensors' constructor.
22 | */
23 | #define IN_4 4
24 |
25 | /**
26 | * Constant to refer to input 5 (use this in the sensors' constructor.
27 | */
28 | #define IN_5 5
29 |
30 | /**
31 | * Constant to refer to input 6 (use this in the sensors' constructor.
32 | */
33 | #define IN_6 6
34 |
35 |
36 | /**
37 | *
38 | * Sensors represent passive devices you attach to the Leguino board, like
39 | * switches, buttons, knobs, light sensors, distance sensors, etc. Sensors
40 | * usually require one input.
41 | *
42 | *
43 | *
44 | * Add sensors to your program in the setup function, after initializing
45 | * Leguino, using the following example pattern:
46 | * leguino.add(button = new Switch(IN_1));
47 | * or
48 | * leguino.add(brightness = new LightSensor(IN_3));
49 | * or
50 | * leguino.add(distance = new DistanceSensor(IN_5));
51 | * where button
, brightness
, and
52 | * distance
are global variables.
53 | *
54 | *
55 | *
56 | * In the main loop, after the regular update call to the Leguino platform,
57 | * use the sensor's methods to query the inputs, blockingly or non-blockingly.
58 | *
59 | */
60 | class Sensor
61 | {
62 | public:
63 |
64 | /**
65 | * Destroys the sensor.
66 | * Don't call this method from your program.
67 | */
68 | virtual ~Sensor();
69 |
70 | /**
71 | * Internal Leguino method to update the sensor.
72 | * Don't call this method from your program.
73 | * @param msecs The number of milli-seconds since the last update.
74 | */
75 | virtual void update(uint16 timeStep) = NULL;
76 |
77 | protected:
78 |
79 | Sensor();
80 | };
81 |
82 |
83 | #endif
84 |
--------------------------------------------------------------------------------
/sensor/SingleSensor.cpp:
--------------------------------------------------------------------------------
1 | SingleSensor::SingleSensor(int8 input)
2 | {
3 | switch (input)
4 | {
5 | case IN_1: pin = A0; analogPin = 0; break;
6 | case IN_2: pin = A1; analogPin = 1; break;
7 | case IN_3: pin = A2; analogPin = 2; break;
8 | case IN_4: pin = A3; analogPin = 3; break;
9 | case IN_5: pin = A4; analogPin = 4; break;
10 | case IN_6: pin = A5; analogPin = 5; break;
11 |
12 | default: pin = -1; analogPin = -1;
13 | }
14 |
15 | pinMode(pin, INPUT);
16 | digitalWrite(pin, 0);
17 |
18 | valueCache = -1;
19 | }
20 |
21 | uint16 SingleSensor::getMilliVolts()
22 | {
23 | return (uint16) (getRawValue() / 1023.0 * 5000.0);
24 | }
25 |
26 | uint16 SingleSensor::getRawValue()
27 | {
28 | if (valueCache < 0)
29 | valueCache = (int16) analogRead(analogPin);
30 |
31 | return valueCache;
32 | }
33 |
34 | void SingleSensor::update(uint16 timeStep)
35 | {
36 | valueCache = -1;
37 | }
38 |
39 | bool SingleSensor::waitUntilRaw(char comparator, int16 value, uint16 timeout)
40 | {
41 | uint32 start = millis();
42 | uint32 end = start + timeout;
43 | uint32 current = millis();
44 | while (timeout == 0 || current < end && current >= start)
45 | {
46 | leguino.delay(20);
47 |
48 | if (comparator == '=' && getRawValue() == value
49 | || comparator == '>' && getRawValue() > value
50 | || comparator == 'G' && getRawValue() >= value
51 | || comparator == '<' && getRawValue() < value
52 | || comparator == 'L' && getRawValue() <= value
53 | || comparator == '!' && getRawValue() != value)
54 | return true;
55 |
56 | current = millis();
57 | }
58 |
59 | return false;
60 | }
61 |
--------------------------------------------------------------------------------
/sensor/SingleSensor.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_SINGLESENSOR_H
2 | #define __LEGUINO_SINGLESENSOR_H
3 |
4 |
5 | /**
6 | * A Leguino sensor that requires exactly one input jack (e.g. switches,
7 | * light barriers, distance sensors). You can use sub-classes of this class,
8 | * or use the single sensor directly to get raw values, e.g. for knobs or
9 | * probes. Remember to use pull-ups or pull-downs if your input may be open,
10 | * as Leguino inputs have high input resistance.
11 | *
12 | * @see Switch
13 | * @see LightBarrier
14 | * @see LightSensor
15 | * @see DistanceSensor
16 | */
17 | class SingleSensor : public Sensor
18 | {
19 | public:
20 |
21 | /**
22 | * Creates a new single sensor.
23 | * @param input The input the sensor is connected to.
24 | * Use the constants IN_1 thru IN_6.
25 | */
26 | SingleSensor(int8 input);
27 |
28 | /**
29 | * Returns the current raw input voltage of the sensor, without any
30 | * transformation to represent the part specifications.
31 | * @return The raw input voltage, from 0 to 5000 milli-Volts.
32 | */
33 | uint16 getMilliVolts();
34 |
35 | /**
36 | * Returns the current raw input value of the sensor, without any
37 | * transformation to represent the part specifications.
38 | * @return The raw input value, from 0 (0 Volts) to 1023 (5 Volts).
39 | */
40 | uint16 getRawValue();
41 |
42 | /**
43 | * Internal Leguino method to update the sensor.
44 | * Don't call this method from your program.
45 | * @param msecs The number of milli-seconds since the last update.
46 | */
47 | virtual void update(uint16 timeStep);
48 |
49 | protected:
50 |
51 | int8 analogPin;
52 | int8 pin;
53 | int16 valueCache;
54 |
55 | bool waitUntilRaw(char comparator, int16 value, uint16 timeout);
56 | };
57 |
58 |
59 | #endif
60 |
--------------------------------------------------------------------------------
/sensor/Switch.cpp:
--------------------------------------------------------------------------------
1 | Switch::Switch(int8 input)
2 | : SingleSensor(input)
3 | {
4 | digitalWrite(pin, 1);
5 | }
6 |
7 | bool Switch::isOff()
8 | {
9 | return getRawValue() >= 512;
10 | }
11 |
12 | bool Switch::isOn()
13 | {
14 | return getRawValue() < 512;
15 | }
16 |
17 | bool Switch::waitOff(uint16 timeout)
18 | {
19 | return waitUntilRaw('G', 512, timeout);
20 | }
21 |
22 | bool Switch::waitOn(uint16 timeout)
23 | {
24 | return waitUntilRaw('<', 512, timeout);
25 | }
26 |
--------------------------------------------------------------------------------
/sensor/Switch.h:
--------------------------------------------------------------------------------
1 | #ifndef __LEGUINO_SWITCH_H
2 | #define __LEGUINO_SWITCH_H
3 |
4 |
5 | /**
6 | * A switch sensor (on-off switch, N/O button, N/C button, etc.) connected to
7 | * a Leguino input and ground (-). Use a pull-up resistor of 10k between the
8 | * input and VCC (+).
9 | *
10 | * @see Sensor
11 | * @see SingleSensor
12 | */
13 | class Switch : public SingleSensor
14 | {
15 | public:
16 |
17 | /**
18 | * Creates a new single sensor.
19 | * @param input The input the sensor is connected to.
20 | * Use the constants IN_1 thru IN_6.
21 | */
22 | Switch(int8 input);
23 |
24 | /**
25 | * Returns whether the switch is currently in "off" position.
26 | * @return Whether the switch is currently in "off" position.
27 | */
28 | bool isOff();
29 |
30 | /**
31 | * Returns whether the switch is currently in "on" position.
32 | * @return Whether the switch is currently in "on" position.
33 | */
34 | bool isOn();
35 |
36 | /**
37 | * Waits (blocks) until the switch is in "off" position.
38 | * @param msecs The number of milli-seconds to wait before giving up,
39 | * or 0 (the default) to wait forever.
40 | * @return Whether the event actually happened. false indicates a
41 | * timeout.
42 | */
43 | bool waitOff(uint16 timeout = 0);
44 |
45 | /**
46 | * Waits (blocks) until the switch is in "on" position.
47 | * @param msecs The number of milli-seconds to wait before giving up,
48 | * or 0 (the default) to wait forever.
49 | * @return Whether the event actually happened. false indicates a
50 | * timeout.
51 | */
52 | bool waitOn(uint16 timeout = 0);
53 | };
54 |
55 |
56 | #endif
57 |
--------------------------------------------------------------------------------