Initial commit

master
Michael Reber 5 years ago
parent c1853f427c
commit 5581e518fc

@ -1,3 +1,118 @@
# project-beverage-vending-machine
A fully automated beverage dispenser, controllable via an Android or Iphone app
A fully automated beverage dispenser, controllable via an Android or Iphone app
It has been designed to hold up to 9 bottles of ingredients for making the cocktails, dispensing the correct amount from each to mix your cocktail of choice.
Cocktails can be chosen using the mobile app (available for iOS and Android) that connects to the machine via Bluetooth. In the app you can also enable/disable ingredients, change the position of each ingredient, edit the recipes and change the amount of each ingredient used in the cocktails and so on.
## Getting started
### Requirements
* Node.js
* Npm (Node comes with npm)
* Android SDK tools [ [installing Cordova requirements](https://cordova.apache.org/docs/en/latest/guide/platforms/android/#installing-the-requirements) ] or Xcode depending on which platform you want to use
* Arduino IDE
### Client
* Clone this repository
* From the client app directory, run `npm install`
* Install Cordova globally `npm install -g cordova`
* Install Ionic CLI globally `npm install -g ionic@2.2.3`
* Run `ionic serve` in a terminal from the `client` directory
* At this point, Ionic CLI should open the app in your browser
### The beverage dispenser
* Clone this repository
* Start the Arduino IDE and open the `_Getraenkeautomat.ino`
* In Arduino IDE, select your board from the `Tools -> Board` menu (right now we're not supporting other boards than Arduino Mega)
* Select the serial port to which Arduino is connected from the `Tools -> Serial Port` menu
* Click the Verify button to see that the code is ok
* Click the Upload button
* If all goes well, that's it
## Required Hardware parts
* NEMA 17 stepper motor
* Pololu A4988 stepper driver
* Hitec HS-7955TG servo motor
* Pololu Micro Maestro 6-Channel servo controller
* Bluetooth module HC-05
* GT2 6mm wide timing belt
* GT2 timing pulley 20 teeth 5mm bore
* Timing belt bearing
* 2 x Chrome plated round rail 1200mm x 12mm
* 4 x SK12 12mm bore linear rail shaft support
* 4 x SC12UU aluminium pillow block housing
* 9 x 40ml Beaumont Metrix SL spirit measure
* 3 x Wall 3 bottle rack
* Endstop microswitch
* Arduino Mega 2560
* Cable carrier
* DC-DC converter (12V to 5V)
* AC power supply 12V (6.67A)
### List of 3D parts used in this project
* [NEMA 17 mount](https://www.thingiverse.com/thing:5391)
* [Adjustable belt holder](https://www.thingiverse.com/thing:745934)
* [Idler pulley mount](https://www.thingiverse.com/thing:1225670)
## Wiring diagram
<img src="https://code.michu-it.com/michael/project-beverage-vending-machine/raw/branch/master/_drawings/wiring_diagram.jpg" alt="Wiring diagram">
## Communication
The mobile app and the machine communicates over the Serial port using the Bluetooth module HC-05 (with a few small changes, you can use other methods for communication like USB or WiFi too). See all available communication commands below in the "Available commands" section.
## Available commands
Multiple commands can be sent in a single message by separating them with a comma ",". All the commands will be executed one after another in the order in which they're written. The messages must be ended with a newline "\n" character to be run.
**Example**
```
X-4995,F2 H2500 W3000,X-1990,F6 H2300 W2300,H
```
### X: Move X axis
**Usage**
`Xnnn`
**Parameters**
Xnnn - The position to move to on the X axis
**Example**
```
X-4995 ; Move to -4995 position on the X axis
```
### H: Home X axis
**Usage**
`H`
**Parameters**
*This command can be used without any parameters*
**Example**
```
H ; Home the X axis
```
### F: Pour
**Usage**
`Fnnn Hnnn Wnnn`
**Parameters**
Fnnn - Times to pour
Hnnn - Time duration (in ms) to hold dispenser in open position
Wnnn - Time duration (in ms) to wait till next pour
**Example**
```
F2 H2500 W3000 ; Pour two times, hold dispenser open for 2500ms and wait for 3000ms between each pour
```
## Additional information
* Dispensers used in this project won't work with liqueur and other thick drinks. You might also have problems with sugary drinks as they stick inner dispenser parts together if you leave the liquid inside the dispenser for hours
* You can use Coca-Cola and other carbonated drinks with these dispensers, but don't forget to make a hole at the bottom of the bottle before mounting the dispenser to the bottle in order to let air get out, otherwise you will have a big fountain. Use empty bottles and fill them later through the holes after mounting the dispensers
* Wash dispensers very well after every use, otherwise the inner dispenser parts will stick together. I would also recommend you to wash them before every use

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

File diff suppressed because it is too large Load Diff

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 739 KiB

@ -0,0 +1,644 @@
// AccelStepper.cpp
//
// Copyright (C) 2009-2013 Mike McCauley
// $Id: AccelStepper.cpp,v 1.23 2016/08/09 00:39:10 mikem Exp mikem $
#include "AccelStepper.h"
#if 0
// Some debugging assistance
void dump(uint8_t* p, int l)
{
int i;
for (i = 0; i < l; i++)
{
Serial.print(p[i], HEX);
Serial.print(" ");
}
Serial.println("");
}
#endif
void AccelStepper::moveTo(long absolute)
{
if (_targetPos != absolute)
{
_targetPos = absolute;
computeNewSpeed();
// compute new n?
}
}
void AccelStepper::move(long relative)
{
moveTo(_currentPos + relative);
}
// Implements steps according to the current step interval
// You must call this at least once per step
// returns true if a step occurred
boolean AccelStepper::runSpeed()
{
// Dont do anything unless we actually have a step interval
if (!_stepInterval)
return false;
unsigned long time = micros();
if (time - _lastStepTime >= _stepInterval)
{
if (_direction == DIRECTION_CW)
{
// Clockwise
_currentPos += 1;
}
else
{
// Anticlockwise
_currentPos -= 1;
}
step(_currentPos);
_lastStepTime = time;
return true;
}
else
{
return false;
}
}
long AccelStepper::distanceToGo()
{
return _targetPos - _currentPos;
}
long AccelStepper::targetPosition()
{
return _targetPos;
}
long AccelStepper::currentPosition()
{
return _currentPos;
}
// Useful during initialisations or after initial positioning
// Sets speed to 0
void AccelStepper::setCurrentPosition(long position)
{
_targetPos = _currentPos = position;
_n = 0;
_stepInterval = 0;
_speed = 0.0;
}
void AccelStepper::computeNewSpeed()
{
long distanceTo = distanceToGo(); // +ve is clockwise from curent location
long stepsToStop = (long)((_speed * _speed) / (2.0 * _acceleration)); // Equation 16
if (distanceTo == 0 && stepsToStop <= 1)
{
// We are at the target and its time to stop
_stepInterval = 0;
_speed = 0.0;
_n = 0;
return;
}
if (distanceTo > 0)
{
// We are anticlockwise from the target
// Need to go clockwise from here, maybe decelerate now
if (_n > 0)
{
// Currently accelerating, need to decel now? Or maybe going the wrong way?
if ((stepsToStop >= distanceTo) || _direction == DIRECTION_CCW)
_n = -stepsToStop; // Start deceleration
}
else if (_n < 0)
{
// Currently decelerating, need to accel again?
if ((stepsToStop < distanceTo) && _direction == DIRECTION_CW)
_n = -_n; // Start accceleration
}
}
else if (distanceTo < 0)
{
// We are clockwise from the target
// Need to go anticlockwise from here, maybe decelerate
if (_n > 0)
{
// Currently accelerating, need to decel now? Or maybe going the wrong way?
if ((stepsToStop >= -distanceTo) || _direction == DIRECTION_CW)
_n = -stepsToStop; // Start deceleration
}
else if (_n < 0)
{
// Currently decelerating, need to accel again?
if ((stepsToStop < -distanceTo) && _direction == DIRECTION_CCW)
_n = -_n; // Start accceleration
}
}
// Need to accelerate or decelerate
if (_n == 0)
{
// First step from stopped
_cn = _c0;
_direction = (distanceTo > 0) ? DIRECTION_CW : DIRECTION_CCW;
}
else
{
// Subsequent step. Works for accel (n is +_ve) and decel (n is -ve).
_cn = _cn - ((2.0 * _cn) / ((4.0 * _n) + 1)); // Equation 13
_cn = max(_cn, _cmin);
}
_n++;
_stepInterval = _cn;
_speed = 1000000.0 / _cn;
if (_direction == DIRECTION_CCW)
_speed = -_speed;
#if 0
Serial.println(_speed);
Serial.println(_acceleration);
Serial.println(_cn);
Serial.println(_c0);
Serial.println(_n);
Serial.println(_stepInterval);
Serial.println(distanceTo);
Serial.println(stepsToStop);
Serial.println("-----");
#endif
}
// Run the motor to implement speed and acceleration in order to proceed to the target position
// You must call this at least once per step, preferably in your main loop
// If the motor is in the desired position, the cost is very small
// returns true if the motor is still running to the target position.
boolean AccelStepper::run()
{
if (runSpeed())
computeNewSpeed();
return _speed != 0.0 || distanceToGo() != 0;
}
AccelStepper::AccelStepper(uint8_t interface, uint8_t pin1, uint8_t pin2, uint8_t pin3, uint8_t pin4, bool enable)
{
_interface = interface;
_currentPos = 0;
_targetPos = 0;
_speed = 0.0;
_maxSpeed = 1.0;
_acceleration = 0.0;
_sqrt_twoa = 1.0;
_stepInterval = 0;
_minPulseWidth = 1;
_enablePin = 0xff;
_lastStepTime = 0;
_pin[0] = pin1;
_pin[1] = pin2;
_pin[2] = pin3;
_pin[3] = pin4;
// NEW
_n = 0;
_c0 = 0.0;
_cn = 0.0;
_cmin = 1.0;
_direction = DIRECTION_CCW;
int i;
for (i = 0; i < 4; i++)
_pinInverted[i] = 0;
if (enable)
enableOutputs();
// Some reasonable default
setAcceleration(1);
}
AccelStepper::AccelStepper(void (*forward)(), void (*backward)())
{
_interface = 0;
_currentPos = 0;
_targetPos = 0;
_speed = 0.0;
_maxSpeed = 1.0;
_acceleration = 0.0;
_sqrt_twoa = 1.0;
_stepInterval = 0;
_minPulseWidth = 1;
_enablePin = 0xff;
_lastStepTime = 0;
_pin[0] = 0;
_pin[1] = 0;
_pin[2] = 0;
_pin[3] = 0;
_forward = forward;
_backward = backward;
// NEW
_n = 0;
_c0 = 0.0;
_cn = 0.0;
_cmin = 1.0;
_direction = DIRECTION_CCW;
int i;
for (i = 0; i < 4; i++)
_pinInverted[i] = 0;
// Some reasonable default
setAcceleration(1);
}
void AccelStepper::setMaxSpeed(float speed)
{
if (_maxSpeed != speed)
{
_maxSpeed = speed;
_cmin = 1000000.0 / speed;
// Recompute _n from current speed and adjust speed if accelerating or cruising
if (_n > 0)
{
_n = (long)((_speed * _speed) / (2.0 * _acceleration)); // Equation 16
computeNewSpeed();
}
}
}
float AccelStepper::maxSpeed()
{
return _maxSpeed;
}
void AccelStepper::setAcceleration(float acceleration)
{
if (acceleration == 0.0)
return;
if (_acceleration != acceleration)
{
// Recompute _n per Equation 17
_n = _n * (_acceleration / acceleration);
// New c0 per Equation 7, with correction per Equation 15
_c0 = 0.676 * sqrt(2.0 / acceleration) * 1000000.0; // Equation 15
_acceleration = acceleration;
computeNewSpeed();
}
}
void AccelStepper::setSpeed(float speed)
{
if (speed == _speed)
return;
speed = constrain(speed, -_maxSpeed, _maxSpeed);
if (speed == 0.0)
_stepInterval = 0;
else
{
_stepInterval = fabs(1000000.0 / speed);
_direction = (speed > 0.0) ? DIRECTION_CW : DIRECTION_CCW;
}
_speed = speed;
}
float AccelStepper::speed()
{
return _speed;
}
// Subclasses can override
void AccelStepper::step(long step)
{
switch (_interface)
{
case FUNCTION:
step0(step);
break;
case DRIVER:
step1(step);
break;
case FULL2WIRE:
step2(step);
break;
case FULL3WIRE:
step3(step);
break;
case FULL4WIRE:
step4(step);
break;
case HALF3WIRE:
step6(step);
break;
case HALF4WIRE:
step8(step);
break;
}
}
// You might want to override this to implement eg serial output
// bit 0 of the mask corresponds to _pin[0]
// bit 1 of the mask corresponds to _pin[1]
// ....
void AccelStepper::setOutputPins(uint8_t mask)
{
uint8_t numpins = 2;
if (_interface == FULL4WIRE || _interface == HALF4WIRE)
numpins = 4;
else if (_interface == FULL3WIRE || _interface == HALF3WIRE)
numpins = 3;
uint8_t i;
for (i = 0; i < numpins; i++)
digitalWrite(_pin[i], (mask & (1 << i)) ? (HIGH ^ _pinInverted[i]) : (LOW ^ _pinInverted[i]));
}
// 0 pin step function (ie for functional usage)
void AccelStepper::step0(long step)
{
if (_speed > 0)
_forward();
else
_backward();
}
// 1 pin step function (ie for stepper drivers)
// This is passed the current step number (0 to 7)
// Subclasses can override
void AccelStepper::step1(long step)
{
// _pin[0] is step, _pin[1] is direction
setOutputPins(_direction ? 0b10 : 0b00); // Set direction first else get rogue pulses
setOutputPins(_direction ? 0b11 : 0b01); // step HIGH
// Caution 200ns setup time
// Delay the minimum allowed pulse width
delayMicroseconds(_minPulseWidth);
setOutputPins(_direction ? 0b10 : 0b00); // step LOW
}
// 2 pin step function
// This is passed the current step number (0 to 7)
// Subclasses can override
void AccelStepper::step2(long step)
{
switch (step & 0x3)
{
case 0: /* 01 */
setOutputPins(0b10);
break;
case 1: /* 11 */
setOutputPins(0b11);
break;
case 2: /* 10 */
setOutputPins(0b01);
break;
case 3: /* 00 */
setOutputPins(0b00);
break;
}
}
// 3 pin step function
// This is passed the current step number (0 to 7)
// Subclasses can override
void AccelStepper::step3(long step)
{
switch (step % 3)
{
case 0: // 100
setOutputPins(0b100);
break;
case 1: // 001
setOutputPins(0b001);
break;
case 2: //010
setOutputPins(0b010);
break;
}
}
// 4 pin step function for half stepper
// This is passed the current step number (0 to 7)
// Subclasses can override
void AccelStepper::step4(long step)
{
switch (step & 0x3)
{
case 0: // 1010
setOutputPins(0b0101);
break;
case 1: // 0110
setOutputPins(0b0110);
break;
case 2: //0101
setOutputPins(0b1010);
break;
case 3: //1001
setOutputPins(0b1001);
break;
}
}
// 3 pin half step function
// This is passed the current step number (0 to 7)
// Subclasses can override
void AccelStepper::step6(long step)
{
switch (step % 6)
{
case 0: // 100
setOutputPins(0b100);
break;
case 1: // 101
setOutputPins(0b101);
break;
case 2: // 001
setOutputPins(0b001);
break;
case 3: // 011
setOutputPins(0b011);
break;
case 4: // 010
setOutputPins(0b010);
break;
case 5: // 011
setOutputPins(0b110);
break;
}
}
// 4 pin half step function
// This is passed the current step number (0 to 7)
// Subclasses can override
void AccelStepper::step8(long step)
{
switch (step & 0x7)
{
case 0: // 1000
setOutputPins(0b0001);
break;
case 1: // 1010
setOutputPins(0b0101);
break;
case 2: // 0010
setOutputPins(0b0100);
break;
case 3: // 0110
setOutputPins(0b0110);
break;
case 4: // 0100
setOutputPins(0b0010);
break;
case 5: //0101
setOutputPins(0b1010);
break;
case 6: // 0001
setOutputPins(0b1000);
break;
case 7: //1001
setOutputPins(0b1001);
break;
}
}
// Prevents power consumption on the outputs
void AccelStepper::disableOutputs()
{
if (! _interface) return;
setOutputPins(0); // Handles inversion automatically
if (_enablePin != 0xff)
{
pinMode(_enablePin, OUTPUT);
digitalWrite(_enablePin, LOW ^ _enableInverted);
}
}
void AccelStepper::enableOutputs()
{
if (! _interface)
return;
pinMode(_pin[0], OUTPUT);
pinMode(_pin[1], OUTPUT);
if (_interface == FULL4WIRE || _interface == HALF4WIRE)
{
pinMode(_pin[2], OUTPUT);
pinMode(_pin[3], OUTPUT);
}
else if (_interface == FULL3WIRE || _interface == HALF3WIRE)
{
pinMode(_pin[2], OUTPUT);
}
if (_enablePin != 0xff)
{
pinMode(_enablePin, OUTPUT);
digitalWrite(_enablePin, HIGH ^ _enableInverted);
}
}
void AccelStepper::setMinPulseWidth(unsigned int minWidth)
{
_minPulseWidth = minWidth;
}
void AccelStepper::setEnablePin(uint8_t enablePin)
{
_enablePin = enablePin;
// This happens after construction, so init pin now.
if (_enablePin != 0xff)
{
pinMode(_enablePin, OUTPUT);
digitalWrite(_enablePin, HIGH ^ _enableInverted);
}
}
void AccelStepper::setPinsInverted(bool directionInvert, bool stepInvert, bool enableInvert)
{
_pinInverted[0] = stepInvert;
_pinInverted[1] = directionInvert;
_enableInverted = enableInvert;
}
void AccelStepper::setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)
{
_pinInverted[0] = pin1Invert;
_pinInverted[1] = pin2Invert;
_pinInverted[2] = pin3Invert;
_pinInverted[3] = pin4Invert;
_enableInverted = enableInvert;
}
// Blocks until the target position is reached and stopped
void AccelStepper::runToPosition()
{
while (run())
;
}
boolean AccelStepper::runSpeedToPosition()
{
if (_targetPos == _currentPos)
return false;
if (_targetPos >_currentPos)
_direction = DIRECTION_CW;
else
_direction = DIRECTION_CCW;
return runSpeed();
}
// Blocks until the new target position is reached
void AccelStepper::runToNewPosition(long position)
{
moveTo(position);
runToPosition();
}
void AccelStepper::stop()
{
if (_speed != 0.0)
{
long stepsToStop = (long)((_speed * _speed) / (2.0 * _acceleration)) + 1; // Equation 16 (+integer rounding)
if (_speed > 0)
move(stepsToStop);
else
move(-stepsToStop);
}
}
bool AccelStepper::isRunning()
{
return !(_speed == 0.0 && _targetPos == _currentPos);
}

@ -0,0 +1,714 @@
// AccelStepper.h
//
/// \mainpage AccelStepper library for Arduino
///
/// This is the Arduino AccelStepper library.
/// It provides an object-oriented interface for 2, 3 or 4 pin stepper motors.
///
/// The standard Arduino IDE includes the Stepper library
/// (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is
/// perfectly adequate for simple, single motor applications.
///
/// AccelStepper significantly improves on the standard Arduino Stepper library in several ways:
/// \li Supports acceleration and deceleration
/// \li Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper
/// \li API functions never delay() or block
/// \li Supports 2, 3 and 4 wire steppers, plus 3 and 4 wire half steppers.
/// \li Supports alternate stepping functions to enable support of AFMotor (https://github.com/adafruit/Adafruit-Motor-Shield-library)
/// \li Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip)
/// \li Very slow speeds are supported
/// \li Extensive API
/// \li Subclass support
///
/// The latest version of this documentation can be downloaded from
/// http://www.airspayce.com/mikem/arduino/AccelStepper
/// The version of the package that this documentation refers to can be downloaded
/// from http://www.airspayce.com/mikem/arduino/AccelStepper/AccelStepper-1.53.zip
///
/// Example Arduino programs are included to show the main modes of use.
///
/// You can also find online help and discussion at http://groups.google.com/group/accelstepper
/// Please use that group for all questions and discussions on this topic.
/// Do not contact the author directly, unless it is to discuss commercial licensing.
/// Before asking a question or reporting a bug, please read http://www.catb.org/esr/faqs/smart-questions.html
///
/// Tested on Arduino Diecimila and Mega with arduino-0018 & arduino-0021
/// on OpenSuSE 11.1 and avr-libc-1.6.1-1.15,
/// cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5.
/// Tested on Teensy http://www.pjrc.com/teensy including Teensy 3.1 built using Arduino IDE 1.0.5 with
/// teensyduino addon 1.18 and later.
///
/// \par Installation
///
/// Install in the usual way: unzip the distribution zip file to the libraries
/// sub-folder of your sketchbook.
///
/// \par Theory
///
/// This code uses speed calculations as described in
/// "Generate stepper-motor speed profiles in real time" by David Austin
/// http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf or
/// http://www.embedded.com/design/mcus-processors-and-socs/4006438/Generate-stepper-motor-speed-profiles-in-real-time or
/// http://web.archive.org/web/20140705143928/http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf
/// with the exception that AccelStepper uses steps per second rather than radians per second
/// (because we dont know the step angle of the motor)
/// An initial step interval is calculated for the first step, based on the desired acceleration
/// On subsequent steps, shorter step intervals are calculated based
/// on the previous step until max speed is achieved.
///
/// \par Adafruit Motor Shield V2
///
/// The included examples AFMotor_* are for Adafruit Motor Shield V1 and do not work with Adafruit Motor Shield V2.
/// See https://github.com/adafruit/Adafruit_Motor_Shield_V2_Library for examples that work with Adafruit Motor Shield V2.
///
/// \par Donations
///
/// This library is offered under a free GPL license for those who want to use it that way.
/// We try hard to keep it up to date, fix bugs
/// and to provide free support. If this library has helped you save time or money, please consider donating at
/// http://www.airspayce.com or here:
///
/// \htmlonly <form action="https://www.paypal.com/cgi-bin/webscr" method="post"><input type="hidden" name="cmd" value="_donations" /> <input type="hidden" name="business" value="mikem@airspayce.com" /> <input type="hidden" name="lc" value="AU" /> <input type="hidden" name="item_name" value="Airspayce" /> <input type="hidden" name="item_number" value="AccelStepper" /> <input type="hidden" name="currency_code" value="USD" /> <input type="hidden" name="bn" value="PP-DonationsBF:btn_donateCC_LG.gif:NonHosted" /> <input type="image" alt="PayPal — The safer, easier way to pay online." name="submit" src="https://www.paypalobjects.com/en_AU/i/btn/btn_donateCC_LG.gif" /> <img alt="" src="https://www.paypalobjects.com/en_AU/i/scr/pixel.gif" width="1" height="1" border="0" /></form> \endhtmlonly
///
/// \par Trademarks
///
/// AccelStepper is a trademark of AirSpayce Pty Ltd. The AccelStepper mark was first used on April 26 2010 for
/// international trade, and is used only in relation to motor control hardware and software.
/// It is not to be confused with any other similar marks covering other goods and services.
///
/// \par Copyright
///
/// This software is Copyright (C) 2010 Mike McCauley. Use is subject to license
/// conditions. The main licensing options available are GPL V2 or Commercial:
///
/// \par Open Source Licensing GPL V2
/// This is the appropriate option if you want to share the source code of your
/// application with everyone you distribute it to, and you also want to give them
/// the right to share who uses it. If you wish to use this software under Open
/// Source Licensing, you must contribute all your source code to the open source
/// community in accordance with the GPL Version 2 when your application is
/// distributed. See http://www.gnu.org/copyleft/gpl.html
///
/// \par Commercial Licensing
/// This is the appropriate option if you are creating proprietary applications
/// and you are not prepared to distribute and share the source code of your
/// application. Contact info@airspayce.com for details.
///
/// \par Revision History
/// \version 1.0 Initial release
///
/// \version 1.1 Added speed() function to get the current speed.
/// \version 1.2 Added runSpeedToPosition() submitted by Gunnar Arndt.
/// \version 1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1
/// \version 1.4 Added functional contructor to support AFMotor, contributed by Limor, with example sketches.
/// \version 1.5 Improvements contributed by Peter Mousley: Use of microsecond steps and other speed improvements
/// to increase max stepping speed to about 4kHz. New option for user to set the min allowed pulse width.
/// Added checks for already running at max speed and skip further calcs if so.
/// \version 1.6 Fixed a problem with wrapping of microsecond stepping that could cause stepping to hang.
/// Reported by Sandy Noble.
/// Removed redundant _lastRunTime member.
/// \version 1.7 Fixed a bug where setCurrentPosition() did not always work as expected.
/// Reported by Peter Linhart.
/// \version 1.8 Added support for 4 pin half-steppers, requested by Harvey Moon
/// \version 1.9 setCurrentPosition() now also sets motor speed to 0.
/// \version 1.10 Builds on Arduino 1.0
/// \version 1.11 Improvments from Michael Ellison:
/// Added optional enable line support for stepper drivers
/// Added inversion for step/direction/enable lines for stepper drivers
/// \version 1.12 Announce Google Group
/// \version 1.13 Improvements to speed calculation. Cost of calculation is now less in the worst case,
/// and more or less constant in all cases. This should result in slightly beter high speed performance, and
/// reduce anomalous speed glitches when other steppers are accelerating.
/// However, its hard to see how to replace the sqrt() required at the very first step from 0 speed.
/// \version 1.14 Fixed a problem with compiling under arduino 0021 reported by EmbeddedMan
/// \version 1.15 Fixed a problem with runSpeedToPosition which did not correctly handle
/// running backwards to a smaller target position. Added examples
/// \version 1.16 Fixed some cases in the code where abs() was used instead of fabs().
/// \version 1.17 Added example ProportionalControl
/// \version 1.18 Fixed a problem: If one calls the funcion runSpeed() when Speed is zero, it makes steps
/// without counting. reported by Friedrich, Klappenbach.
/// \version 1.19 Added MotorInterfaceType and symbolic names for the number of pins to use
/// for the motor interface. Updated examples to suit.
/// Replaced individual pin assignment variables _pin1, _pin2 etc with array _pin[4].
/// _pins member changed to _interface.
/// Added _pinInverted array to simplify pin inversion operations.
/// Added new function setOutputPins() which sets the motor output pins.
/// It can be overridden in order to provide, say, serial output instead of parallel output
/// Some refactoring and code size reduction.
/// \version 1.20 Improved documentation and examples to show need for correctly
/// specifying AccelStepper::FULL4WIRE and friends.
/// \version 1.21 Fixed a problem where desiredSpeed could compute the wrong step acceleration
/// when _speed was small but non-zero. Reported by Brian Schmalz.
/// Precompute sqrt_twoa to improve performance and max possible stepping speed
/// \version 1.22 Added Bounce.pde example
/// Fixed a problem where calling moveTo(), setMaxSpeed(), setAcceleration() more
/// frequently than the step time, even
/// with the same values, would interfere with speed calcs. Now a new speed is computed
/// only if there was a change in the set value. Reported by Brian Schmalz.
/// \version 1.23 Rewrite of the speed algorithms in line with
/// http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf
/// Now expect smoother and more linear accelerations and decelerations. The desiredSpeed()
/// function was removed.
/// \version 1.24 Fixed a problem introduced in 1.23: with runToPosition, which did never returned
/// \version 1.25 Now ignore attempts to set acceleration to 0.0
/// \version 1.26 Fixed a problem where certina combinations of speed and accelration could cause
/// oscillation about the target position.
/// \version 1.27 Added stop() function to stop as fast as possible with current acceleration parameters.
/// Also added new Quickstop example showing its use.
/// \version 1.28 Fixed another problem where certain combinations of speed and accelration could cause
/// oscillation about the target position.
/// Added support for 3 wire full and half steppers such as Hard Disk Drive spindle.
/// Contributed by Yuri Ivatchkovitch.
/// \version 1.29 Fixed a problem that could cause a DRIVER stepper to continually step
/// with some sketches. Reported by Vadim.
/// \version 1.30 Fixed a problem that could cause stepper to back up a few steps at the end of
/// accelerated travel with certain speeds. Reported and patched by jolo.
/// \version 1.31 Updated author and distribution location details to airspayce.com
/// \version 1.32 Fixed a problem with enableOutputs() and setEnablePin on Arduino Due that
/// prevented the enable pin changing stae correctly. Reported by Duane Bishop.
/// \version 1.33 Fixed an error in example AFMotor_ConstantSpeed.pde did not setMaxSpeed();
/// Fixed a problem that caused incorrect pin sequencing of FULL3WIRE and HALF3WIRE.
/// Unfortunately this meant changing the signature for all step*() functions.
/// Added example MotorShield, showing how to use AdaFruit Motor Shield to control
/// a 3 phase motor such as a HDD spindle motor (and without using the AFMotor library.
/// \version 1.34 Added setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)
/// to allow inversion of 2, 3 and 4 wire stepper pins. Requested by Oleg.
/// \version 1.35 Removed default args from setPinsInverted(bool, bool, bool, bool, bool) to prevent ambiguity with
/// setPinsInverted(bool, bool, bool). Reported by Mac Mac.
/// \version 1.36 Changed enableOutputs() and disableOutputs() to be virtual so can be overridden.
/// Added new optional argument 'enable' to constructor, which allows you toi disable the
/// automatic enabling of outputs at construction time. Suggested by Guido.
/// \version 1.37 Fixed a problem with step1 that could cause a rogue step in the
/// wrong direction (or not,
/// depending on the setup-time requirements of the connected hardware).
/// Reported by Mark Tillotson.
/// \version 1.38 run() function incorrectly always returned true. Updated function and doc so it returns true
/// if the motor is still running to the target position.
/// \version 1.39 Updated typos in keywords.txt, courtesey Jon Magill.
/// \version 1.40 Updated documentation, including testing on Teensy 3.1
/// \version 1.41 Fixed an error in the acceleration calculations, resulting in acceleration of haldf the intended value
/// \version 1.42 Improved support for FULL3WIRE and HALF3WIRE output pins. These changes were in Yuri's original
/// contribution but did not make it into production.<br>
/// \version 1.43 Added DualMotorShield example. Shows how to use AccelStepper to control 2 x 2 phase steppers using the
/// Itead Studio Arduino Dual Stepper Motor Driver Shield model IM120417015.<br>
/// \version 1.44 examples/DualMotorShield/DualMotorShield.ino examples/DualMotorShield/DualMotorShield.pde
/// was missing from the distribution.<br>
/// \version 1.45 Fixed a problem where if setAcceleration was not called, there was no default
/// acceleration. Reported by Michael Newman.<br>
/// \version 1.45 Fixed inaccuracy in acceleration rate by using Equation 15, suggested by Sebastian Gracki.<br>
/// Performance improvements in runSpeed suggested by Jaakko Fagerlund.<br>
/// \version 1.46 Fixed error in documentation for runToPosition().
/// Reinstated time calculations in runSpeed() since new version is reported
/// not to work correctly under some circumstances. Reported by Oleg V Gavva.<br>
/// \version 1.48 2015-08-25
/// Added new class MultiStepper that can manage multiple AccelSteppers,
/// and cause them all to move
/// to selected positions at such a (constant) speed that they all arrive at their
/// target position at the same time. Suitable for X-Y flatbeds etc.<br>
/// Added new method maxSpeed() to AccelStepper to return the currently configured maxSpeed.<br>
/// \version 1.49 2016-01-02
/// Testing with VID28 series instrument stepper motors and EasyDriver.
/// OK, although with light pointers
/// and slow speeds like 180 full steps per second the motor movement can be erratic,
/// probably due to some mechanical resonance. Best to accelerate through this speed.<br>
/// Added isRunning().<br>
/// \version 1.50 2016-02-25
/// AccelStepper::disableOutputs now sets the enable pion to OUTPUT mode if the enable pin is defined.
/// Patch from Piet De Jong.<br>
/// Added notes about the fact that AFMotor_* examples do not work with Adafruit Motor Shield V2.<br>
/// \version 1.51 2016-03-24
/// Fixed a problem reported by gregor: when resetting the stepper motor position using setCurrentPosition() the
/// stepper speed is reset by setting _stepInterval to 0, but _speed is not
/// reset. this results in the stepper motor not starting again when calling
/// setSpeed() with the same speed the stepper was set to before.
/// \version 1.52 2016-08-09
/// Added MultiStepper to keywords.txt.
/// Improvements to efficiency of AccelStepper::runSpeed() as suggested by David Grayson.
/// Improvements to speed accuracy as suggested by David Grayson.
/// \verwsion 1.53 2016-08-14
/// Backed out Improvements to speed accuracy from 1.52 as it did not work correctly.
///
/// \author Mike McCauley (mikem@airspayce.com) DO NOT CONTACT THE AUTHOR DIRECTLY: USE THE LISTS
// Copyright (C) 2009-2013 Mike McCauley
// $Id: AccelStepper.h,v 1.26 2016/08/09 00:39:10 mikem Exp mikem $
#ifndef AccelStepper_h
#define AccelStepper_h
#include <stdlib.h>
#if ARDUINO >= 100
#include <Arduino.h>
#else
#include <WProgram.h>
#include <wiring.h>
#endif
// These defs cause trouble on some versions of Arduino
#undef round
/////////////////////////////////////////////////////////////////////
/// \class AccelStepper AccelStepper.h <AccelStepper.h>
/// \brief Support for stepper motors with acceleration etc.
///
/// This defines a single 2 or 4 pin stepper motor, or stepper moter with fdriver chip, with optional
/// acceleration, deceleration, absolute positioning commands etc. Multiple
/// simultaneous steppers are supported, all moving
/// at different speeds and accelerations.
///
/// \par Operation
/// This module operates by computing a step time in microseconds. The step
/// time is recomputed after each step and after speed and acceleration
/// parameters are changed by the caller. The time of each step is recorded in
/// microseconds. The run() function steps the motor once if a new step is due.
/// The run() function must be called frequently until the motor is in the
/// desired position, after which time run() will do nothing.
///
/// \par Positioning
/// Positions are specified by a signed long integer. At
/// construction time, the current position of the motor is consider to be 0. Positive
/// positions are clockwise from the initial position; negative positions are
/// anticlockwise. The current position can be altered for instance after
/// initialization positioning.
///
/// \par Caveats
/// This is an open loop controller: If the motor stalls or is oversped,
/// AccelStepper will not have a correct
/// idea of where the motor really is (since there is no feedback of the motor's
/// real position. We only know where we _think_ it is, relative to the
/// initial starting point).
///
/// \par Performance
/// The fastest motor speed that can be reliably supported is about 4000 steps per
/// second at a clock frequency of 16 MHz on Arduino such as Uno etc.
/// Faster processors can support faster stepping speeds.
/// However, any speed less than that
/// down to very slow speeds (much less than one per second) are also supported,
/// provided the run() function is called frequently enough to step the motor
/// whenever required for the speed set.
/// Calling setAcceleration() is expensive,
/// since it requires a square root to be calculated.
///
/// Gregor Christandl reports that with an Arduino Due and a simple test program,
/// he measured 43163 steps per second using runSpeed(),
/// and 16214 steps per second using run();
class AccelStepper
{
public:
/// \brief Symbolic names for number of pins.
/// Use this in the pins argument the AccelStepper constructor to
/// provide a symbolic name for the number of pins
/// to use.
typedef enum
{
FUNCTION = 0, ///< Use the functional interface, implementing your own driver functions (internal use only)
DRIVER = 1, ///< Stepper Driver, 2 driver pins required
FULL2WIRE = 2, ///< 2 wire stepper, 2 motor pins required
FULL3WIRE = 3, ///< 3 wire stepper, such as HDD spindle, 3 motor pins required
FULL4WIRE = 4, ///< 4 wire full stepper, 4 motor pins required
HALF3WIRE = 6, ///< 3 wire half stepper, such as HDD spindle, 3 motor pins required
HALF4WIRE = 8 ///< 4 wire half stepper, 4 motor pins required
} MotorInterfaceType;
/// Constructor. You can have multiple simultaneous steppers, all moving
/// at different speeds and accelerations, provided you call their run()
/// functions at frequent enough intervals. Current Position is set to 0, target
/// position is set to 0. MaxSpeed and Acceleration default to 1.0.
/// The motor pins will be initialised to OUTPUT mode during the
/// constructor by a call to enableOutputs().
/// \param[in] interface Number of pins to interface to. 1, 2, 4 or 8 are
/// supported, but it is preferred to use the \ref MotorInterfaceType symbolic names.
/// AccelStepper::DRIVER (1) means a stepper driver (with Step and Direction pins).
/// If an enable line is also needed, call setEnablePin() after construction.
/// You may also invert the pins using setPinsInverted().
/// AccelStepper::FULL2WIRE (2) means a 2 wire stepper (2 pins required).
/// AccelStepper::FULL3WIRE (3) means a 3 wire stepper, such as HDD spindle (3 pins required).
/// AccelStepper::FULL4WIRE (4) means a 4 wire stepper (4 pins required).
/// AccelStepper::HALF3WIRE (6) means a 3 wire half stepper, such as HDD spindle (3 pins required)
/// AccelStepper::HALF4WIRE (8) means a 4 wire half stepper (4 pins required)
/// Defaults to AccelStepper::FULL4WIRE (4) pins.
/// \param[in] pin1 Arduino digital pin number for motor pin 1. Defaults
/// to pin 2. For a AccelStepper::DRIVER (interface==1),
/// this is the Step input to the driver. Low to high transition means to step)
/// \param[in] pin2 Arduino digital pin number for motor pin 2. Defaults
/// to pin 3. For a AccelStepper::DRIVER (interface==1),
/// this is the Direction input the driver. High means forward.
/// \param[in] pin3 Arduino digital pin number for motor pin 3. Defaults
/// to pin 4.
/// \param[in] pin4 Arduino digital pin number for motor pin 4. Defaults
/// to pin 5.
/// \param[in] enable If this is true (the default), enableOutputs() will be called to enable
/// the output pins at construction time.
AccelStepper(uint8_t interface = AccelStepper::FULL4WIRE, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5, bool enable = true);
/// Alternate Constructor which will call your own functions for forward and backward steps.
/// You can have multiple simultaneous steppers, all moving
/// at different speeds and accelerations, provided you call their run()
/// functions at frequent enough intervals. Current Position is set to 0, target
/// position is set to 0. MaxSpeed and Acceleration default to 1.0.
/// Any motor initialization should happen before hand, no pins are used or initialized.
/// \param[in] forward void-returning procedure that will make a forward step
/// \param[in] backward void-returning procedure that will make a backward step
AccelStepper(void (*forward)(), void (*backward)());
/// Set the target position. The run() function will try to move the motor (at most one step per call)
/// from the current position to the target position set by the most
/// recent call to this function. Caution: moveTo() also recalculates the speed for the next step.
/// If you are trying to use constant speed movements, you should call setSpeed() after calling moveTo().
/// \param[in] absolute The desired absolute position. Negative is
/// anticlockwise from the 0 position.
void moveTo(long absolute);
/// Set the target position relative to the current position
/// \param[in] relative The desired position relative to the current position. Negative is
/// anticlockwise from the current position.
void move(long relative);
/// Poll the motor and step it if a step is due, implementing
/// accelerations and decelerations to acheive the target position. You must call this as
/// frequently as possible, but at least once per minimum step time interval,
/// preferably in your main loop. Note that each call to run() will make at most one step, and then only when a step is due,
/// based on the current speed and the time since the last step.
/// \return true if the motor is still running to the target position.
boolean run();
/// Poll the motor and step it if a step is due, implementing a constant
/// speed as set by the most recent call to setSpeed(). You must call this as
/// frequently as possible, but at least once per step interval,
/// \return true if the motor was stepped.
boolean runSpeed();
/// Sets the maximum permitted speed. The run() function will accelerate
/// up to the speed set by this function.
/// Caution: the maximum speed achievable depends on your processor and clock speed.
/// \param[in] speed The desired maximum speed in steps per second. Must
/// be > 0. Caution: Speeds that exceed the maximum speed supported by the processor may
/// Result in non-linear accelerations and decelerations.
void setMaxSpeed(float speed);
/// returns the maximum speed configured for this stepper
/// that was previously set by setMaxSpeed();
/// \return The currently configured maximum speed
float maxSpeed();
/// Sets the acceleration/deceleration rate.
/// \param[in] acceleration The desired acceleration in steps per second
/// per second. Must be > 0.0. This is an expensive call since it requires a square
/// root to be calculated. Dont call more ofthen than needed
void setAcceleration(float acceleration);
/// Sets the desired constant speed for use with runSpeed().
/// \param[in] speed The desired constant speed in steps per
/// second. Positive is clockwise. Speeds of more than 1000 steps per
/// second are unreliable. Very slow speeds may be set (eg 0.00027777 for
/// once per hour, approximately. Speed accuracy depends on the Arduino
/// crystal. Jitter depends on how frequently you call the runSpeed() function.
void setSpeed(float speed);
/// The most recently set speed
/// \return the most recent speed in steps per second
float speed();
/// The distance from the current position to the target position.
/// \return the distance from the current position to the target position
/// in steps. Positive is clockwise from the current position.
long distanceToGo();
/// The most recently set target position.
/// \return the target position
/// in steps. Positive is clockwise from the 0 position.
long targetPosition();
/// The currently motor position.
/// \return the current motor position
/// in steps. Positive is clockwise from the 0 position.
long currentPosition();
/// Resets the current position of the motor, so that wherever the motor
/// happens to be right now is considered to be the new 0 position. Useful
/// for setting a zero position on a stepper after an initial hardware
/// positioning move.
/// Has the side effect of setting the current motor speed to 0.
/// \param[in] position The position in steps of wherever the motor
/// happens to be right now.
void setCurrentPosition(long position);
/// Moves the motor (with acceleration/deceleration)
/// to the target position and blocks until it is at
/// position. Dont use this in event loops, since it blocks.
void runToPosition();
/// Runs at the currently selected speed until the target position is reached
/// Does not implement accelerations.
/// \return true if it stepped
boolean runSpeedToPosition();
/// Moves the motor (with acceleration/deceleration)
/// to the new target position and blocks until it is at
/// position. Dont use this in event loops, since it blocks.
/// \param[in] position The new target position.
void runToNewPosition(long position);
/// Sets a new target position that causes the stepper
/// to stop as quickly as possible, using the current speed and acceleration parameters.
void stop();
/// Disable motor pin outputs by setting them all LOW
/// Depending on the design of your electronics this may turn off
/// the power to the motor coils, saving power.
/// This is useful to support Arduino low power modes: disable the outputs
/// during sleep and then reenable with enableOutputs() before stepping
/// again.
/// If the enable Pin is defined, sets it to OUTPUT mode and clears the pin to disabled.
virtual void disableOutputs();
/// Enable motor pin outputs by setting the motor pins to OUTPUT
/// mode. Called automatically by the constructor.
/// If the enable Pin is defined, sets it to OUTPUT mode and sets the pin to enabled.
virtual void enableOutputs();
/// Sets the minimum pulse width allowed by the stepper driver. The minimum practical pulse width is
/// approximately 20 microseconds. Times less than 20 microseconds
/// will usually result in 20 microseconds or so.
/// \param[in] minWidth The minimum pulse width in microseconds.
void setMinPulseWidth(unsigned int minWidth);
/// Sets the enable pin number for stepper drivers.
/// 0xFF indicates unused (default).
/// Otherwise, if a pin is set, the pin will be turned on when
/// enableOutputs() is called and switched off when disableOutputs()
/// is called.
/// \param[in] enablePin Arduino digital pin number for motor enable
/// \sa setPinsInverted
void setEnablePin(uint8_t enablePin = 0xff);
/// Sets the inversion for stepper driver pins
/// \param[in] directionInvert True for inverted direction pin, false for non-inverted
/// \param[in] stepInvert True for inverted step pin, false for non-inverted
/// \param[in] enableInvert True for inverted enable pin, false (default) for non-inverted
void setPinsInverted(bool directionInvert = false, bool stepInvert = false, bool enableInvert = false);
/// Sets the inversion for 2, 3 and 4 wire stepper pins
/// \param[in] pin1Invert True for inverted pin1, false for non-inverted
/// \param[in] pin2Invert True for inverted pin2, false for non-inverted
/// \param[in] pin3Invert True for inverted pin3, false for non-inverted
/// \param[in] pin4Invert True for inverted pin4, false for non-inverted
/// \param[in] enableInvert True for inverted enable pin, false (default) for non-inverted
void setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert);
/// Checks to see if the motor is currently running to a target
/// \return true if the speed is not zero or not at the target position
bool isRunning();
protected:
/// \brief Direction indicator
/// Symbolic names for the direction the motor is turning
typedef enum
{
DIRECTION_CCW = 0, ///< Clockwise
DIRECTION_CW = 1 ///< Counter-Clockwise
} Direction;
/// Forces the library to compute a new instantaneous speed and set that as
/// the current speed. It is called by
/// the library:
/// \li after each step
/// \li after change to maxSpeed through setMaxSpeed()
/// \li after change to acceleration through setAcceleration()
/// \li after change to target position (relative or absolute) through
/// move() or moveTo()
void computeNewSpeed();
/// Low level function to set the motor output pins
/// bit 0 of the mask corresponds to _pin[0]
/// bit 1 of the mask corresponds to _pin[1]
/// You can override this to impment, for example serial chip output insted of using the
/// output pins directly
virtual void setOutputPins(uint8_t mask);
/// Called to execute a step. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default calls step1(), step2(), step4() or step8() depending on the
/// number of pins defined for the stepper.
/// \param[in] step The current step phase number (0 to 7)
virtual void step(long step);
/// Called to execute a step using stepper functions (pins = 0) Only called when a new step is
/// required. Calls _forward() or _backward() to perform the step
/// \param[in] step The current step phase number (0 to 7)
virtual void step0(long step);
/// Called to execute a step on a stepper driver (ie where pins == 1). Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of Step pin1 to step,
/// and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond
/// which is the minimum STEP pulse width for the 3967 driver.
/// \param[in] step The current step phase number (0 to 7)
virtual void step1(long step);
/// Called to execute a step on a 2 pin motor. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1 and pin2
/// \param[in] step The current step phase number (0 to 7)
virtual void step2(long step);
/// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1, pin2,
/// pin3
/// \param[in] step The current step phase number (0 to 7)
virtual void step3(long step);
/// Called to execute a step on a 4 pin motor. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1, pin2,
/// pin3, pin4.
/// \param[in] step The current step phase number (0 to 7)
virtual void step4(long step);
/// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1, pin2,
/// pin3
/// \param[in] step The current step phase number (0 to 7)
virtual void step6(long step);
/// Called to execute a step on a 4 pin half-steper motor. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1, pin2,
/// pin3, pin4.
/// \param[in] step The current step phase number (0 to 7)
virtual void step8(long step);
private:
/// Number of pins on the stepper motor. Permits 2 or 4. 2 pins is a
/// bipolar, and 4 pins is a unipolar.
uint8_t _interface; // 0, 1, 2, 4, 8, See MotorInterfaceType
/// Arduino pin number assignments for the 2 or 4 pins required to interface to the
/// stepper motor or driver
uint8_t _pin[4];
/// Whether the _pins is inverted or not
uint8_t _pinInverted[4];
/// The current absolution position in steps.
long _currentPos; // Steps
/// The target position in steps. The AccelStepper library will move the
/// motor from the _currentPos to the _targetPos, taking into account the
/// max speed, acceleration and deceleration
long _targetPos; // Steps
/// The current motos speed in steps per second
/// Positive is clockwise
float _speed; // Steps per second
/// The maximum permitted speed in steps per second. Must be > 0.
float _maxSpeed;
/// The acceleration to use to accelerate or decelerate the motor in steps
/// per second per second. Must be > 0
float _acceleration;
float _sqrt_twoa; // Precomputed sqrt(2*_acceleration)
/// The current interval between steps in microseconds.
/// 0 means the motor is currently stopped with _speed == 0
unsigned long _stepInterval;
/// The last step time in microseconds
unsigned long _lastStepTime;
/// The minimum allowed pulse width in microseconds
unsigned int _minPulseWidth;
/// Is the direction pin inverted?
///bool _dirInverted; /// Moved to _pinInverted[1]
/// Is the step pin inverted?
///bool _stepInverted; /// Moved to _pinInverted[0]
/// Is the enable pin inverted?
bool _enableInverted;
/// Enable pin for stepper driver, or 0xFF if unused.
uint8_t _enablePin;
/// The pointer to a forward-step procedure
void (*_forward)();
/// The pointer to a backward-step procedure
void (*_backward)();
/// The step counter for speed calculations
long _n;
/// Initial step size in microseconds
float _c0;
/// Last step size in microseconds
float _cn;
/// Min step size in microseconds based on maxSpeed
float _cmin; // at max speed
/// Current direction motor is spinning in
boolean _direction; // 1 == CW
};
/// @example Random.pde
/// Make a single stepper perform random changes in speed, position and acceleration
/// @example Overshoot.pde
/// Check overshoot handling
/// which sets a new target position and then waits until the stepper has
/// achieved it. This is used for testing the handling of overshoots
/// @example MultipleSteppers.pde
/// Shows how to multiple simultaneous steppers
/// Runs one stepper forwards and backwards, accelerating and decelerating
/// at the limits. Runs other steppers at the same time
/// @example ConstantSpeed.pde
/// Shows how to run AccelStepper in the simplest,
/// fixed speed mode with no accelerations
/// @example Blocking.pde
/// Shows how to use the blocking call runToNewPosition
/// Which sets a new target position and then waits until the stepper has
/// achieved it.
/// @example AFMotor_MultiStepper.pde
/// Control both Stepper motors at the same time with different speeds
/// and accelerations.
/// @example AFMotor_ConstantSpeed.pde
/// Shows how to run AccelStepper in the simplest,
/// fixed speed mode with no accelerations
/// @example ProportionalControl.pde
/// Make a single stepper follow the analog value read from a pot or whatever
/// The stepper will move at a constant speed to each newly set posiiton,
/// depending on the value of the pot.
/// @example Bounce.pde
/// Make a single stepper bounce from one limit to another, observing
/// accelrations at each end of travel
/// @example Quickstop.pde
/// Check stop handling.
/// Calls stop() while the stepper is travelling at full speed, causing
/// the stepper to stop as quickly as possible, within the constraints of the
/// current acceleration.
/// @example MotorShield.pde
/// Shows how to use AccelStepper to control a 3-phase motor, such as a HDD spindle motor
/// using the Adafruit Motor Shield http://www.ladyada.net/make/mshield/index.html.
/// @example DualMotorShield.pde
/// Shows how to use AccelStepper to control 2 x 2 phase steppers using the
/// Itead Studio Arduino Dual Stepper Motor Driver Shield
/// model IM120417015
#endif

@ -0,0 +1,31 @@
#ifndef CONFIGURATION_H //Falls Check Variable, nicht schon definiert..
#define CONFIGURATION_H //.. Wird si nun definiert, und alle Konfigurationen Neu geladen.
#define maestroSerial SERIAL_PORT_HARDWARE_OPEN // Festlegen unserer maestroSerial Variable
// Stepper Treiber Variabeln
#define X_INTERFACE_TYPE 1 // Festlegen des Interface Typs
#define X_STEP_PIN 3 // Festlegen des Stepper Treiber, Stitte Pins
#define X_DIR_PIN 4 // Festlegen des Stepper Treiber, Dir Pins
// Stepper Motor Konfiguration
#define X_PARK_SPEED 150 // Geschwindigkeit, kurz vor den Führungsenden
#define X_HOME_SPEED 700 // Geschwindikeit, um zur (Start), Ausgangsposition zurückzukehren.
#define X_MAX_SPEED 1500 // Die Maximale Geschwindikeit, die zulässig ist.
#define X_ACCELERATION 3000 // Acceleration/deceleration in Schritten pro Sekunde, in einer Sekunde
#define X_MAX_POS -4995 // Der maximale Wert, für die Positionierung der X Achse! (Sicherheit falls App falsch konfiguriert.)
// Servo Motor Konfiguration
#define SERVO_MAX_POS 4120 // Servo Getränke Auslass Position (Sollte ca. Passen, wird noch angepasst!)
#define SERVO_MIN_POS 6000 // Servo Ausgangsposition (Links nach unten zeigend..)
#define SERVO_RAISE_SPEED 30 // Die max. Geschwindigkeit des Servos, von der Max, zur Min(Normal), Position.
#define SERVO_RELEASE_SPEED 0 // Die max. Geschwindigkeit des Servos, von der Min, zur Max, Position.
// Endstop Schaltung
#define X_ENDSTOP_PIN 5 // Festlegen des Pins, für den Endstop
// Weiteres
#define TOTAL_ACTIONS 30 // Totale Anzahl von ausführbaren Abfolgen, pro Auftrag
#define DELAY_BETWEEN_INGREDIENTS 600 // Wartezeit, von einer Zutat zur nächsten.
#endif

@ -0,0 +1,223 @@
// Copyright (C) Pololu Corporation. See LICENSE.txt for details.
#include "PololuMaestro.h"
Maestro::Maestro(Stream &stream,
uint8_t resetPin,
uint8_t deviceNumber,
bool CRCEnabled)
{
_stream = &stream;
_deviceNumber = deviceNumber;
_resetPin = resetPin;
_CRCEnabled = CRCEnabled;
}
void Maestro::reset()
{
if (_resetPin != noResetPin)
{
digitalWrite(_resetPin, LOW);
pinMode(_resetPin, OUTPUT); // Drive low.
delay(1);
pinMode(_resetPin, INPUT); // Return to high-impedance input (reset is
// internally pulled up on Maestro).
delay(200); // Wait for Maestro to boot up after reset.
}
}
void Maestro::setTargetMiniSSC(uint8_t channelNumber, uint8_t target)
{
_stream->write(miniSscCommand);
_stream->write(channelNumber);
_stream->write(target);
}
void Maestro::goHome()
{
writeCommand(goHomeCommand);
writeCRC();
}
void Maestro::stopScript()
{
writeCommand(stopScriptCommand);
writeCRC();
}
void Maestro::restartScript(uint8_t subroutineNumber)
{
writeCommand(restartScriptAtSubroutineCommand);
write7BitData(subroutineNumber);
writeCRC();
}
void Maestro::restartScriptWithParameter(uint8_t subroutineNumber,
uint16_t parameter)
{
writeCommand(restartScriptAtSubroutineWithParameterCommand);
write7BitData(subroutineNumber);
write14BitData(parameter);
writeCRC();
}
void Maestro::setTarget(uint8_t channelNumber, uint16_t target)
{
writeCommand(setTargetCommand);
write7BitData(channelNumber);
write14BitData(target);
writeCRC();
}
void Maestro::setSpeed(uint8_t channelNumber, uint16_t speed)
{
writeCommand(setSpeedCommand);
write7BitData(channelNumber);
write14BitData(speed);
writeCRC();
}
void Maestro::setAcceleration(uint8_t channelNumber, uint16_t acceleration)
{
writeCommand(setAccelerationCommand);
write7BitData(channelNumber);
write14BitData(acceleration);
writeCRC();
}
uint16_t Maestro::getPosition(uint8_t channelNumber)
{
writeCommand(getPositionCommand);
write7BitData(channelNumber);
writeCRC();
while (_stream->available() < 2);
uint8_t lowerByte = _stream->read();
uint8_t upperByte = _stream->read();
return (upperByte << 8) | (lowerByte & 0xFF);
}
uint8_t Maestro::getMovingState()
{
writeCommand(getMovingStateCommand);
writeCRC();
while (_stream->available() < 1);
return _stream->read();
}
uint16_t Maestro::getErrors()
{
writeCommand(getErrorsCommand);
writeCRC();
while (_stream->available() < 2);
uint8_t lowerByte = _stream->read();
uint8_t upperByte = _stream->read();
return (upperByte << 8) | (lowerByte & 0xFF);
}
uint8_t Maestro::getScriptStatus()
{
writeCommand(getScriptStatusCommand);
writeCRC();
while (_stream->available() < 1);
return _stream->read();
}
void Maestro::writeByte(uint8_t dataByte)
{
_stream->write(dataByte);
if(_CRCEnabled)
{
_CRCByte ^= dataByte;
for (uint8_t j = 0; j < 8; j++)
{
if (_CRCByte & 1)
{
_CRCByte ^= CRC7Polynomial;
}
_CRCByte >>= 1;
}
}
}
void Maestro::writeCRC()
{
if(_CRCEnabled)
{
_stream->write(_CRCByte);
_CRCByte = 0; // Reset CRCByte to initial value.
}
}
void Maestro::writeCommand(uint8_t commandByte)
{
if (_deviceNumber != deviceNumberDefault)
{
writeByte(baudRateIndication);
write7BitData(_deviceNumber);
write7BitData(commandByte);
}
else
{
writeByte(commandByte);
}
}
void Maestro::write7BitData(uint8_t data)
{
writeByte(data & 0x7F);
}
void Maestro::write14BitData(uint16_t data)
{
writeByte(data & 0x7F);
writeByte((data >> 7) & 0x7F);
}
MicroMaestro::MicroMaestro(Stream &stream,
uint8_t resetPin,
uint8_t deviceNumber,
bool CRCEnabled) : Maestro(stream,
resetPin,
deviceNumber,
CRCEnabled)
{
}
MiniMaestro::MiniMaestro(Stream &stream,
uint8_t resetPin,
uint8_t deviceNumber,
bool CRCEnabled) : Maestro(stream,
resetPin,
deviceNumber,
CRCEnabled)
{
}
void MiniMaestro::setPWM(uint16_t onTime, uint16_t period)
{
writeCommand(setPwmCommand);
write14BitData(onTime);
write14BitData(period);
writeCRC();
}
void MiniMaestro::setMultiTarget(uint8_t numberOfTargets,
uint8_t firstChannel,
uint16_t *targetList)
{
writeCommand(setMultipleTargetsCommand);
write7BitData(numberOfTargets);
write7BitData(firstChannel);
for (int i = 0; i < numberOfTargets; i++)
{
write14BitData(targetList[i]);
}
writeCRC();
}

@ -0,0 +1,381 @@
// Copyright (C) Pololu Corporation. See LICENSE.txt for details.
/*! \file PololuMaestro.h
*
* This is the main header file for the Pololu Maestro Servo Controller library
* for Arduino.
*
*
* For an overview of the library's features, see
* https://github.com/pololu/maestro-arduino. That is the main repository for
* the library.
*/
#pragma once
#include <Arduino.h>
#include <Stream.h>
/*! \brief Main Maestro class that handles common functions between the Micro
* Maestro and Mini Maestro.
*
* The subclasses, MicroMaestro and MiniMaestro inherit all of the functions
* from Maestro. The Maestro class is not meant to be instantiated directly; use
* the MicroMaestro or MiniMaestro subclasses instead.
*/
class Maestro
{
public:
/** \brief The default device number, used to construct a MicroMaestro or
MiniMaestro object that will use the compact protocol.
*/
static const uint8_t deviceNumberDefault = 255;
/** \brief The default reset pin is no reset pin, used to construct a
MicroMaestro or MiniMaestro object that will not have a reset pin.
*/
static const uint8_t noResetPin = 255;
/** \brief Resets the Maestro by toggling the \p resetPin, if a \p resetPin
* was given.
*
* By default this function will do nothing. If the \p resetPin was
* specified while constructing the Maestro object, it will toggle that pin.
* That pin needs to be wired to the Maestro's RST pin for it to reset the
* servo controller.
*/
void reset();
/** \brief Sets the \a target of the servo on \a channelNumber using the
* Mini SSC protocol.
*
* @param channelNumber A servo number from 0 to 254.
*
* @param target A target position from 0 to 254.
*
*/
void setTargetMiniSSC(uint8_t channelNumber, uint8_t target);
/** \brief Sets the \a target of the servo on \a channelNumber.
*
* @param channelNumber A servo number from 0 to 127.
*
* @param target A number from 0 to 16383.
*
* If the channel is configured as a servo, then the target represents the
* pulse width to transmit in units of quarter-microseconds. A \a target
* value of 0 tells the Maestro to stop sending pulses to the servo.
*
* If the channel is configured as a digital output, values less than 6000
* tell the Maestro to drive the line low, while values of 6000 or greater
* tell the Maestro to drive the line high.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
void setTarget(uint8_t channelNumber, uint16_t target);
/** \brief Sets the \a speed limit of \a channelNumber.
*
* @param channelNumber A servo number from 0 to 127.
*
* @param speed A number from 0 to 16383.
*
* Limits the speed a servo channels output value changes.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
void setSpeed(uint8_t channelNumber, uint16_t speed);
/** \brief Sets the \a acceleration limit of \a channelNumber.
*
* @param channelNumber A servo number from 0 to 127.
*
* @param acceleration A number from 0 to 16383.
*
* Limits the acceleration a servo channels output value changes.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
void setAcceleration(uint8_t channelNumber, uint16_t acceleration);
/** \brief Sends the servos and outputs to home position.
*
* If the "On startup or error" setting for a servo or output channel is set
* to "Ignore", the position will be unchanged.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
void goHome();
/** \brief Stops the script.
*
* Stops the script, if it is currently running.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
void stopScript();
/** \brief Starts loaded script at specified \a subroutineNumber location.
*
* @param subroutineNumber A subroutine number defined in script's compiled
* code.
*
* Starts the loaded script at location specified by the subroutine number.
* Subroutines are numbered in the order they are defined in loaded script.
* Click the "View Compiled Code..." button and look at the subroutine list
* to find the number for a particular subroutine.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
void restartScript(uint8_t subroutineNumber);
/** \brief Starts loaded script at specified \a subroutineNumber location
* after loading \a parameter on to the stack.
*
* @param subroutineNumber A subroutine number defined in script's compiled
* code.
*
* @param parameter A number from 0 to 16383.
*
* Similar to the \p restartScript function, except it loads the parameter
* on to the stack before starting the script at the specified subroutine
* number location.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
void restartScriptWithParameter(uint8_t subroutineNumber, uint16_t parameter);
/** \brief Gets the position of \a channelNumber.
*
* @param channelNumber A servo number from 0 to 127.
*
* @return two-byte position value
*
* If channel is configured as a servo, then the position value represents
* the current pulse width transmitted on the channel in units of
* quarter-microseconds.
*
* If the channel is configured as a digital output, a position value less
* than 6000 means the Maestro is driving the line low, while a position
* value of 6000 or greater means the Maestro is driving the line high.
*
* If channel is configured as an input, then the position value represents
* the voltage measured. Analog inputs for channels 0-11: their values range
* from 0 to 1023, representing 0 to 5V. Digital inputs for channels 12-23:
* their values are exactly 0 or exactly 1023.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
uint16_t getPosition(uint8_t channelNumber);
/** \brief Gets the moving state for all configured servo channels.
*
* @return 1 if at least one servo limited by speed or acceleration is still
* moving, 0 if not.
*
* Determines if the servo outputs have reached their targets or are still
* changing and will return 1 as as long as there is at least one servo that
* is limited by a speed or acceleration setting.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
uint8_t getMovingState();
/** \brief Gets if the script is running or stopped.
*
* @return 1 if script is stopped, 0 if running.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
uint8_t getScriptStatus();
/** \brief Gets the error register.
*
* @return Two-byte error code.
*
* Returns the error register in two bytes then all the error bits are
* cleared on the Maestro. See the Errors section of the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
uint16_t getErrors();
/** \cond
*
* This should be considered a private implementation detail of the library.
**/
protected:
Maestro(Stream &stream,
uint8_t resetPin,
uint8_t deviceNumber,
bool CRCEnabled);
void writeByte(uint8_t dataByte);
void writeCRC();
void writeCommand(uint8_t commandByte);
void write7BitData(uint8_t data);
void write14BitData(uint16_t data);
/** \endcond **/
private:
static const uint8_t CRC7Polynomial = 0x91;
static const uint8_t baudRateIndication = 0xAA;
static const uint8_t miniSscCommand = 0xFF;
static const uint8_t setTargetCommand = 0x84;
static const uint8_t setSpeedCommand = 0x87;
static const uint8_t setAccelerationCommand = 0x89;
static const uint8_t getPositionCommand = 0x90;
static const uint8_t getMovingStateCommand = 0x93;
static const uint8_t getErrorsCommand = 0xA1;
static const uint8_t goHomeCommand = 0xA2;
static const uint8_t stopScriptCommand = 0xA4;
static const uint8_t restartScriptAtSubroutineCommand = 0xA7;
static const uint8_t restartScriptAtSubroutineWithParameterCommand = 0xA8;
static const uint8_t getScriptStatusCommand = 0xAE;
uint8_t _deviceNumber;
uint8_t _resetPin;
bool _CRCEnabled;
uint8_t _CRCByte;
Stream *_stream;
};
class MicroMaestro : public Maestro
{
public:
/** \brief Create a MicroMaestro object.
*
* @param stream A class that descends from Stream, like SoftwareSerial or
* one of the Hardware Serial ports.
*
* @param resetPin The pin used by reset() to reset the Maestro. The default
* value is Maestro::noResetPin, which makes reset() do nothing.
*
* @param deviceNumber The device number configured on the Serial Settings
* tab in the Maestro Control Center. When deviceNumber is anything but
* Maestro::deviceNumberDefault, the Maestro communicates via the Pololu
* protocol. Otherwise, it uses the Compact protocol.
*
* @param CRCEnabled When true, the object computes the CRC value for a
* command packet and sends it at the end. The Maestro also has to have the
* Enable CRC option checked on the Serial Settings tab of the Maestro
* Control Center.
*/
MicroMaestro(Stream &stream,
uint8_t resetPin = noResetPin,
uint8_t deviceNumber = deviceNumberDefault,
bool CRCEnabled = false);
};
class MiniMaestro : public Maestro
{
public:
/** \brief Create a MiniMaestro object.
*
* @param stream A class that descends from Stream, like SoftwareSerial or
* one of the Hardware Serial ports.
*
* @param resetPin The pin used by reset() to reset the Maestro. The default
* value is Maestro::noResetPin, which makes reset() do nothing.
*
* @param deviceNumber The device number configured on the Serial Settings
* tab in the Maestro Control Center. When deviceNumber is anything but
* Maestro::deviceNumberDefault, the Maestro communicates via the Pololu
* protocol. Otherwise, it uses the Compact protocol.
*
* @param CRCEnabled When true, the object computes the CRC value for a
* command packet and sends it at the end. The Maestro also has to have the
* Enable CRC option checked on the Serial Settings tab of the Maestro
* Control Center.
*
* The MiniMaestro object adds serial commands only availabe on the Mini
* Maestro servo controllers: setPWM and setMultiTarget.
*/
MiniMaestro(Stream &stream,
uint8_t resetPin = noResetPin,
uint8_t deviceNumber = deviceNumberDefault,
bool CRCEnabled = false);
/** \brief Sets the PWM specified by \a onTime and \a period in units of
* 1/48 microseconds.
*
* @param onTime A number from 0 to 16320.
*
* @param period A number from 4 to 16384.
*
* Sets the PWM output to the specified on time and period, in units of 1/48
* microseconds.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
void setPWM(uint16_t onTime, uint16_t period);
/** \brief Sets multiple targets starting with the channel specified by \a
* firstChannel to a list of values listed in \a targetList for a
* contiguous block of channels specified by \a numberOfTargets.
*
* @param numberOfTargets A number from 0 to 24.
*
* @param firstChannel A channel number from 0 to (24 -
* \a numberOfTargets)
*
* @param targetList An array of numbers from 0 to 16383.
*
* The target value representation based on the channel's configuration
* (servo and output) is the same as the Set Target command.
*
* See the Serial Interface section in the [Maestro User's
* Guide](http://www.pololu.com/docs/0J40) for more details.
*
* The compact protocol is used by default. If the %deviceNumber was given
* to the constructor, it uses the Pololu protocol.
*/
void setMultiTarget(uint8_t numberOfTargets,
uint8_t firstChannel,
uint16_t *targetList);
private:
static const uint8_t setPwmCommand = 0x8A;
static const uint8_t setMultipleTargetsCommand = 0x9F;
};

@ -0,0 +1,181 @@
#include "AccelStepper.h" //Including der Servo Library
#include "PololuMaestro.h" //Including der PolouMaestro Library, für den Motor Driver
#include "Configuration.h" //Including unseres Konfigurationsfiles!
String serialBuffer = ""; //Leeren der SerialBuffer Variable!
String actions[TOTAL_ACTIONS]; //Holen des ersten wertes, aus dem Konfigurationsfile, (Max Aktionen.)
int counter = 0; //Counter Variable zum Start auf 0 Setzen, (Zählt Schritte)
int lastIndex = 0; //Index Variable auch auf 0 -> Index für den Standort
AccelStepper stepper(X_INTERFACE_TYPE, X_STEP_PIN, X_DIR_PIN); // Definition, der Variabeln aus dem Konfigurationsfile für dem Steppermotor! Pins für (Schritte, Interface, und Dir)
MicroMaestro maestro(maestroSerial); // Definiert einen neuen Servo Controller, anhand der Eingebundenen Librarys und des Konfigurationsfiles!
void setup() {
Serial.begin(9600); // Festlegen des Serial port für das Debugging
maestroSerial.begin(9600); // Festlegen des Servo controller Ports, gleich wie Debugging!
Serial2.begin(9600); // Festlegen des Bluetooth module Port. -> Auch gleich um Meldungen zu übergeben!
stepper.setMaxSpeed(X_MAX_SPEED); // Setzt die max. Geschwindigkeit für den Stepper, aus unserem Konfigurationsfile.
pinMode(X_ENDSTOP_PIN, INPUT_PULLUP); // Initialisiert den Endstop Pin, als Pullup-Schalter -> also Kontaktschalter!
homeXAxis(); // Bei jedem Start, soll der Getränkeautomat, an seine Start; Ausgangsposition zurückfahren!
}
// Die Funktion um die Startposition automatisch zu finden:
void homeXAxis() {
int endStopState = digitalRead(X_ENDSTOP_PIN);
while (endStopState == HIGH) {
stepper.moveTo(100);
stepper.setSpeed(X_HOME_SPEED);
stepper.runSpeed();
endStopState = digitalRead(X_ENDSTOP_PIN);
}
stepper.moveTo(stepper.currentPosition() - 50);
while (stepper.distanceToGo() != 0) {
stepper.setSpeed(X_PARK_SPEED * -1);
stepper.runSpeed();
}
endStopState = digitalRead(X_ENDSTOP_PIN);
while (endStopState == HIGH) {
stepper.moveTo(100);
stepper.setSpeed(X_PARK_SPEED);
stepper.runSpeed();
endStopState = digitalRead(X_ENDSTOP_PIN);
}
stepper.setCurrentPosition(0);
}
void loop() {
while(Serial2.available() > 0) {
char ch = Serial2.read();
serialBuffer += ch;
if (ch == '\n') {
for(int i=0; i<serialBuffer.length(); i++) {
if(serialBuffer.substring(i, i+1) == ",") {
actions[counter] = serialBuffer.substring(lastIndex, i);
lastIndex = i + 1;
counter++;
}
if(i == serialBuffer.length() - 1) {
actions[counter] = serialBuffer.substring(lastIndex, i);
}
}
for(int z=0; z<TOTAL_ACTIONS; z++) {
if(actions[z] != "0") {
parseInput(actions[z]);
}
}
Serial2.println("H");
for(int y=0; y<TOTAL_ACTIONS; y++) {
actions[y] = "0";
}
serialBuffer = "";
counter = 0;
lastIndex = 0;
}
}
}
void parseInput(String input) {
input.trim();
byte command = input.charAt(0);
switch(command) {
case 'H':
homeXAxis();
break;
case 'X':
moveXTo(input);
break;
case 'F':
pour(input);
break;
}
}
//Funktion, um zu der jeweiligen Flasche zu fahren.
void moveXTo(String input) {
int pos = input.substring(1).toInt(); //Bestimmt aktuelle Position des Schrittmotors!
Serial.print("X geht zu: "); //Ausgabe1 auf Debugging-Monitor
Serial.println(pos); //Ausgabe2 der Position!
Serial2.println(input); //Ausgabe3 der Inputs, von der App (Smartphone)
if(pos < 0 && pos >= X_MAX_POS) { //Wenn die Position zwischen 0 und dem festgelegten max Wert liegt, wird fortgefahren.
stepper.setAcceleration(X_ACCELERATION); //Holen des X_Acceleration Wertes aus dem Konfigurationsfile
stepper.moveTo(pos); //Legt den wert (Wo er hin muss) für den Stepper Motor fest!
if(pos < stepper.currentPosition()) { //Wenn die angegebene Position kleiner ist als die Aktuelle..
stepper.setSpeed(-100); //..wird die Geschwindigkeit gedrosselt!
} else {
stepper.setSpeed(100); //..sonst nicht.
}
while(stepper.distanceToGo() != 0) { // Bis die Distanz für das Ziel nicht 0 also der Stepper Motor am Ausgangspunkt angekommen ist, wird stepper.run() weiter ausgeführt!
stepper.run(); //Fährt den Motor zurück!
}
} else {
Serial.println("Die Position, sollte zwischen -4995 und 0 sein!"); // Ein Fehler ist aufgetreten, er kann nicht automatisch die Startposition finden. (Sollte nicht mehr passieren, ist jedoch trozdem sicherer so!) ->> Lösung: Strom ausschalten & manuell zurückfahren
}
}
// Hauptfunktion für das herauslassen der Getränke:
void pour(String input) { //Methode pour, wird durch Ionic vorgegeben und umschreibt eine Kommunikationsart. (Gleichername verwendet, einfachheitshalber)
int count = 0; // Setzen der Count Variable, zur Zählung der Zutaten
int times = 0; // Setzen der Times Variabel, wie viele Male, eine Zutat gewählt wird!
int holdDuration = 0; // Setzen der Öffnungsdauer, wie lange auf eine Flasche gedrückt wird.
int waitDuration = 0; // Setzen der Wartezeit, bis die nächste Zutat gewählt wird.
for(int z=0; z<input.length(); z++) {
byte parameter = input.substring(z, z+1).charAt(0);
switch(parameter) {
case 'F':
times = getParameterValue(input, z);
break;
case 'H':
holdDuration = getParameterValue(input, z);
break;
case 'W':
waitDuration = getParameterValue(input, z);
break;
}
}
if(holdDuration > 0 && waitDuration > 0) {
for(int i=0; i<times; i++) {
maestro.setSpeed(0, SERVO_RAISE_SPEED);
maestro.setTarget(0, SERVO_MAX_POS);
delay(holdDuration);
maestro.setSpeed(0, SERVO_RELEASE_SPEED);
maestro.setTarget(0, SERVO_MIN_POS);
if(times - 1 > count) {
delay(waitDuration);
} else {
delay(DELAY_BETWEEN_INGREDIENTS);
}
count++;
}
} else {
Serial.println("Die Öffnungsdauer und Wartezeit, kann nicht kleiner, gleich 0 sein!");
}
}
int getParameterValue(String input, int z) {
for(int y=z+1; y<input.length(); y++) {
if(input.substring(y, y+1) == " ") {
return input.substring(z+1, y).toInt();
break;
}
if(y == input.length() - 1) {
return input.substring(z+1, y+1).toInt();
}
}
}

@ -0,0 +1,17 @@
# EditorConfig helps developers define and maintain consistent coding styles between different editors and IDEs
# editorconfig.org
root = true
[*]
indent_style = space
indent_size = 2
# We recommend you to keep these unchanged
end_of_line = lf
charset = utf-8
trim_trailing_whitespace = true
insert_final_newline = true
[*.md]
trim_trailing_whitespace = false

@ -0,0 +1,83 @@
<?xml version='1.0' encoding='utf-8'?>
<widget id="com.ionicframework.barbot898900" version="0.0.1" xmlns="http://www.w3.org/ns/widgets" xmlns:cdv="http://cordova.apache.org/ns/1.0">
<name>Cocktail Master</name>
<description>Unser Getränkeautomat lässt sich anhand dieser App via Bluetooth steuern!</description>
<author email="" href="" />
<content src="index.html" />
<access origin="*" />
<allow-intent href="http://*/*" />
<allow-intent href="https://*/*" />
<allow-intent href="tel:*" />
<allow-intent href="sms:*" />
<allow-intent href="mailto:*" />
<allow-intent href="geo:*" />
<platform name="android">
<allow-intent href="market:*" />
<icon density="ldpi" src="resources/android/icon/drawable-ldpi-icon.png" />
<icon density="mdpi" src="resources/android/icon/drawable-mdpi-icon.png" />
<icon density="hdpi" src="resources/android/icon/drawable-hdpi-icon.png" />
<icon density="xhdpi" src="resources/android/icon/drawable-xhdpi-icon.png" />
<icon density="xxhdpi" src="resources/android/icon/drawable-xxhdpi-icon.png" />
<icon density="xxxhdpi" src="resources/android/icon/drawable-xxxhdpi-icon.png" />
<splash density="port-ldpi" src="resources/android/splash/drawable-port-ldpi-screen.png" />
<splash density="port-mdpi" src="resources/android/splash/drawable-port-mdpi-screen.png" />
<splash density="port-hdpi" src="resources/android/splash/drawable-port-hdpi-screen.png" />
<splash density="port-xhdpi" src="resources/android/splash/drawable-port-xhdpi-screen.png" />
<splash density="port-xxhdpi" src="resources/android/splash/drawable-port-xxhdpi-screen.png" />
<splash density="port-xxxhdpi" src="resources/android/splash/drawable-port-xxxhdpi-screen.png" />
</platform>
<platform name="ios">
<allow-intent href="itms:*" />
<allow-intent href="itms-apps:*" />
<icon height="57" src="resources/ios/icon/icon.png" width="57" />
<icon height="114" src="resources/ios/icon/icon@2x.png" width="114" />
<icon height="40" src="resources/ios/icon/icon-40.png" width="40" />
<icon height="80" src="resources/ios/icon/icon-40@2x.png" width="80" />
<icon height="120" src="resources/ios/icon/icon-40@3x.png" width="120" />
<icon height="50" src="resources/ios/icon/icon-50.png" width="50" />
<icon height="100" src="resources/ios/icon/icon-50@2x.png" width="100" />
<icon height="60" src="resources/ios/icon/icon-60.png" width="60" />
<icon height="120" src="resources/ios/icon/icon-60@2x.png" width="120" />
<icon height="180" src="resources/ios/icon/icon-60@3x.png" width="180" />
<icon height="72" src="resources/ios/icon/icon-72.png" width="72" />
<icon height="144" src="resources/ios/icon/icon-72@2x.png" width="144" />
<icon height="76" src="resources/ios/icon/icon-76.png" width="76" />
<icon height="152" src="resources/ios/icon/icon-76@2x.png" width="152" />
<icon height="167" src="resources/ios/icon/icon-83.5@2x.png" width="167" />
<icon height="29" src="resources/ios/icon/icon-small.png" width="29" />
<icon height="58" src="resources/ios/icon/icon-small@2x.png" width="58" />
<icon height="87" src="resources/ios/icon/icon-small@3x.png" width="87" />
<splash height="1136" src="resources/ios/splash/Default-568h@2x~iphone.png" width="640" />
<splash height="1334" src="resources/ios/splash/Default-667h.png" width="750" />
<splash height="2208" src="resources/ios/splash/Default-736h.png" width="1242" />
<splash height="2048" src="resources/ios/splash/Default-Portrait@2x~ipad.png" width="1536" />
<splash height="2732" src="resources/ios/splash/Default-Portrait@~ipadpro.png" width="2048" />
<splash height="1024" src="resources/ios/splash/Default-Portrait~ipad.png" width="768" />
<splash height="960" src="resources/ios/splash/Default@2x~iphone.png" width="640" />
<splash height="480" src="resources/ios/splash/Default~iphone.png" width="320" />
</platform>
<preference name="webviewbounce" value="false" />
<preference name="UIWebViewBounce" value="false" />
<preference name="DisallowOverscroll" value="true" />
<preference name="android-minSdkVersion" value="16" />
<preference name="BackupWebStorage" value="none" />
<preference name="SplashMaintainAspectRatio" value="true" />
<preference name="orientation" value="portrait" />
<preference name="AutoHideSplashScreen" value="false" />
<preference name="SplashScreenDelay" value="20000" />
<preference name="FadeSplashScreen" value="false" />
<preference name="ShowSplashScreenSpinner" value="false" />
<preference name="SplashShowOnlyFirstTime" value="false" />
<preference name="SplashScreen" value="screen" />
<feature name="StatusBar">
<param name="ios-package" onload="true" value="CDVStatusBar" />
</feature>
<plugin name="ionic-plugin-keyboard" spec="~2.2.1" />
<plugin name="cordova-plugin-whitelist" spec="1.3.1" />
<plugin name="cordova-plugin-console" spec="1.0.5" />
<plugin name="cordova-plugin-statusbar" spec="2.2.1" />
<plugin name="cordova-plugin-device" spec="1.1.4" />
<plugin name="cordova-plugin-splashscreen" spec="~4.0.1" />
<engine name="ios" spec="~4.4.0" />
<engine name="android" spec="~6.1.2" />
</widget>

@ -0,0 +1,196 @@
<!--
#
# Licensed to the Apache Software Foundation (ASF) under one
# or more contributor license agreements. See the NOTICE file
# distributed with this work for additional information
# regarding copyright ownership. The ASF licenses this file
# to you under the Apache License, Version 2.0 (the
# "License"); you may not use this file except in compliance
# with the License. You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing,
# software distributed under the License is distributed on an
# "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY
# KIND, either express or implied. See the License for the
# specific language governing permissions and limitations
# under the License.
#
-->
# Cordova Hooks
Cordova Hooks represent special scripts which could be added by application and plugin developers or even by your own build system to customize cordova commands. Hook scripts could be defined by adding them to the special predefined folder (`/hooks`) or via configuration files (`config.xml` and `plugin.xml`) and run serially in the following order:
* Application hooks from `/hooks`;
* Application hooks from `config.xml`;
* Plugin hooks from `plugins/.../plugin.xml`.
__Remember__: Make your scripts executable.
__Note__: `.cordova/hooks` directory is also supported for backward compatibility, but we don't recommend using it as it is deprecated.
## Supported hook types
The following hook types are supported:
after_build/
after_compile/
after_docs/
after_emulate/
after_platform_add/
after_platform_rm/
after_platform_ls/
after_plugin_add/
after_plugin_ls/
after_plugin_rm/
after_plugin_search/
after_plugin_install/ <-- Plugin hooks defined in plugin.xml are executed exclusively for a plugin being installed
after_prepare/
after_run/
after_serve/
before_build/
before_compile/
before_docs/
before_emulate/
before_platform_add/
before_platform_rm/
before_platform_ls/
before_plugin_add/
before_plugin_ls/
before_plugin_rm/
before_plugin_search/
before_plugin_install/ <-- Plugin hooks defined in plugin.xml are executed exclusively for a plugin being installed
before_plugin_uninstall/ <-- Plugin hooks defined in plugin.xml are executed exclusively for a plugin being uninstalled
before_prepare/
before_run/
before_serve/
pre_package/ <-- Windows 8 and Windows Phone only.
## Ways to define hooks
### Via '/hooks' directory
To execute custom action when corresponding hook type is fired, use hook type as a name for a subfolder inside 'hooks' directory and place you script file here, for example:
# script file will be automatically executed after each build
hooks/after_build/after_build_custom_action.js
### Config.xml
Hooks can be defined in project's `config.xml` using `<hook>` elements, for example:
<hook type="before_build" src="scripts/appBeforeBuild.bat" />
<hook type="before_build" src="scripts/appBeforeBuild.js" />
<hook type="before_plugin_install" src="scripts/appBeforePluginInstall.js" />
<platform name="wp8">
<hook type="before_build" src="scripts/wp8/appWP8BeforeBuild.bat" />
<hook type="before_build" src="scripts/wp8/appWP8BeforeBuild.js" />
<hook type="before_plugin_install" src="scripts/wp8/appWP8BeforePluginInstall.js" />
...
</platform>
<platform name="windows8">
<hook type="before_build" src="scripts/windows8/appWin8BeforeBuild.bat" />
<hook type="before_build" src="scripts/windows8/appWin8BeforeBuild.js" />
<hook type="before_plugin_install" src="scripts/windows8/appWin8BeforePluginInstall.js" />
...
</platform>
### Plugin hooks (plugin.xml)
As a plugin developer you can define hook scripts using `<hook>` elements in a `plugin.xml` like that:
<hook type="before_plugin_install" src="scripts/beforeInstall.js" />
<hook type="after_build" src="scripts/afterBuild.js" />
<platform name="wp8">
<hook type="before_plugin_install" src="scripts/wp8BeforeInstall.js" />
<hook type="before_build" src="scripts/wp8BeforeBuild.js" />
...
</platform>
`before_plugin_install`, `after_plugin_install`, `before_plugin_uninstall` plugin hooks will be fired exclusively for the plugin being installed/uninstalled.
## Script Interface
### Javascript
If you are writing hooks in Javascript you should use the following module definition:
```javascript
module.exports = function(context) {
...
}
```
You can make your scipts async using Q:
```javascript
module.exports = function(context) {
var Q = context.requireCordovaModule('q');
var deferral = new Q.defer();
setTimeout(function(){
console.log('hook.js>> end');
deferral.resolve();
}, 1000);
return deferral.promise;
}
```
`context` object contains hook type, executed script full path, hook options, command-line arguments passed to Cordova and top-level "cordova" object:
```json
{
"hook": "before_plugin_install",
"scriptLocation": "c:\\script\\full\\path\\appBeforePluginInstall.js",
"cmdLine": "The\\exact\\command\\cordova\\run\\with arguments",
"opts": {
"projectRoot":"C:\\path\\to\\the\\project",
"cordova": {
"platforms": ["wp8"],
"plugins": ["com.plugin.withhooks"],
"version": "0.21.7-dev"
},
"plugin": {
"id": "com.plugin.withhooks",
"pluginInfo": {
...
},
"platform": "wp8",
"dir": "C:\\path\\to\\the\\project\\plugins\\com.plugin.withhooks"
}
},
"cordova": {...}
}
```
`context.opts.plugin` object will only be passed to plugin hooks scripts.
You can also require additional Cordova modules in your script using `context.requireCordovaModule` in the following way:
```javascript
var Q = context.requireCordovaModule('q');
```
__Note__: new module loader script interface is used for the `.js` files defined via `config.xml` or `plugin.xml` only.
For compatibility reasons hook files specified via `/hooks` folders are run via Node child_process spawn, see 'Non-javascript' section below.
### Non-javascript
Non-javascript scripts are run via Node child_process spawn from the project's root directory and have the root directory passes as the first argument. All other options are passed to the script using environment variables:
* CORDOVA_VERSION - The version of the Cordova-CLI.
* CORDOVA_PLATFORMS - Comma separated list of platforms that the command applies to (e.g.: android, ios).
* CORDOVA_PLUGINS - Comma separated list of plugin IDs that the command applies to (e.g.: org.apache.cordova.file, org.apache.cordova.file-transfer)
* CORDOVA_HOOK - Path to the hook that is being executed.
* CORDOVA_CMDLINE - The exact command-line arguments passed to cordova (e.g.: cordova run ios --emulate)
If a script returns a non-zero exit code, then the parent cordova command will be aborted.
## Writing hooks
We highly recommend writing your hooks using Node.js so that they are
cross-platform. Some good examples are shown here:
[http://devgirl.org/2013/11/12/three-hooks-your-cordovaphonegap-project-needs/](http://devgirl.org/2013/11/12/three-hooks-your-cordovaphonegap-project-needs/)
Also, note that even if you are working on Windows, and in case your hook scripts aren't bat files (which is recommended, if you want your scripts to work in non-Windows operating systems) Cordova CLI will expect a shebang line as the first line for it to know the interpreter it needs to use to launch the script. The shebang line should match the following example:
#!/usr/bin/env [name_of_interpreter_executable]

@ -0,0 +1,5 @@
{
"name": "Getraenkeautomat",
"app_id": "abcc1a5f",
"type": "ionic-angular"
}

File diff suppressed because it is too large Load Diff

@ -0,0 +1,76 @@
{
"name": "Getraenkeautomat",
"private": true,
"scripts": {
"clean": "ionic-app-scripts clean",
"build": "ionic-app-scripts build",
"ionic:build": "ionic-app-scripts build",
"ionic:serve": "ionic-app-scripts serve"
},
"dependencies": {
"@angular/common": "2.2.1",
"@angular/compiler": "2.2.1",
"@angular/compiler-cli": "2.2.1",
"@angular/core": "2.2.1",
"@angular/forms": "2.2.1",
"@angular/http": "2.2.1",
"@angular/platform-browser": "2.2.1",
"@angular/platform-browser-dynamic": "2.2.1",
"@angular/platform-server": "2.2.1",
"@ionic/storage": "1.1.7",
"cordova-android": "^6.1.2",
"cordova-ios": "^4.4.0",
"cordova-plugin-console": "^1.0.5",
"cordova-plugin-device": "^1.1.4",
"cordova-plugin-splashscreen": "^4.0.3",
"cordova-plugin-statusbar": "^2.2.1",
"cordova-plugin-whitelist": "^1.3.1",
"ionic-angular": "2.0.0-rc.4",
"ionic-native": "2.2.11",
"ionic-plugin-keyboard": "^2.2.1",
"ionicons": "3.0.0",
"rxjs": "5.0.0-beta.12",
"uuid": "^3.0.1",
"zone.js": "0.6.26"
},
"devDependencies": {
"@ionic/app-scripts": "^1.3.7",
"@ionic/cli-plugin-cordova": "1.3.0",
"@ionic/cli-plugin-ionic-angular": "1.3.0",
"typescript": "2.0.9"
},
"cordovaPlugins": [
"cordova-plugin-whitelist",
"cordova-plugin-console",
"cordova-plugin-statusbar",
"cordova-plugin-device",
"cordova-plugin-splashscreen",
"ionic-plugin-keyboard",
"cordova-plugin-bluetooth-serial",
"cordova-plugin-dialogs",
"cordova-plugin-x-toast"
],
"cordovaPlatforms": [
"ios",
{
"platform": "ios",
"version": "",
"locator": "ios"
}
],
"description": "client: An Ionic project",
"cordova": {
"plugins": {
"cordova-plugin-console": {},
"cordova-plugin-device": {},
"cordova-plugin-splashscreen": {},
"cordova-plugin-statusbar": {},
"cordova-plugin-whitelist": {},
"ionic-plugin-keyboard": {}
},
"platforms": [
"android",
"ios"
]
}
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.8 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 7.5 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 14 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 21 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 521 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 114 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 219 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.1 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.8 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.7 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.3 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.2 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.7 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 7.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.8 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 19 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 14 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.3 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 15 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.5 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.6 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.4 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.5 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.6 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 954 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.2 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.9 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.2 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.1 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1019 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 816 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 220 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.8 MiB

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save