Added entirety of CAD files, Software and the translated documentation

This commit is contained in:
Raphael Maenle
2019-11-12 19:55:35 +01:00
commit 134990e892
266 changed files with 48020 additions and 0 deletions

View File

@ -0,0 +1,651 @@
// AccelStepper.cpp
//
// Copyright (C) 2009-2013 Mike McCauley
// $Id: AccelStepper.cpp,v 1.23 2016/08/09 00:39:10 mikem Exp $
#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; // Caution: does not account for costs in step()
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 (speed < 0.0)
speed = -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 < 0.0)
acceleration = -acceleration;
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)
{
(void)(step); // Unused
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)
{
(void)(step); // Unused
// _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);
}

View File

@ -0,0 +1,728 @@
// 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 and motor drivers.
///
/// 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.57.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://en.wikipedia.org/wiki/Wikipedia:Reference_desk/How_to_ask_a_software_question
/// - http://www.catb.org/esr/faqs/smart-questions.html
/// - http://www.chiark.greenend.org.uk/~shgtatham/bugs.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 https://www.gnu.org/licenses/gpl-2.0.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. Purchase commercial licenses at http://airspayce.binpress.com/
///
/// \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.
/// \version 1.53 2016-08-14
/// Backed out Improvements to speed accuracy from 1.52 as it did not work correctly.
/// \version 1.54 2017-01-24
/// Fixed some warnings about unused arguments.
/// \version 1.55 2017-01-25
/// Fixed another warning in MultiStepper.cpp
/// \version 1.56 2017-02-03
/// Fixed minor documentation error with DIRECTION_CCW and DIRECTION_CW. Reported by David Mutterer.
/// Added link to Binpress commercial license purchasing.
/// \version 1.57 2017-03-28
/// _direction moved to protected at the request of Rudy Ercek.
/// setMaxSpeed() and setAcceleration() now correct negative values to be positive.
///
/// \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.27 2016/08/14 10:26:54 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. Integer values 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, ///< Counter-Clockwise
DIRECTION_CW = 1 ///< 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);
/// Current direction motor is spinning in
/// Protected because some peoples subclasses need it to be so
boolean _direction; // 1 == CW
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
};
/// @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

View File

@ -0,0 +1,17 @@
This software is Copyright (C) 2008 Mike McCauley. Use is subject to license
conditions. The main licensing options available are GPL V2 or Commercial:
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
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@open.com.au for details.

View File

@ -0,0 +1,38 @@
AccelStepper/Makefile
AccelStepper/AccelStepper.h
AccelStepper/AccelStepper.cpp
AccelStepper/MultiStepper.h
AccelStepper/MultiStepper.cpp
AccelStepper/MANIFEST
AccelStepper/LICENSE
AccelStepper/project.cfg
AccelStepper/keywords.txt
AccelStepper/doc
AccelStepper/examples/Blocking/Blocking.pde
AccelStepper/examples/MultipleSteppers/MultipleSteppers.pde
AccelStepper/examples/Overshoot/Overshoot.pde
AccelStepper/examples/ConstantSpeed/ConstantSpeed.pde
AccelStepper/examples/Random/Random.pde
AccelStepper/examples/AFMotor_ConstantSpeed/AFMotor_ConstantSpeed.pde
AccelStepper/examples/AFMotor_MultiStepper/AFMotor_MultiStepper.pde
AccelStepper/examples/ProportionalControl/ProportionalControl.pde
AccelStepper/examples/Bounce/Bounce.pde
AccelStepper/examples/Quickstop/Quickstop.pde
AccelStepper/examples/MotorShield/MotorShield.pde
AccelStepper/examples/DualMotorShield/DualMotorShield.pde
AccelStepper/examples/MultiStepper/MultiStepper.pde
AccelStepper/doc
AccelStepper/doc/index.html
AccelStepper/doc/functions.html
AccelStepper/doc/annotated.html
AccelStepper/doc/tab_l.gif
AccelStepper/doc/tabs.css
AccelStepper/doc/files.html
AccelStepper/doc/classAccelStepper-members.html
AccelStepper/doc/doxygen.css
AccelStepper/doc/AccelStepper_8h-source.html
AccelStepper/doc/tab_r.gif
AccelStepper/doc/doxygen.png
AccelStepper/doc/tab_b.gif
AccelStepper/doc/functions_func.html
AccelStepper/doc/classAccelStepper.html

View File

@ -0,0 +1,30 @@
# Makefile
#
# Makefile for the Arduino AccelStepper project
#
# Author: Mike McCauley (mikem@airspayce.com)
# Copyright (C) 2010 Mike McCauley
# $Id: Makefile,v 1.6 2015/08/25 04:57:29 mikem Exp mikem $
PROJNAME = AccelStepper
VERSION_MAJOR = 1
VERSION_MINOR = 57
DISTFILE = $(PROJNAME)-$(VERSION_MAJOR).$(VERSION_MINOR).zip
all: versioning doxygen dist upload
versioning:
sed -i.bak -e 's/AccelStepper-.*\.zip/$(DISTFILE)/' AccelStepper.h
doxygen:
doxygen project.cfg
ci:
(cd ..;ci -l `cat $(PROJNAME)/MANIFEST`)
dist:
(cd ..; zip $(PROJNAME)/$(DISTFILE) `cat $(PROJNAME)/MANIFEST`)
upload:
rsync -avz $(DISTFILE) doc/ www.airspayce.com:public_html/mikem/arduino/$(PROJNAME)

View File

@ -0,0 +1,73 @@
// MultiStepper.cpp
//
// Copyright (C) 2015 Mike McCauley
// $Id: MultiStepper.cpp,v 1.2 2015/10/04 05:16:38 mikem Exp $
#include "MultiStepper.h"
#include "AccelStepper.h"
MultiStepper::MultiStepper()
: _num_steppers(0)
{
}
boolean MultiStepper::addStepper(AccelStepper& stepper)
{
if (_num_steppers >= MULTISTEPPER_MAX_STEPPERS)
return false; // No room for more
_steppers[_num_steppers++] = &stepper;
return true;
}
void MultiStepper::moveTo(long absolute[])
{
// First find the stepper that will take the longest time to move
float longestTime = 0.0;
uint8_t i;
for (i = 0; i < _num_steppers; i++)
{
long thisDistance = absolute[i] - _steppers[i]->currentPosition();
float thisTime = abs(thisDistance) / _steppers[i]->maxSpeed();
if (thisTime > longestTime)
longestTime = thisTime;
}
if (longestTime > 0.0)
{
// Now work out a new max speed for each stepper so they will all
// arrived at the same time of longestTime
for (i = 0; i < _num_steppers; i++)
{
long thisDistance = absolute[i] - _steppers[i]->currentPosition();
float thisSpeed = thisDistance / longestTime;
_steppers[i]->moveTo(absolute[i]); // New target position (resets speed)
_steppers[i]->setSpeed(thisSpeed); // New speed
}
}
}
// Returns true if any motor is still running to the target position.
boolean MultiStepper::run()
{
uint8_t i;
boolean ret = false;
for (i = 0; i < _num_steppers; i++)
{
if ( _steppers[i]->distanceToGo() != 0)
{
_steppers[i]->runSpeed();
ret = true;
}
}
return ret;
}
// Blocks until all steppers reach their target position and are stopped
void MultiStepper::runSpeedToPosition()
{
while (run())
;
}

View File

@ -0,0 +1,78 @@
// MultiStepper.h
#ifndef MultiStepper_h
#define MultiStepper_h
#include <stdlib.h>
#if ARDUINO >= 100
#include <Arduino.h>
#else
#include <WProgram.h>
#include <wiring.h>
#endif
#define MULTISTEPPER_MAX_STEPPERS 10
class AccelStepper;
/////////////////////////////////////////////////////////////////////
/// \class MultiStepper MultiStepper.h <MultiStepper.h>
/// \brief Operate multiple AccelSteppers in a co-ordinated fashion
///
/// This class can manage multiple AccelSteppers (up to MULTISTEPPER_MAX_STEPPERS = 10),
/// 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. This can be used to support devices with multiple steppers
/// on say multiple axes to cause linear diagonal motion. Suitable for use with X-Y plotters, flatbeds,
/// 3D printers etc
/// to get linear straight line movement between arbitrary 2d (or 3d or ...) positions.
///
/// Caution: only constant speed stepper motion is supported: acceleration and deceleration is not supported
/// All the steppers managed by MultiStepper will step at a constant speed to their
/// target (albeit perhaps different speeds for each stepper).
class MultiStepper
{
public:
/// Constructor
MultiStepper();
/// Add a stepper to the set of managed steppers
/// There is an upper limit of MULTISTEPPER_MAX_STEPPERS = 10 to the number of steppers that can be managed
/// \param[in] stepper Reference to a stepper to add to the managed list
/// \return true if successful. false if the number of managed steppers would exceed MULTISTEPPER_MAX_STEPPERS
boolean addStepper(AccelStepper& stepper);
/// Set the target positions of all managed steppers
/// according to a coordinate array.
/// New speeds will be computed for each stepper so they will all arrive at their
/// respective targets at very close to the same time.
/// \param[in] absolute An array of desired absolute stepper positions. absolute[0] will be used to set
/// the absolute position of the first stepper added by addStepper() etc. The array must be at least as long as
/// the number of steppers that have been added by addStepper, else results are undefined.
void moveTo(long absolute[]);
/// Calls runSpeed() on all the managed steppers
/// that have not acheived their target position.
/// \return true if any stepper is still in the process of running to its target position.
boolean run();
/// Runs all managed steppers until they acheived their target position.
/// Blocks until all that position is acheived. If you dont
/// want blocking consider using run() instead.
void runSpeedToPosition();
private:
/// Array of pointers to the steppers we are controlling.
/// Fills from 0 onwards
AccelStepper* _steppers[MULTISTEPPER_MAX_STEPPERS];
/// Number of steppers we are controlling and the number
/// of steppers in _steppers[]
uint8_t _num_steppers;
};
/// @example MultiStepper.pde
/// Use MultiStepper class to manage multiple steppers and make them all move to
/// the same position at the same time for linear 2d (or 3d) motion.
#endif

View File

@ -0,0 +1,420 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
<title>AccelStepper: AccelStepper.h Source File</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<!-- Generated by Doxygen 1.5.6 -->
<div class="navigation" id="top">
<div class="tabs">
<ul>
<li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<h1>AccelStepper.h</h1><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">// AccelStepper.h</span>
<a name="l00002"></a>00002 <span class="comment">//</span><span class="comment"></span>
<a name="l00003"></a>00003 <span class="comment">/// \mainpage AccelStepper library for Arduino</span>
<a name="l00004"></a>00004 <span class="comment">///</span>
<a name="l00005"></a>00005 <span class="comment">/// This is the Arduino AccelStepper library.</span>
<a name="l00006"></a>00006 <span class="comment">/// It provides an object-oriented interface for 2 or 4 pin stepper motors.</span>
<a name="l00007"></a>00007 <span class="comment">///</span>
<a name="l00008"></a>00008 <span class="comment">/// The standard Arduino IDE includes the Stepper library</span>
<a name="l00009"></a>00009 <span class="comment">/// (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is</span>
<a name="l00010"></a>00010 <span class="comment">/// perfectly adequate for simple, single motor applications.</span>
<a name="l00011"></a>00011 <span class="comment">///</span>
<a name="l00012"></a>00012 <span class="comment">/// AccelStepper significantly improves on the standard Arduino Stepper library in several ways:</span>
<a name="l00013"></a>00013 <span class="comment">/// \li Supports acceleration and deceleration</span>
<a name="l00014"></a>00014 <span class="comment">/// \li Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper</span>
<a name="l00015"></a>00015 <span class="comment">/// \li API functions never delay() or block</span>
<a name="l00016"></a>00016 <span class="comment">/// \li Supports 2 and 4 wire steppers, plus 4 wire half steppers.</span>
<a name="l00017"></a>00017 <span class="comment">/// \li Supports alternate stepping functions to enable support of AFMotor (https://github.com/adafruit/Adafruit-Motor-Shield-library)</span>
<a name="l00018"></a>00018 <span class="comment">/// \li Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip)</span>
<a name="l00019"></a>00019 <span class="comment">/// \li Very slow speeds are supported</span>
<a name="l00020"></a>00020 <span class="comment">/// \li Extensive API</span>
<a name="l00021"></a>00021 <span class="comment">/// \li Subclass support</span>
<a name="l00022"></a>00022 <span class="comment">///</span>
<a name="l00023"></a>00023 <span class="comment">/// The latest version of this documentation can be downloaded from </span>
<a name="l00024"></a>00024 <span class="comment">/// http://www.open.com.au/mikem/arduino/AccelStepper</span>
<a name="l00025"></a>00025 <span class="comment">///</span>
<a name="l00026"></a>00026 <span class="comment">/// Example Arduino programs are included to show the main modes of use.</span>
<a name="l00027"></a>00027 <span class="comment">///</span>
<a name="l00028"></a>00028 <span class="comment">/// The version of the package that this documentation refers to can be downloaded </span>
<a name="l00029"></a>00029 <span class="comment">/// from http://www.open.com.au/mikem/arduino/AccelStepper/AccelStepper-1.11.zip</span>
<a name="l00030"></a>00030 <span class="comment">/// You can find the latest version at http://www.open.com.au/mikem/arduino/AccelStepper</span>
<a name="l00031"></a>00031 <span class="comment">///</span>
<a name="l00032"></a>00032 <span class="comment">/// Tested on Arduino Diecimila and Mega with arduino-0018 &amp; arduino-0021 </span>
<a name="l00033"></a>00033 <span class="comment">/// on OpenSuSE 11.1 and avr-libc-1.6.1-1.15,</span>
<a name="l00034"></a>00034 <span class="comment">/// cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5.</span>
<a name="l00035"></a>00035 <span class="comment">///</span>
<a name="l00036"></a>00036 <span class="comment">/// \par Installation</span>
<a name="l00037"></a>00037 <span class="comment">/// Install in the usual way: unzip the distribution zip file to the libraries</span>
<a name="l00038"></a>00038 <span class="comment">/// sub-folder of your sketchbook. </span>
<a name="l00039"></a>00039 <span class="comment">///</span>
<a name="l00040"></a>00040 <span class="comment">/// This software is Copyright (C) 2010 Mike McCauley. Use is subject to license</span>
<a name="l00041"></a>00041 <span class="comment">/// conditions. The main licensing options available are GPL V2 or Commercial:</span>
<a name="l00042"></a>00042 <span class="comment">/// </span>
<a name="l00043"></a>00043 <span class="comment">/// \par Open Source Licensing GPL V2</span>
<a name="l00044"></a>00044 <span class="comment">/// This is the appropriate option if you want to share the source code of your</span>
<a name="l00045"></a>00045 <span class="comment">/// application with everyone you distribute it to, and you also want to give them</span>
<a name="l00046"></a>00046 <span class="comment">/// the right to share who uses it. If you wish to use this software under Open</span>
<a name="l00047"></a>00047 <span class="comment">/// Source Licensing, you must contribute all your source code to the open source</span>
<a name="l00048"></a>00048 <span class="comment">/// community in accordance with the GPL Version 2 when your application is</span>
<a name="l00049"></a>00049 <span class="comment">/// distributed. See http://www.gnu.org/copyleft/gpl.html</span>
<a name="l00050"></a>00050 <span class="comment">/// </span>
<a name="l00051"></a>00051 <span class="comment">/// \par Commercial Licensing</span>
<a name="l00052"></a>00052 <span class="comment">/// This is the appropriate option if you are creating proprietary applications</span>
<a name="l00053"></a>00053 <span class="comment">/// and you are not prepared to distribute and share the source code of your</span>
<a name="l00054"></a>00054 <span class="comment">/// application. Contact info@open.com.au for details.</span>
<a name="l00055"></a>00055 <span class="comment">///</span>
<a name="l00056"></a>00056 <span class="comment">/// \par Revision History</span>
<a name="l00057"></a>00057 <span class="comment">/// \version 1.0 Initial release</span>
<a name="l00058"></a>00058 <span class="comment">///</span>
<a name="l00059"></a>00059 <span class="comment">/// \version 1.1 Added speed() function to get the current speed.</span>
<a name="l00060"></a>00060 <span class="comment">/// \version 1.2 Added runSpeedToPosition() submitted by Gunnar Arndt.</span>
<a name="l00061"></a>00061 <span class="comment">/// \version 1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1</span>
<a name="l00062"></a>00062 <span class="comment">/// \version 1.4 Added functional contructor to support AFMotor, contributed by Limor, with example sketches.</span>
<a name="l00063"></a>00063 <span class="comment">/// \version 1.5 Improvements contributed by Peter Mousley: Use of microsecond steps and other speed improvements</span>
<a name="l00064"></a>00064 <span class="comment">/// to increase max stepping speed to about 4kHz. New option for user to set the min allowed pulse width.</span>
<a name="l00065"></a>00065 <span class="comment">/// Added checks for already running at max speed and skip further calcs if so. </span>
<a name="l00066"></a>00066 <span class="comment">/// \version 1.6 Fixed a problem with wrapping of microsecond stepping that could cause stepping to hang. </span>
<a name="l00067"></a>00067 <span class="comment">/// Reported by Sandy Noble.</span>
<a name="l00068"></a>00068 <span class="comment">/// Removed redundant _lastRunTime member.</span>
<a name="l00069"></a>00069 <span class="comment">/// \version 1.7 Fixed a bug where setCurrentPosition() did always work as expected. Reported by Peter Linhart.</span>
<a name="l00070"></a>00070 <span class="comment">/// Reported by Sandy Noble.</span>
<a name="l00071"></a>00071 <span class="comment">/// Removed redundant _lastRunTime member.</span>
<a name="l00072"></a>00072 <span class="comment">/// \version 1.8 Added support for 4 pin half-steppers, requested by Harvey Moon</span>
<a name="l00073"></a>00073 <span class="comment">/// \version 1.9 setCurrentPosition() now also sets motor speed to 0.</span>
<a name="l00074"></a>00074 <span class="comment">/// \version 1.10 Builds on Arduino 1.0</span>
<a name="l00075"></a>00075 <span class="comment">/// \version 1.11 Improvments from Michael Ellison:</span>
<a name="l00076"></a>00076 <span class="comment">/// Added optional enable line support for stepper drivers</span>
<a name="l00077"></a>00077 <span class="comment">/// Added inversion for step/direction/enable lines for stepper drivers</span>
<a name="l00078"></a>00078 <span class="comment">///</span>
<a name="l00079"></a>00079 <span class="comment">/// \author Mike McCauley (mikem@open.com.au)</span>
<a name="l00080"></a>00080 <span class="comment"></span><span class="comment">// Copyright (C) 2009 Mike McCauley</span>
<a name="l00081"></a>00081 <span class="comment">// $Id: AccelStepper.h,v 1.5 2011/03/21 00:42:15 mikem Exp mikem $</span>
<a name="l00082"></a>00082
<a name="l00083"></a>00083 <span class="preprocessor">#ifndef AccelStepper_h</span>
<a name="l00084"></a>00084 <span class="preprocessor"></span><span class="preprocessor">#define AccelStepper_h</span>
<a name="l00085"></a>00085 <span class="preprocessor"></span>
<a name="l00086"></a>00086 <span class="preprocessor">#include &lt;stdlib.h&gt;</span>
<a name="l00087"></a>00087 <span class="preprocessor">#if ARDUINO &gt;= 100</span>
<a name="l00088"></a>00088 <span class="preprocessor"></span><span class="preprocessor">#include &lt;Arduino.h&gt;</span>
<a name="l00089"></a>00089 <span class="preprocessor">#else</span>
<a name="l00090"></a>00090 <span class="preprocessor"></span><span class="preprocessor">#include &lt;wiring.h&gt;</span>
<a name="l00091"></a>00091 <span class="preprocessor">#endif</span>
<a name="l00092"></a>00092 <span class="preprocessor"></span>
<a name="l00093"></a>00093 <span class="comment">// These defs cause trouble on some versions of Arduino</span>
<a name="l00094"></a>00094 <span class="preprocessor">#undef round</span>
<a name="l00095"></a>00095 <span class="preprocessor"></span><span class="comment"></span>
<a name="l00096"></a>00096 <span class="comment">/////////////////////////////////////////////////////////////////////</span>
<a name="l00097"></a>00097 <span class="comment">/// \class AccelStepper AccelStepper.h &lt;AccelStepper.h&gt;</span>
<a name="l00098"></a>00098 <span class="comment">/// \brief Support for stepper motors with acceleration etc.</span>
<a name="l00099"></a>00099 <span class="comment">///</span>
<a name="l00100"></a>00100 <span class="comment">/// This defines a single 2 or 4 pin stepper motor, or stepper moter with fdriver chip, with optional</span>
<a name="l00101"></a>00101 <span class="comment">/// acceleration, deceleration, absolute positioning commands etc. Multiple</span>
<a name="l00102"></a>00102 <span class="comment">/// simultaneous steppers are supported, all moving </span>
<a name="l00103"></a>00103 <span class="comment">/// at different speeds and accelerations. </span>
<a name="l00104"></a>00104 <span class="comment">///</span>
<a name="l00105"></a>00105 <span class="comment">/// \par Operation</span>
<a name="l00106"></a>00106 <span class="comment">/// This module operates by computing a step time in microseconds. The step</span>
<a name="l00107"></a>00107 <span class="comment">/// time is recomputed after each step and after speed and acceleration</span>
<a name="l00108"></a>00108 <span class="comment">/// parameters are changed by the caller. The time of each step is recorded in</span>
<a name="l00109"></a>00109 <span class="comment">/// microseconds. The run() function steps the motor if a new step is due.</span>
<a name="l00110"></a>00110 <span class="comment">/// The run() function must be called frequently until the motor is in the</span>
<a name="l00111"></a>00111 <span class="comment">/// desired position, after which time run() will do nothing.</span>
<a name="l00112"></a>00112 <span class="comment">///</span>
<a name="l00113"></a>00113 <span class="comment">/// \par Positioning</span>
<a name="l00114"></a>00114 <span class="comment">/// Positions are specified by a signed long integer. At</span>
<a name="l00115"></a>00115 <span class="comment">/// construction time, the current position of the motor is consider to be 0. Positive</span>
<a name="l00116"></a>00116 <span class="comment">/// positions are clockwise from the initial position; negative positions are</span>
<a name="l00117"></a>00117 <span class="comment">/// anticlockwise. The curent position can be altered for instance after</span>
<a name="l00118"></a>00118 <span class="comment">/// initialization positioning.</span>
<a name="l00119"></a>00119 <span class="comment">///</span>
<a name="l00120"></a>00120 <span class="comment">/// \par Caveats</span>
<a name="l00121"></a>00121 <span class="comment">/// This is an open loop controller: If the motor stalls or is oversped,</span>
<a name="l00122"></a>00122 <span class="comment">/// AccelStepper will not have a correct </span>
<a name="l00123"></a>00123 <span class="comment">/// idea of where the motor really is (since there is no feedback of the motor's</span>
<a name="l00124"></a>00124 <span class="comment">/// real position. We only know where we _think_ it is, relative to the</span>
<a name="l00125"></a>00125 <span class="comment">/// initial starting point).</span>
<a name="l00126"></a>00126 <span class="comment">///</span>
<a name="l00127"></a>00127 <span class="comment">/// The fastest motor speed that can be reliably supported is 4000 steps per</span>
<a name="l00128"></a>00128 <span class="comment">/// second (4 kHz) at a clock frequency of 16 MHz. However, any speed less than that</span>
<a name="l00129"></a>00129 <span class="comment">/// down to very slow speeds (much less than one per second) are also supported,</span>
<a name="l00130"></a>00130 <span class="comment">/// provided the run() function is called frequently enough to step the motor</span>
<a name="l00131"></a>00131 <span class="comment">/// whenever required for the speed set.</span>
<a name="l00132"></a><a class="code" href="classAccelStepper.html">00132</a> <span class="comment"></span><span class="keyword">class </span><a class="code" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc.">AccelStepper</a>
<a name="l00133"></a>00133 {
<a name="l00134"></a>00134 <span class="keyword">public</span>:<span class="comment"></span>
<a name="l00135"></a>00135 <span class="comment"> /// Constructor. You can have multiple simultaneous steppers, all moving</span>
<a name="l00136"></a>00136 <span class="comment"> /// at different speeds and accelerations, provided you call their run()</span>
<a name="l00137"></a>00137 <span class="comment"> /// functions at frequent enough intervals. Current Position is set to 0, target</span>
<a name="l00138"></a>00138 <span class="comment"> /// position is set to 0. MaxSpeed and Acceleration default to 1.0.</span>
<a name="l00139"></a>00139 <span class="comment"> /// The motor pins will be initialised to OUTPUT mode during the</span>
<a name="l00140"></a>00140 <span class="comment"> /// constructor by a call to enableOutputs().</span>
<a name="l00141"></a>00141 <span class="comment"> /// \param[in] pins Number of pins to interface to. 1, 2 or 4 are</span>
<a name="l00142"></a>00142 <span class="comment"> /// supported. 1 means a stepper driver (with Step and Direction pins).</span>
<a name="l00143"></a>00143 <span class="comment"> /// If an enable line is also needed, call setEnablePin() after construction.</span>
<a name="l00144"></a>00144 <span class="comment"> /// You may also invert the pins using setPinsInverted().</span>
<a name="l00145"></a>00145 <span class="comment"> /// 2 means a 2 wire stepper. 4 means a 4 wire stepper. 8 means a 4 wire half stepper</span>
<a name="l00146"></a>00146 <span class="comment"> /// Defaults to 4 pins.</span>
<a name="l00147"></a>00147 <span class="comment"> /// \param[in] pin1 Arduino digital pin number for motor pin 1. Defaults</span>
<a name="l00148"></a>00148 <span class="comment"> /// to pin 2. For a driver (pins==1), this is the Step input to the driver. Low to high transition means to step)</span>
<a name="l00149"></a>00149 <span class="comment"> /// \param[in] pin2 Arduino digital pin number for motor pin 2. Defaults</span>
<a name="l00150"></a>00150 <span class="comment"> /// to pin 3. For a driver (pins==1), this is the Direction input the driver. High means forward.</span>
<a name="l00151"></a>00151 <span class="comment"> /// \param[in] pin3 Arduino digital pin number for motor pin 3. Defaults</span>
<a name="l00152"></a>00152 <span class="comment"> /// to pin 4.</span>
<a name="l00153"></a>00153 <span class="comment"> /// \param[in] pin4 Arduino digital pin number for motor pin 4. Defaults</span>
<a name="l00154"></a>00154 <span class="comment"> /// to pin 5.</span>
<a name="l00155"></a>00155 <span class="comment"></span> <a class="code" href="classAccelStepper.html#a1290897df35915069e5eca9d034038c">AccelStepper</a>(uint8_t pins = 4, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5);
<a name="l00156"></a>00156 <span class="comment"></span>
<a name="l00157"></a>00157 <span class="comment"> /// Alternate Constructor which will call your own functions for forward and backward steps. </span>
<a name="l00158"></a>00158 <span class="comment"> /// You can have multiple simultaneous steppers, all moving</span>
<a name="l00159"></a>00159 <span class="comment"> /// at different speeds and accelerations, provided you call their run()</span>
<a name="l00160"></a>00160 <span class="comment"> /// functions at frequent enough intervals. Current Position is set to 0, target</span>
<a name="l00161"></a>00161 <span class="comment"> /// position is set to 0. MaxSpeed and Acceleration default to 1.0.</span>
<a name="l00162"></a>00162 <span class="comment"> /// Any motor initialization should happen before hand, no pins are used or initialized.</span>
<a name="l00163"></a>00163 <span class="comment"> /// \param[in] forward void-returning procedure that will make a forward step</span>
<a name="l00164"></a>00164 <span class="comment"> /// \param[in] backward void-returning procedure that will make a backward step</span>
<a name="l00165"></a>00165 <span class="comment"></span> <a class="code" href="classAccelStepper.html#a1290897df35915069e5eca9d034038c">AccelStepper</a>(<span class="keywordtype">void</span> (*forward)(), <span class="keywordtype">void</span> (*backward)());
<a name="l00166"></a>00166 <span class="comment"></span>
<a name="l00167"></a>00167 <span class="comment"> /// Set the target position. The run() function will try to move the motor</span>
<a name="l00168"></a>00168 <span class="comment"> /// from the current position to the target position set by the most</span>
<a name="l00169"></a>00169 <span class="comment"> /// recent call to this function.</span>
<a name="l00170"></a>00170 <span class="comment"> /// \param[in] absolute The desired absolute position. Negative is</span>
<a name="l00171"></a>00171 <span class="comment"> /// anticlockwise from the 0 position.</span>
<a name="l00172"></a>00172 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#ce236ede35f87c63d18da25810ec9736">moveTo</a>(<span class="keywordtype">long</span> absolute);
<a name="l00173"></a>00173 <span class="comment"></span>
<a name="l00174"></a>00174 <span class="comment"> /// Set the target position relative to the current position</span>
<a name="l00175"></a>00175 <span class="comment"> /// \param[in] relative The desired position relative to the current position. Negative is</span>
<a name="l00176"></a>00176 <span class="comment"> /// anticlockwise from the current position.</span>
<a name="l00177"></a>00177 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#68942c66e78fb7f7b5f0cdade6eb7f06">move</a>(<span class="keywordtype">long</span> relative);
<a name="l00178"></a>00178 <span class="comment"></span>
<a name="l00179"></a>00179 <span class="comment"> /// Poll the motor and step it if a step is due, implementing</span>
<a name="l00180"></a>00180 <span class="comment"> /// accelerations and decelerations to achive the ratget position. You must call this as</span>
<a name="l00181"></a>00181 <span class="comment"> /// fequently as possible, but at least once per minimum step interval,</span>
<a name="l00182"></a>00182 <span class="comment"> /// preferably in your main loop.</span>
<a name="l00183"></a>00183 <span class="comment"> /// \return true if the motor is at the target position.</span>
<a name="l00184"></a>00184 <span class="comment"></span> <span class="keywordtype">boolean</span> <a class="code" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run</a>();
<a name="l00185"></a>00185 <span class="comment"></span>
<a name="l00186"></a>00186 <span class="comment"> /// Poll the motor and step it if a step is due, implmenting a constant</span>
<a name="l00187"></a>00187 <span class="comment"> /// speed as set by the most recent call to setSpeed().</span>
<a name="l00188"></a>00188 <span class="comment"> /// \return true if the motor was stepped.</span>
<a name="l00189"></a>00189 <span class="comment"></span> <span class="keywordtype">boolean</span> <a class="code" href="classAccelStepper.html#a4a6bdf99f698284faaeb5542b0b7514">runSpeed</a>();
<a name="l00190"></a>00190 <span class="comment"></span>
<a name="l00191"></a>00191 <span class="comment"> /// Sets the maximum permitted speed. the run() function will accelerate</span>
<a name="l00192"></a>00192 <span class="comment"> /// up to the speed set by this function.</span>
<a name="l00193"></a>00193 <span class="comment"> /// \param[in] speed The desired maximum speed in steps per second. Must</span>
<a name="l00194"></a>00194 <span class="comment"> /// be &gt; 0. Speeds of more than 1000 steps per second are unreliable. </span>
<a name="l00195"></a>00195 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#bee8d466229b87accba33d6ec929c18f">setMaxSpeed</a>(<span class="keywordtype">float</span> <a class="code" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">speed</a>);
<a name="l00196"></a>00196 <span class="comment"></span>
<a name="l00197"></a>00197 <span class="comment"> /// Sets the acceleration and deceleration parameter.</span>
<a name="l00198"></a>00198 <span class="comment"> /// \param[in] acceleration The desired acceleration in steps per second</span>
<a name="l00199"></a>00199 <span class="comment"> /// per second. Must be &gt; 0.</span>
<a name="l00200"></a>00200 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#dfb19e3cd2a028a1fe78131787604fd1">setAcceleration</a>(<span class="keywordtype">float</span> acceleration);
<a name="l00201"></a>00201 <span class="comment"></span>
<a name="l00202"></a>00202 <span class="comment"> /// Sets the desired constant speed for use with runSpeed().</span>
<a name="l00203"></a>00203 <span class="comment"> /// \param[in] speed The desired constant speed in steps per</span>
<a name="l00204"></a>00204 <span class="comment"> /// second. Positive is clockwise. Speeds of more than 1000 steps per</span>
<a name="l00205"></a>00205 <span class="comment"> /// second are unreliable. Very slow speeds may be set (eg 0.00027777 for</span>
<a name="l00206"></a>00206 <span class="comment"> /// once per hour, approximately. Speed accuracy depends on the Arduino</span>
<a name="l00207"></a>00207 <span class="comment"> /// crystal. Jitter depends on how frequently you call the runSpeed() function.</span>
<a name="l00208"></a>00208 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#e79c49ad69d5ccc9da0ee691fa4ca235">setSpeed</a>(<span class="keywordtype">float</span> speed);
<a name="l00209"></a>00209 <span class="comment"></span>
<a name="l00210"></a>00210 <span class="comment"> /// The most recently set speed</span>
<a name="l00211"></a>00211 <span class="comment"> /// \return the most recent speed in steps per second</span>
<a name="l00212"></a>00212 <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">speed</a>();
<a name="l00213"></a>00213 <span class="comment"></span>
<a name="l00214"></a>00214 <span class="comment"> /// The distance from the current position to the target position.</span>
<a name="l00215"></a>00215 <span class="comment"> /// \return the distance from the current position to the target position</span>
<a name="l00216"></a>00216 <span class="comment"> /// in steps. Positive is clockwise from the current position.</span>
<a name="l00217"></a>00217 <span class="comment"></span> <span class="keywordtype">long</span> <a class="code" href="classAccelStepper.html#748665c3962e66fbc0e9373eb14c69c1">distanceToGo</a>();
<a name="l00218"></a>00218 <span class="comment"></span>
<a name="l00219"></a>00219 <span class="comment"> /// The most recently set target position.</span>
<a name="l00220"></a>00220 <span class="comment"> /// \return the target position</span>
<a name="l00221"></a>00221 <span class="comment"> /// in steps. Positive is clockwise from the 0 position.</span>
<a name="l00222"></a>00222 <span class="comment"></span> <span class="keywordtype">long</span> <a class="code" href="classAccelStepper.html#96685e0945b7cf75d5959da679cd911e">targetPosition</a>();
<a name="l00223"></a>00223
<a name="l00224"></a>00224 <span class="comment"></span>
<a name="l00225"></a>00225 <span class="comment"> /// The currently motor position.</span>
<a name="l00226"></a>00226 <span class="comment"> /// \return the current motor position</span>
<a name="l00227"></a>00227 <span class="comment"> /// in steps. Positive is clockwise from the 0 position.</span>
<a name="l00228"></a>00228 <span class="comment"></span> <span class="keywordtype">long</span> <a class="code" href="classAccelStepper.html#5dce13ab2a1b02b8f443318886bf6fc5">currentPosition</a>();
<a name="l00229"></a>00229 <span class="comment"></span>
<a name="l00230"></a>00230 <span class="comment"> /// Resets the current position of the motor, so that wherever the motor</span>
<a name="l00231"></a>00231 <span class="comment"> /// happens to be right now is considered to be the new 0 position. Useful</span>
<a name="l00232"></a>00232 <span class="comment"> /// for setting a zero position on a stepper after an initial hardware</span>
<a name="l00233"></a>00233 <span class="comment"> /// positioning move.</span>
<a name="l00234"></a>00234 <span class="comment"> /// Has the side effect of setting the current motor speed to 0.</span>
<a name="l00235"></a>00235 <span class="comment"> /// \param[in] position The position in steps of wherever the motor</span>
<a name="l00236"></a>00236 <span class="comment"> /// happens to be right now.</span>
<a name="l00237"></a>00237 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#9d917f014317fb9d3b5dc14e66f6c689">setCurrentPosition</a>(<span class="keywordtype">long</span> position);
<a name="l00238"></a>00238 <span class="comment"></span>
<a name="l00239"></a>00239 <span class="comment"> /// Moves the motor to the target position and blocks until it is at</span>
<a name="l00240"></a>00240 <span class="comment"> /// position. Dont use this in event loops, since it blocks.</span>
<a name="l00241"></a>00241 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#344f58fef8cc34ac5aa75ba4b665d21c">runToPosition</a>();
<a name="l00242"></a>00242 <span class="comment"></span>
<a name="l00243"></a>00243 <span class="comment"> /// Runs at the currently selected speed until the target position is reached</span>
<a name="l00244"></a>00244 <span class="comment"> /// Does not implement accelerations.</span>
<a name="l00245"></a>00245 <span class="comment"></span> <span class="keywordtype">boolean</span> <a class="code" href="classAccelStepper.html#9270d20336e76ac1fd5bcd5b9c34f301">runSpeedToPosition</a>();
<a name="l00246"></a>00246 <span class="comment"></span>
<a name="l00247"></a>00247 <span class="comment"> /// Moves the motor to the new target position and blocks until it is at</span>
<a name="l00248"></a>00248 <span class="comment"> /// position. Dont use this in event loops, since it blocks.</span>
<a name="l00249"></a>00249 <span class="comment"> /// \param[in] position The new target position.</span>
<a name="l00250"></a>00250 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#176c5d2e4c2f21e9e92b12e39a6f0e67">runToNewPosition</a>(<span class="keywordtype">long</span> position);
<a name="l00251"></a>00251 <span class="comment"></span>
<a name="l00252"></a>00252 <span class="comment"> /// Disable motor pin outputs by setting them all LOW</span>
<a name="l00253"></a>00253 <span class="comment"> /// Depending on the design of your electronics this may turn off</span>
<a name="l00254"></a>00254 <span class="comment"> /// the power to the motor coils, saving power.</span>
<a name="l00255"></a>00255 <span class="comment"> /// This is useful to support Arduino low power modes: disable the outputs</span>
<a name="l00256"></a>00256 <span class="comment"> /// during sleep and then reenable with enableOutputs() before stepping</span>
<a name="l00257"></a>00257 <span class="comment"> /// again.</span>
<a name="l00258"></a>00258 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#3591e29a236e2935afd7f64ff6c22006">disableOutputs</a>();
<a name="l00259"></a>00259 <span class="comment"></span>
<a name="l00260"></a>00260 <span class="comment"> /// Enable motor pin outputs by setting the motor pins to OUTPUT</span>
<a name="l00261"></a>00261 <span class="comment"> /// mode. Called automatically by the constructor.</span>
<a name="l00262"></a>00262 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#a279a50d30d0413f570c692cff071643">enableOutputs</a>();
<a name="l00263"></a>00263 <span class="comment"></span>
<a name="l00264"></a>00264 <span class="comment"> /// Sets the minimum pulse width allowed by the stepper driver.</span>
<a name="l00265"></a>00265 <span class="comment"> /// \param[in] minWidth The minimum pulse width in microseconds.</span>
<a name="l00266"></a>00266 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#f4d3818e691dad5dc518308796ccf154">setMinPulseWidth</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> minWidth);
<a name="l00267"></a>00267 <span class="comment"></span>
<a name="l00268"></a>00268 <span class="comment"> /// Sets the enable pin number for stepper drivers.</span>
<a name="l00269"></a>00269 <span class="comment"> /// 0xFF indicates unused (default).</span>
<a name="l00270"></a>00270 <span class="comment"> /// Otherwise, if a pin is set, the pin will be turned on when </span>
<a name="l00271"></a>00271 <span class="comment"> /// enableOutputs() is called and switched off when disableOutputs() </span>
<a name="l00272"></a>00272 <span class="comment"> /// is called.</span>
<a name="l00273"></a>00273 <span class="comment"> /// \param[in] enablePin Arduino digital pin number for motor enable</span>
<a name="l00274"></a>00274 <span class="comment"> /// \sa setPinsInverted</span>
<a name="l00275"></a>00275 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#56a81c5f00d02ca19646718e88e974c0">setEnablePin</a>(uint8_t enablePin = 0xff);
<a name="l00276"></a>00276 <span class="comment"></span>
<a name="l00277"></a>00277 <span class="comment"> /// Sets the inversion for stepper driver pins</span>
<a name="l00278"></a>00278 <span class="comment"> /// \param[in] direction True for inverted direction pin, false for non-inverted</span>
<a name="l00279"></a>00279 <span class="comment"> /// \param[in] step True for inverted step pin, false for non-inverted</span>
<a name="l00280"></a>00280 <span class="comment"> /// \param[in] enable True for inverted enable pin, false (default) for non-inverted</span>
<a name="l00281"></a>00281 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#797b4bdb580d4ca7a1cfeabe3df0de35">setPinsInverted</a>(<span class="keywordtype">bool</span> direction, <span class="keywordtype">bool</span> <a class="code" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">step</a>, <span class="keywordtype">bool</span> enable = <span class="keyword">false</span>);
<a name="l00282"></a>00282
<a name="l00283"></a>00283 <span class="keyword">protected</span>:
<a name="l00284"></a>00284 <span class="comment"></span>
<a name="l00285"></a>00285 <span class="comment"> /// Forces the library to compute a new instantaneous speed and set that as</span>
<a name="l00286"></a>00286 <span class="comment"> /// the current speed. Calls</span>
<a name="l00287"></a>00287 <span class="comment"> /// desiredSpeed(), which can be overridden by subclasses. It is called by</span>
<a name="l00288"></a>00288 <span class="comment"> /// the library:</span>
<a name="l00289"></a>00289 <span class="comment"> /// \li after each step</span>
<a name="l00290"></a>00290 <span class="comment"> /// \li after change to maxSpeed through setMaxSpeed()</span>
<a name="l00291"></a>00291 <span class="comment"> /// \li after change to acceleration through setAcceleration()</span>
<a name="l00292"></a>00292 <span class="comment"> /// \li after change to target position (relative or absolute) through</span>
<a name="l00293"></a>00293 <span class="comment"> /// move() or moveTo()</span>
<a name="l00294"></a>00294 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#ffbee789b5c19165846cf0409860ae79">computeNewSpeed</a>();
<a name="l00295"></a>00295 <span class="comment"></span>
<a name="l00296"></a>00296 <span class="comment"> /// Called to execute a step. Only called when a new step is</span>
<a name="l00297"></a>00297 <span class="comment"> /// required. Subclasses may override to implement new stepping</span>
<a name="l00298"></a>00298 <span class="comment"> /// interfaces. The default calls step1(), step2(), step4() or step8() depending on the</span>
<a name="l00299"></a>00299 <span class="comment"> /// number of pins defined for the stepper.</span>
<a name="l00300"></a>00300 <span class="comment"> /// \param[in] step The current step phase number (0 to 7)</span>
<a name="l00301"></a>00301 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">step</a>(uint8_t step);
<a name="l00302"></a>00302 <span class="comment"></span>
<a name="l00303"></a>00303 <span class="comment"> /// Called to execute a step using stepper functions (pins = 0) Only called when a new step is</span>
<a name="l00304"></a>00304 <span class="comment"> /// required. Calls _forward() or _backward() to perform the step</span>
<a name="l00305"></a>00305 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#889f109756aa4c0a2feefebd8081a337">step0</a>(<span class="keywordtype">void</span>);
<a name="l00306"></a>00306 <span class="comment"></span>
<a name="l00307"></a>00307 <span class="comment"> /// Called to execute a step on a stepper drover (ie where pins == 1). Only called when a new step is</span>
<a name="l00308"></a>00308 <span class="comment"> /// required. Subclasses may override to implement new stepping</span>
<a name="l00309"></a>00309 <span class="comment"> /// interfaces. The default sets or clears the outputs of Step pin1 to step, </span>
<a name="l00310"></a>00310 <span class="comment"> /// and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond</span>
<a name="l00311"></a>00311 <span class="comment"> /// which is the minimum STEP pulse width for the 3967 driver.</span>
<a name="l00312"></a>00312 <span class="comment"> /// \param[in] step The current step phase number (0 to 7)</span>
<a name="l00313"></a>00313 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#cc64254ea242b53588e948335fd9305f">step1</a>(uint8_t step);
<a name="l00314"></a>00314 <span class="comment"></span>
<a name="l00315"></a>00315 <span class="comment"> /// Called to execute a step on a 2 pin motor. Only called when a new step is</span>
<a name="l00316"></a>00316 <span class="comment"> /// required. Subclasses may override to implement new stepping</span>
<a name="l00317"></a>00317 <span class="comment"> /// interfaces. The default sets or clears the outputs of pin1 and pin2</span>
<a name="l00318"></a>00318 <span class="comment"> /// \param[in] step The current step phase number (0 to 7)</span>
<a name="l00319"></a>00319 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#88f11bf6361fe002585f731d34fe2e8b">step2</a>(uint8_t step);
<a name="l00320"></a>00320 <span class="comment"></span>
<a name="l00321"></a>00321 <span class="comment"> /// Called to execute a step on a 4 pin motor. Only called when a new step is</span>
<a name="l00322"></a>00322 <span class="comment"> /// required. Subclasses may override to implement new stepping</span>
<a name="l00323"></a>00323 <span class="comment"> /// interfaces. The default sets or clears the outputs of pin1, pin2,</span>
<a name="l00324"></a>00324 <span class="comment"> /// pin3, pin4.</span>
<a name="l00325"></a>00325 <span class="comment"> /// \param[in] step The current step phase number (0 to 7)</span>
<a name="l00326"></a>00326 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#49e448d179bbe4e0f8003a3f9993789d">step4</a>(uint8_t step);
<a name="l00327"></a>00327 <span class="comment"></span>
<a name="l00328"></a>00328 <span class="comment"> /// Called to execute a step on a 4 pin half-steper motor. Only called when a new step is</span>
<a name="l00329"></a>00329 <span class="comment"> /// required. Subclasses may override to implement new stepping</span>
<a name="l00330"></a>00330 <span class="comment"> /// interfaces. The default sets or clears the outputs of pin1, pin2,</span>
<a name="l00331"></a>00331 <span class="comment"> /// pin3, pin4.</span>
<a name="l00332"></a>00332 <span class="comment"> /// \param[in] step The current step phase number (0 to 7)</span>
<a name="l00333"></a>00333 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#5b33d1088e2beaf2176c42b08fb675ea">step8</a>(uint8_t step);
<a name="l00334"></a>00334 <span class="comment"></span>
<a name="l00335"></a>00335 <span class="comment"> /// Compute and return the desired speed. The default algorithm uses</span>
<a name="l00336"></a>00336 <span class="comment"> /// maxSpeed, acceleration and the current speed to set a new speed to</span>
<a name="l00337"></a>00337 <span class="comment"> /// move the motor from teh current position to the target</span>
<a name="l00338"></a>00338 <span class="comment"> /// position. Subclasses may override this to provide an alternate</span>
<a name="l00339"></a>00339 <span class="comment"> /// algorithm (but do not block). Called by computeNewSpeed whenever a new speed neds to be</span>
<a name="l00340"></a>00340 <span class="comment"> /// computed. </span>
<a name="l00341"></a>00341 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">float</span> <a class="code" href="classAccelStepper.html#6e4bd79c395e69beee31d76d0d3287e4">desiredSpeed</a>();
<a name="l00342"></a>00342
<a name="l00343"></a>00343 <span class="keyword">private</span>:<span class="comment"></span>
<a name="l00344"></a>00344 <span class="comment"> /// Number of pins on the stepper motor. Permits 2 or 4. 2 pins is a</span>
<a name="l00345"></a>00345 <span class="comment"> /// bipolar, and 4 pins is a unipolar.</span>
<a name="l00346"></a>00346 <span class="comment"></span> uint8_t _pins; <span class="comment">// 2 or 4</span>
<a name="l00347"></a>00347 <span class="comment"></span>
<a name="l00348"></a>00348 <span class="comment"> /// Arduino pin number for the 2 or 4 pins required to interface to the</span>
<a name="l00349"></a>00349 <span class="comment"> /// stepper motor.</span>
<a name="l00350"></a>00350 <span class="comment"></span> uint8_t _pin1, _pin2, _pin3, _pin4;
<a name="l00351"></a>00351 <span class="comment"></span>
<a name="l00352"></a>00352 <span class="comment"> /// The current absolution position in steps.</span>
<a name="l00353"></a>00353 <span class="comment"></span> <span class="keywordtype">long</span> _currentPos; <span class="comment">// Steps</span>
<a name="l00354"></a>00354 <span class="comment"></span>
<a name="l00355"></a>00355 <span class="comment"> /// The target position in steps. The AccelStepper library will move the</span>
<a name="l00356"></a>00356 <span class="comment"> /// motor from the _currentPos to the _targetPos, taking into account the</span>
<a name="l00357"></a>00357 <span class="comment"> /// max speed, acceleration and deceleration</span>
<a name="l00358"></a>00358 <span class="comment"></span> <span class="keywordtype">long</span> _targetPos; <span class="comment">// Steps</span>
<a name="l00359"></a>00359 <span class="comment"></span>
<a name="l00360"></a>00360 <span class="comment"> /// The current motos speed in steps per second</span>
<a name="l00361"></a>00361 <span class="comment"> /// Positive is clockwise</span>
<a name="l00362"></a>00362 <span class="comment"></span> <span class="keywordtype">float</span> _speed; <span class="comment">// Steps per second</span>
<a name="l00363"></a>00363 <span class="comment"></span>
<a name="l00364"></a>00364 <span class="comment"> /// The maximum permitted speed in steps per second. Must be &gt; 0.</span>
<a name="l00365"></a>00365 <span class="comment"></span> <span class="keywordtype">float</span> _maxSpeed;
<a name="l00366"></a>00366 <span class="comment"></span>
<a name="l00367"></a>00367 <span class="comment"> /// The acceleration to use to accelerate or decelerate the motor in steps</span>
<a name="l00368"></a>00368 <span class="comment"> /// per second per second. Must be &gt; 0</span>
<a name="l00369"></a>00369 <span class="comment"></span> <span class="keywordtype">float</span> _acceleration;
<a name="l00370"></a>00370 <span class="comment"></span>
<a name="l00371"></a>00371 <span class="comment"> /// The current interval between steps in microseconds</span>
<a name="l00372"></a>00372 <span class="comment"></span> <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> _stepInterval;
<a name="l00373"></a>00373 <span class="comment"></span>
<a name="l00374"></a>00374 <span class="comment"> /// The last step time in microseconds</span>
<a name="l00375"></a>00375 <span class="comment"></span> <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> _lastStepTime;
<a name="l00376"></a>00376 <span class="comment"></span>
<a name="l00377"></a>00377 <span class="comment"> /// The minimum allowed pulse width in microseconds</span>
<a name="l00378"></a>00378 <span class="comment"></span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> _minPulseWidth;
<a name="l00379"></a>00379 <span class="comment"></span>
<a name="l00380"></a>00380 <span class="comment"> /// Is the direction pin inverted?</span>
<a name="l00381"></a>00381 <span class="comment"></span> <span class="keywordtype">bool</span> _dirInverted;
<a name="l00382"></a>00382 <span class="comment"></span>
<a name="l00383"></a>00383 <span class="comment"> /// Is the step pin inverted?</span>
<a name="l00384"></a>00384 <span class="comment"></span> <span class="keywordtype">bool</span> _stepInverted;
<a name="l00385"></a>00385 <span class="comment"></span>
<a name="l00386"></a>00386 <span class="comment"> /// Is the enable pin inverted?</span>
<a name="l00387"></a>00387 <span class="comment"></span> <span class="keywordtype">bool</span> _enableInverted;
<a name="l00388"></a>00388 <span class="comment"></span>
<a name="l00389"></a>00389 <span class="comment"> /// Enable pin for stepper driver, or 0xFF if unused.</span>
<a name="l00390"></a>00390 <span class="comment"></span> uint8_t _enablePin;
<a name="l00391"></a>00391
<a name="l00392"></a>00392 <span class="comment">// The pointer to a forward-step procedure</span>
<a name="l00393"></a>00393 void (*_forward)();
<a name="l00394"></a>00394
<a name="l00395"></a>00395 <span class="comment">// The pointer to a backward-step procedure</span>
<a name="l00396"></a>00396 void (*_backward)();
<a name="l00397"></a>00397 };
<a name="l00398"></a>00398
<a name="l00399"></a>00399 <span class="preprocessor">#endif </span>
</pre></div></div>
<hr size="1"><address style="text-align: right;"><small>Generated on Sun Jan 8 17:27:41 2012 for AccelStepper by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
</body>
</html>

View File

@ -0,0 +1,63 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<meta name="generator" content="Doxygen 1.8.11"/>
<title>AccelStepper: Class List</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="jquery.js"></script>
<script type="text/javascript" src="dynsections.js"></script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td id="projectalign" style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.11 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
<li><a href="examples.html"><span>Examples</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li class="current"><a href="annotated.html"><span>Class&#160;List</span></a></li>
<li><a href="functions.html"><span>Class&#160;Members</span></a></li>
</ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title">Class List</div> </div>
</div><!--header-->
<div class="contents">
<div class="textblock">Here are the classes, structs, unions and interfaces with brief descriptions:</div><div class="directory">
<table class="directory">
<tr id="row_0_" class="even"><td class="entry"><span style="width:16px;display:inline-block;">&#160;</span><span class="icona"><span class="icon">C</span></span><a class="el" href="classAccelStepper.html" target="_self">AccelStepper</a></td><td class="desc">Support for stepper motors with acceleration etc </td></tr>
<tr id="row_1_"><td class="entry"><span style="width:16px;display:inline-block;">&#160;</span><span class="icona"><span class="icon">C</span></span><a class="el" href="classMultiStepper.html" target="_self">MultiStepper</a></td><td class="desc">Operate multiple AccelSteppers in a co-ordinated fashion </td></tr>
</table>
</div><!-- directory -->
</div><!-- contents -->
<!-- start footer part -->
<hr class="footer"/><address class="footer"><small>
Generated by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.8.11
</small></address>
</body>
</html>

View File

@ -0,0 +1,108 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<meta name="generator" content="Doxygen 1.8.11"/>
<title>AccelStepper: Member List</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="jquery.js"></script>
<script type="text/javascript" src="dynsections.js"></script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td id="projectalign" style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.11 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
<li><a href="examples.html"><span>Examples</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="annotated.html"><span>Class&#160;List</span></a></li>
<li><a href="functions.html"><span>Class&#160;Members</span></a></li>
</ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title">AccelStepper Member List</div> </div>
</div><!--header-->
<div class="contents">
<p>This is the complete list of members for <a class="el" href="classAccelStepper.html">AccelStepper</a>, including all inherited members.</p>
<table class="directory">
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a35162cdf8ed9a98f98984c177d5ade58">_direction</a></td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a3bc75bd6571b98a6177838ca81ac39ab">AccelStepper</a>(uint8_t interface=AccelStepper::FULL4WIRE, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5, bool enable=true)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#afa3061ce813303a8f2fa206ee8d012bd">AccelStepper</a>(void(*forward)(), void(*backward)())</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#affbee789b5c19165846cf0409860ae79">computeNewSpeed</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a5dce13ab2a1b02b8f443318886bf6fc5">currentPosition</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228">Direction</a> enum name</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228a6959a4549f734bd771d418f995ba4fb4">DIRECTION_CCW</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228ad604e0047f7cb47662c5a1cf6999337c">DIRECTION_CW</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a3591e29a236e2935afd7f64ff6c22006">disableOutputs</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">virtual</span></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a748665c3962e66fbc0e9373eb14c69c1">distanceToGo</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5ac3523e4cf6763ba518d16fec3708ef23">DRIVER</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#aa279a50d30d0413f570c692cff071643">enableOutputs</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">virtual</span></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a62a305b52f749ff8c89138273fbb012d">FULL2WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a0b8eea5cf0f8ce70b1959d2977ccc996">FULL3WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5adedd394a375190a3df8d4519c0d4dc2f">FULL4WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5af5bb99ad9d67ad2d85f840e3abcfe068">FUNCTION</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a00c2387a5af43d8e97639699ab7a5c7f">HALF3WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5aecc0900c55b777d2e885581b8c434b07">HALF4WIRE</a> enum value</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a3a60cc0b962f8ceb81ee1e6f36443ceb">isRunning</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a6123a1dfb4495d8bd2646288eae60d7f">maxSpeed</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5">MotorInterfaceType</a> enum name</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a68942c66e78fb7f7b5f0cdade6eb7f06">move</a>(long relative)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#ace236ede35f87c63d18da25810ec9736">moveTo</a>(long absolute)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a608b2395b64ac15451d16d0371fe13ce">run</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#aa4a6bdf99f698284faaeb5542b0b7514">runSpeed</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a9270d20336e76ac1fd5bcd5b9c34f301">runSpeedToPosition</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a176c5d2e4c2f21e9e92b12e39a6f0e67">runToNewPosition</a>(long position)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a344f58fef8cc34ac5aa75ba4b665d21c">runToPosition</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#adfb19e3cd2a028a1fe78131787604fd1">setAcceleration</a>(float acceleration)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a9d917f014317fb9d3b5dc14e66f6c689">setCurrentPosition</a>(long position)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a56a81c5f00d02ca19646718e88e974c0">setEnablePin</a>(uint8_t enablePin=0xff)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#abee8d466229b87accba33d6ec929c18f">setMaxSpeed</a>(float speed)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#af4d3818e691dad5dc518308796ccf154">setMinPulseWidth</a>(unsigned int minWidth)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#af3c2516b6ce7c1ecbc2004107bb2a9ce">setOutputPins</a>(uint8_t mask)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#ac62cae590c2f9c303519a3a1c4adc8ab">setPinsInverted</a>(bool directionInvert=false, bool stepInvert=false, bool enableInvert=false)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a38298ac2dd852fb22259f6c4bbe08c94">setPinsInverted</a>(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#ae79c49ad69d5ccc9da0ee691fa4ca235">setSpeed</a>(float speed)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a4f0989d0ae264e7eadfe1fa720769fb6">speed</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a8a419121702399d8ac66df4cc47481f4">step</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#aa2913db789e6fa05756579ff82fe6e7e">step0</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a63ef416bc039da539294e84a41e7d7dc">step1</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a674e48a6bf99e7ad1f013c1e4414565a">step2</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#ad73c61aade2e10243dfb02aefa7ab8fd">step3</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a8910bd9218a54dfb7e2372a6d0bcca0c">step4</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a4b0faf1ebc0c584ab606c0c0f66986b0">step6</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#aa909c6c3fcd3ea4b3ee1aa8b4d0f7e87">step8</a>(long step)</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"><span class="mlabel">protected</span><span class="mlabel">virtual</span></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classAccelStepper.html#a638817b85aed9d5cd15c76a76c00aced">stop</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classAccelStepper.html#a96685e0945b7cf75d5959da679cd911e">targetPosition</a>()</td><td class="entry"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="entry"></td></tr>
</table></div><!-- contents -->
<!-- start footer part -->
<hr class="footer"/><address class="footer"><small>
Generated by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.8.11
</small></address>
</body>
</html>

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.7 KiB

View File

@ -0,0 +1,62 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<meta name="generator" content="Doxygen 1.8.11"/>
<title>AccelStepper: File List</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="jquery.js"></script>
<script type="text/javascript" src="dynsections.js"></script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td id="projectalign" style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.11 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
<li><a href="examples.html"><span>Examples</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li class="current"><a href="files.html"><span>File&#160;List</span></a></li>
</ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title">File List</div> </div>
</div><!--header-->
<div class="contents">
<div class="textblock">Here is a list of all documented files with brief descriptions:</div><div class="directory">
<table class="directory">
<tr id="row_0_" class="even"><td class="entry"><span style="width:16px;display:inline-block;">&#160;</span><a href="AccelStepper_8h_source.html"><span class="icondoc"></span></a><b>AccelStepper.h</b></td><td class="desc"></td></tr>
<tr id="row_1_"><td class="entry"><span style="width:16px;display:inline-block;">&#160;</span><a href="MultiStepper_8h_source.html"><span class="icondoc"></span></a><b>MultiStepper.h</b></td><td class="desc"></td></tr>
</table>
</div><!-- directory -->
</div><!-- contents -->
<!-- start footer part -->
<hr class="footer"/><address class="footer"><small>
Generated by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.8.11
</small></address>
</body>
</html>

View File

@ -0,0 +1,273 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<meta name="generator" content="Doxygen 1.8.11"/>
<title>AccelStepper: Class Members</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="jquery.js"></script>
<script type="text/javascript" src="dynsections.js"></script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td id="projectalign" style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.11 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
<li><a href="examples.html"><span>Examples</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="annotated.html"><span>Class&#160;List</span></a></li>
<li class="current"><a href="functions.html"><span>Class&#160;Members</span></a></li>
</ul>
</div>
<div id="navrow3" class="tabs2">
<ul class="tablist">
<li class="current"><a href="functions.html"><span>All</span></a></li>
<li><a href="functions_func.html"><span>Functions</span></a></li>
<li><a href="functions_vars.html"><span>Variables</span></a></li>
<li><a href="functions_enum.html"><span>Enumerations</span></a></li>
<li><a href="functions_eval.html"><span>Enumerator</span></a></li>
</ul>
</div>
<div id="navrow4" class="tabs3">
<ul class="tablist">
<li><a href="#index__"><span>_</span></a></li>
<li><a href="#index_a"><span>a</span></a></li>
<li><a href="#index_c"><span>c</span></a></li>
<li><a href="#index_d"><span>d</span></a></li>
<li><a href="#index_e"><span>e</span></a></li>
<li><a href="#index_f"><span>f</span></a></li>
<li><a href="#index_h"><span>h</span></a></li>
<li><a href="#index_i"><span>i</span></a></li>
<li><a href="#index_m"><span>m</span></a></li>
<li><a href="#index_r"><span>r</span></a></li>
<li><a href="#index_s"><span>s</span></a></li>
<li class="current"><a href="#index_t"><span>t</span></a></li>
</ul>
</div>
</div><!-- top -->
<div class="contents">
<div class="textblock">Here is a list of all documented class members with links to the class documentation for each member:</div>
<h3><a class="anchor" id="index__"></a>- _ -</h3><ul>
<li>_direction
: <a class="el" href="classAccelStepper.html#a35162cdf8ed9a98f98984c177d5ade58">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_a"></a>- a -</h3><ul>
<li>AccelStepper()
: <a class="el" href="classAccelStepper.html#a3bc75bd6571b98a6177838ca81ac39ab">AccelStepper</a>
</li>
<li>addStepper()
: <a class="el" href="classMultiStepper.html#a383d8486e17ad9de9f1bafcbd9aa52ee">MultiStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_c"></a>- c -</h3><ul>
<li>computeNewSpeed()
: <a class="el" href="classAccelStepper.html#affbee789b5c19165846cf0409860ae79">AccelStepper</a>
</li>
<li>currentPosition()
: <a class="el" href="classAccelStepper.html#a5dce13ab2a1b02b8f443318886bf6fc5">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_d"></a>- d -</h3><ul>
<li>Direction
: <a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228">AccelStepper</a>
</li>
<li>DIRECTION_CCW
: <a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228a6959a4549f734bd771d418f995ba4fb4">AccelStepper</a>
</li>
<li>DIRECTION_CW
: <a class="el" href="classAccelStepper.html#a7468f91a925c689c3ba250f8d074d228ad604e0047f7cb47662c5a1cf6999337c">AccelStepper</a>
</li>
<li>disableOutputs()
: <a class="el" href="classAccelStepper.html#a3591e29a236e2935afd7f64ff6c22006">AccelStepper</a>
</li>
<li>distanceToGo()
: <a class="el" href="classAccelStepper.html#a748665c3962e66fbc0e9373eb14c69c1">AccelStepper</a>
</li>
<li>DRIVER
: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5ac3523e4cf6763ba518d16fec3708ef23">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_e"></a>- e -</h3><ul>
<li>enableOutputs()
: <a class="el" href="classAccelStepper.html#aa279a50d30d0413f570c692cff071643">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_f"></a>- f -</h3><ul>
<li>FULL2WIRE
: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a62a305b52f749ff8c89138273fbb012d">AccelStepper</a>
</li>
<li>FULL3WIRE
: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a0b8eea5cf0f8ce70b1959d2977ccc996">AccelStepper</a>
</li>
<li>FULL4WIRE
: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5adedd394a375190a3df8d4519c0d4dc2f">AccelStepper</a>
</li>
<li>FUNCTION
: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5af5bb99ad9d67ad2d85f840e3abcfe068">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_h"></a>- h -</h3><ul>
<li>HALF3WIRE
: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5a00c2387a5af43d8e97639699ab7a5c7f">AccelStepper</a>
</li>
<li>HALF4WIRE
: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5aecc0900c55b777d2e885581b8c434b07">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_i"></a>- i -</h3><ul>
<li>isRunning()
: <a class="el" href="classAccelStepper.html#a3a60cc0b962f8ceb81ee1e6f36443ceb">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_m"></a>- m -</h3><ul>
<li>maxSpeed()
: <a class="el" href="classAccelStepper.html#a6123a1dfb4495d8bd2646288eae60d7f">AccelStepper</a>
</li>
<li>MotorInterfaceType
: <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5">AccelStepper</a>
</li>
<li>move()
: <a class="el" href="classAccelStepper.html#a68942c66e78fb7f7b5f0cdade6eb7f06">AccelStepper</a>
</li>
<li>moveTo()
: <a class="el" href="classAccelStepper.html#ace236ede35f87c63d18da25810ec9736">AccelStepper</a>
, <a class="el" href="classMultiStepper.html#a291fec32a79390b6eb00296cffac49ee">MultiStepper</a>
</li>
<li>MultiStepper()
: <a class="el" href="classMultiStepper.html#a14c0c1c0f55e5bbdc4971730e32304c2">MultiStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_r"></a>- r -</h3><ul>
<li>run()
: <a class="el" href="classAccelStepper.html#a608b2395b64ac15451d16d0371fe13ce">AccelStepper</a>
, <a class="el" href="classMultiStepper.html#a26c2f53b1e7ddf5d5dfb333f6fb7fb92">MultiStepper</a>
</li>
<li>runSpeed()
: <a class="el" href="classAccelStepper.html#aa4a6bdf99f698284faaeb5542b0b7514">AccelStepper</a>
</li>
<li>runSpeedToPosition()
: <a class="el" href="classAccelStepper.html#a9270d20336e76ac1fd5bcd5b9c34f301">AccelStepper</a>
, <a class="el" href="classMultiStepper.html#a2592f55864ce3ace125944db624317bc">MultiStepper</a>
</li>
<li>runToNewPosition()
: <a class="el" href="classAccelStepper.html#a176c5d2e4c2f21e9e92b12e39a6f0e67">AccelStepper</a>
</li>
<li>runToPosition()
: <a class="el" href="classAccelStepper.html#a344f58fef8cc34ac5aa75ba4b665d21c">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_s"></a>- s -</h3><ul>
<li>setAcceleration()
: <a class="el" href="classAccelStepper.html#adfb19e3cd2a028a1fe78131787604fd1">AccelStepper</a>
</li>
<li>setCurrentPosition()
: <a class="el" href="classAccelStepper.html#a9d917f014317fb9d3b5dc14e66f6c689">AccelStepper</a>
</li>
<li>setEnablePin()
: <a class="el" href="classAccelStepper.html#a56a81c5f00d02ca19646718e88e974c0">AccelStepper</a>
</li>
<li>setMaxSpeed()
: <a class="el" href="classAccelStepper.html#abee8d466229b87accba33d6ec929c18f">AccelStepper</a>
</li>
<li>setMinPulseWidth()
: <a class="el" href="classAccelStepper.html#af4d3818e691dad5dc518308796ccf154">AccelStepper</a>
</li>
<li>setOutputPins()
: <a class="el" href="classAccelStepper.html#af3c2516b6ce7c1ecbc2004107bb2a9ce">AccelStepper</a>
</li>
<li>setPinsInverted()
: <a class="el" href="classAccelStepper.html#ac62cae590c2f9c303519a3a1c4adc8ab">AccelStepper</a>
</li>
<li>setSpeed()
: <a class="el" href="classAccelStepper.html#ae79c49ad69d5ccc9da0ee691fa4ca235">AccelStepper</a>
</li>
<li>speed()
: <a class="el" href="classAccelStepper.html#a4f0989d0ae264e7eadfe1fa720769fb6">AccelStepper</a>
</li>
<li>step()
: <a class="el" href="classAccelStepper.html#a8a419121702399d8ac66df4cc47481f4">AccelStepper</a>
</li>
<li>step0()
: <a class="el" href="classAccelStepper.html#aa2913db789e6fa05756579ff82fe6e7e">AccelStepper</a>
</li>
<li>step1()
: <a class="el" href="classAccelStepper.html#a63ef416bc039da539294e84a41e7d7dc">AccelStepper</a>
</li>
<li>step2()
: <a class="el" href="classAccelStepper.html#a674e48a6bf99e7ad1f013c1e4414565a">AccelStepper</a>
</li>
<li>step3()
: <a class="el" href="classAccelStepper.html#ad73c61aade2e10243dfb02aefa7ab8fd">AccelStepper</a>
</li>
<li>step4()
: <a class="el" href="classAccelStepper.html#a8910bd9218a54dfb7e2372a6d0bcca0c">AccelStepper</a>
</li>
<li>step6()
: <a class="el" href="classAccelStepper.html#a4b0faf1ebc0c584ab606c0c0f66986b0">AccelStepper</a>
</li>
<li>step8()
: <a class="el" href="classAccelStepper.html#aa909c6c3fcd3ea4b3ee1aa8b4d0f7e87">AccelStepper</a>
</li>
<li>stop()
: <a class="el" href="classAccelStepper.html#a638817b85aed9d5cd15c76a76c00aced">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_t"></a>- t -</h3><ul>
<li>targetPosition()
: <a class="el" href="classAccelStepper.html#a96685e0945b7cf75d5959da679cd911e">AccelStepper</a>
</li>
</ul>
</div><!-- contents -->
<!-- start footer part -->
<hr class="footer"/><address class="footer"><small>
Generated by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.8.11
</small></address>
</body>
</html>

View File

@ -0,0 +1,222 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<meta name="generator" content="Doxygen 1.8.11"/>
<title>AccelStepper: Class Members - Functions</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="jquery.js"></script>
<script type="text/javascript" src="dynsections.js"></script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td id="projectalign" style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.11 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li><a href="index.html"><span>Main&#160;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
<li><a href="examples.html"><span>Examples</span></a></li>
</ul>
</div>
<div id="navrow2" class="tabs2">
<ul class="tablist">
<li><a href="annotated.html"><span>Class&#160;List</span></a></li>
<li class="current"><a href="functions.html"><span>Class&#160;Members</span></a></li>
</ul>
</div>
<div id="navrow3" class="tabs2">
<ul class="tablist">
<li><a href="functions.html"><span>All</span></a></li>
<li class="current"><a href="functions_func.html"><span>Functions</span></a></li>
<li><a href="functions_vars.html"><span>Variables</span></a></li>
<li><a href="functions_enum.html"><span>Enumerations</span></a></li>
<li><a href="functions_eval.html"><span>Enumerator</span></a></li>
</ul>
</div>
<div id="navrow4" class="tabs3">
<ul class="tablist">
<li><a href="#index_a"><span>a</span></a></li>
<li><a href="#index_c"><span>c</span></a></li>
<li><a href="#index_d"><span>d</span></a></li>
<li><a href="#index_e"><span>e</span></a></li>
<li><a href="#index_i"><span>i</span></a></li>
<li><a href="#index_m"><span>m</span></a></li>
<li><a href="#index_r"><span>r</span></a></li>
<li><a href="#index_s"><span>s</span></a></li>
<li class="current"><a href="#index_t"><span>t</span></a></li>
</ul>
</div>
</div><!-- top -->
<div class="contents">
&#160;
<h3><a class="anchor" id="index_a"></a>- a -</h3><ul>
<li>AccelStepper()
: <a class="el" href="classAccelStepper.html#a3bc75bd6571b98a6177838ca81ac39ab">AccelStepper</a>
</li>
<li>addStepper()
: <a class="el" href="classMultiStepper.html#a383d8486e17ad9de9f1bafcbd9aa52ee">MultiStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_c"></a>- c -</h3><ul>
<li>computeNewSpeed()
: <a class="el" href="classAccelStepper.html#affbee789b5c19165846cf0409860ae79">AccelStepper</a>
</li>
<li>currentPosition()
: <a class="el" href="classAccelStepper.html#a5dce13ab2a1b02b8f443318886bf6fc5">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_d"></a>- d -</h3><ul>
<li>disableOutputs()
: <a class="el" href="classAccelStepper.html#a3591e29a236e2935afd7f64ff6c22006">AccelStepper</a>
</li>
<li>distanceToGo()
: <a class="el" href="classAccelStepper.html#a748665c3962e66fbc0e9373eb14c69c1">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_e"></a>- e -</h3><ul>
<li>enableOutputs()
: <a class="el" href="classAccelStepper.html#aa279a50d30d0413f570c692cff071643">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_i"></a>- i -</h3><ul>
<li>isRunning()
: <a class="el" href="classAccelStepper.html#a3a60cc0b962f8ceb81ee1e6f36443ceb">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_m"></a>- m -</h3><ul>
<li>maxSpeed()
: <a class="el" href="classAccelStepper.html#a6123a1dfb4495d8bd2646288eae60d7f">AccelStepper</a>
</li>
<li>move()
: <a class="el" href="classAccelStepper.html#a68942c66e78fb7f7b5f0cdade6eb7f06">AccelStepper</a>
</li>
<li>moveTo()
: <a class="el" href="classAccelStepper.html#ace236ede35f87c63d18da25810ec9736">AccelStepper</a>
, <a class="el" href="classMultiStepper.html#a291fec32a79390b6eb00296cffac49ee">MultiStepper</a>
</li>
<li>MultiStepper()
: <a class="el" href="classMultiStepper.html#a14c0c1c0f55e5bbdc4971730e32304c2">MultiStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_r"></a>- r -</h3><ul>
<li>run()
: <a class="el" href="classAccelStepper.html#a608b2395b64ac15451d16d0371fe13ce">AccelStepper</a>
, <a class="el" href="classMultiStepper.html#a26c2f53b1e7ddf5d5dfb333f6fb7fb92">MultiStepper</a>
</li>
<li>runSpeed()
: <a class="el" href="classAccelStepper.html#aa4a6bdf99f698284faaeb5542b0b7514">AccelStepper</a>
</li>
<li>runSpeedToPosition()
: <a class="el" href="classAccelStepper.html#a9270d20336e76ac1fd5bcd5b9c34f301">AccelStepper</a>
, <a class="el" href="classMultiStepper.html#a2592f55864ce3ace125944db624317bc">MultiStepper</a>
</li>
<li>runToNewPosition()
: <a class="el" href="classAccelStepper.html#a176c5d2e4c2f21e9e92b12e39a6f0e67">AccelStepper</a>
</li>
<li>runToPosition()
: <a class="el" href="classAccelStepper.html#a344f58fef8cc34ac5aa75ba4b665d21c">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_s"></a>- s -</h3><ul>
<li>setAcceleration()
: <a class="el" href="classAccelStepper.html#adfb19e3cd2a028a1fe78131787604fd1">AccelStepper</a>
</li>
<li>setCurrentPosition()
: <a class="el" href="classAccelStepper.html#a9d917f014317fb9d3b5dc14e66f6c689">AccelStepper</a>
</li>
<li>setEnablePin()
: <a class="el" href="classAccelStepper.html#a56a81c5f00d02ca19646718e88e974c0">AccelStepper</a>
</li>
<li>setMaxSpeed()
: <a class="el" href="classAccelStepper.html#abee8d466229b87accba33d6ec929c18f">AccelStepper</a>
</li>
<li>setMinPulseWidth()
: <a class="el" href="classAccelStepper.html#af4d3818e691dad5dc518308796ccf154">AccelStepper</a>
</li>
<li>setOutputPins()
: <a class="el" href="classAccelStepper.html#af3c2516b6ce7c1ecbc2004107bb2a9ce">AccelStepper</a>
</li>
<li>setPinsInverted()
: <a class="el" href="classAccelStepper.html#a38298ac2dd852fb22259f6c4bbe08c94">AccelStepper</a>
</li>
<li>setSpeed()
: <a class="el" href="classAccelStepper.html#ae79c49ad69d5ccc9da0ee691fa4ca235">AccelStepper</a>
</li>
<li>speed()
: <a class="el" href="classAccelStepper.html#a4f0989d0ae264e7eadfe1fa720769fb6">AccelStepper</a>
</li>
<li>step()
: <a class="el" href="classAccelStepper.html#a8a419121702399d8ac66df4cc47481f4">AccelStepper</a>
</li>
<li>step0()
: <a class="el" href="classAccelStepper.html#aa2913db789e6fa05756579ff82fe6e7e">AccelStepper</a>
</li>
<li>step1()
: <a class="el" href="classAccelStepper.html#a63ef416bc039da539294e84a41e7d7dc">AccelStepper</a>
</li>
<li>step2()
: <a class="el" href="classAccelStepper.html#a674e48a6bf99e7ad1f013c1e4414565a">AccelStepper</a>
</li>
<li>step3()
: <a class="el" href="classAccelStepper.html#ad73c61aade2e10243dfb02aefa7ab8fd">AccelStepper</a>
</li>
<li>step4()
: <a class="el" href="classAccelStepper.html#a8910bd9218a54dfb7e2372a6d0bcca0c">AccelStepper</a>
</li>
<li>step6()
: <a class="el" href="classAccelStepper.html#a4b0faf1ebc0c584ab606c0c0f66986b0">AccelStepper</a>
</li>
<li>step8()
: <a class="el" href="classAccelStepper.html#aa909c6c3fcd3ea4b3ee1aa8b4d0f7e87">AccelStepper</a>
</li>
<li>stop()
: <a class="el" href="classAccelStepper.html#a638817b85aed9d5cd15c76a76c00aced">AccelStepper</a>
</li>
</ul>
<h3><a class="anchor" id="index_t"></a>- t -</h3><ul>
<li>targetPosition()
: <a class="el" href="classAccelStepper.html#a96685e0945b7cf75d5959da679cd911e">AccelStepper</a>
</li>
</ul>
</div><!-- contents -->
<!-- start footer part -->
<hr class="footer"/><address class="footer"><small>
Generated by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.8.11
</small></address>
</body>
</html>

View File

@ -0,0 +1,217 @@
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
<meta name="generator" content="Doxygen 1.8.11"/>
<title>AccelStepper: AccelStepper library for Arduino</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="jquery.js"></script>
<script type="text/javascript" src="dynsections.js"></script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<div id="titlearea">
<table cellspacing="0" cellpadding="0">
<tbody>
<tr style="height: 56px;">
<td id="projectalign" style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.11 -->
<div id="navrow1" class="tabs">
<ul class="tablist">
<li class="current"><a href="index.html"><span>Main&#160;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
<li><a href="examples.html"><span>Examples</span></a></li>
</ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title"><a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc. ">AccelStepper</a> library for Arduino </div> </div>
</div><!--header-->
<div class="contents">
<div class="textblock"><p>This is the Arduino <a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc. ">AccelStepper</a> library. It provides an object-oriented interface for 2, 3 or 4 pin stepper motors and motor drivers.</p>
<p>The standard Arduino IDE includes the Stepper library (<a href="http://arduino.cc/en/Reference/Stepper">http://arduino.cc/en/Reference/Stepper</a>) for stepper motors. It is perfectly adequate for simple, single motor applications.</p>
<p><a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc. ">AccelStepper</a> significantly improves on the standard Arduino Stepper library in several ways: </p><ul>
<li>Supports acceleration and deceleration </li>
<li>Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper </li>
<li>API functions never delay() or block </li>
<li>Supports 2, 3 and 4 wire steppers, plus 3 and 4 wire half steppers. </li>
<li>Supports alternate stepping functions to enable support of AFMotor (<a href="https://github.com/adafruit/Adafruit-Motor-Shield-library">https://github.com/adafruit/Adafruit-Motor-Shield-library</a>) </li>
<li>Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip) </li>
<li>Very slow speeds are supported </li>
<li>Extensive API </li>
<li>Subclass support</li>
</ul>
<p>The latest version of this documentation can be downloaded from <a href="http://www.airspayce.com/mikem/arduino/AccelStepper">http://www.airspayce.com/mikem/arduino/AccelStepper</a> The version of the package that this documentation refers to can be downloaded from <a href="http://www.airspayce.com/mikem/arduino/AccelStepper/AccelStepper-1.57.zip">http://www.airspayce.com/mikem/arduino/AccelStepper/AccelStepper-1.57.zip</a></p>
<p>Example Arduino programs are included to show the main modes of use.</p>
<p>You can also find online help and discussion at <a href="http://groups.google.com/group/accelstepper">http://groups.google.com/group/accelstepper</a> 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</p><ul>
<li><a href="http://en.wikipedia.org/wiki/Wikipedia:Reference_desk/How_to_ask_a_software_question">http://en.wikipedia.org/wiki/Wikipedia:Reference_desk/How_to_ask_a_software_question</a></li>
<li><a href="http://www.catb.org/esr/faqs/smart-questions.html">http://www.catb.org/esr/faqs/smart-questions.html</a></li>
<li><a href="http://www.chiark.greenend.org.uk/~shgtatham/bugs.html">http://www.chiark.greenend.org.uk/~shgtatham/bugs.html</a></li>
</ul>
<p>Tested on Arduino Diecimila and Mega with arduino-0018 &amp; 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 <a href="http://www.pjrc.com/teensy">http://www.pjrc.com/teensy</a> including Teensy 3.1 built using Arduino IDE 1.0.5 with teensyduino addon 1.18 and later.</p>
<dl class="section user"><dt>Installation</dt><dd></dd></dl>
<p>Install in the usual way: unzip the distribution zip file to the libraries sub-folder of your sketchbook.</p>
<dl class="section user"><dt>Theory</dt><dd></dd></dl>
<p>This code uses speed calculations as described in "Generate stepper-motor speed profiles in real time" by David Austin <a href="http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf">http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf</a> or <a href="http://www.embedded.com/design/mcus-processors-and-socs/4006438/Generate-stepper-motor-speed-profiles-in-real-time">http://www.embedded.com/design/mcus-processors-and-socs/4006438/Generate-stepper-motor-speed-profiles-in-real-time</a> or <a href="http://web.archive.org/web/20140705143928/http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf">http://web.archive.org/web/20140705143928/http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf</a> with the exception that <a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc. ">AccelStepper</a> 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.</p>
<dl class="section user"><dt>Adafruit Motor Shield V2</dt><dd></dd></dl>
<p>The included examples AFMotor_* are for Adafruit Motor Shield V1 and do not work with Adafruit Motor Shield V2. See <a href="https://github.com/adafruit/Adafruit_Motor_Shield_V2_Library">https://github.com/adafruit/Adafruit_Motor_Shield_V2_Library</a> for examples that work with Adafruit Motor Shield V2.</p>
<dl class="section user"><dt>Donations</dt><dd></dd></dl>
<p>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 <a href="http://www.airspayce.com">http://www.airspayce.com</a> or here:</p>
<p> <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> </p>
<dl class="section user"><dt>Trademarks</dt><dd></dd></dl>
<p><a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc. ">AccelStepper</a> is a trademark of AirSpayce Pty Ltd. The <a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc. ">AccelStepper</a> 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.</p>
<dl class="section user"><dt>Copyright</dt><dd></dd></dl>
<p>This software is Copyright (C) 2010 Mike McCauley. Use is subject to license conditions. The main licensing options available are GPL V2 or Commercial:</p>
<dl class="section user"><dt>Open Source Licensing GPL V2</dt><dd>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 <a href="https://www.gnu.org/licenses/gpl-2.0.html">https://www.gnu.org/licenses/gpl-2.0.html</a></dd></dl>
<dl class="section user"><dt>Commercial Licensing</dt><dd>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. Purchase commercial licenses at <a href="http://airspayce.binpress.com/">http://airspayce.binpress.com/</a></dd></dl>
<dl class="section user"><dt>Revision History</dt><dd></dd></dl>
<dl class="section version"><dt>Version</dt><dd>1.0 Initial release</dd>
<dd>
1.1 Added speed() function to get the current speed. </dd>
<dd>
1.2 Added runSpeedToPosition() submitted by Gunnar Arndt. </dd>
<dd>
1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1 </dd>
<dd>
1.4 Added functional contructor to support AFMotor, contributed by Limor, with example sketches. </dd>
<dd>
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. </dd>
<dd>
1.6 Fixed a problem with wrapping of microsecond stepping that could cause stepping to hang. Reported by Sandy Noble. Removed redundant _lastRunTime member. </dd>
<dd>
1.7 Fixed a bug where setCurrentPosition() did not always work as expected. Reported by Peter Linhart. </dd>
<dd>
1.8 Added support for 4 pin half-steppers, requested by Harvey Moon </dd>
<dd>
1.9 setCurrentPosition() now also sets motor speed to 0. </dd>
<dd>
1.10 Builds on Arduino 1.0 </dd>
<dd>
1.11 Improvments from Michael Ellison: Added optional enable line support for stepper drivers Added inversion for step/direction/enable lines for stepper drivers </dd>
<dd>
1.12 Announce Google Group </dd>
<dd>
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. </dd>
<dd>
1.14 Fixed a problem with compiling under arduino 0021 reported by EmbeddedMan </dd>
<dd>
1.15 Fixed a problem with runSpeedToPosition which did not correctly handle running backwards to a smaller target position. Added examples </dd>
<dd>
1.16 Fixed some cases in the code where abs() was used instead of fabs(). </dd>
<dd>
1.17 Added example ProportionalControl </dd>
<dd>
1.18 Fixed a problem: If one calls the funcion runSpeed() when Speed is zero, it makes steps without counting. reported by Friedrich, Klappenbach. </dd>
<dd>
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. </dd>
<dd>
1.20 Improved documentation and examples to show need for correctly specifying <a class="el" href="classAccelStepper.html#a73bdecf1273d98d8c5fbcb764cabeea5adedd394a375190a3df8d4519c0d4dc2f" title="4 wire full stepper, 4 motor pins required ">AccelStepper::FULL4WIRE</a> and friends. </dd>
<dd>
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 </dd>
<dd>
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. </dd>
<dd>
1.23 Rewrite of the speed algorithms in line with <a href="http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf">http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf</a> Now expect smoother and more linear accelerations and decelerations. The desiredSpeed() function was removed. </dd>
<dd>
1.24 Fixed a problem introduced in 1.23: with runToPosition, which did never returned </dd>
<dd>
1.25 Now ignore attempts to set acceleration to 0.0 </dd>
<dd>
1.26 Fixed a problem where certina combinations of speed and accelration could cause oscillation about the target position. </dd>
<dd>
1.27 Added stop() function to stop as fast as possible with current acceleration parameters. Also added new Quickstop example showing its use. </dd>
<dd>
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. </dd>
<dd>
1.29 Fixed a problem that could cause a DRIVER stepper to continually step with some sketches. Reported by Vadim. </dd>
<dd>
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. </dd>
<dd>
1.31 Updated author and distribution location details to airspayce.com </dd>
<dd>
1.32 Fixed a problem with enableOutputs() and setEnablePin on Arduino Due that prevented the enable pin changing stae correctly. Reported by Duane Bishop. </dd>
<dd>
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. </dd>
<dd>
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. </dd>
<dd>
1.35 Removed default args from setPinsInverted(bool, bool, bool, bool, bool) to prevent ambiguity with setPinsInverted(bool, bool, bool). Reported by Mac Mac. </dd>
<dd>
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. </dd>
<dd>
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. </dd>
<dd>
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. </dd>
<dd>
1.39 Updated typos in keywords.txt, courtesey Jon Magill. </dd>
<dd>
1.40 Updated documentation, including testing on Teensy 3.1 </dd>
<dd>
1.41 Fixed an error in the acceleration calculations, resulting in acceleration of haldf the intended value </dd>
<dd>
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 />
</dd>
<dd>
1.43 Added DualMotorShield example. Shows how to use <a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc. ">AccelStepper</a> to control 2 x 2 phase steppers using the Itead Studio Arduino Dual Stepper Motor Driver Shield model IM120417015.<br />
</dd>
<dd>
1.44 examples/DualMotorShield/DualMotorShield.ino examples/DualMotorShield/DualMotorShield.pde was missing from the distribution.<br />
</dd>
<dd>
1.45 Fixed a problem where if setAcceleration was not called, there was no default acceleration. Reported by Michael Newman.<br />
</dd>
<dd>
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 />
</dd>
<dd>
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 />
</dd>
<dd>
1.48 2015-08-25 Added new class <a class="el" href="classMultiStepper.html" title="Operate multiple AccelSteppers in a co-ordinated fashion. ">MultiStepper</a> 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 <a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc. ">AccelStepper</a> to return the currently configured maxSpeed.<br />
</dd>
<dd>
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 />
</dd>
<dd>
1.50 2016-02-25 <a class="el" href="classAccelStepper.html#a3591e29a236e2935afd7f64ff6c22006">AccelStepper::disableOutputs</a> 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 />
</dd>
<dd>
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. </dd>
<dd>
1.52 2016-08-09 Added <a class="el" href="classMultiStepper.html" title="Operate multiple AccelSteppers in a co-ordinated fashion. ">MultiStepper</a> to keywords.txt. Improvements to efficiency of <a class="el" href="classAccelStepper.html#aa4a6bdf99f698284faaeb5542b0b7514">AccelStepper::runSpeed()</a> as suggested by David Grayson. Improvements to speed accuracy as suggested by David Grayson. </dd>
<dd>
1.53 2016-08-14 Backed out Improvements to speed accuracy from 1.52 as it did not work correctly. </dd>
<dd>
1.54 2017-01-24 Fixed some warnings about unused arguments. </dd>
<dd>
1.55 2017-01-25 Fixed another warning in MultiStepper.cpp </dd>
<dd>
1.56 2017-02-03 Fixed minor documentation error with DIRECTION_CCW and DIRECTION_CW. Reported by David Mutterer. Added link to Binpress commercial license purchasing. </dd>
<dd>
1.57 2017-03-28 _direction moved to protected at the request of Rudy Ercek. setMaxSpeed() and setAcceleration() now correct negative values to be positive.</dd></dl>
<dl class="section author"><dt>Author</dt><dd>Mike McCauley (<a href="#" onclick="location.href='mai'+'lto:'+'mik'+'em'+'@ai'+'rs'+'pay'+'ce'+'.co'+'m'; return false;">mikem<span style="display: none;">.nosp@m.</span>@air<span style="display: none;">.nosp@m.</span>spayc<span style="display: none;">.nosp@m.</span>e.co<span style="display: none;">.nosp@m.</span>m</a>) DO NOT CONTACT THE AUTHOR DIRECTLY: USE THE LISTS </dd></dl>
</div></div><!-- contents -->
<!-- start footer part -->
<hr class="footer"/><address class="footer"><small>
Generated by &#160;<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/>
</a> 1.8.11
</small></address>
</body>
</html>

Binary file not shown.

After

Width:  |  Height:  |  Size: 35 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 706 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.5 KiB

View File

@ -0,0 +1,60 @@
.tabs, .tabs2, .tabs3 {
background-image: url('tab_b.png');
width: 100%;
z-index: 101;
font-size: 13px;
font-family: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif;
}
.tabs2 {
font-size: 10px;
}
.tabs3 {
font-size: 9px;
}
.tablist {
margin: 0;
padding: 0;
display: table;
}
.tablist li {
float: left;
display: table-cell;
background-image: url('tab_b.png');
line-height: 36px;
list-style: none;
}
.tablist a {
display: block;
padding: 0 20px;
font-weight: bold;
background-image:url('tab_s.png');
background-repeat:no-repeat;
background-position:right;
color: #283A5D;
text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9);
text-decoration: none;
outline: none;
}
.tabs3 .tablist a {
padding: 0 10px;
}
.tablist a:hover {
background-image: url('tab_h.png');
background-repeat:repeat-x;
color: #fff;
text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0);
text-decoration: none;
}
.tablist li.current a {
background-image: url('tab_a.png');
background-repeat:repeat-x;
color: #fff;
text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0);
}

View File

@ -0,0 +1,40 @@
// AFMotor_ConstantSpeed.pde
// -*- mode: C++ -*-
//
// Shows how to run AccelStepper in the simplest,
// fixed speed mode with no accelerations
// Requires the AFMotor library
// (https://github.com/adafruit/Adafruit-Motor-Shield-library)
// Caution, does 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.
#include <AccelStepper.h>
#include <AFMotor.h>
AF_Stepper motor1(200, 1);
// you can change these to DOUBLE or INTERLEAVE or MICROSTEP!
void forwardstep() {
motor1.onestep(FORWARD, SINGLE);
}
void backwardstep() {
motor1.onestep(BACKWARD, SINGLE);
}
AccelStepper stepper(forwardstep, backwardstep); // use functions to step
void setup()
{
Serial.begin(9600); // set up Serial library at 9600 bps
Serial.println("Stepper test!");
stepper.setMaxSpeed(50);
stepper.setSpeed(50);
}
void loop()
{
stepper.runSpeed();
}

View File

@ -0,0 +1,57 @@
// AFMotor_MultiStepper.pde
// -*- mode: C++ -*-
//
// Control both Stepper motors at the same time with different speeds
// and accelerations.
// Requires the AFMotor library (https://github.com/adafruit/Adafruit-Motor-Shield-library)
// Caution, does 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.
#include <AccelStepper.h>
#include <AFMotor.h>
// two stepper motors one on each port
AF_Stepper motor1(200, 1);
AF_Stepper motor2(200, 2);
// you can change these to DOUBLE or INTERLEAVE or MICROSTEP!
// wrappers for the first motor!
void forwardstep1() {
motor1.onestep(FORWARD, SINGLE);
}
void backwardstep1() {
motor1.onestep(BACKWARD, SINGLE);
}
// wrappers for the second motor!
void forwardstep2() {
motor2.onestep(FORWARD, SINGLE);
}
void backwardstep2() {
motor2.onestep(BACKWARD, SINGLE);
}
// Motor shield has two motor ports, now we'll wrap them in an AccelStepper object
AccelStepper stepper1(forwardstep1, backwardstep1);
AccelStepper stepper2(forwardstep2, backwardstep2);
void setup()
{
stepper1.setMaxSpeed(200.0);
stepper1.setAcceleration(100.0);
stepper1.moveTo(24);
stepper2.setMaxSpeed(300.0);
stepper2.setAcceleration(100.0);
stepper2.moveTo(1000000);
}
void loop()
{
// Change direction at the limits
if (stepper1.distanceToGo() == 0)
stepper1.moveTo(-stepper1.currentPosition());
stepper1.run();
stepper2.run();
}

View File

@ -0,0 +1,28 @@
// Blocking.pde
// -*- mode: C++ -*-
//
// Shows how to use the blocking call runToNewPosition
// Which sets a new target position and then waits until the stepper has
// achieved it.
//
// Copyright (C) 2009 Mike McCauley
// $Id: Blocking.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
#include <AccelStepper.h>
// Define a stepper and the pins it will use
AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
void setup()
{
stepper.setMaxSpeed(200.0);
stepper.setAcceleration(100.0);
}
void loop()
{
stepper.runToNewPosition(0);
stepper.runToNewPosition(500);
stepper.runToNewPosition(100);
stepper.runToNewPosition(120);
}

View File

@ -0,0 +1,29 @@
// Bounce.pde
// -*- mode: C++ -*-
//
// Make a single stepper bounce from one limit to another
//
// Copyright (C) 2012 Mike McCauley
// $Id: Random.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
#include <AccelStepper.h>
// Define a stepper and the pins it will use
AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
void setup()
{
// Change these to suit your stepper if you want
stepper.setMaxSpeed(100);
stepper.setAcceleration(20);
stepper.moveTo(500);
}
void loop()
{
// If at the end of travel go to the other end
if (stepper.distanceToGo() == 0)
stepper.moveTo(-stepper.currentPosition());
stepper.run();
}

View File

@ -0,0 +1,23 @@
// ConstantSpeed.pde
// -*- mode: C++ -*-
//
// Shows how to run AccelStepper in the simplest,
// fixed speed mode with no accelerations
/// \author Mike McCauley (mikem@airspayce.com)
// Copyright (C) 2009 Mike McCauley
// $Id: ConstantSpeed.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
#include <AccelStepper.h>
AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
void setup()
{
stepper.setMaxSpeed(1000);
stepper.setSpeed(50);
}
void loop()
{
stepper.runSpeed();
}

View File

@ -0,0 +1,49 @@
// DualMotorShield.pde
// -*- mode: C++ -*-
//
// Shows how to run 2 simultaneous steppers
// using the Itead Studio Arduino Dual Stepper Motor Driver Shield
// model IM120417015
// This shield is capable of driving 2 steppers at
// currents of up to 750mA
// and voltages up to 30V
// Runs both steppers forwards and backwards, accelerating and decelerating
// at the limits.
//
// Copyright (C) 2014 Mike McCauley
// $Id: $
#include <AccelStepper.h>
// The X Stepper pins
#define STEPPER1_DIR_PIN 3
#define STEPPER1_STEP_PIN 2
// The Y stepper pins
#define STEPPER2_DIR_PIN 7
#define STEPPER2_STEP_PIN 6
// Define some steppers and the pins the will use
AccelStepper stepper1(AccelStepper::DRIVER, STEPPER1_STEP_PIN, STEPPER1_DIR_PIN);
AccelStepper stepper2(AccelStepper::DRIVER, STEPPER2_STEP_PIN, STEPPER2_DIR_PIN);
void setup()
{
stepper1.setMaxSpeed(200.0);
stepper1.setAcceleration(200.0);
stepper1.moveTo(100);
stepper2.setMaxSpeed(100.0);
stepper2.setAcceleration(100.0);
stepper2.moveTo(100);
}
void loop()
{
// Change direction at the limits
if (stepper1.distanceToGo() == 0)
stepper1.moveTo(-stepper1.currentPosition());
if (stepper2.distanceToGo() == 0)
stepper2.moveTo(-stepper2.currentPosition());
stepper1.run();
stepper2.run();
}

View File

@ -0,0 +1,103 @@
// AFMotor_ConstantSpeed.pde
// -*- mode: C++ -*-
//
// 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.
// Create a subclass of AccelStepper which controls the motor pins via the
// Motor Shield serial-to-parallel interface
#include <AccelStepper.h>
// Arduino pin names for interface to 74HCT595 latch
// on Adafruit Motor Shield
#define MOTORLATCH 12
#define MOTORCLK 4
#define MOTORENABLE 7
#define MOTORDATA 8
// PWM pins, also used to enable motor outputs
#define PWM0A 5
#define PWM0B 6
#define PWM1A 9
#define PWM1B 10
#define PWM2A 11
#define PWM2B 3
// The main purpose of this class is to override setOutputPins to work with Adafruit Motor Shield
class AFMotorShield : public AccelStepper
{
public:
AFMotorShield(uint8_t interface = AccelStepper::FULL4WIRE, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5);
virtual void setOutputPins(uint8_t mask);
};
AFMotorShield::AFMotorShield(uint8_t interface, uint8_t pin1, uint8_t pin2, uint8_t pin3, uint8_t pin4)
: AccelStepper(interface, pin1, pin2, pin3, pin4)
{
// Enable motor control serial to parallel latch
pinMode(MOTORLATCH, OUTPUT);
pinMode(MOTORENABLE, OUTPUT);
pinMode(MOTORDATA, OUTPUT);
pinMode(MOTORCLK, OUTPUT);
digitalWrite(MOTORENABLE, LOW);
// enable both H bridges on motor 1
pinMode(PWM2A, OUTPUT);
pinMode(PWM2B, OUTPUT);
pinMode(PWM0A, OUTPUT);
pinMode(PWM0B, OUTPUT);
digitalWrite(PWM2A, HIGH);
digitalWrite(PWM2B, HIGH);
digitalWrite(PWM0A, HIGH);
digitalWrite(PWM0B, HIGH);
setOutputPins(0); // Reset
};
// Use the AF Motor Shield serial-to-parallel to set the state of the motor pins
// Caution: the mapping of AccelStepper pins to AF motor outputs is not
// obvious:
// AccelStepper Motor Shield output
// pin1 M4A
// pin2 M1A
// pin3 M2A
// pin4 M3A
// Caution this is pretty slow and limits the max speed of the motor to about 500/3 rpm
void AFMotorShield::setOutputPins(uint8_t mask)
{
uint8_t i;
digitalWrite(MOTORLATCH, LOW);
digitalWrite(MOTORDATA, LOW);
for (i=0; i<8; i++)
{
digitalWrite(MOTORCLK, LOW);
if (mask & _BV(7-i))
digitalWrite(MOTORDATA, HIGH);
else
digitalWrite(MOTORDATA, LOW);
digitalWrite(MOTORCLK, HIGH);
}
digitalWrite(MOTORLATCH, HIGH);
}
AFMotorShield stepper(AccelStepper::HALF3WIRE, 0, 0, 0, 0); // 3 phase HDD spindle drive
void setup()
{
stepper.setMaxSpeed(500); // divide by 3 to get rpm
stepper.setAcceleration(80);
stepper.moveTo(10000000);
}
void loop()
{
stepper.run();
}

View File

@ -0,0 +1,44 @@
// MultiStepper.pde
// -*- mode: C++ -*-
// Use MultiStepper class to manage multiple steppers and make them all move to
// the same position at the same time for linear 2d (or 3d) motion.
#include <AccelStepper.h>
#include <MultiStepper.h>
// EG X-Y position bed driven by 2 steppers
// Alas its not possible to build an array of these with different pins for each :-(
AccelStepper stepper1(AccelStepper::FULL4WIRE, 2, 3, 4, 5);
AccelStepper stepper2(AccelStepper::FULL4WIRE, 8, 9, 10, 11);
// Up to 10 steppers can be handled as a group by MultiStepper
MultiStepper steppers;
void setup() {
Serial.begin(9600);
// Configure each stepper
stepper1.setMaxSpeed(100);
stepper2.setMaxSpeed(100);
// Then give them to MultiStepper to manage
steppers.addStepper(stepper1);
steppers.addStepper(stepper2);
}
void loop() {
long positions[2]; // Array of desired stepper positions
positions[0] = 1000;
positions[1] = 50;
steppers.moveTo(positions);
steppers.runSpeedToPosition(); // Blocks until all are in position
delay(1000);
// Move to a different coordinate
positions[0] = -100;
positions[1] = 100;
steppers.moveTo(positions);
steppers.runSpeedToPosition(); // Blocks until all are in position
delay(1000);
}

View File

@ -0,0 +1,41 @@
// MultiStepper.pde
// -*- mode: C++ -*-
//
// 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
//
// Copyright (C) 2009 Mike McCauley
// $Id: MultiStepper.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
#include <AccelStepper.h>
// Define some steppers and the pins the will use
AccelStepper stepper1; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
AccelStepper stepper2(AccelStepper::FULL4WIRE, 6, 7, 8, 9);
AccelStepper stepper3(AccelStepper::FULL2WIRE, 10, 11);
void setup()
{
stepper1.setMaxSpeed(200.0);
stepper1.setAcceleration(100.0);
stepper1.moveTo(24);
stepper2.setMaxSpeed(300.0);
stepper2.setAcceleration(100.0);
stepper2.moveTo(1000000);
stepper3.setMaxSpeed(300.0);
stepper3.setAcceleration(100.0);
stepper3.moveTo(1000000);
}
void loop()
{
// Change direction at the limits
if (stepper1.distanceToGo() == 0)
stepper1.moveTo(-stepper1.currentPosition());
stepper1.run();
stepper2.run();
stepper3.run();
}

View File

@ -0,0 +1,28 @@
// Overshoot.pde
// -*- mode: C++ -*-
//
// 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
//
// Copyright (C) 2009 Mike McCauley
// $Id: Overshoot.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
#include <AccelStepper.h>
// Define a stepper and the pins it will use
AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
void setup()
{
stepper.setMaxSpeed(150);
stepper.setAcceleration(100);
}
void loop()
{
stepper.moveTo(500);
while (stepper.currentPosition() != 300) // Full speed up to 300
stepper.run();
stepper.runToNewPosition(0); // Cause an overshoot then back to 0
}

View File

@ -0,0 +1,32 @@
// ProportionalControl.pde
// -*- mode: C++ -*-
//
// 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.
//
// Copyright (C) 2012 Mike McCauley
// $Id: ProportionalControl.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
#include <AccelStepper.h>
// Define a stepper and the pins it will use
AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
// This defines the analog input pin for reading the control voltage
// Tested with a 10k linear pot between 5v and GND
#define ANALOG_IN A0
void setup()
{
stepper.setMaxSpeed(1000);
}
void loop()
{
// Read new position
int analog_in = analogRead(ANALOG_IN);
stepper.moveTo(analog_in);
stepper.setSpeed(100);
stepper.runSpeedToPosition();
}

View File

@ -0,0 +1,40 @@
// Quickstop.pde
// -*- mode: C++ -*-
//
// 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.
//
// Copyright (C) 2012 Mike McCauley
// $Id: $
#include <AccelStepper.h>
// Define a stepper and the pins it will use
AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
void setup()
{
stepper.setMaxSpeed(150);
stepper.setAcceleration(100);
}
void loop()
{
stepper.moveTo(500);
while (stepper.currentPosition() != 300) // Full speed up to 300
stepper.run();
stepper.stop(); // Stop as fast as possible: sets new target
stepper.runToPosition();
// Now stopped after quickstop
// Now go backwards
stepper.moveTo(-500);
while (stepper.currentPosition() != 0) // Full speed basck to 0
stepper.run();
stepper.stop(); // Stop as fast as possible: sets new target
stepper.runToPosition();
// Now stopped after quickstop
}

View File

@ -0,0 +1,30 @@
// Random.pde
// -*- mode: C++ -*-
//
// Make a single stepper perform random changes in speed, position and acceleration
//
// Copyright (C) 2009 Mike McCauley
// $Id: Random.pde,v 1.1 2011/01/05 01:51:01 mikem Exp mikem $
#include <AccelStepper.h>
// Define a stepper and the pins it will use
AccelStepper stepper; // Defaults to AccelStepper::FULL4WIRE (4 pins) on 2, 3, 4, 5
void setup()
{
}
void loop()
{
if (stepper.distanceToGo() == 0)
{
// Random change to speed, position and acceleration
// Make sure we dont get 0 speed or accelerations
delay(1000);
stepper.moveTo(rand() % 200);
stepper.setMaxSpeed((rand() % 200) + 1);
stepper.setAcceleration((rand() % 200) + 1);
}
stepper.run();
}

View File

@ -0,0 +1,41 @@
#######################################
# Syntax Coloring Map For AccelStepper
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
AccelStepper KEYWORD1
MultiStepper KEYWORD1
#######################################
# Methods and Functions (KEYWORD2)
#######################################
moveTo KEYWORD2
move KEYWORD2
run KEYWORD2
runSpeed KEYWORD2
setMaxSpeed KEYWORD2
setAcceleration KEYWORD2
setSpeed KEYWORD2
speed KEYWORD2
distanceToGo KEYWORD2
targetPosition KEYWORD2
currentPosition KEYWORD2
setCurrentPosition KEYWORD2
runToPosition KEYWORD2
runSpeedToPosition KEYWORD2
runToNewPosition KEYWORD2
stop KEYWORD2
disableOutputs KEYWORD2
enableOutputs KEYWORD2
setMinPulseWidth KEYWORD2
setEnablePin KEYWORD2
setPinsInverted KEYWORD2
maxSpeed KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,25 @@
= Servo Library for Arduino =
This library allows an Arduino board to control RC (hobby) servo motors.
For more information about this library please visit us at
http://www.arduino.cc/en/Reference/Servo
== License ==
Copyright (c) 2013 Arduino LLC. All right reserved.
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA

View File

@ -0,0 +1,27 @@
/*
Controlling a servo position using a potentiometer (variable resistor)
by Michal Rinott <http://people.interaction-ivrea.it/m.rinott>
modified on 8 Nov 2013
by Scott Fitzgerald
http://www.arduino.cc/en/Tutorial/Knob
*/
#include <Servo.h>
Servo myservo; // create servo object to control a servo
int potpin = 0; // analog pin used to connect the potentiometer
int val; // variable to read the value from the analog pin
void setup() {
myservo.attach(9); // attaches the servo on pin 9 to the servo object
}
void loop() {
val = analogRead(potpin); // reads the value of the potentiometer (value between 0 and 1023)
val = map(val, 0, 1023, 0, 180); // scale it to use it with the servo (value between 0 and 180)
myservo.write(val); // sets the servo position according to the scaled value
delay(15); // waits for the servo to get there
}

View File

@ -0,0 +1,32 @@
/* Sweep
by BARRAGAN <http://barraganstudio.com>
This example code is in the public domain.
modified 8 Nov 2013
by Scott Fitzgerald
http://www.arduino.cc/en/Tutorial/Sweep
*/
#include <Servo.h>
Servo myservo; // create servo object to control a servo
// twelve servo objects can be created on most boards
int pos = 0; // variable to store the servo position
void setup() {
myservo.attach(9); // attaches the servo on pin 9 to the servo object
}
void loop() {
for (pos = 0; pos <= 180; pos += 1) { // goes from 0 degrees to 180 degrees
// in steps of 1 degree
myservo.write(pos); // tell servo to go to position in variable 'pos'
delay(15); // waits 15ms for the servo to reach the position
}
for (pos = 180; pos >= 0; pos -= 1) { // goes from 180 degrees to 0 degrees
myservo.write(pos); // tell servo to go to position in variable 'pos'
delay(15); // waits 15ms for the servo to reach the position
}
}

View File

@ -0,0 +1,24 @@
#######################################
# Syntax Coloring Map Servo
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
Servo KEYWORD1 Servo
#######################################
# Methods and Functions (KEYWORD2)
#######################################
attach KEYWORD2
detach KEYWORD2
write KEYWORD2
read KEYWORD2
attached KEYWORD2
writeMicroseconds KEYWORD2
readMicroseconds KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################

View File

@ -0,0 +1,9 @@
name=Servo
version=1.1.2
author=Michael Margolis, Arduino
maintainer=Arduino <info@arduino.cc>
sentence=Allows Arduino/Genuino boards to control a variety of servo motors.
paragraph=This library can control a great number of servos.<br />It makes careful use of timers: the library can control 12 servos using only 1 timer.<br />On the Arduino Due you can control up to 60 servos.<br />
category=Device Control
url=http://www.arduino.cc/en/Reference/Servo
architectures=avr,sam,samd,nrf52,stm32f4

View File

@ -0,0 +1,119 @@
/*
Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
A servo is activated by creating an instance of the Servo class passing
the desired pin to the attach() method.
The servos are pulsed in the background using the value most recently
written using the write() method.
Note that analogWrite of PWM on pins associated with the timer are
disabled when the first servo is attached.
Timers are seized as needed in groups of 12 servos - 24 servos use two
timers, 48 servos will use four.
The sequence used to sieze timers is defined in timers.h
The methods are:
Servo - Class for manipulating servo motors connected to Arduino pins.
attach(pin ) - Attaches a servo motor to an i/o pin.
attach(pin, min, max ) - Attaches to a pin setting min and max values in microseconds
default min is 544, max is 2400
write() - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds)
writeMicroseconds() - Sets the servo pulse width in microseconds
read() - Gets the last written servo pulse width as an angle between 0 and 180.
readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release)
attached() - Returns true if there is a servo attached.
detach() - Stops an attached servos from pulsing its i/o pin.
*/
#ifndef Servo_h
#define Servo_h
#include <inttypes.h>
/*
* Defines for 16 bit timers used with Servo library
*
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
* _Nbr_16timers indicates how many 16 bit timers are available.
*/
// Architecture specific include
#if defined(ARDUINO_ARCH_AVR)
#include "avr/ServoTimers.h"
#elif defined(ARDUINO_ARCH_SAM)
#include "sam/ServoTimers.h"
#elif defined(ARDUINO_ARCH_SAMD)
#include "samd/ServoTimers.h"
#elif defined(ARDUINO_ARCH_STM32F4)
#include "stm32f4/ServoTimers.h"
#elif defined(ARDUINO_ARCH_NRF52)
#include "nrf52/ServoTimers.h"
#else
#error "This library only supports boards with an AVR, SAM, SAMD, NRF52 or STM32F4 processor."
#endif
#define Servo_VERSION 2 // software version of this library
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
#define REFRESH_INTERVAL 20000 // minumim time to refresh servos in microseconds
#define SERVOS_PER_TIMER 12 // the maximum number of servos controlled by one timer
#define MAX_SERVOS (_Nbr_16timers * SERVOS_PER_TIMER)
#define INVALID_SERVO 255 // flag indicating an invalid servo index
#if !defined(ARDUINO_ARCH_STM32F4)
typedef struct {
uint8_t nbr :6 ; // a pin number from 0 to 63
uint8_t isActive :1 ; // true if this channel is enabled, pin not pulsed if false
} ServoPin_t ;
typedef struct {
ServoPin_t Pin;
volatile unsigned int ticks;
} servo_t;
class Servo
{
public:
Servo();
uint8_t attach(int pin); // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure
uint8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes.
void detach();
void write(int value); // if value is < 200 its treated as an angle, otherwise as pulse width in microseconds
void writeMicroseconds(int value); // Write pulse width in microseconds
int read(); // returns current pulse width as an angle between 0 and 180 degrees
int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release)
bool attached(); // return true if this servo is attached, otherwise false
private:
uint8_t servoIndex; // index into the channel data for this servo
int8_t min; // minimum is this value times 4 added to MIN_PULSE_WIDTH
int8_t max; // maximum is this value times 4 added to MAX_PULSE_WIDTH
};
#endif
#endif

View File

@ -0,0 +1,318 @@
/*
Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#if defined(ARDUINO_ARCH_AVR)
#include <avr/interrupt.h>
#include <Arduino.h>
#include "Servo.h"
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009
#define ticksToUs(_ticks) (( (unsigned)_ticks * 8)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays // 12 August 2009
//#define NBR_TIMERS (MAX_SERVOS / SERVOS_PER_TIMER)
static servo_t servos[MAX_SERVOS]; // static array of servo structures
static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
uint8_t ServoCount = 0; // the total number of attached servos
// convenience macros
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % SERVOS_PER_TIMER) // returns the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*SERVOS_PER_TIMER) + _channel) // macro to access servo index by timer and channel
#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
/************ static functions common to all instances ***********************/
static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA)
{
if( Channel[timer] < 0 )
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
else{
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true )
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated
}
Channel[timer]++; // increment to the next channel
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
*OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks;
if(SERVO(timer,Channel[timer]).Pin.isActive == true) // check if activated
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
}
else {
// finished all channels so wait for the refresh period to expire before starting over
if( ((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL) ) // allow a few ticks to ensure the next OCR1A not missed
*OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL);
else
*OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
}
}
#ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform
// Interrupt handlers for Arduino
#if defined(_useTimer1)
SIGNAL (TIMER1_COMPA_vect)
{
handle_interrupts(_timer1, &TCNT1, &OCR1A);
}
#endif
#if defined(_useTimer3)
SIGNAL (TIMER3_COMPA_vect)
{
handle_interrupts(_timer3, &TCNT3, &OCR3A);
}
#endif
#if defined(_useTimer4)
SIGNAL (TIMER4_COMPA_vect)
{
handle_interrupts(_timer4, &TCNT4, &OCR4A);
}
#endif
#if defined(_useTimer5)
SIGNAL (TIMER5_COMPA_vect)
{
handle_interrupts(_timer5, &TCNT5, &OCR5A);
}
#endif
#elif defined WIRING
// Interrupt handlers for Wiring
#if defined(_useTimer1)
void Timer1Service()
{
handle_interrupts(_timer1, &TCNT1, &OCR1A);
}
#endif
#if defined(_useTimer3)
void Timer3Service()
{
handle_interrupts(_timer3, &TCNT3, &OCR3A);
}
#endif
#endif
static void initISR(timer16_Sequence_t timer)
{
#if defined (_useTimer1)
if(timer == _timer1) {
TCCR1A = 0; // normal counting mode
TCCR1B = _BV(CS11); // set prescaler of 8
TCNT1 = 0; // clear the timer count
#if defined(__AVR_ATmega8__)|| defined(__AVR_ATmega128__)
TIFR |= _BV(OCF1A); // clear any pending interrupts;
TIMSK |= _BV(OCIE1A) ; // enable the output compare interrupt
#else
// here if not ATmega8 or ATmega128
TIFR1 |= _BV(OCF1A); // clear any pending interrupts;
TIMSK1 |= _BV(OCIE1A) ; // enable the output compare interrupt
#endif
#if defined(WIRING)
timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service);
#endif
}
#endif
#if defined (_useTimer3)
if(timer == _timer3) {
TCCR3A = 0; // normal counting mode
TCCR3B = _BV(CS31); // set prescaler of 8
TCNT3 = 0; // clear the timer count
#if defined(__AVR_ATmega128__)
TIFR |= _BV(OCF3A); // clear any pending interrupts;
ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt
#else
TIFR3 = _BV(OCF3A); // clear any pending interrupts;
TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt
#endif
#if defined(WIRING)
timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only
#endif
}
#endif
#if defined (_useTimer4)
if(timer == _timer4) {
TCCR4A = 0; // normal counting mode
TCCR4B = _BV(CS41); // set prescaler of 8
TCNT4 = 0; // clear the timer count
TIFR4 = _BV(OCF4A); // clear any pending interrupts;
TIMSK4 = _BV(OCIE4A) ; // enable the output compare interrupt
}
#endif
#if defined (_useTimer5)
if(timer == _timer5) {
TCCR5A = 0; // normal counting mode
TCCR5B = _BV(CS51); // set prescaler of 8
TCNT5 = 0; // clear the timer count
TIFR5 = _BV(OCF5A); // clear any pending interrupts;
TIMSK5 = _BV(OCIE5A) ; // enable the output compare interrupt
}
#endif
}
static void finISR(timer16_Sequence_t timer)
{
//disable use of the given timer
#if defined WIRING // Wiring
if(timer == _timer1) {
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
TIMSK1 &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
#else
TIMSK &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
#endif
timerDetach(TIMER1OUTCOMPAREA_INT);
}
else if(timer == _timer3) {
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
TIMSK3 &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
#else
ETIMSK &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
#endif
timerDetach(TIMER3OUTCOMPAREA_INT);
}
#else
//For arduino - in future: call here to a currently undefined function to reset the timer
(void) timer; // squash "unused parameter 'timer' [-Wunused-parameter]" warning
#endif
}
static boolean isTimerActive(timer16_Sequence_t timer)
{
// returns true if any servo is active on this timer
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
if(SERVO(timer,channel).Pin.isActive == true)
return true;
}
return false;
}
/****************** end of static functions ******************************/
Servo::Servo()
{
if( ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance
servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
}
else
this->servoIndex = INVALID_SERVO ; // too many servos
}
uint8_t Servo::attach(int pin)
{
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
uint8_t Servo::attach(int pin, int min, int max)
{
if(this->servoIndex < MAX_SERVOS ) {
pinMode( pin, OUTPUT) ; // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
this->max = (MAX_PULSE_WIDTH - max)/4;
// initialize the timer if it has not already been initialized
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false)
initISR(timer);
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
}
return this->servoIndex ;
}
void Servo::detach()
{
servos[this->servoIndex].Pin.isActive = false;
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false) {
finISR(timer);
}
}
void Servo::write(int value)
{
if(value < MIN_PULSE_WIDTH)
{ // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
if(value < 0) value = 0;
if(value > 180) value = 180;
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
}
this->writeMicroseconds(value);
}
void Servo::writeMicroseconds(int value)
{
// calculate and store the values for the given channel
byte channel = this->servoIndex;
if( (channel < MAX_SERVOS) ) // ensure channel is valid
{
if( value < SERVO_MIN() ) // ensure pulse width is valid
value = SERVO_MIN();
else if( value > SERVO_MAX() )
value = SERVO_MAX();
value = value - TRIM_DURATION;
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
uint8_t oldSREG = SREG;
cli();
servos[channel].ticks = value;
SREG = oldSREG;
}
}
int Servo::read() // return the value as degrees
{
return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
}
int Servo::readMicroseconds()
{
unsigned int pulsewidth;
if( this->servoIndex != INVALID_SERVO )
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION ; // 12 aug 2009
else
pulsewidth = 0;
return pulsewidth;
}
bool Servo::attached()
{
return servos[this->servoIndex].Pin.isActive ;
}
#endif // ARDUINO_ARCH_AVR

View File

@ -0,0 +1,59 @@
/*
Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
* Defines for 16 bit timers used with Servo library
*
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
* _Nbr_16timers indicates how many 16 bit timers are available.
*/
/**
* AVR Only definitions
* --------------------
*/
// Say which 16 bit timers can be used and in what order
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define _useTimer5
#define _useTimer1
#define _useTimer3
#define _useTimer4
typedef enum { _timer5, _timer1, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t;
#elif defined(__AVR_ATmega32U4__)
#define _useTimer1
typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t;
#elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__)
#define _useTimer3
#define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t;
#elif defined(__AVR_ATmega128__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega2561__)
#define _useTimer3
#define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t;
#else // everything else
#define _useTimer1
typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t;
#endif

View File

@ -0,0 +1,134 @@
/*
Copyright (c) 2016 Arduino. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#if defined(ARDUINO_ARCH_NRF52)
#include <Arduino.h>
#include <Servo.h>
static servo_t servos[MAX_SERVOS]; // static array of servo structures
uint8_t ServoCount = 0; // the total number of attached servos
uint32_t group_pins[3][NRF_PWM_CHANNEL_COUNT]={{NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED}, {NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED}, {NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED, NRF_PWM_PIN_NOT_CONNECTED}};
static uint16_t seq_values[3][NRF_PWM_CHANNEL_COUNT]={{0, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}};
Servo::Servo()
{
if (ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance
} else {
this->servoIndex = INVALID_SERVO; // too many servos
}
}
uint8_t Servo::attach(int pin)
{
return this->attach(pin, 0, 2500);
}
uint8_t Servo::attach(int pin, int min, int max)
{
int servo_min, servo_max;
if (this->servoIndex < MAX_SERVOS) {
pinMode(pin, OUTPUT); // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
if(min < servo_min) min = servo_min;
if (max > servo_max) max = servo_max;
this->min = min;
this->max = max;
servos[this->servoIndex].Pin.isActive = true;
}
return this->servoIndex;
}
void Servo::detach()
{
servos[this->servoIndex].Pin.isActive = false;
}
void Servo::write(int value)
{
if (value < 0)
value = 0;
else if (value > 180)
value = 180;
value = map(value, 0, 180, MIN_PULSE, MAX_PULSE);
writeMicroseconds(value);
}
void Servo::writeMicroseconds(int value)
{
uint8_t channel, instance;
uint8_t pin = servos[this->servoIndex].Pin.nbr;
//instance of pwm module is MSB - look at VWariant.h
instance=(g_APinDescription[pin].ulPWMChannel & 0xF0)/16;
//index of pwm channel is LSB - look at VWariant.h
channel=g_APinDescription[pin].ulPWMChannel & 0x0F;
group_pins[instance][channel]=g_APinDescription[pin].ulPin;
NRF_PWM_Type * PWMInstance = instance == 0 ? NRF_PWM0 : (instance == 1 ? NRF_PWM1 : NRF_PWM2);
//configure pwm instance and enable it
seq_values[instance][channel]= value | 0x8000;
nrf_pwm_sequence_t const seq={
seq_values[instance],
NRF_PWM_VALUES_LENGTH(seq_values),
0,
0
};
nrf_pwm_pins_set(PWMInstance, group_pins[instance]);
nrf_pwm_enable(PWMInstance);
nrf_pwm_configure(PWMInstance, NRF_PWM_CLK_125kHz, NRF_PWM_MODE_UP, 2500); // 20ms - 50Hz
nrf_pwm_decoder_set(PWMInstance, NRF_PWM_LOAD_INDIVIDUAL, NRF_PWM_STEP_AUTO);
nrf_pwm_sequence_set(PWMInstance, 0, &seq);
nrf_pwm_loop_set(PWMInstance, 0UL);
nrf_pwm_task_trigger(PWMInstance, NRF_PWM_TASK_SEQSTART0);
}
int Servo::read() // return the value as degrees
{
return map(readMicroseconds(), MIN_PULSE, MAX_PULSE, 0, 180);
}
int Servo::readMicroseconds()
{
uint8_t channel, instance;
uint8_t pin=servos[this->servoIndex].Pin.nbr;
instance=(g_APinDescription[pin].ulPWMChannel & 0xF0)/16;
channel=g_APinDescription[pin].ulPWMChannel & 0x0F;
// remove the 16th bit we added before
return seq_values[instance][channel] & 0x7FFF;
}
bool Servo::attached()
{
return servos[this->servoIndex].Pin.isActive;
}
#endif // ARDUINO_ARCH_NRF52

View File

@ -0,0 +1,38 @@
/*
Copyright (c) 2016 Arduino. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
* NRF52 doesn't use timer, but pwm. This file include definitions to keep
* compatibility with the Servo library standards.
*/
#ifndef __SERVO_TIMERS_H__
#define __SERVO_TIMERS_H__
/**
* NRF52 Only definitions
* ---------------------
*/
#define MIN_PULSE 55
#define MAX_PULSE 284
// define one timer in order to have MAX_SERVOS = 12
typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t;
#endif // __SERVO_TIMERS_H__

View File

@ -0,0 +1,283 @@
/*
Copyright (c) 2013 Arduino LLC. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#if defined(ARDUINO_ARCH_SAM)
#include <Arduino.h>
#include <Servo.h>
#define usToTicks(_us) (( clockCyclesPerMicrosecond() * _us) / 32) // converts microseconds to tick
#define ticksToUs(_ticks) (( (unsigned)_ticks * 32)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays
static servo_t servos[MAX_SERVOS]; // static array of servo structures
uint8_t ServoCount = 0; // the total number of attached servos
static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
// convenience macros
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % SERVOS_PER_TIMER) // returns the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*SERVOS_PER_TIMER) + _channel) // macro to access servo index by timer and channel
#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
/************ static functions common to all instances ***********************/
//------------------------------------------------------------------------------
/// Interrupt handler for the TC0 channel 1.
//------------------------------------------------------------------------------
void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel);
#if defined (_useTimer1)
void HANDLER_FOR_TIMER1(void) {
Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1);
}
#endif
#if defined (_useTimer2)
void HANDLER_FOR_TIMER2(void) {
Servo_Handler(_timer2, TC_FOR_TIMER2, CHANNEL_FOR_TIMER2);
}
#endif
#if defined (_useTimer3)
void HANDLER_FOR_TIMER3(void) {
Servo_Handler(_timer3, TC_FOR_TIMER3, CHANNEL_FOR_TIMER3);
}
#endif
#if defined (_useTimer4)
void HANDLER_FOR_TIMER4(void) {
Servo_Handler(_timer4, TC_FOR_TIMER4, CHANNEL_FOR_TIMER4);
}
#endif
#if defined (_useTimer5)
void HANDLER_FOR_TIMER5(void) {
Servo_Handler(_timer5, TC_FOR_TIMER5, CHANNEL_FOR_TIMER5);
}
#endif
void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel)
{
// clear interrupt
tc->TC_CHANNEL[channel].TC_SR;
if (Channel[timer] < 0) {
tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // channel set to -1 indicated that refresh interval completed so reset the timer
} else {
if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true) {
digitalWrite(SERVO(timer,Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
}
}
Channel[timer]++; // increment to the next channel
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer,Channel[timer]).ticks;
if(SERVO(timer,Channel[timer]).Pin.isActive == true) { // check if activated
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
}
}
else {
// finished all channels so wait for the refresh period to expire before starting over
if( (tc->TC_CHANNEL[channel].TC_CV) + 4 < usToTicks(REFRESH_INTERVAL) ) { // allow a few ticks to ensure the next OCR1A not missed
tc->TC_CHANNEL[channel].TC_RA = (unsigned int)usToTicks(REFRESH_INTERVAL);
}
else {
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + 4; // at least REFRESH_INTERVAL has elapsed
}
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
}
}
static void _initISR(Tc *tc, uint32_t channel, uint32_t id, IRQn_Type irqn)
{
pmc_enable_periph_clk(id);
TC_Configure(tc, channel,
TC_CMR_TCCLKS_TIMER_CLOCK3 | // MCK/32
TC_CMR_WAVE | // Waveform mode
TC_CMR_WAVSEL_UP_RC ); // Counter running up and reset when equals to RC
/* 84MHz, MCK/32, for 1.5ms: 3937 */
TC_SetRA(tc, channel, 2625); // 1ms
/* Configure and enable interrupt */
NVIC_EnableIRQ(irqn);
// TC_IER_CPAS: RA Compare
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPAS;
// Enables the timer clock and performs a software reset to start the counting
TC_Start(tc, channel);
}
static void initISR(timer16_Sequence_t timer)
{
#if defined (_useTimer1)
if (timer == _timer1)
_initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1);
#endif
#if defined (_useTimer2)
if (timer == _timer2)
_initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2);
#endif
#if defined (_useTimer3)
if (timer == _timer3)
_initISR(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3, ID_TC_FOR_TIMER3, IRQn_FOR_TIMER3);
#endif
#if defined (_useTimer4)
if (timer == _timer4)
_initISR(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4, ID_TC_FOR_TIMER4, IRQn_FOR_TIMER4);
#endif
#if defined (_useTimer5)
if (timer == _timer5)
_initISR(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5, ID_TC_FOR_TIMER5, IRQn_FOR_TIMER5);
#endif
}
static void finISR(timer16_Sequence_t timer)
{
#if defined (_useTimer1)
TC_Stop(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1);
#endif
#if defined (_useTimer2)
TC_Stop(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2);
#endif
#if defined (_useTimer3)
TC_Stop(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3);
#endif
#if defined (_useTimer4)
TC_Stop(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4);
#endif
#if defined (_useTimer5)
TC_Stop(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5);
#endif
}
static boolean isTimerActive(timer16_Sequence_t timer)
{
// returns true if any servo is active on this timer
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
if(SERVO(timer,channel).Pin.isActive == true)
return true;
}
return false;
}
/****************** end of static functions ******************************/
Servo::Servo()
{
if (ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance
servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values
} else {
this->servoIndex = INVALID_SERVO; // too many servos
}
}
uint8_t Servo::attach(int pin)
{
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
uint8_t Servo::attach(int pin, int min, int max)
{
timer16_Sequence_t timer;
if (this->servoIndex < MAX_SERVOS) {
pinMode(pin, OUTPUT); // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
this->max = (MAX_PULSE_WIDTH - max)/4;
// initialize the timer if it has not already been initialized
timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (isTimerActive(timer) == false) {
initISR(timer);
}
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
}
return this->servoIndex;
}
void Servo::detach()
{
timer16_Sequence_t timer;
servos[this->servoIndex].Pin.isActive = false;
timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false) {
finISR(timer);
}
}
void Servo::write(int value)
{
// treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
if (value < MIN_PULSE_WIDTH)
{
if (value < 0)
value = 0;
else if (value > 180)
value = 180;
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
}
writeMicroseconds(value);
}
void Servo::writeMicroseconds(int value)
{
// calculate and store the values for the given channel
byte channel = this->servoIndex;
if( (channel < MAX_SERVOS) ) // ensure channel is valid
{
if (value < SERVO_MIN()) // ensure pulse width is valid
value = SERVO_MIN();
else if (value > SERVO_MAX())
value = SERVO_MAX();
value = value - TRIM_DURATION;
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead
servos[channel].ticks = value;
}
}
int Servo::read() // return the value as degrees
{
return map(readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
}
int Servo::readMicroseconds()
{
unsigned int pulsewidth;
if (this->servoIndex != INVALID_SERVO)
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION;
else
pulsewidth = 0;
return pulsewidth;
}
bool Servo::attached()
{
return servos[this->servoIndex].Pin.isActive;
}
#endif // ARDUINO_ARCH_SAM

View File

@ -0,0 +1,88 @@
/*
Copyright (c) 2013 Arduino LLC. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
* Defines for 16 bit timers used with Servo library
*
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
* _Nbr_16timers indicates how many 16 bit timers are available.
*/
/**
* SAM Only definitions
* --------------------
*/
// For SAM3X:
#define _useTimer1
#define _useTimer2
#define _useTimer3
#define _useTimer4
#define _useTimer5
/*
TC0, chan 0 => TC0_Handler
TC0, chan 1 => TC1_Handler
TC0, chan 2 => TC2_Handler
TC1, chan 0 => TC3_Handler
TC1, chan 1 => TC4_Handler
TC1, chan 2 => TC5_Handler
TC2, chan 0 => TC6_Handler
TC2, chan 1 => TC7_Handler
TC2, chan 2 => TC8_Handler
*/
#if defined (_useTimer1)
#define TC_FOR_TIMER1 TC1
#define CHANNEL_FOR_TIMER1 0
#define ID_TC_FOR_TIMER1 ID_TC3
#define IRQn_FOR_TIMER1 TC3_IRQn
#define HANDLER_FOR_TIMER1 TC3_Handler
#endif
#if defined (_useTimer2)
#define TC_FOR_TIMER2 TC1
#define CHANNEL_FOR_TIMER2 1
#define ID_TC_FOR_TIMER2 ID_TC4
#define IRQn_FOR_TIMER2 TC4_IRQn
#define HANDLER_FOR_TIMER2 TC4_Handler
#endif
#if defined (_useTimer3)
#define TC_FOR_TIMER3 TC1
#define CHANNEL_FOR_TIMER3 2
#define ID_TC_FOR_TIMER3 ID_TC5
#define IRQn_FOR_TIMER3 TC5_IRQn
#define HANDLER_FOR_TIMER3 TC5_Handler
#endif
#if defined (_useTimer4)
#define TC_FOR_TIMER4 TC0
#define CHANNEL_FOR_TIMER4 2
#define ID_TC_FOR_TIMER4 ID_TC2
#define IRQn_FOR_TIMER4 TC2_IRQn
#define HANDLER_FOR_TIMER4 TC2_Handler
#endif
#if defined (_useTimer5)
#define TC_FOR_TIMER5 TC0
#define CHANNEL_FOR_TIMER5 0
#define ID_TC_FOR_TIMER5 ID_TC0
#define IRQn_FOR_TIMER5 TC0_IRQn
#define HANDLER_FOR_TIMER5 TC0_Handler
#endif
typedef enum { _timer1, _timer2, _timer3, _timer4, _timer5, _Nbr_16timers } timer16_Sequence_t ;

View File

@ -0,0 +1,297 @@
/*
Copyright (c) 2015 Arduino LLC. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#if defined(ARDUINO_ARCH_SAMD)
#include <Arduino.h>
#include <Servo.h>
#define usToTicks(_us) ((clockCyclesPerMicrosecond() * _us) / 16) // converts microseconds to tick
#define ticksToUs(_ticks) (((unsigned) _ticks * 16) / clockCyclesPerMicrosecond()) // converts from ticks back to microseconds
#define TRIM_DURATION 5 // compensation ticks to trim adjust for digitalWrite delays
static servo_t servos[MAX_SERVOS]; // static array of servo structures
uint8_t ServoCount = 0; // the total number of attached servos
static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval)
// convenience macros
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % SERVOS_PER_TIMER) // returns the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*SERVOS_PER_TIMER) + _channel) // macro to access servo index by timer and channel
#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
#define WAIT_TC16_REGS_SYNC(x) while(x->COUNT16.STATUS.bit.SYNCBUSY);
/************ static functions common to all instances ***********************/
void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel, uint8_t intFlag);
#if defined (_useTimer1)
void HANDLER_FOR_TIMER1(void) {
Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, INTFLAG_BIT_FOR_TIMER_1);
}
#endif
#if defined (_useTimer2)
void HANDLER_FOR_TIMER2(void) {
Servo_Handler(_timer2, TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, INTFLAG_BIT_FOR_TIMER_2);
}
#endif
void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel, uint8_t intFlag)
{
if (currentServoIndex[timer] < 0) {
tc->COUNT16.COUNT.reg = (uint16_t) 0;
WAIT_TC16_REGS_SYNC(tc)
} else {
if (SERVO_INDEX(timer, currentServoIndex[timer]) < ServoCount && SERVO(timer, currentServoIndex[timer]).Pin.isActive == true) {
digitalWrite(SERVO(timer, currentServoIndex[timer]).Pin.nbr, LOW); // pulse this channel low if activated
}
}
// Select the next servo controlled by this timer
currentServoIndex[timer]++;
if (SERVO_INDEX(timer, currentServoIndex[timer]) < ServoCount && currentServoIndex[timer] < SERVOS_PER_TIMER) {
if (SERVO(timer, currentServoIndex[timer]).Pin.isActive == true) { // check if activated
digitalWrite(SERVO(timer, currentServoIndex[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high
}
// Get the counter value
uint16_t tcCounterValue = tc->COUNT16.COUNT.reg;
WAIT_TC16_REGS_SYNC(tc)
tc->COUNT16.CC[channel].reg = (uint16_t) (tcCounterValue + SERVO(timer, currentServoIndex[timer]).ticks);
WAIT_TC16_REGS_SYNC(tc)
}
else {
// finished all channels so wait for the refresh period to expire before starting over
// Get the counter value
uint16_t tcCounterValue = tc->COUNT16.COUNT.reg;
WAIT_TC16_REGS_SYNC(tc)
if (tcCounterValue + 4UL < usToTicks(REFRESH_INTERVAL)) { // allow a few ticks to ensure the next OCR1A not missed
tc->COUNT16.CC[channel].reg = (uint16_t) usToTicks(REFRESH_INTERVAL);
}
else {
tc->COUNT16.CC[channel].reg = (uint16_t) (tcCounterValue + 4UL); // at least REFRESH_INTERVAL has elapsed
}
WAIT_TC16_REGS_SYNC(tc)
currentServoIndex[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
}
// Clear the interrupt
tc->COUNT16.INTFLAG.reg = intFlag;
}
static inline void resetTC (Tc* TCx)
{
// Disable TCx
TCx->COUNT16.CTRLA.reg &= ~TC_CTRLA_ENABLE;
WAIT_TC16_REGS_SYNC(TCx)
// Reset TCx
TCx->COUNT16.CTRLA.reg = TC_CTRLA_SWRST;
WAIT_TC16_REGS_SYNC(TCx)
while (TCx->COUNT16.CTRLA.bit.SWRST);
}
static void _initISR(Tc *tc, uint8_t channel, uint32_t id, IRQn_Type irqn, uint8_t gcmForTimer, uint8_t intEnableBit)
{
// Enable GCLK for timer 1 (timer counter input clock)
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(gcmForTimer));
while (GCLK->STATUS.bit.SYNCBUSY);
// Reset the timer
// TODO this is not the right thing to do if more than one channel per timer is used by the Servo library
resetTC(tc);
// Set timer counter mode to 16 bits
tc->COUNT16.CTRLA.reg |= TC_CTRLA_MODE_COUNT16;
// Set timer counter mode as normal PWM
tc->COUNT16.CTRLA.reg |= TC_CTRLA_WAVEGEN_NPWM;
// Set the prescaler factor to GCLK_TC/16. At nominal 48MHz GCLK_TC this is 3000 ticks per millisecond
tc->COUNT16.CTRLA.reg |= TC_CTRLA_PRESCALER_DIV16;
// Count up
tc->COUNT16.CTRLBCLR.bit.DIR = 1;
WAIT_TC16_REGS_SYNC(tc)
// First interrupt request after 1 ms
tc->COUNT16.CC[channel].reg = (uint16_t) usToTicks(1000UL);
WAIT_TC16_REGS_SYNC(tc)
// Configure interrupt request
// TODO this should be changed if more than one channel per timer is used by the Servo library
NVIC_DisableIRQ(irqn);
NVIC_ClearPendingIRQ(irqn);
NVIC_SetPriority(irqn, 0);
NVIC_EnableIRQ(irqn);
// Enable the match channel interrupt request
tc->COUNT16.INTENSET.reg = intEnableBit;
// Enable the timer and start it
tc->COUNT16.CTRLA.reg |= TC_CTRLA_ENABLE;
WAIT_TC16_REGS_SYNC(tc)
}
static void initISR(timer16_Sequence_t timer)
{
#if defined (_useTimer1)
if (timer == _timer1)
_initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1, GCM_FOR_TIMER_1, INTENSET_BIT_FOR_TIMER_1);
#endif
#if defined (_useTimer2)
if (timer == _timer2)
_initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2, GCM_FOR_TIMER_2, INTENSET_BIT_FOR_TIMER_2);
#endif
}
static void finISR(timer16_Sequence_t timer)
{
#if defined (_useTimer1)
// Disable the match channel interrupt request
TC_FOR_TIMER1->COUNT16.INTENCLR.reg = INTENCLR_BIT_FOR_TIMER_1;
#endif
#if defined (_useTimer2)
// Disable the match channel interrupt request
TC_FOR_TIMER2->COUNT16.INTENCLR.reg = INTENCLR_BIT_FOR_TIMER_2;
#endif
}
static boolean isTimerActive(timer16_Sequence_t timer)
{
// returns true if any servo is active on this timer
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
if(SERVO(timer,channel).Pin.isActive == true)
return true;
}
return false;
}
/****************** end of static functions ******************************/
Servo::Servo()
{
if (ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance
servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values
} else {
this->servoIndex = INVALID_SERVO; // too many servos
}
}
uint8_t Servo::attach(int pin)
{
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
uint8_t Servo::attach(int pin, int min, int max)
{
timer16_Sequence_t timer;
if (this->servoIndex < MAX_SERVOS) {
pinMode(pin, OUTPUT); // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
this->max = (MAX_PULSE_WIDTH - max)/4;
// initialize the timer if it has not already been initialized
timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (isTimerActive(timer) == false) {
initISR(timer);
}
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
}
return this->servoIndex;
}
void Servo::detach()
{
timer16_Sequence_t timer;
servos[this->servoIndex].Pin.isActive = false;
timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false) {
finISR(timer);
}
}
void Servo::write(int value)
{
// treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
if (value < MIN_PULSE_WIDTH)
{
if (value < 0)
value = 0;
else if (value > 180)
value = 180;
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
}
writeMicroseconds(value);
}
void Servo::writeMicroseconds(int value)
{
// calculate and store the values for the given channel
byte channel = this->servoIndex;
if( (channel < MAX_SERVOS) ) // ensure channel is valid
{
if (value < SERVO_MIN()) // ensure pulse width is valid
value = SERVO_MIN();
else if (value > SERVO_MAX())
value = SERVO_MAX();
value = value - TRIM_DURATION;
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead
servos[channel].ticks = value;
}
}
int Servo::read() // return the value as degrees
{
return map(readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
}
int Servo::readMicroseconds()
{
unsigned int pulsewidth;
if (this->servoIndex != INVALID_SERVO)
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION;
else
pulsewidth = 0;
return pulsewidth;
}
bool Servo::attached()
{
return servos[this->servoIndex].Pin.isActive;
}
#endif // ARDUINO_ARCH_SAMD

View File

@ -0,0 +1,71 @@
/*
Copyright (c) 2015 Arduino LLC. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
* Defines for 16 bit timers used with Servo library
*
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
* _Nbr_16timers indicates how many 16 bit timers are available.
*/
#ifndef __SERVO_TIMERS_H__
#define __SERVO_TIMERS_H__
/**
* SAMD Only definitions
* ---------------------
*/
// For SAMD:
#define _useTimer1
//#define _useTimer2 // <- TODO do not activate until the code in Servo.cpp has been changed in order
// to manage more than one channel per timer on the SAMD architecture
#if defined (_useTimer1)
#define TC_FOR_TIMER1 TC4
#define CHANNEL_FOR_TIMER1 0
#define INTENSET_BIT_FOR_TIMER_1 TC_INTENSET_MC0
#define INTENCLR_BIT_FOR_TIMER_1 TC_INTENCLR_MC0
#define INTFLAG_BIT_FOR_TIMER_1 TC_INTFLAG_MC0
#define ID_TC_FOR_TIMER1 ID_TC4
#define IRQn_FOR_TIMER1 TC4_IRQn
#define HANDLER_FOR_TIMER1 TC4_Handler
#define GCM_FOR_TIMER_1 GCM_TC4_TC5
#endif
#if defined (_useTimer2)
#define TC_FOR_TIMER2 TC4
#define CHANNEL_FOR_TIMER2 1
#define INTENSET_BIT_FOR_TIMER_2 TC_INTENSET_MC1
#define INTENCLR_BIT_FOR_TIMER_2 TC_INTENCLR_MC1
#define ID_TC_FOR_TIMER2 ID_TC4
#define IRQn_FOR_TIMER2 TC4_IRQn
#define HANDLER_FOR_TIMER2 TC4_Handler
#define GCM_FOR_TIMER_2 GCM_TC4_TC5
#endif
typedef enum {
#if defined (_useTimer1)
_timer1,
#endif
#if defined (_useTimer2)
_timer2,
#endif
_Nbr_16timers } timer16_Sequence_t;
#endif // __SERVO_TIMERS_H__

View File

@ -0,0 +1,194 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010, LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
#if defined(ARDUINO_ARCH_STM32F4)
#include "ServoTimers.h"
#include "boards.h"
#include "io.h"
#include "pwm.h"
#include "math.h"
// 20 millisecond period config. For a 1-based prescaler,
//
// (prescaler * overflow / CYC_MSEC) msec = 1 timer cycle = 20 msec
// => prescaler * overflow = 20 * CYC_MSEC
//
// This picks the smallest prescaler that allows an overflow < 2^16.
#define MAX_OVERFLOW ((1 << 16) - 1)
#define CYC_MSEC (1000 * CYCLES_PER_MICROSECOND)
#define TAU_MSEC 20
#define TAU_USEC (TAU_MSEC * 1000)
#define TAU_CYC (TAU_MSEC * CYC_MSEC)
#define SERVO_PRESCALER (TAU_CYC / MAX_OVERFLOW + 1)
#define SERVO_OVERFLOW ((uint16)round((double)TAU_CYC / SERVO_PRESCALER))
// Unit conversions
#define US_TO_COMPARE(us) ((uint16)map((us), 0, TAU_USEC, 0, SERVO_OVERFLOW))
#define COMPARE_TO_US(c) ((uint32)map((c), 0, SERVO_OVERFLOW, 0, TAU_USEC))
#define ANGLE_TO_US(a) ((uint16)(map((a), this->minAngle, this->maxAngle, \
this->minPW, this->maxPW)))
#define US_TO_ANGLE(us) ((int16)(map((us), this->minPW, this->maxPW, \
this->minAngle, this->maxAngle)))
Servo::Servo() {
this->resetFields();
}
bool Servo::attach(uint8 pin, uint16 minPW, uint16 maxPW, int16 minAngle, int16 maxAngle)
{
// SerialUSB.begin(115200);
// SerialUSB.println(MAX_OVERFLOW);
timer_dev *tdev = PIN_MAP[pin].timer_device;
analogWriteResolution(16);
int prescaler = 6;
int overflow = 65400;
int minPW_correction = 300;
int maxPW_correction = 300;
pinMode(pin, OUTPUT);
if (tdev == NULL) {
// don't reset any fields or ASSERT(0), to keep driving any
// previously attach()ed servo.
return false;
}
if ( (tdev == TIMER1) || (tdev == TIMER8) || (tdev == TIMER10) || (tdev == TIMER11))
{
prescaler = 54;
overflow = 65400;
minPW_correction = 40;
maxPW_correction = 50;
}
if ( (tdev == TIMER2) || (tdev == TIMER3) || (tdev == TIMER4) || (tdev == TIMER5) )
{
prescaler = 6;
overflow = 64285;
minPW_correction = 370;
maxPW_correction = 350;
}
if ( (tdev == TIMER6) || (tdev == TIMER7) )
{
prescaler = 6;
overflow = 65400;
minPW_correction = 0;
maxPW_correction = 0;
}
if ( (tdev == TIMER9) || (tdev == TIMER12) || (tdev == TIMER13) || (tdev == TIMER14) )
{
prescaler = 6;
overflow = 65400;
minPW_correction = 30;
maxPW_correction = 0;
}
if (this->attached()) {
this->detach();
}
this->pin = pin;
this->minPW = (minPW + minPW_correction);
this->maxPW = (maxPW + maxPW_correction);
this->minAngle = minAngle;
this->maxAngle = maxAngle;
timer_pause(tdev);
timer_set_prescaler(tdev, prescaler); // prescaler is 1-based
timer_set_reload(tdev, overflow);
timer_generate_update(tdev);
timer_resume(tdev);
return true;
}
bool Servo::detach() {
if (!this->attached()) {
return false;
}
timer_dev *tdev = PIN_MAP[this->pin].timer_device;
uint8 tchan = PIN_MAP[this->pin].timer_channel;
timer_set_mode(tdev, tchan, TIMER_DISABLED);
this->resetFields();
return true;
}
void Servo::write(int degrees) {
degrees = constrain(degrees, this->minAngle, this->maxAngle);
this->writeMicroseconds(ANGLE_TO_US(degrees));
}
int Servo::read() const {
int a = US_TO_ANGLE(this->readMicroseconds());
// map() round-trips in a weird way we mostly correct for here;
// the round-trip is still sometimes off-by-one for write(1) and
// write(179).
return a == this->minAngle || a == this->maxAngle ? a : a + 1;
}
void Servo::writeMicroseconds(uint16 pulseWidth) {
if (!this->attached()) {
ASSERT(0);
return;
}
pulseWidth = constrain(pulseWidth, this->minPW, this->maxPW);
analogWrite(this->pin, US_TO_COMPARE(pulseWidth));
}
uint16 Servo::readMicroseconds() const {
if (!this->attached()) {
ASSERT(0);
return 0;
}
stm32_pin_info pin_info = PIN_MAP[this->pin];
uint16 compare = timer_get_compare(pin_info.timer_device,
pin_info.timer_channel);
return COMPARE_TO_US(compare);
}
void Servo::resetFields(void) {
this->pin = NOT_ATTACHED;
this->minAngle = MIN_ANGLE;
this->maxAngle = MAX_ANGLE;
this->minPW = MIN_PULSE_WIDTH;
this->maxPW = MAX_PULSE_WIDTH;
}
#endif

View File

@ -0,0 +1,207 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010, LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/*
* Arduino srl - www.arduino.org
* 2017 Feb 23: Edited by Francesco Alessi (alfran) - francesco@arduino.org
*/
#ifndef _SERVO_H_
#define _SERVO_H_
#include "types.h"
#include "timer.h"
#include "wiring.h" /* hack for IDE compile */
/*
* Note on Arduino compatibility:
*
* In the Arduino implementation, PWM is done "by hand" in the sense
* that timer channels are hijacked in groups and an ISR is set which
* toggles Servo::attach()ed pins using digitalWrite().
*
* While this scheme allows any pin to drive a servo, it chews up
* cycles and complicates the programmer's notion of when a particular
* timer channel will be in use.
*
* This implementation only allows Servo instances to attach() to pins
* that already have a timer channel associated with them, and just
* uses pwmWrite() to drive the wave.
*
* This introduces an incompatibility: while the Arduino
* implementation of attach() returns the affected channel on success
* and 0 on failure, this one returns true on success and false on
* failure.
*
* RC Servos expect a pulse every 20ms. Since periods are set for
* entire timers, rather than individual channels, attach()ing a Servo
* to a pin can interfere with other pins associated with the same
* timer. As always, your board's pin map is your friend.
*/
// Pin number of unattached pins
#define NOT_ATTACHED (-1)
#define _Nbr_16timers 14 // mumber of STM32F469 Timers
#define SERVOS_PER_TIMER 4 // Number of timer channels
// Default min/max pulse widths (in microseconds) and angles (in
// degrees). Values chosen for Arduino compatibility. These values
// are part of the public API; DO NOT CHANGE THEM.
#define MIN_ANGLE 0
#define MAX_ANGLE 180
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
/** Class for interfacing with RC servomotors. */
class Servo {
public:
/**
* @brief Construct a new Servo instance.
*
* The new instance will not be attached to any pin.
*/
Servo();
/**
* @brief Associate this instance with a servomotor whose input is
* connected to pin.
*
* If this instance is already attached to a pin, it will be
* detached before being attached to the new pin. This function
* doesn't detach any interrupt attached with the pin's timer
* channel.
*
* @param pin Pin connected to the servo pulse wave input. This
* pin must be capable of PWM output.
*
* @param minPulseWidth Minimum pulse width to write to pin, in
* microseconds. This will be associated
* with a minAngle degree angle. Defaults to
* SERVO_DEFAULT_MIN_PW = 544.
*
* @param maxPulseWidth Maximum pulse width to write to pin, in
* microseconds. This will be associated
* with a maxAngle degree angle. Defaults to
* SERVO_DEFAULT_MAX_PW = 2400.
*
* @param minAngle Target angle (in degrees) associated with
* minPulseWidth. Defaults to
* SERVO_DEFAULT_MIN_ANGLE = 0.
*
* @param maxAngle Target angle (in degrees) associated with
* maxPulseWidth. Defaults to
* SERVO_DEFAULT_MAX_ANGLE = 180.
*
* @sideeffect May set pinMode(pin, PWM).
*
* @return true if successful, false when pin doesn't support PWM.
*/
bool attach(uint8 pin,
uint16 minPulseWidth=MIN_PULSE_WIDTH,
uint16 maxPulseWidth=MAX_PULSE_WIDTH,
int16 minAngle=MIN_ANGLE,
int16 maxAngle=MAX_ANGLE);
/**
* @brief Stop driving the servo pulse train.
*
* If not currently attached to a motor, this function has no effect.
*
* @return true if this call did anything, false otherwise.
*/
bool detach();
/**
* @brief Set the servomotor target angle.
*
* @param angle Target angle, in degrees. If the target angle is
* outside the range specified at attach() time, it
* will be clamped to lie in that range.
*
* @see Servo::attach()
*/
void write(int angle);
/**
* @brief Set the pulse width, in microseconds.
*
* @param pulseWidth Pulse width to send to the servomotor, in
* microseconds. If outside of the range
* specified at attach() time, it is clamped to
* lie in that range.
*
* @see Servo::attach()
*/
void writeMicroseconds(uint16 pulseWidth);
/**
* Get the servomotor's target angle, in degrees. This will
* lie inside the range specified at attach() time.
*
* @see Servo::attach()
*/
int read() const;
/**
* Get the current pulse width, in microseconds. This will
* lie within the range specified at attach() time.
*
* @see Servo::attach()
*/
uint16 readMicroseconds() const;
/**
* @brief Check if this instance is attached to a servo.
* @return true if this instance is attached to a servo, false otherwise.
* @see Servo::attachedPin()
*/
bool attached() const { return this->pin != NOT_ATTACHED; }
/**
* @brief Get the pin this instance is attached to.
* @return Pin number if currently attached to a pin, NOT_ATTACHED
* otherwise.
* @see Servo::attach()
*/
int attachedPin() const { return this->pin; }
private:
int16 pin;
uint16 minPW;
uint16 maxPW;
int16 minAngle;
int16 maxAngle;
void resetFields(void);
};
#endif /* _SERVO_H_ */

View File

@ -0,0 +1,458 @@
GNU LESSER GENERAL PUBLIC LICENSE
Version 2.1, February 1999
Copyright (C) 1991, 1999 Free Software Foundation, Inc.
51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
[This is the first released version of the Lesser GPL. It also counts
as the successor of the GNU Library Public License, version 2, hence
the version number 2.1.]
Preamble
The licenses for most software are designed to take away your
freedom to share and change it. By contrast, the GNU General Public
Licenses are intended to guarantee your freedom to share and change
free software--to make sure the software is free for all its users.
This license, the Lesser General Public License, applies to some
specially designated software packages--typically libraries--of the
Free Software Foundation and other authors who decide to use it. You
can use it too, but we suggest you first think carefully about whether
this license or the ordinary General Public License is the better
strategy to use in any particular case, based on the explanations below.
When we speak of free software, we are referring to freedom of use,
not price. Our General Public Licenses are designed to make sure that
you have the freedom to distribute copies of free software (and charge
for this service if you wish); that you receive source code or can get
it if you want it; that you can change the software and use pieces of
it in new free programs; and that you are informed that you can do
these things.
To protect your rights, we need to make restrictions that forbid
distributors to deny you these rights or to ask you to surrender these
rights. These restrictions translate to certain responsibilities for
you if you distribute copies of the library or if you modify it.
For example, if you distribute copies of the library, whether gratis
or for a fee, you must give the recipients all the rights that we gave
you. You must make sure that they, too, receive or can get the source
code. If you link other code with the library, you must provide
complete object files to the recipients, so that they can relink them
with the library after making changes to the library and recompiling
it. And you must show them these terms so they know their rights.
We protect your rights with a two-step method: (1) we copyright the
library, and (2) we offer you this license, which gives you legal
permission to copy, distribute and/or modify the library.
To protect each distributor, we want to make it very clear that
there is no warranty for the free library. Also, if the library is
modified by someone else and passed on, the recipients should know
that what they have is not the original version, so that the original
author's reputation will not be affected by problems that might be
introduced by others.
Finally, software patents pose a constant threat to the existence of
any free program. We wish to make sure that a company cannot
effectively restrict the users of a free program by obtaining a
restrictive license from a patent holder. Therefore, we insist that
any patent license obtained for a version of the library must be
consistent with the full freedom of use specified in this license.
Most GNU software, including some libraries, is covered by the
ordinary GNU General Public License. This license, the GNU Lesser
General Public License, applies to certain designated libraries, and
is quite different from the ordinary General Public License. We use
this license for certain libraries in order to permit linking those
libraries into non-free programs.
When a program is linked with a library, whether statically or using
a shared library, the combination of the two is legally speaking a
combined work, a derivative of the original library. The ordinary
General Public License therefore permits such linking only if the
entire combination fits its criteria of freedom. The Lesser General
Public License permits more lax criteria for linking other code with
the library.
We call this license the "Lesser" General Public License because it
does Less to protect the user's freedom than the ordinary General
Public License. It also provides other free software developers Less
of an advantage over competing non-free programs. These disadvantages
are the reason we use the ordinary General Public License for many
libraries. However, the Lesser license provides advantages in certain
special circumstances.
For example, on rare occasions, there may be a special need to
encourage the widest possible use of a certain library, so that it becomes
a de-facto standard. To achieve this, non-free programs must be
allowed to use the library. A more frequent case is that a free
library does the same job as widely used non-free libraries. In this
case, there is little to gain by limiting the free library to free
software only, so we use the Lesser General Public License.
In other cases, permission to use a particular library in non-free
programs enables a greater number of people to use a large body of
free software. For example, permission to use the GNU C Library in
non-free programs enables many more people to use the whole GNU
operating system, as well as its variant, the GNU/Linux operating
system.
Although the Lesser General Public License is Less protective of the
users' freedom, it does ensure that the user of a program that is
linked with the Library has the freedom and the wherewithal to run
that program using a modified version of the Library.
The precise terms and conditions for copying, distribution and
modification follow. Pay close attention to the difference between a
"work based on the library" and a "work that uses the library". The
former contains code derived from the library, whereas the latter must
be combined with the library in order to run.
GNU LESSER GENERAL PUBLIC LICENSE
TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION
0. This License Agreement applies to any software library or other
program which contains a notice placed by the copyright holder or
other authorized party saying it may be distributed under the terms of
this Lesser General Public License (also called "this License").
Each licensee is addressed as "you".
A "library" means a collection of software functions and/or data
prepared so as to be conveniently linked with application programs
(which use some of those functions and data) to form executables.
The "Library", below, refers to any such software library or work
which has been distributed under these terms. A "work based on the
Library" means either the Library or any derivative work under
copyright law: that is to say, a work containing the Library or a
portion of it, either verbatim or with modifications and/or translated
straightforwardly into another language. (Hereinafter, translation is
included without limitation in the term "modification".)
"Source code" for a work means the preferred form of the work for
making modifications to it. For a library, complete source code means
all the source code for all modules it contains, plus any associated
interface definition files, plus the scripts used to control compilation
and installation of the library.
Activities other than copying, distribution and modification are not
covered by this License; they are outside its scope. The act of
running a program using the Library is not restricted, and output from
such a program is covered only if its contents constitute a work based
on the Library (independent of the use of the Library in a tool for
writing it). Whether that is true depends on what the Library does
and what the program that uses the Library does.
1. You may copy and distribute verbatim copies of the Library's
complete source code as you receive it, in any medium, provided that
you conspicuously and appropriately publish on each copy an
appropriate copyright notice and disclaimer of warranty; keep intact
all the notices that refer to this License and to the absence of any
warranty; and distribute a copy of this License along with the
Library.
You may charge a fee for the physical act of transferring a copy,
and you may at your option offer warranty protection in exchange for a
fee.
2. You may modify your copy or copies of the Library or any portion
of it, thus forming a work based on the Library, and copy and
distribute such modifications or work under the terms of Section 1
above, provided that you also meet all of these conditions:
a) The modified work must itself be a software library.
b) You must cause the files modified to carry prominent notices
stating that you changed the files and the date of any change.
c) You must cause the whole of the work to be licensed at no
charge to all third parties under the terms of this License.
d) If a facility in the modified Library refers to a function or a
table of data to be supplied by an application program that uses
the facility, other than as an argument passed when the facility
is invoked, then you must make a good faith effort to ensure that,
in the event an application does not supply such function or
table, the facility still operates, and performs whatever part of
its purpose remains meaningful.
(For example, a function in a library to compute square roots has
a purpose that is entirely well-defined independent of the
application. Therefore, Subsection 2d requires that any
application-supplied function or table used by this function must
be optional: if the application does not supply it, the square
root function must still compute square roots.)
These requirements apply to the modified work as a whole. If
identifiable sections of that work are not derived from the Library,
and can be reasonably considered independent and separate works in
themselves, then this License, and its terms, do not apply to those
sections when you distribute them as separate works. But when you
distribute the same sections as part of a whole which is a work based
on the Library, the distribution of the whole must be on the terms of
this License, whose permissions for other licensees extend to the
entire whole, and thus to each and every part regardless of who wrote
it.
Thus, it is not the intent of this section to claim rights or contest
your rights to work written entirely by you; rather, the intent is to
exercise the right to control the distribution of derivative or
collective works based on the Library.
In addition, mere aggregation of another work not based on the Library
with the Library (or with a work based on the Library) on a volume of
a storage or distribution medium does not bring the other work under
the scope of this License.
3. You may opt to apply the terms of the ordinary GNU General Public
License instead of this License to a given copy of the Library. To do
this, you must alter all the notices that refer to this License, so
that they refer to the ordinary GNU General Public License, version 2,
instead of to this License. (If a newer version than version 2 of the
ordinary GNU General Public License has appeared, then you can specify
that version instead if you wish.) Do not make any other change in
these notices.
Once this change is made in a given copy, it is irreversible for
that copy, so the ordinary GNU General Public License applies to all
subsequent copies and derivative works made from that copy.
This option is useful when you wish to copy part of the code of
the Library into a program that is not a library.
4. You may copy and distribute the Library (or a portion or
derivative of it, under Section 2) in object code or executable form
under the terms of Sections 1 and 2 above provided that you accompany
it with the complete corresponding machine-readable source code, which
must be distributed under the terms of Sections 1 and 2 above on a
medium customarily used for software interchange.
If distribution of object code is made by offering access to copy
from a designated place, then offering equivalent access to copy the
source code from the same place satisfies the requirement to
distribute the source code, even though third parties are not
compelled to copy the source along with the object code.
5. A program that contains no derivative of any portion of the
Library, but is designed to work with the Library by being compiled or
linked with it, is called a "work that uses the Library". Such a
work, in isolation, is not a derivative work of the Library, and
therefore falls outside the scope of this License.
However, linking a "work that uses the Library" with the Library
creates an executable that is a derivative of the Library (because it
contains portions of the Library), rather than a "work that uses the
library". The executable is therefore covered by this License.
Section 6 states terms for distribution of such executables.
When a "work that uses the Library" uses material from a header file
that is part of the Library, the object code for the work may be a
derivative work of the Library even though the source code is not.
Whether this is true is especially significant if the work can be
linked without the Library, or if the work is itself a library. The
threshold for this to be true is not precisely defined by law.
If such an object file uses only numerical parameters, data
structure layouts and accessors, and small macros and small inline
functions (ten lines or less in length), then the use of the object
file is unrestricted, regardless of whether it is legally a derivative
work. (Executables containing this object code plus portions of the
Library will still fall under Section 6.)
Otherwise, if the work is a derivative of the Library, you may
distribute the object code for the work under the terms of Section 6.
Any executables containing that work also fall under Section 6,
whether or not they are linked directly with the Library itself.
6. As an exception to the Sections above, you may also combine or
link a "work that uses the Library" with the Library to produce a
work containing portions of the Library, and distribute that work
under terms of your choice, provided that the terms permit
modification of the work for the customer's own use and reverse
engineering for debugging such modifications.
You must give prominent notice with each copy of the work that the
Library is used in it and that the Library and its use are covered by
this License. You must supply a copy of this License. If the work
during execution displays copyright notices, you must include the
copyright notice for the Library among them, as well as a reference
directing the user to the copy of this License. Also, you must do one
of these things:
a) Accompany the work with the complete corresponding
machine-readable source code for the Library including whatever
changes were used in the work (which must be distributed under
Sections 1 and 2 above); and, if the work is an executable linked
with the Library, with the complete machine-readable "work that
uses the Library", as object code and/or source code, so that the
user can modify the Library and then relink to produce a modified
executable containing the modified Library. (It is understood
that the user who changes the contents of definitions files in the
Library will not necessarily be able to recompile the application
to use the modified definitions.)
b) Use a suitable shared library mechanism for linking with the
Library. A suitable mechanism is one that (1) uses at run time a
copy of the library already present on the user's computer system,
rather than copying library functions into the executable, and (2)
will operate properly with a modified version of the library, if
the user installs one, as long as the modified version is
interface-compatible with the version that the work was made with.
c) Accompany the work with a written offer, valid for at
least three years, to give the same user the materials
specified in Subsection 6a, above, for a charge no more
than the cost of performing this distribution.
d) If distribution of the work is made by offering access to copy
from a designated place, offer equivalent access to copy the above
specified materials from the same place.
e) Verify that the user has already received a copy of these
materials or that you have already sent this user a copy.
For an executable, the required form of the "work that uses the
Library" must include any data and utility programs needed for
reproducing the executable from it. However, as a special exception,
the materials to be distributed need not include anything that is
normally distributed (in either source or binary form) with the major
components (compiler, kernel, and so on) of the operating system on
which the executable runs, unless that component itself accompanies
the executable.
It may happen that this requirement contradicts the license
restrictions of other proprietary libraries that do not normally
accompany the operating system. Such a contradiction means you cannot
use both them and the Library together in an executable that you
distribute.
7. You may place library facilities that are a work based on the
Library side-by-side in a single library together with other library
facilities not covered by this License, and distribute such a combined
library, provided that the separate distribution of the work based on
the Library and of the other library facilities is otherwise
permitted, and provided that you do these two things:
a) Accompany the combined library with a copy of the same work
based on the Library, uncombined with any other library
facilities. This must be distributed under the terms of the
Sections above.
b) Give prominent notice with the combined library of the fact
that part of it is a work based on the Library, and explaining
where to find the accompanying uncombined form of the same work.
8. You may not copy, modify, sublicense, link with, or distribute
the Library except as expressly provided under this License. Any
attempt otherwise to copy, modify, sublicense, link with, or
distribute the Library is void, and will automatically terminate your
rights under this License. However, parties who have received copies,
or rights, from you under this License will not have their licenses
terminated so long as such parties remain in full compliance.
9. You are not required to accept this License, since you have not
signed it. However, nothing else grants you permission to modify or
distribute the Library or its derivative works. These actions are
prohibited by law if you do not accept this License. Therefore, by
modifying or distributing the Library (or any work based on the
Library), you indicate your acceptance of this License to do so, and
all its terms and conditions for copying, distributing or modifying
the Library or works based on it.
10. Each time you redistribute the Library (or any work based on the
Library), the recipient automatically receives a license from the
original licensor to copy, distribute, link with or modify the Library
subject to these terms and conditions. You may not impose any further
restrictions on the recipients' exercise of the rights granted herein.
You are not responsible for enforcing compliance by third parties with
this License.
11. If, as a consequence of a court judgment or allegation of patent
infringement or for any other reason (not limited to patent issues),
conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License. If you cannot
distribute so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you
may not distribute the Library at all. For example, if a patent
license would not permit royalty-free redistribution of the Library by
all those who receive copies directly or indirectly through you, then
the only way you could satisfy both it and this License would be to
refrain entirely from distribution of the Library.
If any portion of this section is held invalid or unenforceable under any
particular circumstance, the balance of the section is intended to apply,
and the section as a whole is intended to apply in other circumstances.
It is not the purpose of this section to induce you to infringe any
patents or other property right claims or to contest validity of any
such claims; this section has the sole purpose of protecting the
integrity of the free software distribution system which is
implemented by public license practices. Many people have made
generous contributions to the wide range of software distributed
through that system in reliance on consistent application of that
system; it is up to the author/donor to decide if he or she is willing
to distribute software through any other system and a licensee cannot
impose that choice.
This section is intended to make thoroughly clear what is believed to
be a consequence of the rest of this License.
12. If the distribution and/or use of the Library is restricted in
certain countries either by patents or by copyrighted interfaces, the
original copyright holder who places the Library under this License may add
an explicit geographical distribution limitation excluding those countries,
so that distribution is permitted only in or among countries not thus
excluded. In such case, this License incorporates the limitation as if
written in the body of this License.
13. The Free Software Foundation may publish revised and/or new
versions of the Lesser General Public License from time to time.
Such new versions will be similar in spirit to the present version,
but may differ in detail to address new problems or concerns.
Each version is given a distinguishing version number. If the Library
specifies a version number of this License which applies to it and
"any later version", you have the option of following the terms and
conditions either of that version or of any later version published by
the Free Software Foundation. If the Library does not specify a
license version number, you may choose any version ever published by
the Free Software Foundation.
14. If you wish to incorporate parts of the Library into other free
programs whose distribution conditions are incompatible with these,
write to the author to ask for permission. For software which is
copyrighted by the Free Software Foundation, write to the Free
Software Foundation; we sometimes make exceptions for this. Our
decision will be guided by the two goals of preserving the free status
of all derivatives of our free software and of promoting the sharing
and reuse of software generally.
NO WARRANTY
15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO
WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW.
EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR
OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY
KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE
LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME
THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN
WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY
AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU
FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR
CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE
LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING
RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A
FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF
SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
DAMAGES.

View File

@ -0,0 +1,120 @@
VarSpeedServo.h
===============
The VarSpeedServo.h Arduino library allows the use of up to 8 servos moving asynchronously (because it uses interrupts). In addition, you can set the speed of a move, optionally wait (block) until the servo move is complete, and create sequences of moves that run asynchronously.
This code is an adaptation of the standard Arduino Servo.h library, which was first adapted by Korman and posted on the [Arduino forum](http://forum.arduino.cc/index.php?topic=61586.0) to add the speed capability. Philip van Allen updated it for Arduino 1.0 + and added the ability to to wait for the move to complete.
* Supports up to 8 servos
* Allows simultaneous, asynchronous movement of all servos
* The speed of a move can be set
* The write() function initiates a move and can optionally wait for completion of the move before returning
* A servo can be sent a sequence of moves (where each move has a position and speed)
Sample Code - one servo moving, wait for first movement to finish, then execute another movement
----------------------------
```
#include <VarSpeedServo.h>
VarSpeedServo myservo; // create servo object to control a servo
void setup() {
myservo.attach(9); // attaches the servo on pin 9 to the servo object
}
void loop() {
myservo.write(180, 30, true); // move to 180 degrees, use a speed of 30, wait until move is complete
myservo.write(0, 30, true); // move to 0 degrees, use a speed of 30, wait until move is complete
}
```
Sample Code - two servo moving in the same time with different speed, wait for both to finish and do another move
----------------------------
```
#include <VarSpeedServo.h>
// create servo objects
VarSpeedServo myservo1;
VarSpeedServo myservo2;
void setup() {
myservo1.attach(9);
myservo2.attach(8);
}
void loop() {
int LEF = 0;
int RIG = 180;
int SPEED1 = 160;
int SPEED2 = 100;
myservo1.write(LEF, SPEED1);
myservo2.write(LEF, SPEED2);
myservo1.wait(); // wait for servo 1 to finish
myservo2.wait(); // wait for servo 2 to finish
myservo1.write(RIG, SPEED1);
myservo1.wait(); // wait for S1
myservo1.write(LEF, SPEED1);
myservo2.write(RIG, SPEED2);
myservo1.wait();
myservo2.wait();
myservo1.write(RIG, SPEED1);
myservo1.wait();
delay(1000);
}
```
Additional examples are included in the distribution and are available in the Arduino Examples section.
Class methods
================
A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method. The servos are pulsed in the background using the value most recently written using the write() method
VarSpeedServo - Class for manipulating servo motors connected to Arduino pins. Methods:
attach(pin ) - Attaches a servo motor to an i/o pin.
attach(pin, min, max ) - Attaches to a pin setting min and max values in microseconds
default min is 544, max is 2400
write(value) - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds)
write(value, speed) - speed varies the speed of the move to new position 0=full speed, 1-255 slower to faster
write(value, speed, wait) - wait is a boolean that, if true, causes the function call to block until move is complete
writeMicroseconds() - Sets the servo pulse width in microseconds
read() - Gets the last written servo pulse width as an angle between 0 and 180.
readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release)
attached() - Returns true if there is a servo attached.
detach() - Stops an attached servos from pulsing its i/o pin.
slowmove(value, speed) - The same as write(value, speed), retained for compatibility with Korman's version
stop() - stops the servo at the current position
sequencePlay(sequence, sequencePositions); // play a looping sequence starting at position 0
sequencePlay(sequence, sequencePositions, loop, startPosition); // play sequence with number of positions, loop if true, start at position
sequenceStop(); // stop sequence at current position
wait(); // wait for movement to finish
isMoving() // return true if servo is still moving
Installation
=============
* Download the .zip file from the releases section of GitHub
* In Arduino, select SKETCH>IMPORT LIBRARY...>ADD LIBRARY... and find the .zip file
* This will install the library in your My Documents (Windows) or Documents (Mac) folder under Arduino/libraries
* You can also unzip the file, and install it in the above libraries folder manually
* See [arduino.cc/en/Guide/Libraries](http://arduino.cc/en/Guide/Libraries) for more info on libraries

View File

@ -0,0 +1,569 @@
/*
Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
Function slowmove and supporting code added 2010 by Korman. Above limitations apply
to all added code, except for the official maintainer of the Servo library. If he,
and only he deems the enhancment a good idea to add to the official Servo library,
he may add it without the requirement to name the author of the parts original to
this version of the library.
*/
/*
Updated 2013 by Philip van Allen (pva),
-- updated for Arduino 1.0 +
-- consolidated slowmove into the write command (while keeping slowmove() for compatibility
with Korman's version)
-- added wait parameter to allow write command to block until move is complete
-- added sequence playing ability to asynchronously move the servo through a series of positions, must be called in a loop
A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
The servos are pulsed in the background using the value most recently written using the write() method
Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
The sequence used to sieze timers is defined in timers.h
The methods are:
VarSpeedServo - Class for manipulating servo motors connected to Arduino pins.
attach(pin ) - Attaches a servo motor to an i/o pin.
attach(pin, min, max ) - Attaches to a pin setting min and max values in microseconds
default min is 544, max is 2400
write(value) - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds)
write(value, speed) - speed varies the speed of the move to new position 0=full speed, 1-255 slower to faster
write(value, speed, wait) - wait is a boolean that, if true, causes the function call to block until move is complete
writeMicroseconds() - Sets the servo pulse width in microseconds
read() - Gets the last written servo pulse width as an angle between 0 and 180.
readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release)
attached() - Returns true if there is a servo attached.
detach() - Stops an attached servos from pulsing its i/o pin.
slowmove(value, speed) - The same as write(value, speed), retained for compatibility with Korman's version
stop() - stops the servo at the current position
sequencePlay(sequence, sequencePositions); // play a looping sequence starting at position 0
sequencePlay(sequence, sequencePositions, loop, startPosition); // play sequence with number of positions, loop if true, start at position
sequenceStop(); // stop sequence at current position
*/
#include <avr/interrupt.h>
#include <Arduino.h> // updated from WProgram.h to Arduino.h for Arduino 1.0+, pva
#include "VarSpeedServo.h"
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009
#define ticksToUs(_ticks) (( (unsigned)_ticks * 8)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays // 12 August 2009
//#define NBR_TIMERS (MAX_SERVOS / SERVOS_PER_TIMER)
static servo_t servos[MAX_SERVOS]; // static array of servo structures
static volatile int8_t Channel[_Nbr_16timers ]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
uint8_t ServoCount = 0; // the total number of attached servos
// sequence vars
servoSequencePoint initSeq[] = {{0,100},{45,100}};
//sequence_t sequences[MAX_SEQUENCE];
// convenience macros
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % SERVOS_PER_TIMER) // returns the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*SERVOS_PER_TIMER) + _channel) // macro to access servo index by timer and channel
#define SERVO(_timer,_channel) (servos[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
#define SERVO_MIN() (MIN_PULSE_WIDTH - this->min * 4) // minimum value in uS for this servo
#define SERVO_MAX() (MAX_PULSE_WIDTH - this->max * 4) // maximum value in uS for this servo
/************ static functions common to all instances ***********************/
static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA)
{
if( Channel[timer] < 0 )
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
else{
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true )
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated
}
Channel[timer]++; // increment to the next channel
if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
// Extension for slowmove
if (SERVO(timer,Channel[timer]).speed) {
// Increment ticks by speed until we reach the target.
// When the target is reached, speed is set to 0 to disable that code.
if (SERVO(timer,Channel[timer]).target > SERVO(timer,Channel[timer]).ticks) {
SERVO(timer,Channel[timer]).ticks += SERVO(timer,Channel[timer]).speed;
if (SERVO(timer,Channel[timer]).target <= SERVO(timer,Channel[timer]).ticks) {
SERVO(timer,Channel[timer]).ticks = SERVO(timer,Channel[timer]).target;
SERVO(timer,Channel[timer]).speed = 0;
}
}
else {
SERVO(timer,Channel[timer]).ticks -= SERVO(timer,Channel[timer]).speed;
if (SERVO(timer,Channel[timer]).target >= SERVO(timer,Channel[timer]).ticks) {
SERVO(timer,Channel[timer]).ticks = SERVO(timer,Channel[timer]).target;
SERVO(timer,Channel[timer]).speed = 0;
}
}
}
// End of Extension for slowmove
// Todo
*OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks;
if(SERVO(timer,Channel[timer]).Pin.isActive == true) // check if activated
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
}
else {
// finished all channels so wait for the refresh period to expire before starting over
if( (unsigned)*TCNTn < (usToTicks(REFRESH_INTERVAL) + 4) ) // allow a few ticks to ensure the next OCR1A not missed
*OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL);
else
*OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
}
}
#ifndef WIRING // Wiring pre-defines signal handlers so don't define any if compiling for the Wiring platform
// Interrupt handlers for Arduino
#if defined(_useTimer1)
SIGNAL (TIMER1_COMPA_vect)
{
handle_interrupts(_timer1, &TCNT1, &OCR1A);
}
#endif
#if defined(_useTimer3)
SIGNAL (TIMER3_COMPA_vect)
{
handle_interrupts(_timer3, &TCNT3, &OCR3A);
}
#endif
#if defined(_useTimer4)
SIGNAL (TIMER4_COMPA_vect)
{
handle_interrupts(_timer4, &TCNT4, &OCR4A);
}
#endif
#if defined(_useTimer5)
SIGNAL (TIMER5_COMPA_vect)
{
handle_interrupts(_timer5, &TCNT5, &OCR5A);
}
#endif
#elif defined WIRING
// Interrupt handlers for Wiring
#if defined(_useTimer1)
void Timer1Service()
{
handle_interrupts(_timer1, &TCNT1, &OCR1A);
}
#endif
#if defined(_useTimer3)
void Timer3Service()
{
handle_interrupts(_timer3, &TCNT3, &OCR3A);
}
#endif
#endif
static void initISR(timer16_Sequence_t timer)
{
#if defined (_useTimer1)
if(timer == _timer1) {
TCCR1A = 0; // normal counting mode
TCCR1B = _BV(CS11); // set prescaler of 8
TCNT1 = 0; // clear the timer count
#if defined(__AVR_ATmega8__)|| defined(__AVR_ATmega128__)
TIFR |= _BV(OCF1A); // clear any pending interrupts;
TIMSK |= _BV(OCIE1A) ; // enable the output compare interrupt
#else
// here if not ATmega8 or ATmega128
TIFR1 |= _BV(OCF1A); // clear any pending interrupts;
TIMSK1 |= _BV(OCIE1A) ; // enable the output compare interrupt
#endif
#if defined(WIRING)
timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service);
#endif
}
#endif
#if defined (_useTimer3)
if(timer == _timer3) {
TCCR3A = 0; // normal counting mode
TCCR3B = _BV(CS31); // set prescaler of 8
TCNT3 = 0; // clear the timer count
#if defined(__AVR_ATmega128__)
TIFR |= _BV(OCF3A); // clear any pending interrupts;
ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt
#else
TIFR3 = _BV(OCF3A); // clear any pending interrupts;
TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt
#endif
#if defined(WIRING)
timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only
#endif
}
#endif
#if defined (_useTimer4)
if(timer == _timer4) {
TCCR4A = 0; // normal counting mode
TCCR4B = _BV(CS41); // set prescaler of 8
TCNT4 = 0; // clear the timer count
TIFR4 = _BV(OCF4A); // clear any pending interrupts;
TIMSK4 = _BV(OCIE4A) ; // enable the output compare interrupt
}
#endif
#if defined (_useTimer5)
if(timer == _timer5) {
TCCR5A = 0; // normal counting mode
TCCR5B = _BV(CS51); // set prescaler of 8
TCNT5 = 0; // clear the timer count
TIFR5 = _BV(OCF5A); // clear any pending interrupts;
TIMSK5 = _BV(OCIE5A) ; // enable the output compare interrupt
}
#endif
}
static void finISR(timer16_Sequence_t timer)
{
//disable use of the given timer
#if defined WIRING // Wiring
if(timer == _timer1) {
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
TIMSK1 &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
#else
TIMSK &= ~_BV(OCIE1A) ; // disable timer 1 output compare interrupt
#endif
timerDetach(TIMER1OUTCOMPAREA_INT);
}
else if(timer == _timer3) {
#if defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
TIMSK3 &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
#else
ETIMSK &= ~_BV(OCIE3A); // disable the timer3 output compare A interrupt
#endif
timerDetach(TIMER3OUTCOMPAREA_INT);
}
#else
//For arduino - in future: call here to a currently undefined function to reset the timer
#endif
}
static boolean isTimerActive(timer16_Sequence_t timer)
{
// returns true if any servo is active on this timer
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
if(SERVO(timer,channel).Pin.isActive == true)
return true;
}
return false;
}
/****************** end of static functions ******************************/
VarSpeedServo::VarSpeedServo()
{
if( ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance
servos[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
this->curSeqPosition = 0;
this->curSequence = initSeq;
}
else
this->servoIndex = INVALID_SERVO ; // too many servos
}
uint8_t VarSpeedServo::attach(int pin)
{
return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
}
uint8_t VarSpeedServo::attach(int pin, int min, int max)
{
if(this->servoIndex < MAX_SERVOS ) {
pinMode( pin, OUTPUT) ; // set servo pin to output
servos[this->servoIndex].Pin.nbr = pin;
// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128
this->min = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
this->max = (MAX_PULSE_WIDTH - max)/4;
// initialize the timer if it has not already been initialized
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false)
initISR(timer);
servos[this->servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
}
return this->servoIndex ;
}
void VarSpeedServo::detach()
{
servos[this->servoIndex].Pin.isActive = false;
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if(isTimerActive(timer) == false) {
finISR(timer);
}
}
void VarSpeedServo::write(int value)
{
byte channel = this->servoIndex;
servos[channel].value = value;
if(value < MIN_PULSE_WIDTH)
{ // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
// updated to use constrain() instead of if(), pva
value = constrain(value, 0, 180);
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
}
this->writeMicroseconds(value);
}
void VarSpeedServo::writeMicroseconds(int value)
{
// calculate and store the values for the given channel
byte channel = this->servoIndex;
servos[channel].value = value;
if( (channel >= 0) && (channel < MAX_SERVOS) ) // ensure channel is valid
{
if( value < SERVO_MIN() ) // ensure pulse width is valid
value = SERVO_MIN();
else if( value > SERVO_MAX() )
value = SERVO_MAX();
value -= TRIM_DURATION;
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
uint8_t oldSREG = SREG;
cli();
servos[channel].ticks = value;
SREG = oldSREG;
// Extension for slowmove
// Disable slowmove logic.
servos[channel].speed = 0;
// End of Extension for slowmove
}
}
// Extension for slowmove
/*
write(value, speed) - Just like write but at reduced speed.
value - Target position for the servo. Identical use as value of the function write.
speed - Speed at which to move the servo.
speed=0 - Full speed, identical to write
speed=1 - Minimum speed
speed=255 - Maximum speed
*/
void VarSpeedServo::write(int value, uint8_t speed) {
// This fuction is a copy of write and writeMicroseconds but value will be saved
// in target instead of in ticks in the servo structure and speed will be save
// there too.
byte channel = this->servoIndex;
servos[channel].value = value;
if (speed) {
if (value < MIN_PULSE_WIDTH) {
// treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
// updated to use constrain instead of if, pva
value = constrain(value, 0, 180);
value = map(value, 0, 180, SERVO_MIN(), SERVO_MAX());
}
// calculate and store the values for the given channel
if( (channel >= 0) && (channel < MAX_SERVOS) ) { // ensure channel is valid
// updated to use constrain instead of if, pva
value = constrain(value, SERVO_MIN(), SERVO_MAX());
value = value - TRIM_DURATION;
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
// Set speed and direction
uint8_t oldSREG = SREG;
cli();
servos[channel].target = value;
servos[channel].speed = speed;
SREG = oldSREG;
}
}
else {
write (value);
}
}
void VarSpeedServo::write(int value, uint8_t speed, bool wait) {
write(value, speed);
if (wait) { // block until the servo is at its new position
if (value < MIN_PULSE_WIDTH) {
while (read() != value) {
delay(5);
}
} else {
while (readMicroseconds() != value) {
delay(5);
}
}
}
}
void VarSpeedServo::stop() {
write(read());
}
void VarSpeedServo::slowmove(int value, uint8_t speed) {
// legacy function to support original version of VarSpeedServo
write(value, speed);
}
// End of Extension for slowmove
int VarSpeedServo::read() // return the value as degrees
{
return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
}
int VarSpeedServo::readMicroseconds()
{
unsigned int pulsewidth;
if( this->servoIndex != INVALID_SERVO )
pulsewidth = ticksToUs(servos[this->servoIndex].ticks) + TRIM_DURATION ; // 12 aug 2009
else
pulsewidth = 0;
return pulsewidth;
}
bool VarSpeedServo::attached()
{
return servos[this->servoIndex].Pin.isActive ;
}
uint8_t VarSpeedServo::sequencePlay(servoSequencePoint sequenceIn[], uint8_t numPositions, bool loop, uint8_t startPos) {
uint8_t oldSeqPosition = this->curSeqPosition;
if( this->curSequence != sequenceIn) {
//Serial.println("newSeq");
this->curSequence = sequenceIn;
this->curSeqPosition = startPos;
oldSeqPosition = 255;
}
if (read() == sequenceIn[this->curSeqPosition].position && this->curSeqPosition != CURRENT_SEQUENCE_STOP) {
this->curSeqPosition++;
if (this->curSeqPosition >= numPositions) { // at the end of the loop
if (loop) { // reset to the beginning of the loop
this->curSeqPosition = 0;
} else { // stop the loop
this->curSeqPosition = CURRENT_SEQUENCE_STOP;
}
}
}
if (this->curSeqPosition != oldSeqPosition && this->curSeqPosition != CURRENT_SEQUENCE_STOP) {
// CURRENT_SEQUENCE_STOP position means the animation has ended, and should no longer be played
// otherwise move to the next position
write(sequenceIn[this->curSeqPosition].position, sequenceIn[this->curSeqPosition].speed);
//Serial.println(this->seqCurPosition);
}
return this->curSeqPosition;
}
uint8_t VarSpeedServo::sequencePlay(servoSequencePoint sequenceIn[], uint8_t numPositions) {
return sequencePlay(sequenceIn, numPositions, true, 0);
}
void VarSpeedServo::sequenceStop() {
write(read());
this->curSeqPosition = CURRENT_SEQUENCE_STOP;
}
// to be used only with "write(value, speed)"
void VarSpeedServo::wait() {
byte channel = this->servoIndex;
int value = servos[channel].value;
// wait until is done
if (value < MIN_PULSE_WIDTH) {
while (read() != value) {
delay(5);
}
} else {
while (readMicroseconds() != value) {
delay(5);
}
}
}
bool VarSpeedServo::isMoving() {
byte channel = this->servoIndex;
int value = servos[channel].value;
if (value < MIN_PULSE_WIDTH) {
if (read() != value) {
return true;
}
} else {
if (readMicroseconds() != value) {
return true;
}
}
return false;
}
/*
To do
int VarSpeedServo::targetPosition() {
byte channel = this->servoIndex;
return map( servos[channel].target+1, SERVO_MIN(), SERVO_MAX(), 0, 180);
}
int VarSpeedServo::targetPositionMicroseconds() {
byte channel = this->servoIndex;
return servos[channel].target;
}
*/

View File

@ -0,0 +1,183 @@
/*
VarSpeedServo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/*
Function slowmove and supporting code added 2010 by Korman. Above limitations apply
to all added code, except for the official maintainer of the Servo library. If he,
and only he deems the enhancment a good idea to add to the official Servo library,
he may add it without the requirement to name the author of the parts original to
this version of the library.
*/
/*
Updated 2013 by Philip van Allen (pva),
-- updated for Arduino 1.0 +
-- consolidated slowmove into the write command (while keeping slowmove() for compatibility
with Korman's version)
-- added wait parameter to allow write command to block until move is complete
-- added sequence playing ability to asynchronously move the servo through a series of positions, must be called in a loop
A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
The servos are pulsed in the background using the value most recently written using the write() method
Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
The sequence used to sieze timers is defined in timers.h
The methods are:
VarSpeedServo - Class for manipulating servo motors connected to Arduino pins.
attach(pin ) - Attaches a servo motor to an i/o pin.
attach(pin, min, max ) - Attaches to a pin setting min and max values in microseconds
default min is 544, max is 2400
write(value) - Sets the servo angle in degrees. (invalid angle that is valid as pulse in microseconds is treated as microseconds)
write(value, speed) - speed varies the speed of the move to new position 0=full speed, 1-255 slower to faster
write(value, speed, wait) - wait is a boolean that, if true, causes the function call to block until move is complete
writeMicroseconds() - Sets the servo pulse width in microseconds
read() - Gets the last written servo pulse width as an angle between 0 and 180.
readMicroseconds() - Gets the last written servo pulse width in microseconds. (was read_us() in first release)
attached() - Returns true if there is a servo attached.
detach() - Stops an attached servos from pulsing its i/o pin.
slowmove(value, speed) - The same as write(value, speed), retained for compatibility with Korman's version
stop() - stops the servo at the current position
sequencePlay(sequence, sequencePositions); // play a looping sequence starting at position 0
sequencePlay(sequence, sequencePositions, loop, startPosition); // play sequence with number of positions, loop if true, start at position
sequenceStop(); // stop sequence at current position
*/
#ifndef VarSpeedServo_h
#define VarSpeedServo_h
#include <inttypes.h>
/*
* Defines for 16 bit timers used with Servo library
*
* If _useTimerX is defined then TimerX is a 16 bit timer on the curent board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
* _Nbr_16timers indicates how many 16 bit timers are available.
*
*/
// Say which 16 bit timers can be used and in what order
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define _useTimer5
#define _useTimer1
#define _useTimer3
#define _useTimer4
typedef enum { _timer5, _timer1, _timer3, _timer4, _Nbr_16timers } timer16_Sequence_t ;
#elif defined(__AVR_ATmega32U4__)
#define _useTimer3
#define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ;
#elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__)
#define _useTimer3
#define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ;
#elif defined(__AVR_ATmega128__) ||defined(__AVR_ATmega1281__)||defined(__AVR_ATmega2561__)
#define _useTimer3
#define _useTimer1
typedef enum { _timer3, _timer1, _Nbr_16timers } timer16_Sequence_t ;
#else // everything else
#define _useTimer1
typedef enum { _timer1, _Nbr_16timers } timer16_Sequence_t ;
#endif
#define VarSpeedServo_VERSION 2 // software version of this library
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
#define REFRESH_INTERVAL 20000 // minumim time to refresh servos in microseconds
#define SERVOS_PER_TIMER 12 // the maximum number of servos controlled by one timer
#define MAX_SERVOS (_Nbr_16timers * SERVOS_PER_TIMER)
#define INVALID_SERVO 255 // flag indicating an invalid servo index
#define CURRENT_SEQUENCE_STOP 255 // used to indicate the current sequence is not used and sequence should stop
typedef struct {
uint8_t nbr :6 ; // a pin number from 0 to 63
uint8_t isActive :1 ; // true if this channel is enabled, pin not pulsed if false
} ServoPin_t ;
typedef struct {
ServoPin_t Pin;
unsigned int ticks;
unsigned int value; // Extension for external wait (Gill)
unsigned int target; // Extension for slowmove
uint8_t speed; // Extension for slowmove
} servo_t;
typedef struct {
uint8_t position;
uint8_t speed;
} servoSequencePoint;
class VarSpeedServo
{
public:
VarSpeedServo();
uint8_t attach(int pin); // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure
uint8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes.
void detach();
void write(int value); // if value is < 200 its treated as an angle, otherwise as pulse width in microseconds
void write(int value, uint8_t speed); // Move to given position at reduced speed.
// speed=0 is identical to write, speed=1 slowest and speed=255 fastest.
// On the RC-Servos tested, speeds differences above 127 can't be noticed,
// because of the mechanical limits of the servo.
void write(int value, uint8_t speed, bool wait); // wait parameter causes call to block until move completes
void writeMicroseconds(int value); // Write pulse width in microseconds
void slowmove(int value, uint8_t speed);
void stop(); // stop the servo where it is
int read(); // returns current pulse width as an angle between 0 and 180 degrees
int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release)
bool attached(); // return true if this servo is attached, otherwise false
uint8_t sequencePlay(servoSequencePoint sequenceIn[], uint8_t numPositions, bool loop, uint8_t startPos);
uint8_t sequencePlay(servoSequencePoint sequenceIn[], uint8_t numPositions); // play a looping sequence starting at position 0
void sequenceStop(); // stop movement
void wait(); // wait for movement to finish
bool isMoving(); // return true if servo is still moving
private:
uint8_t servoIndex; // index into the channel data for this servo
int8_t min; // minimum is this value times 4 added to MIN_PULSE_WIDTH
int8_t max; // maximum is this value times 4 added to MAX_PULSE_WIDTH
servoSequencePoint * curSequence; // for sequences
uint8_t curSeqPosition; // for sequences
};
#endif

View File

@ -0,0 +1,31 @@
/*
Knob
Controlling a servo position using a potentiometer (variable resistor)
by Michal Rinott <http://people.interaction-ivrea.it/m.rinott>
Adapted by Philip van Allen <philvanallen.com> for the VarSpeedServo.h library (October 2013)
This example code is in the public domain
Moves a servo to a position, determined by a scaled value from an analog input, driven by a knob (potentiometer)
Note that servos usually require more power than is available from the USB port - use an external power supply!
*/
#include <VarSpeedServo.h>
VarSpeedServo myservo; // create servo object to control a servo
const int potPin = 0; // analog pin used to connect the potentiometer
const int servoPin = 9; // the digital pin used for the servo
int val; // variable to read the value from the analog pin
void setup() {
myservo.attach(servoPin); // attaches the servo on pin 9 to the servo object
}
void loop() {
val = analogRead(potPin); // reads the value of the potentiometer (value between 0 and 1023)
val = map(val, 0, 1023, 0, 180); // scale it to use it with the servo (value from 0 and 180)
myservo.write(val); // sets the servo position according to the scaled value
delay(15); // waits a bit before the next value is read and written
}

View File

@ -0,0 +1,37 @@
/*
ServoSequence
Reads an analog input, and plays different servo sequences depending on the analog value
This example code is in the public domain.
*/
#include <VarSpeedServo.h>
VarSpeedServo myservo1;
const int servoPin1 = 9; // the digital pin used for the servo
// sequences are defined as an array of points in the sequence
// each point has a position from 0 - 180, and a speed to get to that position
servoSequencePoint slow[] = {{100,20},{20,20},{60,50}}; // go to position 100 at speed of 20, position 20 speed 20, position 60, speed 50
servoSequencePoint twitchy[] = {{0,255},{180,40},{90,127},{120,60}};
const int analogPin = A0;
// the setup routine runs once when you press reset:
void setup() {
myservo1.attach(servoPin1);
}
// the loop routine runs over and over again forever:
void loop() {
// read the input on analog pin 0:
int sensorValue = analogRead(analogPin);
if (sensorValue > 200) {
myservo1.sequencePlay(slow, 3); // play sequence "slowHalf" that has 3 positions, loop and start at first position
} else {
myservo1.sequencePlay(twitchy, 4, true, 2); // play sequence "twitchy", loop, start at third position
}
delay(2); // delay in between reads for analogin stability
}

View File

@ -0,0 +1,29 @@
/*
Sweep
by BARRAGAN <http://barraganstudio.com>
Adapted by Philip van Allen <philvanallen.com> for the VarSpeedServo.h library (October 2013)
This example code is in the public domain
Sweep a servo back and forth from 0-180 degrees, 180-0 degrees
Uses the wait feature of the 2013 version of VarSpeedServo to stop the code until the servo finishes moving
Note that servos usually require more power than is available from the USB port - use an external power supply!
*/
#include <VarSpeedServo.h>
VarSpeedServo myservo; // create servo object to control a servo
// a maximum of eight servo objects can be created
const int servoPin = 9; // the digital pin used for the servo
void setup() {
myservo.attach(servoPin); // attaches the servo on pin 9 to the servo object
myservo.write(0,255,true); // set the intial position of the servo, as fast as possible, wait until done
}
void loop() {
myservo.write(180,255,true); // move the servo to 180, max speed, wait until done
// write(degrees 0-180, speed 1-255, wait to complete true-false)
myservo.write(0,30,true); // move the servo to 180, slow speed, wait until done
}

View File

@ -0,0 +1,36 @@
/*
SweepTwoServos
By Philip van Allen <philvanallen.com> for the VarSpeedServo.h library (October 2013)
This example code is in the public domain
Sweep two servos from 0-180, 180-0 in unison
Uses the wait feature of the 2013 version of VarSpeedServo to start the first servo moving in the background
and immediately starting a second servo moving and waiting for the second one to finish.
Note that two servos will require more power than is available from the USB port - use an external power supply!
*/
#include <VarSpeedServo.h>
VarSpeedServo myservo1; // create servo object to control a servo
// a maximum of eight servo objects can be created
VarSpeedServo myservo2;
const int servoPin1 = 9; // the digital pin used for the first servo
const int servoPin2 = 10; // the digital pin used for the second servo
void setup() {
myservo1.attach(servoPin1); // attaches the servo on pin 9 to the servo object
myservo1.write(0,255,false); // set the intial position of the servo, as fast as possible, run in background
myservo2.attach(servoPin2); // attaches the servo on pin 9 to the servo object
myservo2.write(0,255,true); // set the intial position of the servo, as fast as possible, wait until done
}
void loop() {
myservo1.write(180,127,false); // move the servo to 180, fast speed, run background
// write(degrees 0-180, speed 1-255, wait to complete true-false)
myservo2.write(180,127,true); // move the servo to 180, fast speed, wait until done
myservo1.write(0,30,false); // move the servo to 180, slow speed, run in background
myservo2.write(0,30,true); // move the servo to 180, slow speed, wait until done
}

View File

@ -0,0 +1,50 @@
#include <VarSpeedServo.h>
// create servo object to control a servo
VarSpeedServo myservo1;
VarSpeedServo myservo2;
void setup() {
// initialize serial:
//Serial.begin(9600);
myservo1.attach(9);
myservo2.attach(8);
}
void loop() {
int LEF = 0;
int RIG = 180;
int SPEED1 = 160;
int SPEED2 = 100;
for(int i = 0; i < 4; i++) {
myservo1.write(LEF, SPEED1);
myservo2.write(LEF, SPEED2);
myservo1.wait();
myservo2.wait();
myservo1.write(RIG, SPEED1);
myservo1.wait();
myservo1.write(LEF, SPEED1);
myservo2.write(RIG, SPEED2);
myservo1.wait();
myservo2.wait();
myservo1.write(RIG, SPEED1);
myservo1.wait();
}
///*
delay(3000);
myservo1.detach();
myservo2.detach();
// */
}

View File

@ -0,0 +1,29 @@
#######################################
# Syntax Coloring Map Servo
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
VarSpeedServo KEYWORD1
#######################################
# Methods and Functions (KEYWORD2)
#######################################
attach KEYWORD2
detach KEYWORD2
write KEYWORD2
read KEYWORD2
stop KEYWORD2
attached KEYWORD2
writeMicroseconds KEYWORD2
readMicroseconds KEYWORD2
slowmove KEYWORD2
sequencePlay KEYWORD2
sequenceStop KEYWORD2
wait KEYWORD2
isMoving KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################

View File

@ -0,0 +1,561 @@
/**************************************************************************/
/*!
@file ams_as5048b.cpp
@author SOSAndroid (E. Ha.)
@license BSD (see license.txt)
Library to interface the AS5048B magnetic rotary encoder from AMS over the I2C bus
@section HISTORY
v1.0.0 - First release
v1.0.1 - Typo to allow compiling on Codebender.cc (Math.h vs math.h)
v1.0.2 - setZeroReg() issue raised by @MechatronicsWorkman
v1.0.3 - Small bug fix and improvement by @DavidHowlett
*/
/**************************************************************************/
#include <stdlib.h>
#include <math.h>
#include <Wire.h>
#include "ams_as5048b.h"
/*========================================================================*/
/* CONSTRUCTORS */
/*========================================================================*/
/**************************************************************************/
/*!
Constructor
*/
/**************************************************************************/
AMS_AS5048B::AMS_AS5048B(void) {
_chipAddress = AS5048_ADDRESS;
_debugFlag = false;
}
AMS_AS5048B::AMS_AS5048B(uint8_t chipAddress) {
_chipAddress = chipAddress;
_debugFlag = false;
}
/*========================================================================*/
/* PUBLIC FUNCTIONS */
/*========================================================================*/
/**************************************************************************/
/*!
@brief init values and overall behaviors for AS5948B use
@params
none
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::begin(void) {
#ifdef USE_WIREBEGIN_ENABLED
Wire.begin();
#endif
#ifdef SERIAL_DEBUG_ENABLED
_debugFlag = true;
if (!Serial) {
Serial.begin(9600);
}
#endif
_clockWise = false;
_lastAngleRaw = 0.0;
_zeroRegVal = AMS_AS5048B::zeroRegR();
_addressRegVal = AMS_AS5048B::addressRegR();
AMS_AS5048B::resetMovingAvgExp();
return;
}
/**************************************************************************/
/*!
@brief Toggle debug output to serial
@params
none
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::toggleDebug(void) {
_debugFlag = !_debugFlag;
return;
}
/**************************************************************************/
/*!
@brief Set / unset clock wise counting - sensor counts CCW natively
@params[in]
boolean cw - true: CW, false: CCW
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::setClockWise(boolean cw) {
_clockWise = cw;
_lastAngleRaw = 0.0;
AMS_AS5048B::resetMovingAvgExp();
return;
}
/**************************************************************************/
/*!
@brief writes OTP control register
@params[in]
unit8_t register value
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::progRegister(uint8_t regVal) {
AMS_AS5048B::writeReg(AS5048B_PROG_REG, regVal);
return;
}
/**************************************************************************/
/*!
@brief Burn values to the slave address OTP register
@params[in]
none
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::doProg(void) {
//enable special programming mode
AMS_AS5048B::progRegister(0xFD);
delay(10);
//set the burn bit: enables automatic programming procedure
AMS_AS5048B::progRegister(0x08);
delay(10);
//disable special programming mode
AMS_AS5048B::progRegister(0x00);
delay(10);
return;
}
/**************************************************************************/
/*!
@brief Burn values to the zero position OTP register
@params[in]
none
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::doProgZero(void) {
//this will burn the zero position OTP register like described in the datasheet
//enable programming mode
AMS_AS5048B::progRegister(0x01);
delay(10);
//set the burn bit: enables automatic programming procedure
AMS_AS5048B::progRegister(0x08);
delay(10);
//read angle information (equals to 0)
AMS_AS5048B::readReg16(AS5048B_ANGLMSB_REG);
delay(10);
//enable verification
AMS_AS5048B::progRegister(0x40);
delay(10);
//read angle information (equals to 0)
AMS_AS5048B::readReg16(AS5048B_ANGLMSB_REG);
delay(10);
return;
}
/**************************************************************************/
/*!
@brief write I2C address value (5 bits) into the address register
@params[in]
unit8_t register value
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::addressRegW(uint8_t regVal) {
// write the new chip address to the register
AMS_AS5048B::writeReg(AS5048B_ADDR_REG, regVal);
// update our chip address with our 5 programmable bits
// the MSB is internally inverted, so we flip the leftmost bit
_chipAddress = ((regVal << 2) | (_chipAddress & 0b11)) ^ (1 << 6);
return;
}
/**************************************************************************/
/*!
@brief reads I2C address register value
@params[in]
none
@returns
uint8_t register value
*/
/**************************************************************************/
uint8_t AMS_AS5048B::addressRegR(void) {
return AMS_AS5048B::readReg8(AS5048B_ADDR_REG);
}
/**************************************************************************/
/*!
@brief sets current angle as the zero position
@params[in]
none
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::setZeroReg(void) {
AMS_AS5048B::zeroRegW((uint16_t) 0x00); //Issue closed by @MechatronicsWorkman and @oilXander. The last sequence avoids any offset for the new Zero position
uint16_t newZero = AMS_AS5048B::readReg16(AS5048B_ANGLMSB_REG);
AMS_AS5048B::zeroRegW(newZero);
return;
}
/**************************************************************************/
/*!
@brief writes the 2 bytes Zero position register value
@params[in]
unit16_t register value
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::zeroRegW(uint16_t regVal) {
AMS_AS5048B::writeReg(AS5048B_ZEROMSB_REG, (uint8_t) (regVal >> 6));
AMS_AS5048B::writeReg(AS5048B_ZEROLSB_REG, (uint8_t) (regVal & 0x3F));
return;
}
/**************************************************************************/
/*!
@brief reads the 2 bytes Zero position register value
@params[in]
none
@returns
uint16_t register value trimmed on 14 bits
*/
/**************************************************************************/
uint16_t AMS_AS5048B::zeroRegR(void) {
return AMS_AS5048B::readReg16(AS5048B_ZEROMSB_REG);
}
/**************************************************************************/
/*!
@brief reads the 2 bytes magnitude register value
@params[in]
none
@returns
uint16_t register value trimmed on 14 bits
*/
/**************************************************************************/
uint16_t AMS_AS5048B::magnitudeR(void) {
return AMS_AS5048B::readReg16(AS5048B_MAGNMSB_REG);
}
uint16_t AMS_AS5048B::angleRegR(void) {
return AMS_AS5048B::readReg16(AS5048B_ANGLMSB_REG);
}
/**************************************************************************/
/*!
@brief reads the 1 bytes auto gain register value
@params[in]
none
@returns
uint8_t register value
*/
/**************************************************************************/
uint8_t AMS_AS5048B::getAutoGain(void) {
return AMS_AS5048B::readReg8(AS5048B_GAIN_REG);
}
/**************************************************************************/
/*!
@brief reads the 1 bytes diagnostic register value
@params[in]
none
@returns
uint8_t register value
*/
/**************************************************************************/
uint8_t AMS_AS5048B::getDiagReg(void) {
return AMS_AS5048B::readReg8(AS5048B_DIAG_REG);
}
/**************************************************************************/
/*!
@brief reads current angle value and converts it into the desired unit
@params[in]
String unit : string expressing the unit of the angle. Sensor raw value as default
@params[in]
Boolean newVal : have a new measurement or use the last read one. True as default
@returns
Double angle value converted into the desired unit
*/
/**************************************************************************/
double AMS_AS5048B::angleR(int unit, boolean newVal) {
double angleRaw;
if (newVal) {
if(_clockWise) {
angleRaw = (double) (0b11111111111111 - AMS_AS5048B::readReg16(AS5048B_ANGLMSB_REG));
}
else {
angleRaw = (double) AMS_AS5048B::readReg16(AS5048B_ANGLMSB_REG);
}
_lastAngleRaw = angleRaw;
}
else {
angleRaw = _lastAngleRaw;
}
return AMS_AS5048B::convertAngle(unit, angleRaw);
}
/**************************************************************************/
/*!
@brief Performs an exponential moving average on the angle.
Works on Sine and Cosine of the angle to avoid issues 0°/360° discontinuity
@params[in]
none
@returns
none
*/
/**************************************************************************/
void AMS_AS5048B::updateMovingAvgExp(void) {
//sine and cosine calculation on angles in radian
double angle = AMS_AS5048B::angleR(U_RAD, true);
if (_movingAvgCountLoop < EXP_MOVAVG_LOOP) {
_movingAvgExpSin += sin(angle);
_movingAvgExpCos += cos(angle);
if (_movingAvgCountLoop == (EXP_MOVAVG_LOOP - 1)) {
_movingAvgExpSin = _movingAvgExpSin / EXP_MOVAVG_LOOP;
_movingAvgExpCos = _movingAvgExpCos / EXP_MOVAVG_LOOP;
}
_movingAvgCountLoop ++;
}
else {
double movavgexpsin = _movingAvgExpSin + _movingAvgExpAlpha * (sin(angle) - _movingAvgExpSin);
double movavgexpcos = _movingAvgExpCos + _movingAvgExpAlpha * (cos(angle) - _movingAvgExpCos);
_movingAvgExpSin = movavgexpsin;
_movingAvgExpCos = movavgexpcos;
_movingAvgExpAngle = getExpAvgRawAngle();
}
return;
}
/**************************************************************************/
/*!
@brief sent back the exponential moving averaged angle in the desired unit
@params[in]
String unit : string expressing the unit of the angle. Sensor raw value as default
@returns
Double exponential moving averaged angle value
*/
/**************************************************************************/
double AMS_AS5048B::getMovingAvgExp(int unit) {
return AMS_AS5048B::convertAngle(unit, _movingAvgExpAngle);
}
void AMS_AS5048B::resetMovingAvgExp(void) {
_movingAvgExpAngle = 0.0;
_movingAvgCountLoop = 0;
_movingAvgExpAlpha = 2.0 / (EXP_MOVAVG_N + 1.0);
return;
}
/*========================================================================*/
/* PRIVATE FUNCTIONS */
/*========================================================================*/
uint8_t AMS_AS5048B::readReg8(uint8_t address) {
uint8_t readValue;
byte requestResult;
uint8_t nbByte2Read = 1;
Wire.beginTransmission(_chipAddress);
Wire.write(address);
requestResult = Wire.endTransmission(false);
if (requestResult){
Serial.print("I2C error: ");
Serial.println(requestResult);
}
Wire.requestFrom(_chipAddress, nbByte2Read);
readValue = (uint8_t) Wire.read();
return readValue;
}
uint16_t AMS_AS5048B::readReg16(uint8_t address) {
//16 bit value got from 2 8bits registers (7..0 MSB + 5..0 LSB) => 14 bits value
uint8_t nbByte2Read = 2;
byte requestResult;
byte readArray[2];
uint16_t readValue = 0;
Wire.beginTransmission(_chipAddress);
Wire.write(address);
requestResult = Wire.endTransmission(false);
if (requestResult){
Serial.print("I2C error: ");
Serial.println(requestResult);
}
Wire.requestFrom(_chipAddress, nbByte2Read);
for (byte i=0; i < nbByte2Read; i++) {
readArray[i] = Wire.read();
}
readValue = (((uint16_t) readArray[0]) << 6);
readValue += (readArray[1] & 0x3F);
/*
Serial.println(readArray[0], BIN);
Serial.println(readArray[1], BIN);
Serial.println(readValue, BIN);
*/
return readValue;
}
void AMS_AS5048B::writeReg(uint8_t address, uint8_t value) {
Wire.beginTransmission(_chipAddress);
Wire.write(address);
Wire.write(value);
Wire.endTransmission();
return;
}
double AMS_AS5048B::convertAngle(int unit, double angle) {
// convert raw sensor reading into angle unit
double angleConv;
switch (unit) {
case U_RAW:
//Sensor raw measurement
angleConv = angle;
break;
case U_TRN:
//full turn ratio
angleConv = (angle / AS5048B_RESOLUTION);
break;
case U_DEG:
//degree
angleConv = (angle / AS5048B_RESOLUTION) * 360.0;
break;
case U_RAD:
//Radian
angleConv = (angle / AS5048B_RESOLUTION) * 2 * M_PI;
break;
case U_MOA:
//minute of arc
angleConv = (angle / AS5048B_RESOLUTION) * 60.0 * 360.0;
break;
case U_SOA:
//second of arc
angleConv = (angle / AS5048B_RESOLUTION) * 60.0 * 60.0 * 360.0;
break;
case U_GRAD:
//grade
angleConv = (angle / AS5048B_RESOLUTION) * 400.0;
break;
case U_MILNATO:
//NATO MIL
angleConv = (angle / AS5048B_RESOLUTION) * 6400.0;
break;
case U_MILSE:
//Swedish MIL
angleConv = (angle / AS5048B_RESOLUTION) * 6300.0;
break;
case U_MILRU:
//Russian MIL
angleConv = (angle / AS5048B_RESOLUTION) * 6000.0;
break;
default:
//no conversion => raw angle
angleConv = angle;
break;
}
return angleConv;
}
double AMS_AS5048B::getExpAvgRawAngle(void) {
double angle;
double twopi = 2 * M_PI;
if (_movingAvgExpSin < 0.0) {
angle = twopi - acos(_movingAvgExpCos);
}
else {
angle = acos(_movingAvgExpCos);
}
angle = (angle / twopi) * AS5048B_RESOLUTION;
return angle;
}
void AMS_AS5048B::printDebug(void) {
return;
}

View File

@ -0,0 +1,150 @@
/**************************************************************************/
/*!
@file ams_as5048b.h
@author SOSAndroid.fr (E. Ha.)
@section HISTORY
v1.0 - First release
v1.0.1 - Typo to allow compiling on Codebender.cc (Math.h vs math.h)
v1.0.2 - Small bug fix and improvement by @DavidHowlett
Library to interface the AS5048B magnetic rotary encoder from AMS over the I2C bus
@section LICENSE
Software License Agreement (BSD License)
Copyright (c) 2013, SOSAndroid.fr (E. Ha.)
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
3. Neither the name of the copyright holders nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**************************************************************************/
#if ARDUINO >= 100
#include <Arduino.h>
#else
#include <WProgram.h>
#endif
#include <math.h>
#include <Wire.h>
#ifndef _AMS_AS5048B_H_
#define _AMS_AS5048B_H_
// OPERATIONS
#define SERIAL_DEBUG_ENABLED
#define USE_WIREBEGIN_ENABLED // to comment if Wire.begin() function is called in Setup() for instance. Usefull to manage one or several I2C devices in the same sketch
// Default addresses for AS5048B
#define AS5048_ADDRESS 0x40 // 0b10000 + ( A1 & A2 to GND)
#define AS5048B_PROG_REG 0x03
#define AS5048B_ADDR_REG 0x15
#define AS5048B_ZEROMSB_REG 0x16 //bits 0..7
#define AS5048B_ZEROLSB_REG 0x17 //bits 0..5
#define AS5048B_GAIN_REG 0xFA
#define AS5048B_DIAG_REG 0xFB
#define AS5048B_MAGNMSB_REG 0xFC //bits 0..7
#define AS5048B_MAGNLSB_REG 0xFD //bits 0..5
#define AS5048B_ANGLMSB_REG 0xFE //bits 0..7
#define AS5048B_ANGLLSB_REG 0xFF //bits 0..5
#define AS5048B_RESOLUTION 16384.0 //14 bits
// Moving Exponential Average on angle - beware heavy calculation for some Arduino boards
// This is a 1st order low pass filter
// Moving average is calculated on Sine et Cosine values of the angle to provide an extrapolated accurate angle value.
#define EXP_MOVAVG_N 5 //history length impact on moving average impact - keep in mind the moving average will be impacted by the measurement frequency too
#define EXP_MOVAVG_LOOP 1 //number of measurements before starting mobile Average - starting with a simple average - 1 allows a quick start. Value must be 1 minimum
//unit consts - just to make the units more readable
#define U_RAW 1
#define U_TRN 2
#define U_DEG 3
#define U_RAD 4
#define U_GRAD 5
#define U_MOA 6
#define U_SOA 7
#define U_MILNATO 8
#define U_MILSE 9
#define U_MILRU 10
class AMS_AS5048B {
public:
AMS_AS5048B(void);
AMS_AS5048B(uint8_t chipAddress);
void begin(void); // to init the object, must be called in the setup loop
void toggleDebug(void); // start / stop debug through serial at anytime
void setClockWise(boolean cw = true); //set clockwise counting, default is false (native sensor)
void progRegister(uint8_t regVal); //nothing so far - manipulate the OTP register
void doProg(void); //progress programming slave address OTP
void doProgZero(void); //progress programming zero position OTP
void addressRegW(uint8_t regVal); //change the chip address
uint8_t addressRegR(void); //read chip address
void setZeroReg(void); //set Zero to current angle position
void zeroRegW(uint16_t regVal); //write Zero register value
uint16_t zeroRegR(void); //read Zero register value
uint16_t angleRegR(void); //read raw value of the angle register
uint8_t diagR(void); //read diagnostic register
uint16_t magnitudeR(void); //read current magnitude
double angleR(int unit = U_RAW, boolean newVal = true); //Read current angle or get last measure with unit conversion : RAW, TRN, DEG, RAD, GRAD, MOA, SOA, MILNATO, MILSE, MILRU
uint8_t getAutoGain(void);
uint8_t getDiagReg(void);
void updateMovingAvgExp(void); //measure the current angle and feed the Exponential Moving Average calculation
double getMovingAvgExp(int unit = U_RAW); //get Exponential Moving Average calculation
void resetMovingAvgExp(void); //reset Exponential Moving Average calculation values
private:
//variables
boolean _debugFlag;
boolean _clockWise;
uint8_t _chipAddress;
uint8_t _addressRegVal;
uint16_t _zeroRegVal;
double _lastAngleRaw;
double _movingAvgExpAngle;
double _movingAvgExpSin;
double _movingAvgExpCos;
double _movingAvgExpAlpha;
int _movingAvgCountLoop;
//methods
uint8_t readReg8(uint8_t address);
uint16_t readReg16(uint8_t address); //16 bit value got from 2x8bits registers (7..0 MSB + 5..0 LSB) => 14 bits value
void writeReg(uint8_t address, uint8_t value);
double convertAngle(int unit, double angle); //RAW, TRN, DEG, RAD, GRAD, MOA, SOA, MILNATO, MILSE, MILRU
double getExpAvgRawAngle(void);
void printDebug(void);
};
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,593 @@
:100000000C9463000C948B000C948B000C94690589
:100010000C9469050C9469050C948B000C948B006E
:100020000C948B000C948B000C948B000C94A80403
:100030000C948B000C948B000C948B000C948B0014
:100040000C9434080C948B000C9448030C942203F9
:100050000C948B000C948B000C948B000C948B00F4
:100060000C947A030C948B000000000024002700FD
:100070002A0000000008000201000003040700003D
:1000800000000000000000000000250028002B00F8
:1000900000000000230026002900040404040404D6
:1000A0000404020202020202030303030303010227
:1000B00004081020408001020408102001020408F6
:1000C00010200C0CF00B11241FBECFEFD8E0DEBFC8
:1000D000CDBF11E0A0E0B1E0E4E8F4E202C0059099
:1000E0000D92AA36B107D9F723E0AAE6B1E001C024
:1000F0001D92A03CB207E1F710E0C2E6D0E004C0D8
:100100002197FE010E942310C136D107C9F70E9432
:10011000A5080C9435120C940000CF92DF92EF9258
:10012000FF920F931F93CF93DF936C017A018B01A2
:10013000C0E0D0E0CE15DF0589F0D8016D918D01CA
:10014000D601ED91FC910190F081E02DC601099559
:10015000892B11F47E0102C02196ECCFC701DF91FB
:10016000CF911F910F91FF90EF90DF90CF90089566
:10017000FC01538D448D252F30E0842F90E0821BAD
:10018000930B541710F0CF96089501970895FC0132
:10019000918D828D981761F0828DDF01A80FB11DBE
:1001A0005D968C91928D9F5F9F73928F90E00895E2
:1001B0008FEF9FEF0895FC01918D828D981731F09C
:1001C000828DE80FF11D858D90E008958FEF9FEFF0
:1001D0000895FC01918D228D892F90E0805C9F4FC6
:1001E000821B91098F739927089585E692E00E94FA
:1001F000E90021E0892B09F420E0822F0895FC0119
:10020000848DDF01A80FB11DA35ABF4F2C91848D9F
:1002100090E001968F739927848FA689B7892C93D4
:10022000A089B1898C9180648C93938D848D98136F
:1002300006C00288F389E02D80818F7D8083089538
:10024000EF92FF920F931F93CF93DF93EC0181E026
:10025000888F9B8D8C8D981305C0E889F9898081E2
:1002600085FD24C0F62E0B8D10E00F5F1F4F0F731E
:100270001127E02E8C8DE8120CC00FB607FCFACFC8
:10028000E889F989808185FFF5CFCE010E94FF00C2
:10029000F1CF8B8DFE01E80FF11DE35AFF4FF08285
:1002A0000B8FEA89FB898081806207C0EE89FF8914
:1002B0006083E889F98980818064808381E090E0AF
:1002C000DF91CF911F910F91FF90EF900895CF9301
:1002D000DF93EC01888D8823C9F0EA89FB8980814E
:1002E00085FD05C0A889B9898C9186FD0FC00FB620
:1002F00007FCF5CF808185FFF2CFA889B9898C9161
:1003000085FFEDCFCE010E94FF00E7CFDF91CF91B7
:10031000089580E090E0892B29F00E94F50081117A
:100320000C940000089585ED8093BC008091BC0082
:1003300084FDFCCF1092400208954091D101262FF8
:1003400030E0240F311D21323105DCF420914002D0
:100350002430C9F4FC0180E090E0861758F4309115
:10036000D1012191DC01A155BE4FA30FB11D2C93EA
:100370000196F3CF8091D101680F6093D10180E0A5
:10038000089581E0089582E008952091AC013091B4
:10039000AD012817390771F49091AB018091AA0142
:1003A000981741F0E091AB01F0E0E659FE4F8081F3
:1003B00090E008958FEF9FEF089508951F93CF93D6
:1003C000DF93DC015C962D913C915D972115310501
:1003D00039F481E090E013969C938E9312973DC080
:1003E0005196ED91FC91529750969C915097892F80
:1003F00080951FB75E964C915E9741FB772770F909
:1004000041FD6095F8944081772311F0492B01C09C
:1004100048234083E9012197F1F748E0508160FFCC
:1004200002C0592B01C058235083E9012197F1F7ED
:100430006695415099F7772321F090818923808335
:1004400003C08081982B90831FBF5C968D919C91F7
:100450005D970197F1F721E030E0C901DF91CF917D
:100460001F9108952091AC013091AD0128173907F3
:1004700071F48091AA012091AB0190E0805C9F4FC4
:10048000821B910960E470E00E94FB0F089580E0F8
:1004900090E008952091AC013091AD012817390703
:1004A000B9F49091AB018091AA01981789F0E0917D
:1004B000AB01F0E0E659FE4F80812091AB0130E0C6
:1004C0002F5F3F4F2F7333272093AB0190E00895A8
:1004D0008FEF9FEF08950895E091F9018091F80161
:1004E000E81730F4F0E0E650FE4F808190E0089588
:1004F0008FEF9FEF08959091F9018091F80198177F
:1005000050F4E92FF0E0E650FE4F208130E09F5F8D
:100510009093F90102C02FEF3FEFC9010895809138
:10052000F80190E02091F901821B91090895CF9282
:10053000DF92EF92FF920F931F93CF93DF937C0193
:10054000262F972F8A0180914102882391F0C62F90
:10055000D72F6E01C40ED51ECC15DD0571F0699143
:10056000D701ED91FC910190F081E02DC701099533
:10057000F3CF642F822F0E949D01C801DF91CF919C
:100580001F910F91FF90EF90DF90CF900895CF9340
:10059000DF931F92CDB7DEB76983209141022223FA
:1005A000D1F020916402203240F021E030E0FC01E3
:1005B0003383228380E090E015C080914202E82FCF
:1005C000F0E0ED5BFD4F998190838F5F8093420255
:1005D0008093640205C061E0CE0101960E949D01F6
:1005E00081E090E00F90DF91CF910895089580E031
:1005F00090E008950E9420121092F9011092F801E3
:1006000010924202109264021092400281E08093A4
:100610003F0210921A0261E082E10E94870761E0C6
:1006200083E10E948707E9EBF0E080818E7F808381
:1006300080818D7F808388E48093B80085E48093F7
:10064000BC0008951F920F920FB60F9211242F93A2
:100650003F934F935F936F937F938F939F93AF934A
:10066000BF93EF93FF9385E692E00E94FF00FF9116
:10067000EF91BF91AF919F918F917F916F915F911A
:100680004F913F912F910F900FBE0F901F90189593
:100690001F920F920FB60F9211242F938F939F9357
:1006A000EF93FF93E0917502F09176028081E091E3
:1006B0007B02F0917C0282FD12C0908180917E02CB
:1006C0008F5F8F7320917F02821751F0E0917E023D
:1006D000F0E0EB59FD4F958F80937E0201C0808141
:1006E000FF91EF919F918F912F910F900FBE0F90DF
:1006F0001F9018951F920F920FB60F9211242F93EF
:100700003F934F935F936F937F938F939F93AF9399
:10071000BF93EF93FF938091B900887F803609F4EF
:100720009CC068F5883209F45BC090F4803109F40C
:1007300054C038F4882309F4F6C0883009F44DC059
:10074000F6C0883109F44CC0803209F45DC0EFC0B6
:10075000803409F468C048F4803309F455C0883304
:1007600009F0E5C080933E02D8C0803509F44FC03F
:10077000883509F45DC0883409F0D9C0D6C08839FD
:1007800009F4C7C0A8F4883709F467C038F488367C
:1007900009F463C0803709F460C0C9C0883809F41F
:1007A000B8C0803909F45FC0803809F0C0C05BC0B0
:1007B000803B09F486C038F4803A09F466C0883A70
:1007C00009F47FC0B4C0803C09F4A7C0883C09F498
:1007D000A4C0883B09F48AC0AAC080911B0210C043
:1007E00090913D0280913C02981770F5E0913D0296
:1007F00081E08E0F80933D02F0E0E45EFD4F80814A
:100800008093BB0085EC86C080933E028EC0E09151
:100810003D0281E08E0F80933D028091BB00F0E0AD
:10082000E45EFD4F808390913D0280913C026EC05A
:10083000E0913D0281E08E0F80933D028091BB00EC
:10084000F0E0E45EFD4F808380913F0281116DC036
:1008500081E080931A0284EA61C083E080934002C1
:100860001092F501CFCF8091F501803208F051C090
:10087000E091F50181E08E0F8093F5018091BB003E
:10088000F0E0EB52FE4F8083BDCF85EC8093BC003F
:10089000109240028091F501803230F4E091F50130
:1008A000F0E0EB52FE4F10826091F50170E0E091B4
:1008B000D301F091D40185ED91E009951092F501F5
:1008C00036C084E0809340021092D2011092D10190
:1008D000E091CF01F091D00109958091D101811172
:1008E00005C081E08093D1011092AF01E091D20167
:1008F00081E08E0F8093D201F0E0E155FE4F8081C0
:100900008093BB009091D2018091D101981708F497
:1009100079CF85E88093BC000AC085EC8093BC0049
:100920001092400204C010923E020E949301FF9177
:10093000EF91BF91AF919F918F917F916F915F9157
:100940004F913F912F910F900FBE0F901F901895D0
:100950001F920F920FB60F9211242F933F934F9334
:100960005F936F937F938F939F93AF93BF93EF9317
:10097000FF938091AE0187FF05C010928500109211
:1009800084001BC02091AE01022E000C330B80911D
:10099000320390E02817390784F48091AE01082EC5
:1009A000000C990BFC01EE0FFF1F8E0F9F1FFC0127
:1009B000E25FFC4F808186FD15C08091AE018F5FA4
:1009C0008093AE012091AE01022E000C330B80917A
:1009D000320390E028173907C4F48091AE018C30BF
:1009E00064F113C08091AE01082E000C990BFC013C
:1009F000EE0FFF1F8E0F9F1FFC01E25FFC4F8081F7
:100A000060E08F730E948707D8CF80918400909117
:100A10008500049680349C4918F480E49CE905C064
:100A20008091840090918500049690938900809332
:100A300088008FEF8093AE013BC0209184003091FD
:100A400085008091AE01082E000C990BFC01EE0F81
:100A5000FF1F8E0F9F1FFC01E25FFC4F818192817F
:100A6000820F931F90938900809388008091AE013C
:100A7000082E000C990BFC01EE0FFF1F8E0F9F1F1D
:100A8000FC01E25FFC4F808186FF12C08091AE01C5
:100A9000082E000C990BFC01EE0FFF1F8E0F9F1FFD
:100AA000FC01E25FFC4F808161E08F730E94870749
:100AB000FF91EF91BF91AF919F918F917F916F9136
:100AC0005F914F913F912F910F900FBE0F901F900C
:100AD00018951F920F920FB60F9211242F933F93E8
:100AE0004F935F936F937F938F939F93AF93BF9336
:100AF000EF93FF93E091AC01F091AD01309709F4D1
:100B000051C0968DA685B785858591FF04C09C91BF
:100B1000892329F447C09C91892309F043C0A38904
:100B2000B4899C918589809589238C93868997893E
:100B30000197F1F7608D718DA685B785558538E0F1
:100B400020E0CB010197F1F7822F90E095958795F2
:100B5000282F4C91452309F02068315091F7868D5C
:100B600081FD20958091AA0190E001968F739927CD
:100B70003091AB01381749F0A091AA01B0E0A65915
:100B8000BE4F2C938093AA0103C0868D8160868F0F
:100B9000828D938D0197F1F7A389B4899C91858902
:100BA000892B8C93FF91EF91BF91AF919F918F9182
:100BB0007F916F915F914F913F912F910F900FBE59
:100BC0000F901F901895009769F0FC01019000208C
:100BD000E9F73197AF01481B590BBC0185E692E05C
:100BE0000C948D0080E090E008958F929F92AF92D8
:100BF000BF920F931F93CF93DF93CDB7DEB7A1972B
:100C00000FB6F894DEBF0FBECDBF19A2423008F474
:100C10004AE08E010F5D1F4F842E912CA12CB12C28
:100C2000A50194010E94A60EE62FB901CA01015048
:100C30001109EA3014F4E05D01C0E95CD801EC93DD
:100C4000232B242B252B61F7C8010E94E305A196D5
:100C50000FB6F894DEBF0FBECDBFDF91CF911F91CD
:100C60000F91BF90AF909F908F900895382F209153
:100C7000640290916302213208F049C080914002E1
:100C80008111FCCF42E04093400230933F023FEF9E
:100C900030933E0210923D0220933C02A3E4B2E066
:100CA0004CE152E0FA013E2F341B321718F43D910B
:100CB0003193F9CF10921B0220911B02990F922BB6
:100CC00090931B0290911A02913061F410921A02D3
:100CD00090911B029093BB009091BC0093FDF8CFC4
:100CE00095EC01C095EE9093BC009091400292303B
:100CF000E1F390913E029F3F79F080913E02803275
:100D000041F080913E02803331F084E005C081E003
:100D100003C082E001C083E010924202109264029C
:100D2000109241020895909140029111FCCF6132DE
:100D300008F060E291E09093400290933F022FEF21
:100D400020933E0210923D02260F20933C02909386
:100D50001B0290911B02880F892B80931B028091AC
:100D60001A02813061F410921A0280911B02809362
:100D7000BB008091BC0083FDF8CF85EC01C085EEFF
:100D80008093BC00809140028130E1F380913D026C
:100D9000861710F460913D02ACE1B2E02AEF31E039
:100DA000F9018E2F821B861718F48D918193F9CF4C
:100DB0001092F9016093F801862F0895CF93DF9385
:100DC0009091350321E020934102909363021092A9
:100DD000420210926402682F82E093E00E94C702F0
:100DE00080E00E943606C82F882379F08CE391E0DA
:100DF0000E94E3056C2F70E080E090E04AE00E94E2
:100E0000F50588E491E00E94E30562E080913503F6
:100E10000E94930682E093E00E947B02EC0182E054
:100E200093E00E947B02DD2796E0CC0FDD1F9A95B0
:100E3000E1F78F739E01280F311DC901DF91CF911A
:100E400008952FB7F8948091B8039091B903A091B9
:100E5000BA03B091BB032FBF80939C0390939D0373
:100E6000A0939E03B0939F03E0919403F0919503A8
:100E70000284F385E02D84E993E0099597FF26C06D
:100E80002FB7F8948091B8039091B903A091BA0359
:100E9000B091BB032FBF40919C0350919D03609183
:100EA0009E0370919F03841B950BA60BB70B40917B
:100EB00098035091990360919A0370919B03841752
:100EC0009507A607B70780F28FEF9FEF089560E0C0
:100ED00082E093E00C94C702CF93C62F90919303C6
:100EE00021E02093410290936302109242021092FB
:100EF0006402682F82E093E00E94C7026C2F82E0B8
:100F000093E00E94C70281E0CF910C94360690E0F6
:100F1000FC01EE58FF4F3491FC01E255FF4F249144
:100F2000FC01E656FF4FE491EE2309F43BC0332366
:100F300039F1333091F038F43130A9F0323001F525
:100F400084B58F7D12C0373091F03830A1F0343045
:100F5000B9F4809180008F7D03C0809180008F77ED
:100F6000809380000DC084B58F7784BD09C08091C7
:100F7000B0008F7703C08091B0008F7D8093B00068
:100F8000F0E0EE0FFF1FEA57FF4FA591B4918FB726
:100F9000F894EC91611103C020952E2301C02E2BF3
:100FA0002C938FBF0895CF93DF9390E0FC01E2551F
:100FB000FF4F2491FC01E656FF4F8491882361F195
:100FC00090E0880F991FFC01E859FF4FC591D4911B
:100FD000FC01EA57FF4FA591B491611109C09FB779
:100FE000F8948881209582238883EC912E230BC06E
:100FF000623061F49FB7F8943881822F8095832303
:101000008883EC912E2B2C939FBF06C08FB7F8944A
:10101000E8812E2B28838FBFDF91CF9108953FB7B2
:10102000F8948091B4039091B503A091B603B09168
:10103000B70326B5A89B05C02F3F19F00196A11D47
:10104000B11D3FBFBA2FA92F982F8827820F911D5E
:10105000A11DB11DBC01CD0142E0660F771F881FA5
:10106000991F4A95D1F708951F920F920FB60F92CC
:1010700011242F933F938F939F93AF93BF938091AE
:10108000B8039091B903A091BA03B091BB0330911A
:10109000B30323E0230F2D3720F40196A11DB11DCA
:1010A00005C026E8230F0296A11DB11D2093B303AE
:1010B0008093B8039093B903A093BA03B093BB0392
:1010C0008091B4039091B503A091B603B091B7039A
:1010D0000196A11DB11D8093B4039093B503A09315
:1010E000B603B093B703BF91AF919F918F913F919A
:1010F0002F910F900FBE0F901F9018950F931F9375
:10110000CF93DF93EC0188819981009729F02A81A0
:101110003B812617370788F48B016F5F7F4F0E9452
:101120005611009761F0998388831B830A832C8171
:101130003D81232B11F4FC01108281E001C080E08D
:10114000DF91CF911F910F910895CF93DF93CDB78A
:10115000DEB728970FB6F894DEBF0FBECDBF7894E8
:1011600084B5826084BD84B5816084BD85B58260AC
:1011700085BD85B5816085BD80916E00816080935D
:101180006E001092810080918100826080938100C6
:1011900080918100816080938100809180008160D6
:1011A000809380008091B10084608093B100809131
:1011B000B00081608093B00080917A008460809359
:1011C0007A0080917A00826080937A0080917A0020
:1011D000816080937A0080917A00806880937A00A1
:1011E0001092C100E0917502F091760282E0808356
:1011F000E0917102F09172021082E0917302F0911D
:1012000074028FEC808310927D02E0917902F0915C
:101210007A0286E08083E0917702F0917802808103
:1012200080618083E0917702F0917802808188600C
:101230008083E0917702F0917802808180688083DA
:10124000E0917702F091780280818F7D808382E047
:1012500093E090935703809356030E94FC0282E030
:1012600093E00E94FC0260E080E00E946C0780E452
:1012700096E090935A03809359038091930391E0F1
:101280009093410280936302109242021092640292
:1012900060E082E093E00E94C70281E00E9436068F
:1012A00061E0809193030E94930682E093E00E94A4
:1012B0007B02182F682F6F76606180E00E946C07B8
:1012C00063E08EEF0E946C07612F80E00E946C0744
:1012D0000E940F084B015C0195E0C92ED12CE12C36
:1012E000F12C0E940F08DC01CB0188199909AA0989
:1012F000BB09883E9340A105B10558F021E0C21A10
:10130000D108E108F10888EE880E83E0981EA11C40
:10131000B11CC114D104E104F10419F7612F616A11
:1013200080E00E946C0716E001E080919303009337
:101330004102809363021092420210926402612F74
:1013400082E093E00E94C7020E9467070E9467073D
:101350000E9467070E94670781E00E9436061C5FB3
:10136000163419F70091540310915503F8012285A2
:101370003385AAE0B0E00E94C80E9B01AC01C12CED
:1013800087E8D82E83E9E82E83E0F82EC701B6015E
:101390000E94A60EF801208331834283538300917B
:1013A000520310915303F80122853385AAE0B0E07F
:1013B0000E94C80E9B01AC01C701B6010E94A60E97
:1013C000F801208331834283538380914F038C3013
:1013D00008F051C061E088E00E94D30780914F037C
:1013E000E82FF0E09F01220F331FE20FF31FE25FAF
:1013F000FC4F9081907C98609083109250031092E3
:1014000051036CE00E94EF0FFCE08F9FB0011124AC
:1014100040E050E09A01260F371FF901EE0FFF1F41
:101420002E0F3F1FF901E25FFC4F908196FD16C021
:101430004F5F5F4F4C30510569F781110FC010921B
:10144000800082E0809381001092850010928400D9
:10145000B19A80916F00826080936F00E0914F039A
:10146000F0E0CF01880F991FE80FF91FE25FFC4FF2
:1014700080818064808382E093E00E94FC0211E01E
:1014800010933303109234031092390310923A03ED
:1014900010923B0310923C0386E10E94DE0690937B
:1014A0003803809337038091350310934102809372
:1014B0006302109242021092640265E182E093E0BE
:1014C0000E94C70280E00E943606182F882379F018
:1014D0008CE391E00E94E305612F70E080E090E0F2
:1014E0004AE00E94F50588E491E00E94E30561E08E
:1014F000809135030E94930682E093E00E947B0274
:101500008093360310923D0310923E0310923F03E6
:101510001092400310924E0310924D038BEA9AEA08
:10152000AAEABEE38093490390934A03A0934B0336
:10153000B0934C0322242394312C02E010E084E980
:1015400093E00E943202892B09F448C01A82198262
:101550001C821B821E821D8260E070E0CE0101961B
:101560000E947E0829813A8181110DC02115310523
:1015700019F0C9010E94BE101A8219821E821D82B2
:101580001C821B8223C01E821D826AE471E0C90195
:101590000E942E121BC08F831886ED80FE802FEFD5
:1015A000E21AF20AB701CE0101960E947E08882352
:1015B00069F029813A818D819E81BE01695F7F4FEB
:1015C000820F931F0E942E12FE82ED820E9421073D
:1015D00097FFE1CF89819A810E94BE1085E692E053
:1015E0000E94E90080913403882341F08EEF0E942D
:1015F000DE066FEF7FE3681B790B04C08EEF0E945D
:10160000DE06BC0180E090E00E94500D609339033B
:1016100070933A0380933B0390933C0320E030E0C7
:1016200040E858E30E94B10D20E030E044EB53E481
:101630000E94B10D6B017C014B015C019B01AC016F
:101640000E94EA0F882319F08BE491E01AC026016A
:101650003701E89477F82FEF3FEF4FE75FE7C301DB
:10166000B2010E94EA0F81110FC02FEF3FEF4FE749
:101670005FE7C301B2010E944B0D18162CF48FE4F2
:1016800091E00E94E3058CC02FEF3FEF4FE75FE44E
:10169000C701B6010E94E50F18161CF483E591E01E
:1016A000F0CF2FEF3FEF4FE75FECC701B6010E948D
:1016B0004B0D87FDF3CF20E030E0A901C701B60153
:1016C0000E944B0D87FF11C0E0916502F091660208
:1016D0000190F081E02D6DE285E692E009954601EA
:1016E0005701B7FAB094B7F8B0949AE0F92E60E0D9
:1016F00070E080E09FE320E030E040E251E40E94AF
:10170000440FFA94F110F7CF9B01AC01C501B4016D
:101710000E94D80E6B017C010E94B60F4B015C0148
:101720000E94500D9B01AC01C701B6010E94D70E6B
:101730006B017C014AE0C501B4010E94F505E0910E
:101740006502F09166020190F081E02D6EE285E67F
:1017500092E009958BE0B82EBA94BB2009F120E005
:1017600030E040E251E4C701B6010E94B10D2B0107
:101770003C010E94B60F6B01E12CF12C4AE0C7013D
:10178000B6010E94F505C701B6010E94500D9B01EC
:10179000AC01C301B2010E94D70E6B017C01DCCF0A
:1017A00088E491E00E94E3058091F6019091F701B1
:1017B000009739F0019789F41093F7010093F6012F
:1017C0000CC087E591E00E94E30588E491E00E9467
:1017D000E3053092F7012092F6010E948901AFCE15
:1017E0008EE291E090939503809394038091AC01F5
:1017F0009091AD018459934071F4E091A703F09169
:10180000A80390818091A9038095892380831092F9
:10181000AD011092AC010895109268021092670217
:1018200088EE93E0A0E0B0E08093690290936A02B2
:10183000A0936B02B0936C022AE031E03093660211
:101840002093650225EC30E0309372022093710200
:1018500024EC30E0309374022093730220EC30E0EB
:10186000309376022093750221EC30E030937802B9
:101870002093770222EC30E030937A0220937902B1
:1018800026EC30E030937C0220937B0210927E02A3
:1018900010927F0210928002109281021092050332
:1018A000109204038093060390930703A093080308
:1018B000B09309032CE131E030930303209302033A
:1018C0001092970310929603809398039093990334
:1018D000A0939A03B0939B038EE291E090939503BB
:1018E000809394031092AB031092AA031092AD035D
:1018F0001092AC031092AF031092AE031092B1039A
:101900001092B0036091B2036E7F6D7F6093B2035B
:101910006695617081E0682784E00E94870761E036
:1019200084E00E94D307E2EBF0E0E491E093A403AB
:10193000EEE9F0E0E491F0E0EE0FFF1FEA57FF4F11
:10194000859194919093A6038093A50360E082E033
:101950000E94D3078091B20381FD04C061E082E060
:101960000E94870782E08093A003E0EBF0E0E4911F
:10197000E093A103ECE9F0E0E491F0E0EE0FFF1F4B
:10198000E057FF4F859194919093A3038093A20316
:10199000EDE5F3E01282118213821082DF011197CC
:1019A0001C9211971C92369683E0E537F80791F761
:1019B00086E593E010927F031092820310928F03CA
:1019C00021E6209358032093930321E02093920370
:1019D00028EC30E030938E0320938D039093910395
:1019E0008093900342E04093870347E040938A034B
:1019F00044E04093880343E04093890345E04093EB
:101A00008B0346E040938C0343E853E05093550327
:101A10004093540330937E0320937D03909381037E
:101A20008093800388E0809377038DE080937A032E
:101A30008AE08093780389E0809379038BE0809338
:101A40007B038CE080937C0383E793E090935303C4
:101A500080935203809132038C30A0F491E0980F70
:101A60009093320380934F0390E0FC01EE0FFF1F31
:101A70008E0F9F1FFC01E25FFC4F88EB9BE092837F
:101A8000818303C08FEF80934F0380E480933503FD
:101A90001092330308950E948D0D08F481E008959B
:101AA000E89409C097FB3EF49095809570956195F8
:101AB0007F4F8F4F9F4F9923A9F0F92F96E9BB27AE
:101AC0009395F695879577956795B795F111F8CF2A
:101AD000FAF4BB0F11F460FF1BC06F5F7F4F8F4F95
:101AE0009F4F16C0882311F096E911C0772321F08B
:101AF0009EE8872F762F05C0662371F096E8862F23
:101B000070E060E02AF09A95660F771F881FDAF779
:101B1000880F9695879597F90895990F0008550FA6
:101B2000AA0BE0E8FEEF16161706E807F907C0F063
:101B300012161306E407F50798F0621B730B840B6B
:101B4000950B39F40A2661F0232B242B252B21F445
:101B500008950A2609F4A140A6958FEF811D811DE5
:101B600008950E94C40D0C94350E0E94270E38F083
:101B70000E942E0E20F0952311F00C941E0E0C9452
:101B8000240E11240C94690E0E94460E70F3959F4A
:101B9000C1F3950F50E0551F629FF001729FBB2764
:101BA000F00DB11D639FAA27F00DB11DAA1F649F00
:101BB0006627B00DA11D661F829F2227B00DA11DB3
:101BC000621F739FB00DA11D621F839FA00D611D39
:101BD000221F749F3327A00D611D231F849F600D5A
:101BE000211D822F762F6A2F11249F5750409AF083
:101BF000F1F088234AF0EE0FFF1FBB1F661F771F0F
:101C0000881F91505040A9F79E3F510580F00C94D9
:101C10001E0E0C94690E5F3FE4F3983ED4F3869554
:101C200077956795B795F795E7959F5FC1F7FE2B79
:101C3000880F911D9695879597F9089597F99F6755
:101C400080E870E060E008959FEF80EC0895002444
:101C50000A941616170618060906089500240A9411
:101C600012161306140605060895092E0394000C97
:101C700011F4882352F0BB0F40F4BF2B11F460FF26
:101C800004C06F5F7F4F8F4F9F4F089557FD90584F
:101C9000440F551F59F05F3F71F04795880F97FB30
:101CA000991F61F09F3F79F08795089512161306EA
:101CB0001406551FF2CF4695F1DF08C01616170619
:101CC0001806991FF1CF869571056105089408954E
:101CD000E894BB2766277727CB0197F908952F92C1
:101CE0003F924F925F926F927F928F929F92AF92AC
:101CF000BF92CF92DF92EF92FF920F931F93CF93F9
:101D0000DF93CDB7DEB7CA1BDB0B0FB6F894DEBF8F
:101D10000FBECDBF09942A88398848885F846E84B5
:101D20007D848C849B84AA84B984C884DF80EE80FF
:101D3000FD800C811B81AA81B981CE0FD11D0FB608
:101D4000F894DEBF0FBECDBFED010895A1E21A2EBB
:101D5000AA1BBB1BFD010DC0AA1FBB1FEE1FFF1F4F
:101D6000A217B307E407F50720F0A21BB30BE40B9F
:101D7000F50B661F771F881F991F1A9469F76095E6
:101D80007095809590959B01AC01BD01CF010895A0
:101D9000A29FB001B39FC001A39F700D811D1124AC
:101DA000911DB29F700D811D1124911D08955058F1
:101DB000BB27AA270E94EF0E0C94350E0E94270E17
:101DC00038F00E942E0E20F039F49F3F19F426F4CB
:101DD0000C94240E0EF4E095E7FB0C941E0EE92FF4
:101DE0000E94460E58F3BA176207730784079507D7
:101DF00020F079F4A6F50C94680E0EF4E0950B2E05
:101E0000BA2FA02D0B01B90190010C01CA01A0014C
:101E10001124FF27591B99F0593F50F4503E68F1A7
:101E20001A16F040A22F232F342F4427585FF3CFE8
:101E3000469537952795A795F0405395C9F77EF4B9
:101E40001F16BA0B620B730B840BBAF09150A1F002
:101E5000FF0FBB1F661F771F881FC2F70EC0BA0F88
:101E6000621F731F841F48F4879577956795B79510
:101E7000F7959E3F08F0B0CF9395880F08F099270B
:101E8000EE0F9795879508950E94580F0C94350E84
:101E90000E942E0E58F00E94270E40F029F45F3F5A
:101EA00029F00C941E0E51110C94690E0C94240E02
:101EB0000E94460E68F39923B1F3552391F3951BC5
:101EC000550BBB27AA2762177307840738F09F5F5B
:101ED0005F4F220F331F441FAA1FA9F335D00E2EC8
:101EE0003AF0E0E832D091505040E695001CCAF735
:101EF0002BD0FE2F29D0660F771F881FBB1F2617F8
:101F000037074807AB07B0E809F0BB0B802DBF01CE
:101F1000FF2793585F4F3AF09E3F510578F00C949D
:101F20001E0E0C94690E5F3FE4F3983ED4F3869541
:101F300077956795B795F7959F5FC9F7880F911DBE
:101F40009695879597F90895E1E0660F771F881FAA
:101F5000BB1F621773078407BA0720F0621B730B5D
:101F6000840BBA0BEE1F88F7E09508950E944E0E81
:101F700088F09F5798F0B92F9927B751B0F0E1F04A
:101F8000660F771F881F991F1AF0BA95C9F714C0FA
:101F9000B13091F00E94680EB1E008950C94680E83
:101FA000672F782F8827B85F39F0B93FCCF3869533
:101FB00077956795B395D9F73EF490958095709590
:101FC00061957F4F8F4F9F4F08950E948D0D08F4AC
:101FD0008FEF08950E948D0D880B990B0895991B22
:101FE00079E004C0991F961708F0961B881F7A9510
:101FF000C9F78095089597FB072E16F4009407D033
:1020000077FD09D00E940F1007FC05D03EF4909593
:1020100081959F4F0895709561957F4F0895AA1BF4
:10202000BB1B51E107C0AA1FBB1FA617B70710F0C3
:10203000A61BB70B881F991F5A95A9F780959095F5
:10204000BC01CD010895EE0FFF1F0590F491E02D26
:102050000994CF93DF938230910510F482E090E0F1
:10206000E091BE03F091BF0320E030E0C0E0D0E09B
:10207000309711F14081518148175907C0F0481736
:10208000590761F482819381209719F09B838A8399
:102090002BC09093BF038093BE0326C0211531054A
:1020A00019F04217530718F49A01BE01DF01EF013E
:1020B0000280F381E02DDCCF2115310509F1281BC9
:1020C000390B2430310590F412968D919C91139721
:1020D0006115710521F0FB019383828304C0909305
:1020E000BF038093BE03FD01329644C0FD01E20FA1
:1020F000F31F81939193225031092D933C933AC061
:102100002091BC033091BD03232B41F420910201A7
:10211000309103013093BD032093BC032091000153
:10212000309101012115310541F42DB73EB74091A1
:10213000040150910501241B350BE091BC03F09183
:10214000BD03E217F307A0F42E1B3F0B2817390736
:1021500078F0AC014E5F5F4F2417350748F04E0F03
:102160005F1F5093BD034093BC038193919302C0C2
:10217000E0E0F0E0CF01DF91CF9108950F931F933E
:10218000CF93DF93009709F48CC0FC013297138240
:1021900012820091BE031091BF030115110581F455
:1021A00020813181820F931F2091BC033091BD03A8
:1021B0002817390779F5F093BD03E093BC0371C08C
:1021C000D80140E050E0AE17BF0750F412962D91B1
:1021D0003C911397AD012115310509F1D901F3CFD8
:1021E0009D01DA013383228360817181860F971FFD
:1021F0008217930769F4EC0128813981260F371F74
:102200002E5F3F4F318320838A819B81938382831A
:10221000452B29F4F093BF03E093BE0342C013960D
:10222000FC93EE931297ED01499159919E01240F71
:10223000351FE217F30771F480819181840F951F98
:10224000029611969C938E938281938113969C9310
:102250008E931297E0E0F0E0D80112968D919C9158
:102260001397009719F0F8018C01F6CF8D919C918E
:1022700098012E5F3F4F820F931F2091BC03309136
:10228000BD032817390769F4309729F41092BF036A
:102290001092BE0302C0138212821093BD030093FA
:1022A000BC03DF91CF911F910F910895A0E0B0E0A2
:1022B000ECE5F1E10C94730EEC01009721F4CB01F5
:1022C0000E942910B8C0FC01E60FF71F9C012250A4
:1022D0003109E217F30708F4ACC0D9010D911C9144
:1022E000119706171707B0F00530110508F49FC0C5
:1022F000C80104978617970708F499C0025011097E
:10230000061B170B019311936D937C93CF010E94D1
:10231000BE108DC05B01A01AB10A4C01800E911E47
:10232000A091BE03B091BF0340E050E0E12CF12C3E
:10233000109709F44AC0A815B905D1F56D907C90A5
:102340001197630182E0C80ED11CCA14DB0480F12E
:10235000A3014A195B096A0182E0C80ED11C1296DA
:10236000BC9012971396AC91B5E0CB16D10440F017
:10237000B282A38351834083D9016D937C930AC0B9
:102380000E5F1F4FC301800F911FF901918380835E
:10239000EB2DFA2FE114F10431F0D7011396FC93E1
:1023A000EE93129744C0F093BF03E093BE033FC087
:1023B0008D919C9111974817590708F4AC017D0144
:1023C00012960D90BC91A02DB3CF8091BC0390913B
:1023D000BD0388159905E1F446175707C8F48091A5
:1023E000000190910101009741F48DB79EB7409193
:1023F000040150910501841B950BE817F907C8F4F7
:10240000F093BD03E093BC03F901718360830FC0B7
:10241000CB010E9429107C01009759F0A801BE0150
:102420000E942512CE010E94BE10C70104C0CE0139
:1024300002C080E090E0CDB7DEB7EEE00C948F0EE6
:1024400081E090E0F8940C943512FB01DC0102C0AD
:1024500001900D9241505040D8F70895FB01DC01E6
:1024600001900D920020E1F7089510E0C2E6D0E05F
:1024700004C0FE010E9423102196C336D107C9F77C
:04248000F894FFCFFE
:102484000000C00380000000000020018D00B8009F
:102494006701E900C700DB0000000000C7029702E3
:1024A400F7026B028F027B026C0200000000DE0167
:1024B4008D00F702DD0132024A02C5014932432090
:1024C4006572726F723A20000D0A006E616E0069C7
:1024D4006E66006F76660073746174652073776945
:0A24E40074636820302D3E310000C3
:00000001FF