Upload files to "/"
commit
04c7d8278e
|
|
@ -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
|
||||
#define CONFIGURATION_H
|
||||
|
||||
//#define maestroSerial SERIAL_PORT_HARDWARE_OPEN
|
||||
|
||||
// Stepper driver
|
||||
#define X_INTERFACE_TYPE 1 // Stepper motor interface type
|
||||
#define X_STEP_PIN 3 // Stepper driver step pin
|
||||
#define X_DIR_PIN 4 // Stepper driver dir pin
|
||||
|
||||
// Stepper motor
|
||||
#define X_PARK_SPEED 150 // Parking speed
|
||||
#define X_HOME_SPEED 700 // Homing speed
|
||||
#define X_MAX_SPEED 1500 // The maximum speed in steps per second the X axis accelerate up to
|
||||
#define X_ACCELERATION 3000 // Acceleration/deceleration rate in steps per second per second
|
||||
#define X_MAX_POS -7000 // The maximum position for the X axis
|
||||
|
||||
// Servo motor
|
||||
#define SERVO_MAX_POS 3800 // Servo hold position
|
||||
#define SERVO_MIN_POS 7700 // Servo normal position
|
||||
#define SERVO_RAISE_SPEED 30 // The speed of the servo when travelling from the normal to the hold position
|
||||
#define SERVO_RELEASE_SPEED 20 // The speed of the servo when travelling from the hold to the normal position
|
||||
|
||||
// Endstop
|
||||
#define X_ENDSTOP_PIN 5 // Endstop pin
|
||||
|
||||
// Other
|
||||
#define TOTAL_ACTIONS 30 // Total number of actions
|
||||
#define DELAY_BETWEEN_INGREDIENTS 600 // Time duration to wait before travelling to the next ingredient
|
||||
|
||||
#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 channel’s 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 channel’s 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,299 @@
|
|||
#include "AccelStepper.h"
|
||||
#include "PololuMaestro.h"
|
||||
#include "Configuration.h"
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
SoftwareSerial maestroSerial(10, 11);
|
||||
AccelStepper stepper(X_INTERFACE_TYPE, X_STEP_PIN, X_DIR_PIN); // Define a stepper and the pins it will use
|
||||
MicroMaestro maestro(maestroSerial); // Define a servo controller
|
||||
|
||||
int cafe = -6687;
|
||||
int limao = -4000;
|
||||
int groselha = -5033;
|
||||
int aguaCoco = -4197;
|
||||
int laranja = -3000;
|
||||
int aguaGas = -2528;
|
||||
int ananas = -2000;
|
||||
int cola = -858;
|
||||
int sevenUp = -30;
|
||||
|
||||
void setup() {
|
||||
Serial.begin(9600);
|
||||
Serial.println("A iniciar...");
|
||||
maestroSerial.begin(9600);
|
||||
Serial2.begin(9600);
|
||||
|
||||
stepper.setMaxSpeed(X_MAX_SPEED); // Sets the maximum speed the X axis accelerate up to
|
||||
pinMode(X_ENDSTOP_PIN, INPUT_PULLUP); // Initialize endstop pin with the internal pull-up resistor enabled
|
||||
homeXAxis(); // Return the X axis to it's home position at the startup
|
||||
}
|
||||
|
||||
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 moveXTo(int pos) {
|
||||
Serial.print("X goes to: ");
|
||||
Serial.println(pos);
|
||||
|
||||
if(pos < 0 && pos >= X_MAX_POS) {
|
||||
stepper.setAcceleration(X_ACCELERATION);
|
||||
stepper.moveTo(pos);
|
||||
if(pos < stepper.currentPosition()) {
|
||||
stepper.setSpeed(-100);
|
||||
} else {
|
||||
stepper.setSpeed(100);
|
||||
}
|
||||
while(stepper.distanceToGo() != 0) {
|
||||
stepper.run();
|
||||
}
|
||||
} else {
|
||||
Serial.println("Position should be between -4995 and 0");
|
||||
}
|
||||
}
|
||||
|
||||
void pour(int times, int holdDuration, int waitDuration) {
|
||||
int count = 0;
|
||||
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("Hold and wait duration parameters cannot be lower than or equal to 0");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
String comando = "";
|
||||
|
||||
while(Serial2.available()){
|
||||
char valorLido =(char) Serial2.read();
|
||||
comando += valorLido;
|
||||
Serial.println("O valor recebido foi: " + comando);
|
||||
|
||||
if(comando.equals("1")){
|
||||
cosmopolitan();
|
||||
}
|
||||
|
||||
if(comando.equals("2")){
|
||||
cocktailTropical();
|
||||
}
|
||||
|
||||
if(comando.equals("3")){
|
||||
cinderela();
|
||||
}
|
||||
|
||||
if(comando.equals("4")){
|
||||
sanFrancisco();
|
||||
}
|
||||
|
||||
if(comando.equals("5")){
|
||||
uglyKid();
|
||||
}
|
||||
|
||||
if(comando.equals("6")){
|
||||
belaRagazza();
|
||||
}
|
||||
|
||||
if(comando.equals("7")){
|
||||
tango();
|
||||
}
|
||||
|
||||
if(comando.equals("8")){
|
||||
pneu();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void teste(){
|
||||
moveXTo(-20);
|
||||
}
|
||||
|
||||
void cosmopolitan(){
|
||||
Serial.println("A sair um cosmopolitan...");
|
||||
int posicao [] = {limao,laranja,aguaCoco,groselha};
|
||||
int times [] = {1,1,1,1};
|
||||
int holdDuration [] = {3300,3300,2000,2000};
|
||||
int waitDuration [] = {2500,2500,2500,2500};
|
||||
Serial.println(sizeof(times));
|
||||
for(int i = 0; i < sizeof(posicao) / 2; i++){
|
||||
Serial.print("Posição: ");
|
||||
Serial.println(posicao[i]);
|
||||
Serial.print("Vezes: ");
|
||||
Serial.println(times[i]);
|
||||
Serial.print("Duração: ");
|
||||
Serial.println(holdDuration[i]);
|
||||
Serial.print("Espera: ");
|
||||
Serial.println(waitDuration[i]);
|
||||
moveXTo(posicao[i]);
|
||||
pour(times[i],holdDuration[i],waitDuration[i]);
|
||||
}
|
||||
homeXAxis();
|
||||
}
|
||||
|
||||
/*void cosmopolitan(){
|
||||
int posicao [] = {sevenUp,cola,ananas,aguaGas,laranja,aguaCoco,groselha,limao,cafe};
|
||||
int times [] = {2,2,2,2,2,2,2,2,2};
|
||||
int holdDuration [] = {3300,3300,3300,3300,3300,3300,3300,3300,3300};
|
||||
int waitDuration [] = {600,600,600,600,600,600,600,600,600};
|
||||
Serial.println(sizeof(times));
|
||||
for(int i = 0; i < sizeof(posicao) / 2; i++){
|
||||
Serial.print("Posição: ");
|
||||
Serial.println(posicao[i]);
|
||||
Serial.print("Vezes: ");
|
||||
Serial.println(times[i]);
|
||||
Serial.print("Duração: ");
|
||||
Serial.println(holdDuration[i]);
|
||||
Serial.print("Espera: ");
|
||||
Serial.println(waitDuration[i]);
|
||||
moveXTo(posicao[i]);
|
||||
pour(times[i],holdDuration[i],waitDuration[i]);
|
||||
}
|
||||
homeXAxis();
|
||||
}*/
|
||||
|
||||
void pneu(){
|
||||
Serial.println("A sair um pneu...");
|
||||
int posicao [] = {limao,aguaGas};
|
||||
int times [] = {2,3};
|
||||
int holdDuration [] = {3300,3300};
|
||||
int waitDuration [] ={2500,2500};
|
||||
|
||||
Serial.println(sizeof(times));
|
||||
|
||||
for(int i = 0; i < sizeof(posicao) / 2; i++){
|
||||
moveXTo(posicao[i]);
|
||||
pour(times[i],holdDuration[i],waitDuration[i]);
|
||||
}
|
||||
homeXAxis();
|
||||
}
|
||||
|
||||
void tango(){
|
||||
Serial.println("A sair uma Seven Up + Groselha...");
|
||||
int posicao [] = {sevenUp,groselha};
|
||||
int times [] = {3,1};
|
||||
int holdDuration [] = {3300,3300};
|
||||
int waitDuration [] ={3800,3800};
|
||||
|
||||
Serial.println(sizeof(times));
|
||||
|
||||
for(int i = 0; i < sizeof(posicao) / 2; i++){
|
||||
moveXTo(posicao[i]);
|
||||
pour(times[i],holdDuration[i],waitDuration[i]);
|
||||
}
|
||||
homeXAxis();
|
||||
}
|
||||
|
||||
void cinderela(){
|
||||
Serial.println("A sair uma Seven Up...");
|
||||
int posicao [] = {laranja,limao,ananas};
|
||||
int times [] = {2,2,2};
|
||||
int holdDuration [] = {3300,3300,3300};
|
||||
int waitDuration [] ={2500,2500,2500};
|
||||
|
||||
Serial.println(sizeof(times));
|
||||
|
||||
for(int i = 0; i < sizeof(posicao) / 2; i++){
|
||||
moveXTo(posicao[i]);
|
||||
pour(times[i],holdDuration[i],waitDuration[i]);
|
||||
}
|
||||
homeXAxis();
|
||||
}
|
||||
|
||||
void sanFrancisco(){
|
||||
Serial.println("A sair um Sumo de Laranja...");
|
||||
int posicao [] = {limao,laranja,ananas,groselha};
|
||||
int times [] = {1,1,1,1};
|
||||
int holdDuration [] = {3300,3300,3300,2150};
|
||||
int waitDuration [] ={600,1000,1000,600};
|
||||
|
||||
Serial.println(sizeof(times));
|
||||
|
||||
for(int i = 0; i < sizeof(posicao) / 2; i++){
|
||||
moveXTo(posicao[i]);
|
||||
pour(times[i],holdDuration[i],waitDuration[i]);
|
||||
}
|
||||
homeXAxis();
|
||||
}
|
||||
|
||||
void uglyKid(){
|
||||
Serial.println("A sair um Sumo de Laranja...");
|
||||
int posicao [] = {groselha,laranja,limao};
|
||||
int times [] = {1,2,2};
|
||||
int holdDuration [] = {3000,3300,3300};
|
||||
int waitDuration [] ={600,2500,2500};
|
||||
|
||||
Serial.println(sizeof(times));
|
||||
|
||||
for(int i = 0; i < sizeof(posicao) / 2; i++){
|
||||
moveXTo(posicao[i]);
|
||||
pour(times[i],holdDuration[i],waitDuration[i]);
|
||||
}
|
||||
homeXAxis();
|
||||
}
|
||||
|
||||
void belaRagazza(){
|
||||
Serial.println("A sair uma Coca Cola...");
|
||||
int posicao [] = {limao,cafe,cola};
|
||||
int times [] = {1,1,3};
|
||||
int holdDuration [] = {2150,3300,3300};
|
||||
int waitDuration [] ={600,2500,3800};
|
||||
|
||||
Serial.println(sizeof(times));
|
||||
|
||||
for(int i = 0; i < sizeof(posicao) / 2; i++){
|
||||
moveXTo(posicao[i]);
|
||||
pour(times[i],holdDuration[i],waitDuration[i]);
|
||||
}
|
||||
homeXAxis();
|
||||
}
|
||||
|
||||
void cocktailTropical(){
|
||||
Serial.println("A sair um Cocktail Tropical...");
|
||||
int posicao [] = {limao,laranja,aguaGas};
|
||||
int times [] = {1,1,2};
|
||||
int holdDuration [] = {3300,3300,3300};
|
||||
int waitDuration [] ={2500,2500,3800};
|
||||
|
||||
Serial.println(sizeof(times));
|
||||
|
||||
for(int i = 0; i < sizeof(posicao) / 2; i++){
|
||||
moveXTo(posicao[i]);
|
||||
pour(times[i],holdDuration[i],waitDuration[i]);
|
||||
}
|
||||
homeXAxis();
|
||||
}
|
||||
Loading…
Reference in New Issue