New repo for firmware files

Signed-off-by: Pierros Papadeas <pierros@papadeas.gr>
merge-requests/3/head
Pierros Papadeas 2017-07-28 20:29:04 +03:00
commit 74069d8ade
44 changed files with 8688 additions and 0 deletions

662
LICENSE 100644
View File

@ -0,0 +1,662 @@
GNU AFFERO GENERAL PUBLIC LICENSE
Version 3, 19 November 2007
Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
Preamble
The GNU Affero General Public License is a free, copyleft license for
software and other kinds of works, specifically designed to ensure
cooperation with the community in the case of network server software.
The licenses for most software and other practical works are designed
to take away your freedom to share and change the works. By contrast,
our General Public Licenses are intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users.
When we speak of free software, we are referring to freedom, 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
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.
Developers that use our General Public Licenses protect your rights
with two steps: (1) assert copyright on the software, and (2) offer
you this License which gives you legal permission to copy, distribute
and/or modify the software.
A secondary benefit of defending all users' freedom is that
improvements made in alternate versions of the program, if they
receive widespread use, become available for other developers to
incorporate. Many developers of free software are heartened and
encouraged by the resulting cooperation. However, in the case of
software used on network servers, this result may fail to come about.
The GNU General Public License permits making a modified version and
letting the public access it on a server without ever releasing its
source code to the public.
The GNU Affero General Public License is designed specifically to
ensure that, in such cases, the modified source code becomes available
to the community. It requires the operator of a network server to
provide the source code of the modified version running there to the
users of that server. Therefore, public use of a modified version, on
a publicly accessible server, gives the public access to the source
code of the modified version.
An older license, called the Affero General Public License and
published by Affero, was designed to accomplish similar goals. This is
a different license, not a version of the Affero GPL, but Affero has
released a new version of the Affero GPL which permits relicensing under
this license.
The precise terms and conditions for copying, distribution and
modification follow.
TERMS AND CONDITIONS
0. Definitions.
"This License" refers to version 3 of the GNU Affero General Public License.
"Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.
"The Program" refers to any copyrightable work licensed under this
License. Each licensee is addressed as "you". "Licensees" and
"recipients" may be individuals or organizations.
To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy. The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.
A "covered work" means either the unmodified Program or a work based
on the Program.
To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy. Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.
To "convey" a work means any kind of propagation that enables other
parties to make or receive copies. Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.
An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License. If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.
1. Source Code.
The "source code" for a work means the preferred form of the work
for making modifications to it. "Object code" means any non-source
form of a work.
A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.
The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form. A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.
The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities. However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work. For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.
The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.
The Corresponding Source for a work in source code form is that
same work.
2. Basic Permissions.
All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met. This License explicitly affirms your unlimited
permission to run the unmodified Program. The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work. This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.
You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force. You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright. Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.
Conveying under any other circumstances is permitted solely under
the conditions stated below. Sublicensing is not allowed; section 10
makes it unnecessary.
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.
When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.
4. Conveying Verbatim Copies.
You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.
You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.
5. Conveying Modified Source Versions.
You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:
a) The work must carry prominent notices stating that you modified
it, and giving a relevant date.
b) The work must carry prominent notices stating that it is
released under this License and any conditions added under section
7. This requirement modifies the requirement in section 4 to
"keep intact all notices".
c) You must license the entire work, as a whole, under this
License to anyone who comes into possession of a copy. This
License will therefore apply, along with any applicable section 7
additional terms, to the whole of the work, and all its parts,
regardless of how they are packaged. This License gives no
permission to license the work in any other way, but it does not
invalidate such permission if you have separately received it.
d) If the work has interactive user interfaces, each must display
Appropriate Legal Notices; however, if the Program has interactive
interfaces that do not display Appropriate Legal Notices, your
work need not make them do so.
A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit. Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.
6. Conveying Non-Source Forms.
You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:
a) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by the
Corresponding Source fixed on a durable physical medium
customarily used for software interchange.
b) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by a
written offer, valid for at least three years and valid for as
long as you offer spare parts or customer support for that product
model, to give anyone who possesses the object code either (1) a
copy of the Corresponding Source for all the software in the
product that is covered by this License, on a durable physical
medium customarily used for software interchange, for a price no
more than your reasonable cost of physically performing this
conveying of source, or (2) access to copy the
Corresponding Source from a network server at no charge.
c) Convey individual copies of the object code with a copy of the
written offer to provide the Corresponding Source. This
alternative is allowed only occasionally and noncommercially, and
only if you received the object code with such an offer, in accord
with subsection 6b.
d) Convey the object code by offering access from a designated
place (gratis or for a charge), and offer equivalent access to the
Corresponding Source in the same way through the same place at no
further charge. You need not require recipients to copy the
Corresponding Source along with the object code. If the place to
copy the object code is a network server, the Corresponding Source
may be on a different server (operated by you or a third party)
that supports equivalent copying facilities, provided you maintain
clear directions next to the object code saying where to find the
Corresponding Source. Regardless of what server hosts the
Corresponding Source, you remain obligated to ensure that it is
available for as long as needed to satisfy these requirements.
e) Convey the object code using peer-to-peer transmission, provided
you inform other peers where the object code and Corresponding
Source of the work are being offered to the general public at no
charge under subsection 6d.
A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.
A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling. In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage. For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product. A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.
"Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source. The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.
If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information. But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).
The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed. Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.
Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.
7. Additional Terms.
"Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law. If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.
When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it. (Additional permissions may be written to require their own
removal in certain cases when you modify the work.) You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.
Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:
a) Disclaiming warranty or limiting liability differently from the
terms of sections 15 and 16 of this License; or
b) Requiring preservation of specified reasonable legal notices or
author attributions in that material or in the Appropriate Legal
Notices displayed by works containing it; or
c) Prohibiting misrepresentation of the origin of that material, or
requiring that modified versions of such material be marked in
reasonable ways as different from the original version; or
d) Limiting the use for publicity purposes of names of licensors or
authors of the material; or
e) Declining to grant rights under trademark law for use of some
trade names, trademarks, or service marks; or
f) Requiring indemnification of licensors and authors of that
material by anyone who conveys the material (or modified versions of
it) with contractual assumptions of liability to the recipient, for
any liability that these contractual assumptions directly impose on
those licensors and authors.
All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10. If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term. If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.
If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.
Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.
8. Termination.
You may not propagate or modify a covered work except as expressly
provided under this License. Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).
However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.
Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.
Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License. If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.
9. Acceptance Not Required for Having Copies.
You are not required to accept this License in order to receive or
run a copy of the Program. Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance. However,
nothing other than this License grants you permission to propagate or
modify any covered work. These actions infringe copyright if you do
not accept this License. Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.
10. Automatic Licensing of Downstream Recipients.
Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License. You are not responsible
for enforcing compliance by third parties with this License.
An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations. If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.
You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License. For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.
11. Patents.
A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based. The
work thus licensed is called the contributor's "contributor version".
A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version. For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.
Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.
In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement). To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.
If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients. "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.
If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.
A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License. You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.
Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.
12. No Surrender of Others' Freedom.
If 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 convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all. For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.
13. Remote Network Interaction; Use with the GNU General Public License.
Notwithstanding any other provision of this License, if you modify the
Program, your modified version must prominently offer all users
interacting with it remotely through a computer network (if your version
supports such interaction) an opportunity to receive the Corresponding
Source of your version by providing access to the Corresponding Source
from a network server at no charge, through some standard or customary
means of facilitating copying of software. This Corresponding Source
shall include the Corresponding Source for any work covered by version 3
of the GNU General Public License that is incorporated pursuant to the
following paragraph.
Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU General Public License into a single
combined work, and to convey the resulting work. The terms of this
License will continue to apply to the part which is the covered work,
but the work with which it is combined will remain governed by version
3 of the GNU General Public License.
14. Revised Versions of this License.
The Free Software Foundation may publish revised and/or new versions of
the GNU Affero 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
Program specifies that a certain numbered version of the GNU Affero General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation. If the Program does not specify a version number of the
GNU Affero General Public License, you may choose any version ever published
by the Free Software Foundation.
If the Program specifies that a proxy can decide which future
versions of the GNU Affero General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.
Later license versions may give you additional or different
permissions. However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.
15. Disclaimer of Warranty.
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "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 PROGRAM
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
16. Limitation of Liability.
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM 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 PROGRAM (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 PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.
17. Interpretation of Sections 15 and 16.
If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.
END OF TERMS AND CONDITIONS
How to Apply These Terms to Your New Programs
If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.
To do so, attach the following notices to the program. It is safest
to attach them to the start of each source file to most effectively
state the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.
<one line to give the program's name and a brief idea of what it does.>
Copyright (C) <year> <name of author>
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU Affero General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program 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 Affero General Public License for more details.
You should have received a copy of the GNU Affero General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
Also add information on how to contact you by electronic and paper mail.
If your software can interact with users remotely through a computer
network, you should also make sure that it provides a way for users to
get its source. For example, if your program is a web application, its
interface could display a "Source" link that leads users to an archive
of the code. There are many ways you could offer source, and different
solutions will be better for different programs; see section 13 for the
specific requirements.
You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU AGPL, see
<http://www.gnu.org/licenses/>.

18
README.md 100644
View File

@ -0,0 +1,18 @@
# SatNOGS Rotator Firmware
Firmware [SatNOGS Rotator Controller](https://github.com/satnogs/satnogs-rotator-controller/).
Repository includes all source files for the SatNOGS rotator controller Firmware.
Electronics can be found on [satnogs-rotator-controller](https://github.com/satnogs/satnogs-rotator-controller).
## Instructions
In order to use this code, you need to put the AccelStepper v1.46 library and SoftI2CMaster library in your libraries folder. Thanks to [AccelStepper library](http://www.airspayce.com/mikem/arduino/AccelStepper/) and [SoftI2CMaster](https://github.com/todbot/SoftI2CMaster).
You need to choose the version of the Firmware you will be utilizing based on your controller and rotator setup. Namely we have two different versions (one for DC motors and one for Stepper motors). DC version is on beta state.
## License
&copy; 2014-2017 [Libre Space Foundation](http://libre.space).
Licensed under the [GPLv3](LICENSE).

View File

@ -0,0 +1,568 @@
#include "SoftI2CMaster.h"
#include <Wire.h>
//#include <avr/wdt.h>
/* H-bridge defines */
#define PWM1M1 5
#define PWM2M1 6
#define PWM1M2 9
#define PWM2M2 10
/* Limits for control signal */
#define outMax 120
#define outMin 35
#define Deadband 1
/* Encoder defines */
#define sda_pin 16
#define scl_pin 14
#define as5601_adr 0x36
#define raw_ang_high 0x0c
#define raw_ang_low 0x0d
#define status_reg 0x0b
/* Ratio of worm gear */
#define RATIO 30
/* Maximum Angle for homing scanning */
#define SEEK_MOVE 30
#define MIN_AZ_ANGLE 0
#define MAX_AZ_ANGLE 370
#define MIN_EL_ANGLE 0
#define MAX_EL_ANGLE 110
/* Homing switch */
#define HOME_AZ 4
#define HOME_EL 7
/* Change to LOW according to Home sensor */
#define DEFAULT_HOME_STATE 1
/* Time to disable the motors in millisecond */
#define T_DELAY 1000
/* PIN for Enable or Disable Stepper Motors */
#define EN 8
/* Serial configuration */
#define BufferSize 256
#define BaudRate 19200
#define TX_EN A3
/*Global Variables*/
unsigned long t_DIS = 0; /*time to disable the Motors*/
/* angle offset */
double az_angle_offset = 0;
double el_angle_offset = 0;
/* Encoder */
SoftI2CMaster i2c_soft = SoftI2CMaster(scl_pin, sda_pin, 1);
void setup()
{
/* H-bridge */
pinMode(OUTPUT, PWM1M1);
pinMode(OUTPUT, PWM2M1);
pinMode(OUTPUT, PWM1M2);
pinMode(OUTPUT, PWM2M2);
/* Encoder */
i2c_soft.begin();
Wire.begin();
/* Enable Motors */
pinMode(EN, OUTPUT);
digitalWrite(EN, HIGH);
/* Homing switch */
pinMode(HOME_AZ, INPUT_PULLUP);
pinMode(HOME_EL, INPUT_PULLUP);
/* Serial Communication */
Serial.begin(BaudRate);
/* RS485 */
//Serial1.begin(BaudRate);
pinMode(TX_EN, OUTPUT);
digitalWrite(TX_EN, LOW);
/* WDT */
//cli();
//WDTCSR |= (1<<WDCE) | (1<<WDE);
//WDTCSR = (0<<WDIE) | (1<<WDE) | (0<<WDP3) | (1<<WDP2) | (1<<WDP1) | (0<<WDP0);
//sei();
/* Initial Homing */
//Homing(-MAX_AZ_ANGLE, -MAX_EL_ANGLE, true);
}
void loop()
{
double *set_point;
double curr_pos[2];
/* Read commands from serial */
set_point = cmd_proc();
//set_point = cmd_proc_RS485();
/* Move Motor */
dc_move(set_point);
/* Reset WDT */
//wdt_reset();
/* Time Check */
if (t_DIS == 0)
t_DIS = millis();
/* Disable Motors */
get_position(curr_pos);
if (abs(curr_pos[0]-set_point[0]) < Deadband && abs(curr_pos[1]-set_point[1]) < Deadband && millis()-t_DIS > T_DELAY)
digitalWrite(EN, LOW);
/* Enable Motors */
else
digitalWrite(EN, HIGH);
}
///* EasyComm 2 Protocol for RS485 */
//double * cmd_proc_RS485()
//{
// static double set_point[] = {0, 0};
// /* Serial */
// static char buffer[BufferSize];
// char incomingByte;
// char *Data = buffer;
// char *rawData;
// static int BufferCnt = 0;
// char data[100];
// double pos[2];
//
// /* Read from serial */
// while (Serial1.available() > 0)
// {
// incomingByte = Serial1.read();
// /* New data */
// if (incomingByte == '\n')
// {
// buffer[BufferCnt] = 0;
// if (buffer[0] == 'A' && buffer[1] == 'Z')
// {
// if (buffer[2] == ' ' && buffer[3] == 'E' && buffer[4] == 'L')
// {
// get_position(pos);
// /* Get position */
// digitalWrite(TX_EN, HIGH);
// delay(8);
// Serial1.print("AZ");
// Serial1.print(pos[0], 1);
// Serial1.print(" ");
// Serial1.print("EL");
// Serial1.println(pos[1], 1);
// delay(8);
// digitalWrite(TX_EN, LOW);
// }
// else
// {
// /* Get the absolute value of angle */
// rawData = strtok_r(Data, " " , &Data);
// strncpy(data, rawData + 2, 10);
// if (isNumber(data))
// {
// set_point[0] = atof(data);
// if (set_point[0] > MAX_AZ_ANGLE)
// set_point[0] = MAX_AZ_ANGLE;
// else if (set_point[0] < MIN_AZ_ANGLE)
// set_point[0] = MIN_AZ_ANGLE;
// }
// /* Get the absolute value of angle */
// rawData = strtok_r(Data, " " , &Data);
// if (rawData[0] == 'E' && rawData[1] == 'L')
// {
// strncpy(data, rawData + 2, 10);
// if (isNumber(data))
// {
// set_point[1] = atof(data);
// if (set_point[1] > MAX_EL_ANGLE)
// set_point[1] = MAX_EL_ANGLE;
// else if (set_point[1] < MIN_EL_ANGLE)
// set_point[1] = MIN_EL_ANGLE;
// }
// }
// }
// }
// /* Stop Moving */
// else if (buffer[0] == 'S' && buffer[1] == 'A' && buffer[2] == ' ' && buffer[3] == 'S' && buffer[4] == 'E')
// {
// get_position(pos);
// /* Get position */
// digitalWrite(TX_EN, HIGH);
// delay(8);
// Serial1.print("AZ");
// Serial1.print(pos[0], 1);
// Serial1.print(" ");
// Serial1.print("EL");
// Serial1.println(pos[1], 1);
// delay(8);
// digitalWrite(TX_EN, LOW);
// set_point[0] = pos[0];
// set_point[1] = pos[1];
// }
// /* Reset the rotator */
// else if (buffer[0] == 'R' && buffer[1] == 'E' && buffer[2] == 'S' && buffer[3] == 'E' && buffer[4] == 'T')
// {
// get_position(pos);
// /* Get position */
// digitalWrite(TX_EN, HIGH);
// delay(8);
// Serial1.print("AZ");
// Serial1.print(pos[0], 1);
// Serial1.print(" ");
// Serial1.print("EL");
// Serial1.println(pos[1], 1);
// delay(8);
// digitalWrite(TX_EN, LOW);
// /* Move to initial position */
// Homing(-MAX_AZ_ANGLE, -MAX_EL_ANGLE, false);
// set_point[0] = 0;
// set_point[1] = 0;
// }
// /* Clear serial buffer */
// BufferCnt = 0;
// Serial1.read();
// /* Reset the disable motor time */
// t_DIS = 0;
// }
// /* Fill the buffer with incoming data */
// else {
// buffer[BufferCnt] = incomingByte;
// BufferCnt++;
// }
// }
// return set_point;
//}
/* Homing Function */
void Homing(double AZangle, double ELangle, bool Init)
{
int value_Home_AZ = DEFAULT_HOME_STATE;
int value_Home_EL = DEFAULT_HOME_STATE;
boolean isHome_AZ = false;
boolean isHome_EL = false;
double zero_angle[2];
double curr_angle[2];
double set_point[2];
get_position(zero_angle);
if (Init == true)
{
set_point[0] = zero_angle[0]+SEEK_MOVE;
set_point[1] = zero_angle[1]+SEEK_MOVE;
}
else
{
set_point[0] = 10;//zero_angle[0]-MAX_AZ_ANGLE;
set_point[1] = 10;//zero_angle[1]-MAX_EL_ANGLE;
}
while (isHome_AZ == false || isHome_EL == false)
{
dc_move(set_point);
delay(1);
value_Home_AZ = digitalRead(HOME_AZ);
delay(1);
value_Home_EL = digitalRead(HOME_EL);
/* Change to LOW according to Home sensor */
if (value_Home_AZ == DEFAULT_HOME_STATE && isHome_AZ == false)
{
isHome_AZ = true;
get_position(curr_angle);
set_point[0] = 0;
if (Init)
az_angle_offset = curr_angle[0];
}
if (value_Home_EL == DEFAULT_HOME_STATE && isHome_EL == false)
{
isHome_EL = true;
get_position(curr_angle);
set_point[1] = 0;
if (Init)
el_angle_offset = curr_angle[1];
}
get_position(curr_angle);
if (abs(curr_angle[0] - zero_angle[0]) >= SEEK_MOVE && !isHome_AZ && Init)
set_point[0] = -MAX_AZ_ANGLE;
if (abs(curr_angle[1] - zero_angle[1]) >= SEEK_MOVE && !isHome_EL && Init)
set_point[1] = -MAX_EL_ANGLE;
if ((abs(curr_angle[0] - zero_angle[0]) >= MAX_AZ_ANGLE && !isHome_AZ) || (abs(curr_angle[1] - zero_angle[1]) >= MAX_EL_ANGLE && !isHome_EL))
{
/* set error */
while(1)
{
;
}
}
}
}
void dc_move(double set_point[])
{
double u[2];
double curr_pos[2];
static double prev_pos[] = {0, 0};
double error[2];
double Iterm[2];
double Pterm[2];
double Dterm[2];
double Kp = 200;
double Ki = 2;
double Kd = 0;
double dt = 0.001; // calculate
get_position(curr_pos);
error[0] = set_point[0] - curr_pos[0];
error[1] = set_point[1] - curr_pos[1];
Pterm[0] = Kp * error[0];
Pterm[1] = Kp * error[1];
Iterm[0] += Ki * error[0] * dt;
Iterm[1] += Ki * error[1] * dt;
if (Iterm[0] > outMax) Iterm[0] = outMax;
else if (Iterm[0] < outMin) Iterm[0] = outMin;
if (Iterm[1] > outMax) Iterm[1] = outMax;
else if (Iterm[1] < outMin) Iterm[1] = outMin;
Dterm[0] = Kd * (curr_pos[0] - prev_pos[0]) / dt;
prev_pos[0] = curr_pos[0];
Dterm[1] = Kd * (curr_pos[1] - prev_pos[1]) / dt;
prev_pos[1] = curr_pos[1];
u[0] = Pterm[0] + Iterm[0] + Dterm[0];
u[1] = Pterm[1] + Iterm[1] + Dterm[1];
if (u[0] >= 0)
{
if (u[0] > outMax)
u[0] = outMax;
analogWrite(PWM1M1, u[0]);
analogWrite(PWM2M1, 0);
}
else
{
u[0] = -u[0];
if ( u[0] > outMax)
u[0] = outMax;
analogWrite(PWM1M1, 0);
analogWrite(PWM2M1, u[0]);
}
if (u[1] >= 0)
{
if (u[1] > outMax)
u[1] = outMax;
analogWrite(PWM1M2, u[1]);
analogWrite(PWM2M2, 0);
}
else
{
u[1] = -u[1];
if ( u[1] > outMax)
u[1] = outMax;
analogWrite(PWM1M2, 0);
analogWrite(PWM2M2, u[1]);
}
}
/* Read Encoders */
void get_position(double *new_pos)
{
int low_raw, high_raw, status_val;
double raw_pos = 0;
double delta_raw_pos = 0;
static double raw_prev_pos[] = {0, 0};
static double real_pos[] = {0, 0};
static int n[] = {0, 0};
/* Axis 1*/
/* Read Raw Angle Low Byte */
Wire.beginTransmission(as5601_adr);
Wire.write(raw_ang_low);
Wire.endTransmission();
Wire.requestFrom(as5601_adr, 1);
while(Wire.available() == 0);
low_raw = Wire.read();
/* Read Raw Angle High Byte */
Wire.beginTransmission(as5601_adr);
Wire.write(raw_ang_high);
Wire.endTransmission();
Wire.requestFrom(as5601_adr, 1);
while(Wire.available() == 0);
high_raw = Wire.read();
high_raw = high_raw << 8;
high_raw = high_raw | low_raw;
/* Read Status Bits */
Wire.beginTransmission(as5601_adr);
Wire.write(status_reg);
Wire.endTransmission();
Wire.requestFrom(as5601_adr, 1);
while(Wire.available() == 0);
status_val = Wire.read();
/* Check the status register */
if ((status_val & 0x20) && !(status_val & 0x10) && !(status_val & 0x08))
{
if (high_raw >= 0)
{
raw_pos = (double)high_raw*0.0879;
delta_raw_pos = raw_prev_pos[0] - raw_pos;
if (delta_raw_pos > 180)
n[0]++;
else if (delta_raw_pos < -180)
n[0]--;
real_pos[0] = ((raw_pos + 360 * n[0]) / RATIO) - az_angle_offset;
raw_prev_pos[0] = raw_pos;
}
else
; /* set error */
}
else
; /* set error */
/* Axis 2 */
/* Read Raw Angle Low Byte */
i2c_soft.beginTransmission(as5601_adr);
i2c_soft.write(raw_ang_low);
i2c_soft.endTransmission();
i2c_soft.requestFrom(as5601_adr);
low_raw = i2c_soft.readLast();
i2c_soft.endTransmission();
/* Read Raw Angle High Byte */
i2c_soft.beginTransmission(as5601_adr);
i2c_soft.write(raw_ang_high);
i2c_soft.endTransmission();
i2c_soft.requestFrom(as5601_adr);
high_raw = i2c_soft.readLast();
i2c_soft.endTransmission();
high_raw = high_raw << 8;
high_raw = high_raw | low_raw;
/* Read Status Bits */
i2c_soft.beginTransmission(as5601_adr);
i2c_soft.write(status_reg);
i2c_soft.endTransmission();
i2c_soft.requestFrom(as5601_adr);
status_val = i2c_soft.readLast();
i2c_soft.endTransmission();
/* Check the status register */
if ((status_val & 0x20) && !(status_val & 0x10) && !(status_val & 0x08))
{
if (high_raw >= 0)
{
raw_pos = (double)high_raw*0.0879;
delta_raw_pos = raw_prev_pos[1] - raw_pos;
if (delta_raw_pos > 180)
n[1]++;
else if (delta_raw_pos < -180)
n[1]--;
real_pos[1] = ((raw_pos + 360 * n[1]) / RATIO) - el_angle_offset;
raw_prev_pos[1] = raw_pos;
}
else
; /* set error */
}
else
; /* set error */
new_pos[0] = real_pos[0];
new_pos[1] = real_pos[1];
}
/* EasyComm 2 Protocol */
double * cmd_proc()
{
static double set_point[] = {0, 0};
/* Serial */
char buffer[BufferSize];
char incomingByte;
char *Data = buffer;
char *rawData;
static int BufferCnt = 0;
char data[100];
double pos[2];
/* Read from serial */
while (Serial.available() > 0)
{
incomingByte = Serial.read();
/* New data */
if (incomingByte == '\n')
{
buffer[BufferCnt] = 0;
if (buffer[0] == 'A' && buffer[1] == 'Z')
{
if (buffer[2] == ' ' && buffer[3] == 'E' && buffer[4] == 'L')
{
get_position(pos);
/* Get position */
Serial.print("AZ");
Serial.print(pos[0], 1);
Serial.print(" ");
Serial.print("EL");
Serial.println(pos[1], 1);
}
else
{
/* Get the absolute value of angle */
rawData = strtok_r(Data, " " , &Data);
strncpy(data, rawData + 2, 10);
if (isNumber(data))
{
set_point[0] = atof(data);
if (set_point[0] > MAX_AZ_ANGLE)
set_point[0] = MAX_AZ_ANGLE;
else if (set_point[0] < MIN_AZ_ANGLE)
set_point[0] = MIN_AZ_ANGLE;
}
/* Get the absolute value of angle */
rawData = strtok_r(Data, " " , &Data);
if (rawData[0] == 'E' && rawData[1] == 'L')
{
strncpy(data, rawData + 2, 10);
if (isNumber(data))
{
set_point[1] = atof(data);
if (set_point[1] > MAX_EL_ANGLE)
set_point[1] = MAX_EL_ANGLE;
else if (set_point[1] < MIN_EL_ANGLE)
set_point[1] = MIN_EL_ANGLE;
}
}
}
}
/* Stop Moving */
else if (buffer[0] == 'S' && buffer[1] == 'A' && buffer[2] == ' ' && buffer[3] == 'S' && buffer[4] == 'E')
{
get_position(pos);
/* Get position */
Serial.print("AZ");
Serial.print(pos[0], 1);
Serial.print(" ");
Serial.print("EL");
Serial.println(pos[1], 1);
set_point[0] = pos[0];
set_point[1] = pos[1];
}
/* Reset the rotator */
else if (buffer[0] == 'R' && buffer[1] == 'E' && buffer[2] == 'S' && buffer[3] == 'E' && buffer[4] == 'T')
{
get_position(pos);
/* Get position */
Serial.print("AZ");
Serial.print(pos[0], 1);
Serial.print(" ");
Serial.print("EL");
Serial.println(pos[1], 1);
/* Move to initial position */
Homing(-MAX_AZ_ANGLE, -MAX_EL_ANGLE, false);
set_point[0] = 0;
set_point[1] = 0;
}
BufferCnt = 0;
/* Reset the disable motor time */
t_DIS = 0;
}
/* Fill the buffer with incoming data */
else {
buffer[BufferCnt] = incomingByte;
BufferCnt++;
}
}
return set_point;
}
/* check if is argument in number */
boolean isNumber(char *input)
{
for (int i = 0; input[i] != '\0'; i++)
{
if (isalpha(input[i]))
return false;
}
return true;
}

View File

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

View File

@ -0,0 +1,666 @@
// AccelStepper.h
//
/// \mainpage AccelStepper library for Arduino
///
/// This is the Arduino AccelStepper library.
/// It provides an object-oriented interface for 2, 3 or 4 pin stepper motors.
///
/// The standard Arduino IDE includes the Stepper library
/// (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is
/// perfectly adequate for simple, single motor applications.
///
/// AccelStepper significantly improves on the standard Arduino Stepper library in several ways:
/// \li Supports acceleration and deceleration
/// \li Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper
/// \li API functions never delay() or block
/// \li Supports 2, 3 and 4 wire steppers, plus 3 and 4 wire half steppers.
/// \li Supports alternate stepping functions to enable support of AFMotor (https://github.com/adafruit/Adafruit-Motor-Shield-library)
/// \li Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip)
/// \li Very slow speeds are supported
/// \li Extensive API
/// \li Subclass support
///
/// The latest version of this documentation can be downloaded from
/// http://www.airspayce.com/mikem/arduino/AccelStepper
/// The version of the package that this documentation refers to can be downloaded
/// from http://www.airspayce.com/mikem/arduino/AccelStepper/AccelStepper-1.47.zip
///
/// Example Arduino programs are included to show the main modes of use.
///
/// You can also find online help and discussion at http://groups.google.com/group/accelstepper
/// Please use that group for all questions and discussions on this topic.
/// Do not contact the author directly, unless it is to discuss commercial licensing.
/// Before asking a question or reporting a bug, please read http://www.catb.org/esr/faqs/smart-questions.html
///
/// Tested on Arduino Diecimila and Mega with arduino-0018 & arduino-0021
/// on OpenSuSE 11.1 and avr-libc-1.6.1-1.15,
/// cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5.
/// Tested on Teensy http://www.pjrc.com/teensy including Teensy 3.1 built using Arduino IDE 1.0.5 with
/// teensyduino addon 1.18 and later.
///
/// \par Installation
///
/// Install in the usual way: unzip the distribution zip file to the libraries
/// sub-folder of your sketchbook.
///
/// \par Theory
///
/// This code uses speed calculations as described in
/// "Generate stepper-motor speed profiles in real time" by David Austin
/// http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf
/// 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 Donations
///
/// This library is offered under a free GPL license for those who want to use it that way.
/// We try hard to keep it up to date, fix bugs
/// and to provide free support. If this library has helped you save time or money, please consider donating at
/// http://www.airspayce.com or here:
///
/// \htmlonly <form action="https://www.paypal.com/cgi-bin/webscr" method="post"><input type="hidden" name="cmd" value="_donations" /> <input type="hidden" name="business" value="mikem@airspayce.com" /> <input type="hidden" name="lc" value="AU" /> <input type="hidden" name="item_name" value="Airspayce" /> <input type="hidden" name="item_number" value="AccelStepper" /> <input type="hidden" name="currency_code" value="USD" /> <input type="hidden" name="bn" value="PP-DonationsBF:btn_donateCC_LG.gif:NonHosted" /> <input type="image" alt="PayPal — The safer, easier way to pay online." name="submit" src="https://www.paypalobjects.com/en_AU/i/btn/btn_donateCC_LG.gif" /> <img alt="" src="https://www.paypalobjects.com/en_AU/i/scr/pixel.gif" width="1" height="1" border="0" /></form> \endhtmlonly
///
/// \par Trademarks
///
/// AccelStepper is a trademark of AirSpayce Pty Ltd. The AccelStepper mark was first used on April 26 2010 for
/// international trade, and is used only in relation to motor control hardware and software.
/// It is not to be confused with any other similar marks covering other goods and services.
///
/// \par Copyright
///
/// This software is Copyright (C) 2010 Mike McCauley. Use is subject to license
/// conditions. The main licensing options available are GPL V2 or Commercial:
///
/// \par Open Source Licensing GPL V2
/// This is the appropriate option if you want to share the source code of your
/// application with everyone you distribute it to, and you also want to give them
/// the right to share who uses it. If you wish to use this software under Open
/// Source Licensing, you must contribute all your source code to the open source
/// community in accordance with the GPL Version 2 when your application is
/// distributed. See http://www.gnu.org/copyleft/gpl.html
///
/// \par Commercial Licensing
/// This is the appropriate option if you are creating proprietary applications
/// and you are not prepared to distribute and share the source code of your
/// application. Contact info@airspayce.com for details.
///
/// \par Revision History
/// \version 1.0 Initial release
///
/// \version 1.1 Added speed() function to get the current speed.
/// \version 1.2 Added runSpeedToPosition() submitted by Gunnar Arndt.
/// \version 1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1
/// \version 1.4 Added functional contructor to support AFMotor, contributed by Limor, with example sketches.
/// \version 1.5 Improvements contributed by Peter Mousley: Use of microsecond steps and other speed improvements
/// to increase max stepping speed to about 4kHz. New option for user to set the min allowed pulse width.
/// Added checks for already running at max speed and skip further calcs if so.
/// \version 1.6 Fixed a problem with wrapping of microsecond stepping that could cause stepping to hang.
/// Reported by Sandy Noble.
/// Removed redundant _lastRunTime member.
/// \version 1.7 Fixed a bug where setCurrentPosition() did not always work as expected.
/// Reported by Peter Linhart.
/// \version 1.8 Added support for 4 pin half-steppers, requested by Harvey Moon
/// \version 1.9 setCurrentPosition() now also sets motor speed to 0.
/// \version 1.10 Builds on Arduino 1.0
/// \version 1.11 Improvments from Michael Ellison:
/// Added optional enable line support for stepper drivers
/// Added inversion for step/direction/enable lines for stepper drivers
/// \version 1.12 Announce Google Group
/// \version 1.13 Improvements to speed calculation. Cost of calculation is now less in the worst case,
/// and more or less constant in all cases. This should result in slightly beter high speed performance, and
/// reduce anomalous speed glitches when other steppers are accelerating.
/// However, its hard to see how to replace the sqrt() required at the very first step from 0 speed.
/// \version 1.14 Fixed a problem with compiling under arduino 0021 reported by EmbeddedMan
/// \version 1.15 Fixed a problem with runSpeedToPosition which did not correctly handle
/// running backwards to a smaller target position. Added examples
/// \version 1.16 Fixed some cases in the code where abs() was used instead of fabs().
/// \version 1.17 Added example ProportionalControl
/// \version 1.18 Fixed a problem: If one calls the funcion runSpeed() when Speed is zero, it makes steps
/// without counting. reported by Friedrich, Klappenbach.
/// \version 1.19 Added MotorInterfaceType and symbolic names for the number of pins to use
/// for the motor interface. Updated examples to suit.
/// Replaced individual pin assignment variables _pin1, _pin2 etc with array _pin[4].
/// _pins member changed to _interface.
/// Added _pinInverted array to simplify pin inversion operations.
/// Added new function setOutputPins() which sets the motor output pins.
/// It can be overridden in order to provide, say, serial output instead of parallel output
/// Some refactoring and code size reduction.
/// \version 1.20 Improved documentation and examples to show need for correctly
/// specifying AccelStepper::FULL4WIRE and friends.
/// \version 1.21 Fixed a problem where desiredSpeed could compute the wrong step acceleration
/// when _speed was small but non-zero. Reported by Brian Schmalz.
/// Precompute sqrt_twoa to improve performance and max possible stepping speed
/// \version 1.22 Added Bounce.pde example
/// Fixed a problem where calling moveTo(), setMaxSpeed(), setAcceleration() more
/// frequently than the step time, even
/// with the same values, would interfere with speed calcs. Now a new speed is computed
/// only if there was a change in the set value. Reported by Brian Schmalz.
/// \version 1.23 Rewrite of the speed algorithms in line with
/// http://fab.cba.mit.edu/classes/MIT/961.09/projects/i0/Stepper_Motor_Speed_Profile.pdf
/// Now expect smoother and more linear accelerations and decelerations. The desiredSpeed()
/// function was removed.
/// \version 1.24 Fixed a problem introduced in 1.23: with runToPosition, which did never returned
/// \version 1.25 Now ignore attempts to set acceleration to 0.0
/// \version 1.26 Fixed a problem where certina combinations of speed and accelration could cause
/// oscillation about the target position.
/// \version 1.27 Added stop() function to stop as fast as possible with current acceleration parameters.
/// Also added new Quickstop example showing its use.
/// \version 1.28 Fixed another problem where certain combinations of speed and accelration could cause
/// oscillation about the target position.
/// Added support for 3 wire full and half steppers such as Hard Disk Drive spindle.
/// Contributed by Yuri Ivatchkovitch.
/// \version 1.29 Fixed a problem that could cause a DRIVER stepper to continually step
/// with some sketches. Reported by Vadim.
/// \version 1.30 Fixed a problem that could cause stepper to back up a few steps at the end of
/// accelerated travel with certain speeds. Reported and patched by jolo.
/// \version 1.31 Updated author and distribution location details to airspayce.com
/// \version 1.32 Fixed a problem with enableOutputs() and setEnablePin on Arduino Due that
/// prevented the enable pin changing stae correctly. Reported by Duane Bishop.
/// \version 1.33 Fixed an error in example AFMotor_ConstantSpeed.pde did not setMaxSpeed();
/// Fixed a problem that caused incorrect pin sequencing of FULL3WIRE and HALF3WIRE.
/// Unfortunately this meant changing the signature for all step*() functions.
/// Added example MotorShield, showing how to use AdaFruit Motor Shield to control
/// a 3 phase motor such as a HDD spindle motor (and without using the AFMotor library.
/// \version 1.34 Added setPinsInverted(bool pin1Invert, bool pin2Invert, bool pin3Invert, bool pin4Invert, bool enableInvert)
/// to allow inversion of 2, 3 and 4 wire stepper pins. Requested by Oleg.
/// \version 1.35 Removed default args from setPinsInverted(bool, bool, bool, bool, bool) to prevent ambiguity with
/// setPinsInverted(bool, bool, bool). Reported by Mac Mac.
/// \version 1.36 Changed enableOutputs() and disableOutputs() to be virtual so can be overridden.
/// Added new optional argument 'enable' to constructor, which allows you toi disable the
/// automatic enabling of outputs at construction time. Suggested by Guido.
/// \version 1.37 Fixed a problem with step1 that could cause a rogue step in the
/// wrong direction (or not,
/// depending on the setup-time requirements of the connected hardware).
/// Reported by Mark Tillotson.
/// \version 1.38 run() function incorrectly always returned true. Updated function and doc so it returns true
/// if the motor is still running to the target position.
/// \version 1.39 Updated typos in keywords.txt, courtesey Jon Magill.
/// \version 1.40 Updated documentation, including testing on Teensy 3.1
/// \version 1.41 Fixed an error in the acceleration calculations, resulting in acceleration of haldf the intended value
/// \version 1.42 Improved support for FULL3WIRE and HALF3WIRE output pins. These changes were in Yuri's original
/// contribution but did not make it into production.<br>
/// \version 1.43 Added DualMotorShield example. Shows how to use AccelStepper to control 2 x 2 phase steppers using the
/// Itead Studio Arduino Dual Stepper Motor Driver Shield model IM120417015.<br>
/// \version 1.44 examples/DualMotorShield/DualMotorShield.ino examples/DualMotorShield/DualMotorShield.pde
/// was missing from the distribution.<br>
/// \version 1.45 Fixed a problem where if setAcceleration was not called, there was no default
/// acceleration. Reported by Michael Newman.<br>
/// \version 1.45 Fixed inaccuracy in acceleration rate by using Equation 15, suggested by Sebastian Gracki.<br>
/// Performance improvements in runSpeed suggested by Jaakko Fagerlund.<br>
/// \version 1.46 Fixed error in documentation for runToPosition().
/// Reinstated time calculations in runSpeed() since new version is reported
/// not to work correctly under some circumstances. Reported by Oleg V Gavva.<br>
///
/// \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.21 2014/10/31 06:05:30 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.
class AccelStepper
{
public:
/// \brief Symbolic names for number of pins.
/// Use this in the pins argument the AccelStepper constructor to
/// provide a symbolic name for the number of pins
/// to use.
typedef enum
{
FUNCTION = 0, ///< Use the functional interface, implementing your own driver functions (internal use only)
DRIVER = 1, ///< Stepper Driver, 2 driver pins required
FULL2WIRE = 2, ///< 2 wire stepper, 2 motor pins required
FULL3WIRE = 3, ///< 3 wire stepper, such as HDD spindle, 3 motor pins required
FULL4WIRE = 4, ///< 4 wire full stepper, 4 motor pins required
HALF3WIRE = 6, ///< 3 wire half stepper, such as HDD spindle, 3 motor pins required
HALF4WIRE = 8 ///< 4 wire half stepper, 4 motor pins required
} MotorInterfaceType;
/// Constructor. You can have multiple simultaneous steppers, all moving
/// at different speeds and accelerations, provided you call their run()
/// functions at frequent enough intervals. Current Position is set to 0, target
/// position is set to 0. MaxSpeed and Acceleration default to 1.0.
/// The motor pins will be initialised to OUTPUT mode during the
/// constructor by a call to enableOutputs().
/// \param[in] interface Number of pins to interface to. 1, 2, 4 or 8 are
/// supported, but it is preferred to use the \ref MotorInterfaceType symbolic names.
/// AccelStepper::DRIVER (1) means a stepper driver (with Step and Direction pins).
/// If an enable line is also needed, call setEnablePin() after construction.
/// You may also invert the pins using setPinsInverted().
/// AccelStepper::FULL2WIRE (2) means a 2 wire stepper (2 pins required).
/// AccelStepper::FULL3WIRE (3) means a 3 wire stepper, such as HDD spindle (3 pins required).
/// AccelStepper::FULL4WIRE (4) means a 4 wire stepper (4 pins required).
/// AccelStepper::HALF3WIRE (6) means a 3 wire half stepper, such as HDD spindle (3 pins required)
/// AccelStepper::HALF4WIRE (8) means a 4 wire half stepper (4 pins required)
/// Defaults to AccelStepper::FULL4WIRE (4) pins.
/// \param[in] pin1 Arduino digital pin number for motor pin 1. Defaults
/// to pin 2. For a AccelStepper::DRIVER (interface==1),
/// this is the Step input to the driver. Low to high transition means to step)
/// \param[in] pin2 Arduino digital pin number for motor pin 2. Defaults
/// to pin 3. For a AccelStepper::DRIVER (interface==1),
/// this is the Direction input the driver. High means forward.
/// \param[in] pin3 Arduino digital pin number for motor pin 3. Defaults
/// to pin 4.
/// \param[in] pin4 Arduino digital pin number for motor pin 4. Defaults
/// to pin 5.
/// \param[in] enable If this is true (the default), enableOutputs() will be called to enable
/// the output pins at construction time.
AccelStepper(uint8_t interface = AccelStepper::FULL4WIRE, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5, bool enable = true);
/// Alternate Constructor which will call your own functions for forward and backward steps.
/// You can have multiple simultaneous steppers, all moving
/// at different speeds and accelerations, provided you call their run()
/// functions at frequent enough intervals. Current Position is set to 0, target
/// position is set to 0. MaxSpeed and Acceleration default to 1.0.
/// Any motor initialization should happen before hand, no pins are used or initialized.
/// \param[in] forward void-returning procedure that will make a forward step
/// \param[in] backward void-returning procedure that will make a backward step
AccelStepper(void (*forward)(), void (*backward)());
/// Set the target position. The run() function will try to move the motor (at most one step per call)
/// from the current position to the target position set by the most
/// recent call to this function. Caution: moveTo() also recalculates the speed for the next step.
/// If you are trying to use constant speed movements, you should call setSpeed() after calling moveTo().
/// \param[in] absolute The desired absolute position. Negative is
/// anticlockwise from the 0 position.
void moveTo(long absolute);
/// Set the target position relative to the current position
/// \param[in] relative The desired position relative to the current position. Negative is
/// anticlockwise from the current position.
void move(long relative);
/// Poll the motor and step it if a step is due, implementing
/// accelerations and decelerations to acheive the target position. You must call this as
/// frequently as possible, but at least once per minimum step time interval,
/// preferably in your main loop. Note that each call to run() will make at most one step, and then only when a step is due,
/// based on the current speed and the time since the last step.
/// \return true if the motor is still running to the target position.
boolean run();
/// Poll the motor and step it if a step is due, implementing a constant
/// speed as set by the most recent call to setSpeed(). You must call this as
/// frequently as possible, but at least once per step interval,
/// \return true if the motor was stepped.
boolean runSpeed();
/// Sets the maximum permitted speed. The run() function will accelerate
/// up to the speed set by this function.
/// Caution: the maximum speed achievable depends on your processor and clock speed.
/// \param[in] speed The desired maximum speed in steps per second. Must
/// be > 0. Caution: Speeds that exceed the maximum speed supported by the processor may
/// Result in non-linear accelerations and decelerations.
void setMaxSpeed(float speed);
/// 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.
virtual void disableOutputs();
/// Enable motor pin outputs by setting the motor pins to OUTPUT
/// mode. Called automatically by the constructor.
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);
protected:
/// \brief Direction indicator
/// Symbolic names for the direction the motor is turning
typedef enum
{
DIRECTION_CCW = 0, ///< Clockwise
DIRECTION_CW = 1 ///< Counter-Clockwise
} Direction;
/// Forces the library to compute a new instantaneous speed and set that as
/// the current speed. It is called by
/// the library:
/// \li after each step
/// \li after change to maxSpeed through setMaxSpeed()
/// \li after change to acceleration through setAcceleration()
/// \li after change to target position (relative or absolute) through
/// move() or moveTo()
void computeNewSpeed();
/// Low level function to set the motor output pins
/// bit 0 of the mask corresponds to _pin[0]
/// bit 1 of the mask corresponds to _pin[1]
/// You can override this to impment, for example serial chip output insted of using the
/// output pins directly
virtual void setOutputPins(uint8_t mask);
/// Called to execute a step. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default calls step1(), step2(), step4() or step8() depending on the
/// number of pins defined for the stepper.
/// \param[in] step The current step phase number (0 to 7)
virtual void step(long step);
/// Called to execute a step using stepper functions (pins = 0) Only called when a new step is
/// required. Calls _forward() or _backward() to perform the step
/// \param[in] step The current step phase number (0 to 7)
virtual void step0(long step);
/// Called to execute a step on a stepper driver (ie where pins == 1). Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of Step pin1 to step,
/// and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond
/// which is the minimum STEP pulse width for the 3967 driver.
/// \param[in] step The current step phase number (0 to 7)
virtual void step1(long step);
/// Called to execute a step on a 2 pin motor. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1 and pin2
/// \param[in] step The current step phase number (0 to 7)
virtual void step2(long step);
/// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1, pin2,
/// pin3
/// \param[in] step The current step phase number (0 to 7)
virtual void step3(long step);
/// Called to execute a step on a 4 pin motor. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1, pin2,
/// pin3, pin4.
/// \param[in] step The current step phase number (0 to 7)
virtual void step4(long step);
/// Called to execute a step on a 3 pin motor, such as HDD spindle. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1, pin2,
/// pin3
/// \param[in] step The current step phase number (0 to 7)
virtual void step6(long step);
/// Called to execute a step on a 4 pin half-steper motor. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1, pin2,
/// pin3, pin4.
/// \param[in] step The current step phase number (0 to 7)
virtual void step8(long step);
private:
/// Number of pins on the stepper motor. Permits 2 or 4. 2 pins is a
/// bipolar, and 4 pins is a unipolar.
uint8_t _interface; // 0, 1, 2, 4, 8, See MotorInterfaceType
/// Arduino pin number assignments for the 2 or 4 pins required to interface to the
/// stepper motor or driver
uint8_t _pin[4];
/// Whether the _pins is inverted or not
uint8_t _pinInverted[4];
/// The current absolution position in steps.
long _currentPos; // Steps
/// The target position in steps. The AccelStepper library will move the
/// motor from the _currentPos to the _targetPos, taking into account the
/// max speed, acceleration and deceleration
long _targetPos; // Steps
/// The current motos speed in steps per second
/// Positive is clockwise
float _speed; // Steps per second
/// The maximum permitted speed in steps per second. Must be > 0.
float _maxSpeed;
/// The acceleration to use to accelerate or decelerate the motor in steps
/// per second per second. Must be > 0
float _acceleration;
float _sqrt_twoa; // Precomputed sqrt(2*_acceleration)
/// The current interval between steps in microseconds.
/// 0 means the motor is currently stopped with _speed == 0
unsigned long _stepInterval;
/// The last step time in microseconds
unsigned long _lastStepTime;
/// The minimum allowed pulse width in microseconds
unsigned int _minPulseWidth;
/// Is the direction pin inverted?
///bool _dirInverted; /// Moved to _pinInverted[1]
/// Is the step pin inverted?
///bool _stepInverted; /// Moved to _pinInverted[0]
/// Is the enable pin inverted?
bool _enableInverted;
/// Enable pin for stepper driver, or 0xFF if unused.
uint8_t _enablePin;
/// The pointer to a forward-step procedure
void (*_forward)();
/// The pointer to a backward-step procedure
void (*_backward)();
/// The step counter for speed calculations
long _n;
/// Initial step size in microseconds
float _c0;
/// Last step size in microseconds
float _cn;
/// Min step size in microseconds based on maxSpeed
float _cmin; // at max speed
/// Current direction motor is spinning in
boolean _direction; // 1 == CW
};
/// @example Random.pde
/// Make a single stepper perform random changes in speed, position and acceleration
/// @example Overshoot.pde
/// Check overshoot handling
/// which sets a new target position and then waits until the stepper has
/// achieved it. This is used for testing the handling of overshoots
/// @example MultiStepper.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,35 @@
AccelStepper/Makefile
AccelStepper/AccelStepper.h
AccelStepper/AccelStepper.cpp
AccelStepper/MANIFEST
AccelStepper/LICENSE
AccelStepper/project.cfg
AccelStepper/keywords.txt
AccelStepper/doc
AccelStepper/examples/Blocking/Blocking.pde
AccelStepper/examples/MultiStepper/MultiStepper.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/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.4 2013/03/21 21:48:27 mikem Exp mikem $
PROJNAME = AccelStepper
VERSION_MAJOR = 1
VERSION_MINOR = 47
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,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,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.5"/>
<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 style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.5 -->
<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"><img src="ftv2lastnode.png" alt="\" width="16" height="22" /><img src="ftv2cl.png" alt="C" width="24" height="22" /><a class="el" href="classAccelStepper.html" target="_self">AccelStepper</a></td><td class="desc">Support for stepper motors with acceleration etc </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.5
</small></address>
</body>
</html>

View File

@ -0,0 +1,105 @@
<!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.5"/>
<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 style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.5 -->
<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#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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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><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 class="even"><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.5
</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,61 @@
<!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.5"/>
<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 style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.5 -->
<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"><img src="ftv2lastnode.png" alt="\" width="16" height="22" /><a href="AccelStepper_8h_source.html"><img src="ftv2doc.png" alt="*" width="24" height="22" /></a><b>AccelStepper.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.5
</small></address>
</body>
</html>

View File

@ -0,0 +1,244 @@
<!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.5"/>
<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 style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.5 -->
<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_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_f"><span>f</span></a></li>
<li><a href="#index_h"><span>h</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><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"></a>- a -</h3><ul>
<li>AccelStepper()
: <a class="el" href="classAccelStepper.html#a3bc75bd6571b98a6177838ca81ac39ab">AccelStepper</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_m"></a>- m -</h3><ul>
<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>
</li>
</ul>
<h3><a class="anchor" id="index_r"></a>- r -</h3><ul>
<li>run()
: <a class="el" href="classAccelStepper.html#a608b2395b64ac15451d16d0371fe13ce">AccelStepper</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>
</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.5
</small></address>
</body>
</html>

View File

@ -0,0 +1,201 @@
<!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.5"/>
<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 style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.5 -->
<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_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_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><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>
</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_m"></a>- m -</h3><ul>
<li>move()
: <a class="el" href="classAccelStepper.html#a68942c66e78fb7f7b5f0cdade6eb7f06">AccelStepper</a>
</li>
<li>moveTo()
: <a class="el" href="classAccelStepper.html#ace236ede35f87c63d18da25810ec9736">AccelStepper</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>
</li>
<li>runSpeed()
: <a class="el" href="classAccelStepper.html#aa4a6bdf99f698284faaeb5542b0b7514">AccelStepper</a>
</li>
<li>runSpeedToPosition()
: <a class="el" href="classAccelStepper.html#a9270d20336e76ac1fd5bcd5b9c34f301">AccelStepper</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.5
</small></address>
</body>
</html>

View File

@ -0,0 +1,184 @@
<!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.5"/>
<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 style="padding-left: 0.5em;">
<div id="projectname">AccelStepper
</div>
</td>
</tr>
</tbody>
</table>
</div>
<!-- end header part -->
<!-- Generated by Doxygen 1.8.5 -->
<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.</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.47.zip">http://www.airspayce.com/mikem/arduino/AccelStepper/AccelStepper-1.47.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 <a href="http://www.catb.org/esr/faqs/smart-questions.html">http://www.catb.org/esr/faqs/smart-questions.html</a></p>
<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> 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>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>
<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> <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="http://www.gnu.org/copyleft/gpl.html">http://www.gnu.org/copyleft/gpl.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. Contact <a href="#" onclick="location.href='mai'+'lto:'+'inf'+'o@'+'air'+'sp'+'ayc'+'e.'+'com'; return false;">info@<span style="display: none;">.nosp@m.</span>airs<span style="display: none;">.nosp@m.</span>payce<span style="display: none;">.nosp@m.</span>.com</a> for details.</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></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.5
</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,36 @@
// 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)
#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,54 @@
// 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)
#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,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,40 @@
#######################################
# Syntax Coloring Map For AccelStepper
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
AccelStepper 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
#######################################
# Constants (LITERAL1)
#######################################

View File

@ -0,0 +1,290 @@
# Doxyfile 1.8.2
#---------------------------------------------------------------------------
# Project related configuration options
#---------------------------------------------------------------------------
DOXYFILE_ENCODING = UTF-8
PROJECT_NAME = AccelStepper
PROJECT_NUMBER =
PROJECT_BRIEF =
PROJECT_LOGO =
OUTPUT_DIRECTORY =
CREATE_SUBDIRS = NO
OUTPUT_LANGUAGE = English
BRIEF_MEMBER_DESC = YES
REPEAT_BRIEF = YES
ABBREVIATE_BRIEF =
ALWAYS_DETAILED_SEC = NO
INLINE_INHERITED_MEMB = NO
FULL_PATH_NAMES = YES
STRIP_FROM_PATH =
STRIP_FROM_INC_PATH =
SHORT_NAMES = NO
JAVADOC_AUTOBRIEF = NO
QT_AUTOBRIEF = NO
MULTILINE_CPP_IS_BRIEF = NO
INHERIT_DOCS = YES
SEPARATE_MEMBER_PAGES = NO
TAB_SIZE = 8
ALIASES =
TCL_SUBST =
OPTIMIZE_OUTPUT_FOR_C = NO
OPTIMIZE_OUTPUT_JAVA = NO
OPTIMIZE_FOR_FORTRAN = NO
OPTIMIZE_OUTPUT_VHDL = NO
EXTENSION_MAPPING =
MARKDOWN_SUPPORT = YES
AUTOLINK_SUPPORT = YES
BUILTIN_STL_SUPPORT = NO
CPP_CLI_SUPPORT = NO
SIP_SUPPORT = NO
IDL_PROPERTY_SUPPORT = YES
DISTRIBUTE_GROUP_DOC = NO
SUBGROUPING = YES
INLINE_GROUPED_CLASSES = NO
INLINE_SIMPLE_STRUCTS = NO
TYPEDEF_HIDES_STRUCT = NO
SYMBOL_CACHE_SIZE = 0
LOOKUP_CACHE_SIZE = 0
#---------------------------------------------------------------------------
# Build related configuration options
#---------------------------------------------------------------------------
EXTRACT_ALL = NO
EXTRACT_PRIVATE = NO
EXTRACT_PACKAGE = NO
EXTRACT_STATIC = NO
EXTRACT_LOCAL_CLASSES = YES
EXTRACT_LOCAL_METHODS = NO
EXTRACT_ANON_NSPACES = NO
HIDE_UNDOC_MEMBERS = NO
HIDE_UNDOC_CLASSES = NO
HIDE_FRIEND_COMPOUNDS = NO
HIDE_IN_BODY_DOCS = NO
INTERNAL_DOCS = NO
CASE_SENSE_NAMES = YES
HIDE_SCOPE_NAMES = NO
SHOW_INCLUDE_FILES = YES
FORCE_LOCAL_INCLUDES = NO
INLINE_INFO = YES
SORT_MEMBER_DOCS = YES
SORT_BRIEF_DOCS = NO
SORT_MEMBERS_CTORS_1ST = NO
SORT_GROUP_NAMES = NO
SORT_BY_SCOPE_NAME = NO
STRICT_PROTO_MATCHING = NO
GENERATE_TODOLIST = YES
GENERATE_TESTLIST = YES
GENERATE_BUGLIST = YES
GENERATE_DEPRECATEDLIST= YES
ENABLED_SECTIONS =
MAX_INITIALIZER_LINES = 30
SHOW_USED_FILES = YES
SHOW_FILES = YES
SHOW_NAMESPACES = YES
FILE_VERSION_FILTER =
LAYOUT_FILE =
CITE_BIB_FILES =
#---------------------------------------------------------------------------
# configuration options related to warning and progress messages
#---------------------------------------------------------------------------
QUIET = NO
WARNINGS = YES
WARN_IF_UNDOCUMENTED = YES
WARN_IF_DOC_ERROR = YES
WARN_NO_PARAMDOC = NO
WARN_FORMAT = "$file:$line: $text"
WARN_LOGFILE =
#---------------------------------------------------------------------------
# configuration options related to the input files
#---------------------------------------------------------------------------
INPUT =
INPUT_ENCODING = UTF-8
FILE_PATTERNS =
RECURSIVE = NO
EXCLUDE =
EXCLUDE_SYMLINKS = NO
EXCLUDE_PATTERNS =
EXCLUDE_SYMBOLS =
EXAMPLE_PATH = examples
EXAMPLE_PATTERNS =
EXAMPLE_RECURSIVE = YES
IMAGE_PATH =
INPUT_FILTER =
FILTER_PATTERNS =
FILTER_SOURCE_FILES = NO
FILTER_SOURCE_PATTERNS =
#---------------------------------------------------------------------------
# configuration options related to source browsing
#---------------------------------------------------------------------------
SOURCE_BROWSER = NO
INLINE_SOURCES = NO
STRIP_CODE_COMMENTS = NO
REFERENCED_BY_RELATION = YES
REFERENCES_RELATION = YES
REFERENCES_LINK_SOURCE = YES
USE_HTAGS = NO
VERBATIM_HEADERS = YES
#---------------------------------------------------------------------------
# configuration options related to the alphabetical class index
#---------------------------------------------------------------------------
ALPHABETICAL_INDEX = NO
COLS_IN_ALPHA_INDEX = 5
IGNORE_PREFIX =
#---------------------------------------------------------------------------
# configuration options related to the HTML output
#---------------------------------------------------------------------------
GENERATE_HTML = YES
HTML_OUTPUT = doc
HTML_FILE_EXTENSION = .html
HTML_HEADER =
HTML_FOOTER =
HTML_STYLESHEET =
HTML_EXTRA_STYLESHEET =
HTML_EXTRA_FILES =
HTML_COLORSTYLE_HUE = 220
HTML_COLORSTYLE_SAT = 100
HTML_COLORSTYLE_GAMMA = 80
HTML_TIMESTAMP = NO
HTML_DYNAMIC_SECTIONS = NO
HTML_INDEX_NUM_ENTRIES = 100
GENERATE_DOCSET = NO
DOCSET_FEEDNAME = "Doxygen generated docs"
DOCSET_BUNDLE_ID = org.doxygen.Project
DOCSET_PUBLISHER_ID = org.doxygen.Publisher
DOCSET_PUBLISHER_NAME = Publisher
GENERATE_HTMLHELP = NO
CHM_FILE =
HHC_LOCATION =
GENERATE_CHI = NO
CHM_INDEX_ENCODING =
BINARY_TOC = NO
TOC_EXPAND = NO
GENERATE_QHP = NO
QCH_FILE =
QHP_NAMESPACE = org.doxygen.Project
QHP_VIRTUAL_FOLDER = doc
QHP_CUST_FILTER_NAME =
QHP_CUST_FILTER_ATTRS =
QHP_SECT_FILTER_ATTRS =
QHG_LOCATION =
GENERATE_ECLIPSEHELP = NO
ECLIPSE_DOC_ID = org.doxygen.Project
DISABLE_INDEX = NO
GENERATE_TREEVIEW = NO
ENUM_VALUES_PER_LINE = 4
TREEVIEW_WIDTH = 250
EXT_LINKS_IN_WINDOW = NO
FORMULA_FONTSIZE = 10
FORMULA_TRANSPARENT = YES
USE_MATHJAX = NO
MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest
MATHJAX_EXTENSIONS =
SEARCHENGINE = NO
SERVER_BASED_SEARCH = NO
#---------------------------------------------------------------------------
# configuration options related to the LaTeX output
#---------------------------------------------------------------------------
GENERATE_LATEX = NO
LATEX_OUTPUT = latex
LATEX_CMD_NAME = latex
MAKEINDEX_CMD_NAME = makeindex
COMPACT_LATEX = NO
PAPER_TYPE = a4wide
EXTRA_PACKAGES =
LATEX_HEADER =
LATEX_FOOTER =
PDF_HYPERLINKS = NO
USE_PDFLATEX = NO
LATEX_BATCHMODE = NO
LATEX_HIDE_INDICES = NO
LATEX_SOURCE_CODE = NO
LATEX_BIB_STYLE = plain
#---------------------------------------------------------------------------
# configuration options related to the RTF output
#---------------------------------------------------------------------------
GENERATE_RTF = NO
RTF_OUTPUT = rtf
COMPACT_RTF = NO
RTF_HYPERLINKS = NO
RTF_STYLESHEET_FILE =
RTF_EXTENSIONS_FILE =
#---------------------------------------------------------------------------
# configuration options related to the man page output
#---------------------------------------------------------------------------
GENERATE_MAN = NO
MAN_OUTPUT = man
MAN_EXTENSION = .3
MAN_LINKS = NO
#---------------------------------------------------------------------------
# configuration options related to the XML output
#---------------------------------------------------------------------------
GENERATE_XML = NO
XML_OUTPUT = xml
XML_SCHEMA =
XML_DTD =
XML_PROGRAMLISTING = YES
#---------------------------------------------------------------------------
# configuration options for the AutoGen Definitions output
#---------------------------------------------------------------------------
GENERATE_AUTOGEN_DEF = NO
#---------------------------------------------------------------------------
# configuration options related to the Perl module output
#---------------------------------------------------------------------------
GENERATE_PERLMOD = NO
PERLMOD_LATEX = NO
PERLMOD_PRETTY = YES
PERLMOD_MAKEVAR_PREFIX =
#---------------------------------------------------------------------------
# Configuration options related to the preprocessor
#---------------------------------------------------------------------------
ENABLE_PREPROCESSING = YES
MACRO_EXPANSION = NO
EXPAND_ONLY_PREDEF = NO
SEARCH_INCLUDES = YES
INCLUDE_PATH =
INCLUDE_FILE_PATTERNS =
PREDEFINED =
EXPAND_AS_DEFINED =
SKIP_FUNCTION_MACROS = YES
#---------------------------------------------------------------------------
# Configuration::additions related to external references
#---------------------------------------------------------------------------
TAGFILES =
GENERATE_TAGFILE =
ALLEXTERNALS = NO
EXTERNAL_GROUPS = YES
PERL_PATH = /usr/bin/perl
#---------------------------------------------------------------------------
# Configuration options related to the dot tool
#---------------------------------------------------------------------------
CLASS_DIAGRAMS = YES
MSCGEN_PATH =
HIDE_UNDOC_RELATIONS = YES
HAVE_DOT = NO
DOT_NUM_THREADS = 0
DOT_FONTNAME = Helvetica
DOT_FONTSIZE = 10
DOT_FONTPATH =
CLASS_GRAPH = YES
COLLABORATION_GRAPH = YES
GROUP_GRAPHS = YES
UML_LOOK = NO
UML_LIMIT_NUM_FIELDS = 10
TEMPLATE_RELATIONS = NO
INCLUDE_GRAPH = YES
INCLUDED_BY_GRAPH = YES
CALL_GRAPH = NO
CALLER_GRAPH = NO
GRAPHICAL_HIERARCHY = YES
DIRECTORY_GRAPH = YES
DOT_IMAGE_FORMAT = png
INTERACTIVE_SVG = NO
DOT_PATH =
DOTFILE_DIRS =
MSCFILE_DIRS =
DOT_GRAPH_MAX_NODES = 50
MAX_DOT_GRAPH_DEPTH = 0
DOT_TRANSPARENT = NO
DOT_MULTI_TARGETS = NO
GENERATE_LEGEND = YES
DOT_CLEANUP = YES

View File

@ -0,0 +1,33 @@
Copyright (c) Tod E. Kurt, 2010-2015
---
LICENSE:
Creative Commons - Attribution - ShareAlike 3.0
http://creativecommons.org/licenses/by-sa/3.0/
See why we chose this license: http://www.inmojo.com/licenses/
This work is licensed under the Creative Commons Attribution-ShareAlike 3.0 Unported License. To view a copy of this license, visit http://creativecommons.org/licenses/by-sa/3.0/ or send a letter to Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA.
This is a human-readable summary of the full license.
You are free:
- to Share - to copy, distribute and transmit the work, and
- to Remix - to adapt the work
Under the following conditions:
- Attribution - You must attribute the work in the manner specified by the author or licensor (but not in any way that suggests that they endorse you or your use of the work.)
- Share Alike - If you alter, transform, or build upon this work, you may distribute the resulting work only under the same, similar or a compatible license.
With the understanding that:
- Waiver - Any of the above conditions can be waived if you get permission from the copyright holder.
- Other Rights - In no way are any of the following rights affected by the license:
-- your fair dealing or fair use rights;
-- the author's moral rights; and
-- rights other persons may have either in the work itself or in how the work is used, such as publicity or privacy rights.
Notice - For any reuse or distribution, you must make clear to others the license terms of this work. The best way to do that is with a link to
http://creativecommons.org/licenses/by-sa/3.0/

View File

@ -0,0 +1,16 @@
SoftI2CMaster
2010-2012, Tod E. Kurt, http://todbot.com/blog/
2014, by Testato: update library and examples for follow Wires API of Arduino IDE 1.x
SoftI2CMaster is an Arduino library that implements
a simple "bit-bang" software-only I2C (aka "TWI") Master.
This lets you use any two Arduino pins to be the SDA & SCL
pins needed to communicate with I2C devices like BlinkMs.
SoftI2CMaster was originally in the BlinkMSoftI2CDemo example
in http://code.google.com/p/blinkm-projects/

View File

@ -0,0 +1,328 @@
/*
* SoftI2CMaster.cpp -- Multi-instance software I2C Master library
*
*
* 2010-12 Tod E. Kurt, http://todbot.com/blog/
*
* This code takes some tricks from:
* http://codinglab.blogspot.com/2008/10/i2c-on-avr-using-bit-banging.html
*
* 2014, by Testato: update library and examples for follow Wires API of Arduino IDE 1.x
*
*/
#if (ARDUINO >= 100)
#include <Arduino.h>
#else
#include <WProgram.h>
#endif
#include "SoftI2CMaster.h"
#include <util/delay.h>
#include <string.h>
#define i2cbitdelay 50
#define I2C_ACK 1
#define I2C_NAK 0
#define i2c_scl_release() \
*_sclDirReg &=~ _sclBitMask
#define i2c_sda_release() \
*_sdaDirReg &=~ _sdaBitMask
// sets SCL low and drives output
#define i2c_scl_lo() \
*_sclPortReg &=~ _sclBitMask; \
*_sclDirReg |= _sclBitMask;
// sets SDA low and drives output
#define i2c_sda_lo() \
*_sdaPortReg &=~ _sdaBitMask; \
*_sdaDirReg |= _sdaBitMask;
// set SCL high and to input (releases pin) (i.e. change to input,turnon pullup)
#define i2c_scl_hi() \
*_sclDirReg &=~ _sclBitMask; \
if(usePullups) { *_sclPortReg |= _sclBitMask; }
// set SDA high and to input (releases pin) (i.e. change to input,turnon pullup)
#define i2c_sda_hi() \
*_sdaDirReg &=~ _sdaBitMask; \
if(usePullups) { *_sdaPortReg |= _sdaBitMask; }
//
// Constructor
//
SoftI2CMaster::SoftI2CMaster()
{
// do nothing, use setPins() later
}
//
SoftI2CMaster::SoftI2CMaster(uint8_t sclPin, uint8_t sdaPin)
{
setPins(sclPin, sdaPin, true);
i2c_init();
}
//
SoftI2CMaster::SoftI2CMaster(uint8_t sclPin, uint8_t sdaPin, uint8_t pullups)
{
setPins(sclPin, sdaPin, pullups);
i2c_init();
}
//
// Turn Arduino pin numbers into PORTx, DDRx, and PINx
//
void SoftI2CMaster::setPins(uint8_t sclPin, uint8_t sdaPin, uint8_t pullups)
{
uint8_t port;
usePullups = pullups;
_sclPin = sclPin;
_sdaPin = sdaPin;
_sclBitMask = digitalPinToBitMask(sclPin);
_sdaBitMask = digitalPinToBitMask(sdaPin);
port = digitalPinToPort(sclPin);
_sclPortReg = portOutputRegister(port);
_sclDirReg = portModeRegister(port);
port = digitalPinToPort(sdaPin);
_sdaPortReg = portOutputRegister(port);
_sdaDirReg = portModeRegister(port);
}
//
//
//
uint8_t SoftI2CMaster::beginTransmission(uint8_t address)
{
i2c_start();
uint8_t rc = i2c_write((address<<1) | 0); // clr read bit
return rc;
}
//
uint8_t SoftI2CMaster::requestFrom(uint8_t address)
{
i2c_start();
uint8_t rc = i2c_write((address<<1) | 1); // set read bit
return rc;
}
//
uint8_t SoftI2CMaster::requestFrom(int address)
{
return requestFrom( (uint8_t) address);
}
//
uint8_t SoftI2CMaster::beginTransmission(int address)
{
return beginTransmission((uint8_t)address);
}
//
//
//
uint8_t SoftI2CMaster::endTransmission(void)
{
i2c_stop();
//return ret; // FIXME
return 0;
}
// must be called in:
// slave tx event callback
// or after beginTransmission(address)
uint8_t SoftI2CMaster::write(uint8_t data)
{
return i2c_write(data);
}
// must be called in:
// slave tx event callback
// or after beginTransmission(address)
void SoftI2CMaster::write(uint8_t* data, uint8_t quantity)
{
for(uint8_t i = 0; i < quantity; ++i){
write(data[i]);
}
}
// must be called in:
// slave tx event callback
// or after beginTransmission(address)
void SoftI2CMaster::write(char* data)
{
write((uint8_t*)data, strlen(data));
}
// must be called in:
// slave tx event callback
// or after beginTransmission(address)
void SoftI2CMaster::write(int data)
{
write((uint8_t)data);
}
//--------------------------------------------------------------------
void SoftI2CMaster::i2c_writebit( uint8_t c )
{
if ( c > 0 ) {
i2c_sda_hi();
} else {
i2c_sda_lo();
}
i2c_scl_hi();
_delay_us(i2cbitdelay);
i2c_scl_lo();
_delay_us(i2cbitdelay);
if ( c > 0 ) {
i2c_sda_lo();
}
_delay_us(i2cbitdelay);
}
//
uint8_t SoftI2CMaster::i2c_readbit(void)
{
i2c_sda_hi();
i2c_scl_hi();
_delay_us(i2cbitdelay);
uint8_t port = digitalPinToPort(_sdaPin);
volatile uint8_t* pinReg = portInputRegister(port);
uint8_t c = *pinReg; // I2C_PIN;
i2c_scl_lo();
_delay_us(i2cbitdelay);
return ( c & _sdaBitMask) ? 1 : 0;
}
// Inits bitbanging port, must be called before using the functions below
//
void SoftI2CMaster::i2c_init(void)
{
//I2C_PORT &=~ (_BV( I2C_SDA ) | _BV( I2C_SCL ));
//*_sclPortReg &=~ (_sdaBitMask | _sclBitMask);
i2c_sda_hi();
i2c_scl_hi();
_delay_us(i2cbitdelay);
}
// Send a START Condition
//
void SoftI2CMaster::i2c_start(void)
{
// set both to high at the same time
//I2C_DDR &=~ (_BV( I2C_SDA ) | _BV( I2C_SCL ));
//*_sclDirReg &=~ (_sdaBitMask | _sclBitMask);
i2c_sda_hi();
i2c_scl_hi();
_delay_us(i2cbitdelay);
i2c_sda_lo();
_delay_us(i2cbitdelay);
i2c_scl_lo();
_delay_us(i2cbitdelay);
}
void SoftI2CMaster::i2c_repstart(void)
{
// set both to high at the same time (releases drive on both lines)
//I2C_DDR &=~ (_BV( I2C_SDA ) | _BV( I2C_SCL ));
//*_sclDirReg &=~ (_sdaBitMask | _sclBitMask);
i2c_sda_hi();
i2c_scl_hi();
i2c_scl_lo(); // force SCL low
_delay_us(i2cbitdelay);
i2c_sda_release(); // release SDA
_delay_us(i2cbitdelay);
i2c_scl_release(); // release SCL
_delay_us(i2cbitdelay);
i2c_sda_lo(); // force SDA low
_delay_us(i2cbitdelay);
}
// Send a STOP Condition
//
void SoftI2CMaster::i2c_stop(void)
{
i2c_scl_hi();
_delay_us(i2cbitdelay);
i2c_sda_hi();
_delay_us(i2cbitdelay);
}
// write a byte to the I2C slave device
//
uint8_t SoftI2CMaster::i2c_write( uint8_t c )
{
for ( uint8_t i=0;i<8;i++) {
i2c_writebit( c & 128 );
c<<=1;
}
return i2c_readbit();
}
// read a byte from the I2C slave device
//
uint8_t SoftI2CMaster::i2c_read( uint8_t ack )
{
uint8_t res = 0;
for ( uint8_t i=0;i<8;i++) {
res <<= 1;
res |= i2c_readbit();
}
if ( ack )
i2c_writebit( 0 );
else
i2c_writebit( 1 );
_delay_us(i2cbitdelay);
return res;
}
// FIXME: this isn't right, surely
uint8_t SoftI2CMaster::read( uint8_t ack )
{
return i2c_read( ack );
}
//
uint8_t SoftI2CMaster::read()
{
return i2c_read( I2C_ACK );
}
//
uint8_t SoftI2CMaster::readLast()
{
return i2c_read( I2C_NAK );
}

View File

@ -0,0 +1,68 @@
/*
* SoftI2CMaster.h -- Multi-instance software I2C Master library
*
* 2010-2012 Tod E. Kurt, http://todbot.com/blog/
* 2014, by Testato: update library and examples for follow Wires API of Arduino IDE 1.x
*
*/
#ifndef SoftI2CMaster_h
#define SoftI2CMaster_h
#include <inttypes.h>
#define _SOFTI2CMASTER_VERSION 13 // software version of this library
class SoftI2CMaster
{
private:
// per object data
uint8_t _sclPin;
uint8_t _sdaPin;
uint8_t _sclBitMask;
uint8_t _sdaBitMask;
volatile uint8_t *_sclPortReg;
volatile uint8_t *_sdaPortReg;
volatile uint8_t *_sclDirReg;
volatile uint8_t *_sdaDirReg;
uint8_t usePullups;
// private methods
void i2c_writebit( uint8_t c );
uint8_t i2c_readbit(void);
void i2c_init(void);
void i2c_start(void);
void i2c_repstart(void);
void i2c_stop(void);
uint8_t i2c_write( uint8_t c );
uint8_t i2c_read( uint8_t ack );
public:
// public methods
SoftI2CMaster();
SoftI2CMaster(uint8_t sclPin, uint8_t sdaPin);
SoftI2CMaster(uint8_t sclPin, uint8_t sdaPin, uint8_t usePullups);
void setPins(uint8_t sclPin, uint8_t sdaPin, uint8_t usePullups);
uint8_t beginTransmission(uint8_t address);
uint8_t beginTransmission(int address);
uint8_t endTransmission(void);
uint8_t write(uint8_t);
void write(uint8_t*, uint8_t);
void write(int);
void write(char*);
void begin(void) {return;};
uint8_t requestFrom(int address);
uint8_t requestFrom(uint8_t address);
uint8_t read( uint8_t ack );
uint8_t read();
uint8_t readLast();
};
#endif

View File

@ -0,0 +1,95 @@
/*
* BlinkMSoftI2CDemo -- very simply demonstrate Softi2CMaster library
*
*
*
* 2010 Tod E. Kurt, http://todbot.com/blog/
* 2014, by Testato: update library and examples for follow Wires API of Arduino IDE 1.x
*
*/
const boolean testingI2CReads = true;
// Choose any pins you want. The pins below let you plug in a BlinkM directly
const byte sclPin = 7; // digital pin 7 wired to 'c' on BlinkM
const byte sdaPin = 6; // digital pin 6 wired to 'd' on BlinkM
const byte pwrPin = 5; // digital pin 5 wired to '+' on BlinkM
const byte gndPin = 4; // digital pin 4 wired to '-' on BlinkM
#include "SoftI2CMaster.h"
#include "BlinkM_funcs_soft.h"
byte blinkm_addr = 9;
//
void setup()
{
Serial.begin( 19200 );
Serial.println(F("BlinkMSoftI2CDemo"));
BlinkM_begin( sclPin, sdaPin, pwrPin, gndPin );
delay(100);
BlinkM_off(0);
BlinkM_setFadeSpeed( blinkm_addr, 5);
for( int i=0; i< 10; i++ ) { // flash the blinkms
BlinkM_setRGB( blinkm_addr, 255,255,255 );
delay(20);
BlinkM_setRGB( blinkm_addr, 0,0,0 );
delay(20);
}
if( testingI2CReads ) {
Serial.print(F("BlinkM version: "));
int num = BlinkM_getVersion( blinkm_addr );
char major_version = (char)(num>>8);
char minor_version = (char)(num&0xff);
Serial.print( major_version );
Serial.println( minor_version );
if( major_version == -1 ) {
Serial.println(F("\nERROR: couldn't find a BlinkM\n"));
}
}
}
void loop()
{
byte r = random(255);
byte g = random(255);
byte b = random(255);
Serial.print(F("Setting r,g,b:")); Serial.print(r,HEX);
Serial.print(","); Serial.print(g,HEX);
Serial.print(","); Serial.println(b,HEX);
BlinkM_setRGB( blinkm_addr, r,g,b );
delay(50);
BlinkM_fadeToRGB( blinkm_addr, 0,0,0 );
if( testingI2CReads ) {
for( int i=0; i<10; i++ ) {
showCurrentColor();
delay(100);
}
}
else {
delay(1000);
}
}
//
void showCurrentColor()
{
byte r,g,b;
BlinkM_getRGBColor( blinkm_addr, &r,&g,&b);
Serial.print(F(" r,g,b:")); Serial.print(r,HEX);
Serial.print(","); Serial.print(g,HEX);
Serial.print(","); Serial.println(b,HEX);
}

View File

@ -0,0 +1,127 @@
/**
* BlinkM_funcs_soft.h -- an extremely cut-down version of BlinkM_funcs.h
* for use with SoftI2CMaster library
*
*
* 2010 Tod E. Kurt, http://todbot.com/blog/
* 2014, by Testato: update library and examples for follow Wires API of Arduino IDE 1.x
*
*/
int errcnt;
#include "SoftI2CMaster.h"
SoftI2CMaster i2c = SoftI2CMaster();
// set which arbitrary I/O pins will be "power" and "ground" for the BlinkM
static void BlinkM_setPowerPins(byte pwrpin, byte gndpin)
{
pinMode(pwrpin, OUTPUT);
pinMode(gndpin, OUTPUT);
digitalWrite(pwrpin, HIGH);
digitalWrite(gndpin, LOW);
delay(10); // wait for power to stabilize
}
// set which arbitrary I/O pins will be BlinkMs SCL and SDA
// note, this sets the internal pull-up resistors
static void BlinkM_begin( byte sclpin, byte sdapin )
{
i2c.setPins( sclPin,sdaPin, true );
}
// start up a BlinkM with four arbitrary I/O pins
static void BlinkM_begin( byte sclpin, byte sdapin, byte pwrpin, byte gndpin)
{
BlinkM_setPowerPins( pwrpin, gndpin );
i2c.setPins( sclPin,sdaPin, true );
}
// -----------------------------------------------------------------------------
// many BlinkM commands are 3 arguments in length, here's a generalized form
static void BlinkM_sendCmd3( uint8_t addr, uint8_t c, uint8_t a1, uint8_t a2, uint8_t a3 )
{
if( i2c.beginTransmission( addr ) == 0 ) {
++errcnt;
//Serial.println( errcnt); // FIXME
}
i2c.write( c );
i2c.write( a1 );
i2c.write( a2 );
i2c.write( a3 );
i2c.endTransmission();
}
// other BlinkM commands have a single argument
static void BlinkM_sendCmd1( uint8_t addr, uint8_t c, uint8_t a1)
{
if( i2c.beginTransmission( addr ) == 0 ) {
++errcnt;
//Serial.println( errcnt); // FIXME
}
i2c.write( c );
i2c.write( a1 );
}
static void BlinkM_stopScript(uint8_t addr)
{
i2c.beginTransmission( addr );
i2c.write( 'o' );
i2c.endTransmission();
}
static void BlinkM_setFadeSpeed( uint8_t addr, uint8_t f)
{
BlinkM_sendCmd1( addr, 'f', f );
}
static void BlinkM_fadeToRGB( uint8_t addr, uint8_t r, uint8_t g, uint8_t b )
{
BlinkM_sendCmd3( addr, 'c', r,g,b );
}
static void BlinkM_setRGB( uint8_t addr, uint8_t r, uint8_t g, uint8_t b )
{
BlinkM_sendCmd3( addr, 'n', r,g,b );
}
static void BlinkM_off(uint8_t addr)
{
BlinkM_stopScript( addr );
BlinkM_setFadeSpeed(addr,10);
BlinkM_setRGB(addr, 0,0,0 );
}
// Get the BlinkM firmware version
static int BlinkM_getVersion(byte addr)
{
i2c.beginTransmission( addr );
i2c.write( 'Z' );
i2c.endTransmission();
i2c.requestFrom( addr );
uint8_t major_ver = i2c.read();
uint8_t minor_ver = i2c.readLast();
i2c.endTransmission();
return (major_ver<<8) + minor_ver;
}
//
static void BlinkM_getRGBColor(byte addr, byte* r, byte* g, byte* b)
{
i2c.beginTransmission(addr);
i2c.write('g');
i2c.endTransmission();
i2c.requestFrom( addr );
*r = i2c.read();
*g = i2c.read();
*b = i2c.readLast();
i2c.endTransmission();
}

View File

@ -0,0 +1,317 @@
/* MMA8452Q Example Code
by: Jim Lindblom
SparkFun Electronics
date: October 13, 2011
license: Creative Commons Share-Alike v3.0 (CC BY-SA 3.0)
This code should provide example usage for most features of
the MMA8452Q 3-axis, I2C accelerometer. In the loop function
the accelerometer interrupt outputs will be polled, and either
the x/y/z accel data will be output, or single/double-taps,
portrait/landscape changes will be announced.
The skeleton is here, feel free to cut/paste what code you need.
Play around with the settings in initMMA8452Q. Try running the
code without printing the accel values, to really appreciate
the single/double-tap and portrait landscape functions. The
P/L stuff is really neat, something not many accelerometers have.
Hardware setup:
MMA8452 Breakout ------------ Arduino
3.3V --------------------- 3.3V
SDA ----------------------- A4
SCL ----------------------- A5
INT2 ---------------------- D3
INT1 ---------------------- D2
GND ---------------------- GND
SDA and SCL should have external pull-up resistors (to 3.3V).
10k resistors worked for me. They should be on the breakout
board.
Note: The MMA8452 is an I2C sensor, however this code does
not make use of the Arduino Wire library. Because the sensor
is not 5V tolerant, we can't use the internal pull-ups used
by the Wire library. Instead use the included i2c.h file.
*/
//#include "i2c.h" // not the wire library, can't use pull-ups
#include "SoftI2CMaster.h"
//const int sdaPin = A4;
//const int sclPin = A5;
const int sdaPin = 4;
const int sclPin = 5;
SoftI2CMaster i2c = SoftI2CMaster( sclPin, sdaPin, 0 );
#define SA0 1 // Breakout board defaults to 1, set to 0 if SA0 jumper is set
#if SA0
#define MMA8452_ADDRESS 0x1D // SA0 is high, 0x1C if low
#else
#define MMA8452_ADDRESS 0x1C
#endif
/* Set the scale below either 2, 4 or 8*/
const byte scale = 2; // Sets full-scale range to +/-2, 4, or 8g. Used to calc real g values.
/* Set the output data rate below. Value should be between 0 and 7*/
const byte dataRate = 0; // 0=800Hz, 1=400, 2=200, 3=100, 4=50, 5=12.5, 6=6.25, 7=1.56
/* Pin definitions */
int int1Pin = 2; // These can be changed, 2 and 3 are the Arduinos ext int pins
int int2Pin = 3;
byte data[6]; // x/y/z accel register data store here
int accelCount[3]; // Stores the 12-bit signed value
float accel[3]; // Stores the real accel value in g's
void setup()
{
byte c;
Serial.begin(115200);
/* Set up the interrupt pins, they're set as active high, push-pull */
pinMode(int1Pin, INPUT);
digitalWrite(int1Pin, LOW);
pinMode(int2Pin, INPUT);
digitalWrite(int2Pin, LOW);
/* Read the WHO_AM_I register, this is a good test of communication */
c = readRegister(0x0D); // Read WHO_AM_I register
if (c == 0x2A) // WHO_AM_I should always be 0x2A
{
initMMA8452(scale, dataRate); // init the accelerometer if communication is good
Serial.println(F("MMA8452Q is online..."));
}
else
{
Serial.print(F("Could not connect to MMA8452Q: 0x"));
Serial.println(c, HEX);
while (1) // Loop forever if communication doesn't happen
;
}
}
void loop()
{
static byte source;
/* If int1 goes high, all data registers have new data */
if (digitalRead(int1Pin)) // Interrupt pin, should probably attach to interrupt function
//if (readRegister(0x00)&0x7) // Polling, you can use this instead of the interrupt pins
{
readRegisters(0x01, 6, &data[0]); // Read the six data registers into data array
// For loop to calculate 12-bit ADC and g value for each axis
for (int i=0; i<6; i+=2)
{
accelCount[i/2] = ((data[i] << 8) | data[i+1]) >> 4; // Turn the MSB and LSB into a 12-bit value
if (data[i] > 0x7F)
{ // If the number is negative, we have to make it so manually (no 12-bit data type)
accelCount[i/2] = ~accelCount[i/2] + 1;
accelCount[i/2] *= -1; // Transform into negative 2's complement #
}
accel[i/2] = (float) accelCount[i/2]/((1<<12)/(2*scale)); // get actual g value, this depends on scale being set
}
// For loop to print out values
for (int i=0; i<3; i++)
{
Serial.print(accel[i], 4); // Print g values
//Serial.print(accelCount[i], DEC); // Print adc count values, feel free to uncomment this line
Serial.print("\t\t");
}
Serial.println();
}
/* If int2 goes high, either p/l has changed or there's been a single/double tap */
if (digitalRead(int2Pin))
{
source = readRegister(0x0C); // Read the interrupt source reg.
if ((source & 0x10)==0x10) // If the p/l bit is set, go check those registers
portraitLandscapeHandler();
else if ((source & 0x08)==0x08) // Otherwise, if tap register is set go check that
tapHandler();
delay(100); // Delay here for a little printing visibility, make it longer, or delete it
}
delay(20);
}
/* This function will read the status of the tap source register.
And print if there's been a single or double tap, and on what
axis. */
void tapHandler()
{
byte source = readRegister(0x22); // Reads the PULSE_SRC register
if ((source & 0x10)==0x10) // If AxX bit is set
{
if ((source & 0x08)==0x08) // If DPE (double puls) bit is set
Serial.print(" 2 X");
else
Serial.print("1 X");
if ((source & 0x01)==0x01) // If PoIX is set
Serial.println(" +");
else
Serial.println(" -");
}
if ((source & 0x20)==0x20) // If AxY bit is set
{
if ((source & 0x08)==0x08) // If DPE (double puls) bit is set
Serial.print(" 2 Y");
else
Serial.print("1 Y");
if ((source & 0x02)==0x02) // If PoIY is set
Serial.println(" +");
else
Serial.println(" -");
}
if ((source & 0x40)==0x40) // If AxZ bit is set
{
if ((source & 0x08)==0x08) // If DPE (double puls) bit is set
Serial.print(" 2 Z");
else
Serial.print("1 Z");
if ((source & 0x04)==0x04) // If PoIZ is set
Serial.println(" +");
else
Serial.println(" -");
}
}
/* This function will read the p/l source register and
print what direction the sensor is now facing */
void portraitLandscapeHandler()
{
byte pl = readRegister(0x10); // Reads the PL_STATUS register
switch((pl&0x06)>>1) // Check on the LAPO[1:0] bits
{
case 0:
Serial.print(F("Portrait up, "));
break;
case 1:
Serial.print(F("Portrait Down, "));
break;
case 2:
Serial.print(F("Landscape Right, "));
break;
case 3:
Serial.print(F("Landscape Left, "));
break;
}
if (pl&0x01) // Check the BAFRO bit
Serial.print(F("Back"));
else
Serial.print(F("Front"));
if (pl&0x40) // Check the LO bit
Serial.print(F(", Z-tilt!"));
Serial.println();
}
/* Initialize the MMA8452 registers
See the many application notes for more info on setting
all of these registers:
http://www.freescale.com/webapp/sps/site/prod_summary.jsp?code=MMA8452Q
Feel free to modify any values, these are settings that work well for me.
*/
void initMMA8452(byte fsr, byte dataRate)
{
MMA8452Standby(); // Must be in standby to change registers
/* Set up the full scale range to 2, 4, or 8g. */
if ((fsr==2)||(fsr==4)||(fsr==8))
writeRegister(0x0E, fsr >> 2);
else
writeRegister(0x0E, 0);
/* Setup the 3 data rate bits, from 0 to 7 */
writeRegister(0x2A, readRegister(0x2A) & ~(0x38));
if (dataRate <= 7)
writeRegister(0x2A, readRegister(0x2A) | (dataRate << 3));
/* Set up portrait/landscap registers */
writeRegister(0x11, 0x40); // Enable P/L
writeRegister(0x13, 0x14); // 29deg z-lock,
writeRegister(0x14, 0x84); // 45deg thresh, 14deg hyst
writeRegister(0x12, 0x05); // debounce counter at 100ms
/* Set up single and double tap */
writeRegister(0x21, 0x7F); // enable single/double taps on all axes
writeRegister(0x23, 0x20); // x thresh at 2g
writeRegister(0x24, 0x20); // y thresh at 2g
writeRegister(0x25, 0x8); // z thresh at .5g
writeRegister(0x26, 0x30); // 60ms time limit, the min/max here is very dependent on output data rate
writeRegister(0x27, 0x28); // 200ms between taps min
writeRegister(0x28, 0xFF); // 1.275s (max value) between taps max
/* Set up interrupt 1 and 2 */
writeRegister(0x2C, 0x02); // Active high, push-pull
writeRegister(0x2D, 0x19); // DRDY int enabled, P/L enabled
writeRegister(0x2E, 0x01); // DRDY on INT1, P/L on INT2
MMA8452Active(); // Set to active to start reading
}
/* Sets the MMA8452 to standby mode.
It must be in standby to change most register settings */
void MMA8452Standby()
{
byte c = readRegister(0x2A);
writeRegister(0x2A, c & ~(0x01));
}
/* Sets the MMA8452 to active mode.
Needs to be in this mode to output data */
void MMA8452Active()
{
byte c = readRegister(0x2A);
writeRegister(0x2A, c | 0x01);
}
/* Read i registers sequentially, starting at address
into the dest byte arra */
void readRegisters(byte address, int i, byte * dest)
{
i2c.beginTransmission( MMA8452_ADDRESS );
i2c.write( address );
i2c.endTransmission();
i2c.requestFrom( MMA8452_ADDRESS );
int j;
for( j=0; j<i-1; j++) {
dest[j] = i2c.read();
}
dest[j+1] = i2c.readLast();
i2c.endTransmission();
}
// read a single byte from address and return it as a byte
byte readRegister(uint8_t address)
{
byte data;
i2c.beginTransmission( MMA8452_ADDRESS );
i2c.write( address );
i2c.endTransmission();
i2c.requestFrom( MMA8452_ADDRESS );
data = i2c.readLast();
i2c.endTransmission();
return data;
}
// Writes a single byte (data) into address
void writeRegister(unsigned char address, unsigned char data)
{
i2c.beginTransmission( MMA8452_ADDRESS );
i2c.write( address );
i2c.write( data );
i2c.endTransmission();
}

View File

@ -0,0 +1,307 @@
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include <AccelStepper.h>
#define DIR_AZ 6 /*PIN for Azimuth Direction*/
#define STEP_AZ 5 /*PIN for Azimuth Steps*/
#define DIR_EL 10 /*PIN for Elevation Direction*/
#define STEP_EL 9 /*PIN for Elevation Steps*/
#define EN 8 /*PIN for Enable or Disable Stepper Motors*/
#define SPR 200 /*Step Per Revolution*/
#define RATIO 54 /*Gear ratio*/
#define T_DELAY 60000 /*Time to disable the motors in millisecond*/
#define HOME_AZ 4 /*Homing switch for Azimuth*/
#define HOME_EL 3 /*Homing switch for Elevation*/
#define MAX_AZ_ANGLE 365 /*Maximum Angle of Azimuth for homing scanning*/
#define MAX_EL_ANGLE 365 /*Maximum Angle of Elevation for homing scanning*/
#define MAX_SPEED 300
#define MAX_ACCELERATION 100
#define MIN_PULSE_WIDTH 20 /*in microsecond*/
#define DEFAULT_HOME_STATE HIGH /*Change to LOW according to Home sensor*/
#define HOME_DELAY 6000 /*Time for homing Decceleration in millisecond*/
#define BufferSize 256
#define BaudRate 19200
/*Global Variables*/
unsigned long t_DIS = 0; /*time to disable the Motors*/
/*Define a stepper and the pins it will use*/
AccelStepper AZstepper(1, STEP_AZ, DIR_AZ);
AccelStepper ELstepper(1, STEP_EL, DIR_EL);
void setup()
{
/*Change these to suit your stepper if you want*/
AZstepper.setMaxSpeed(MAX_SPEED);
AZstepper.setAcceleration(MAX_ACCELERATION);
/*Change these to suit your stepper if you want*/
ELstepper.setMaxSpeed(MAX_SPEED);
ELstepper.setAcceleration(MAX_ACCELERATION);
/*Set minimum pulse width*/
AZstepper.setMinPulseWidth(MIN_PULSE_WIDTH);
ELstepper.setMinPulseWidth(MIN_PULSE_WIDTH);
/*Enable Motors*/
pinMode(EN, OUTPUT);
digitalWrite(EN, LOW);
/*Homing switch*/
pinMode(HOME_AZ, INPUT_PULLUP);
pinMode(HOME_EL, INPUT_PULLUP);
/*Serial Communication*/
Serial.begin(BaudRate);
/*Initial Homing*/
Homing(deg2step(-MAX_AZ_ANGLE), deg2step(-MAX_EL_ANGLE));
}
void loop()
{
/*Define the steps*/
static int AZstep = 0;
static int ELstep = 0;
/*Time Check*/
if (t_DIS == 0)
t_DIS = millis();
/*Disable Motors*/
if (AZstep == AZstepper.currentPosition() && ELstep == ELstepper.currentPosition() && millis()-t_DIS > T_DELAY)
digitalWrite(EN, HIGH);
/*Enable Motors*/
else
digitalWrite(EN, LOW);
/*Read the steps from serial*/
cmd_proc(AZstep, ELstep);
/*Move the Azimuth & Elevation Motor*/
stepper_move(AZstep, ELstep);
}
/*Homing Function*/
void Homing(int AZsteps, int ELsteps)
{
int value_Home_AZ = DEFAULT_HOME_STATE;
int value_Home_EL = DEFAULT_HOME_STATE;
boolean isHome_AZ = false;
boolean isHome_EL = false;
AZstepper.moveTo(AZsteps);
ELstepper.moveTo(ELsteps);
while(isHome_AZ == false || isHome_EL == false)
{
value_Home_AZ = digitalRead(HOME_AZ);
value_Home_EL = digitalRead(HOME_EL);
/*Change to LOW according to Home sensor*/
if (value_Home_AZ == DEFAULT_HOME_STATE)
{
AZstepper.moveTo(AZstepper.currentPosition());
isHome_AZ = true;
}
/*Change to LOW according to Home sensor*/
if (value_Home_EL == DEFAULT_HOME_STATE)
{
ELstepper.moveTo(ELstepper.currentPosition());
isHome_EL = true;
}
if (AZstepper.distanceToGo() == 0 && !isHome_AZ)
{
error(0);
break;
}
if (ELstepper.distanceToGo() == 0 && !isHome_EL)
{
error(1);
break;
}
AZstepper.run();
ELstepper.run();
}
/*Delay to Deccelerate*/
long time = millis();
while(millis() - time < HOME_DELAY)
{
AZstepper.run();
ELstepper.run();
}
/*Reset the steps*/
AZstepper.setCurrentPosition(0);
ELstepper.setCurrentPosition(0);
}
/*EasyComm 2 Protocol & Calculate the steps*/
void cmd_proc(int &stepAz, int &stepEl)
{
/*Serial*/
char buffer[BufferSize];
char incomingByte;
char *Data = buffer;
char *rawData;
static int BufferCnt = 0;
char data[100];
double angleAz, angleEl;
/*Read from serial*/
while (Serial.available() > 0)
{
incomingByte = Serial.read();
/* XXX: Get position using custom and test code */
if (incomingByte == '!')
{
/*Get position*/
Serial.print("TM");
Serial.print(1);
Serial.print(" ");
Serial.print("AZ");
Serial.print(10*step2deg(AZstepper.currentPosition()), 1);
Serial.print(" ");
Serial.print("EL");
Serial.println(10*step2deg(ELstepper.currentPosition()), 1);
}
/*new data*/
else if (incomingByte == '\n')
{
buffer[BufferCnt] = 0;
if (buffer[0] == 'A' && buffer[1] == 'Z')
{
if (buffer[2] == ' ' && buffer[3] == 'E' && buffer[4] == 'L')
{
/*Get position*/
Serial.print("AZ");
Serial.print(step2deg(AZstepper.currentPosition()), 1);
Serial.print(" ");
Serial.print("EL");
Serial.print(step2deg(ELstepper.currentPosition()), 1);
Serial.println(" ");
}
else
{
/*Get the absolute value of angle*/
rawData = strtok_r(Data, " " , &Data);
strncpy(data, rawData+2, 10);
if (isNumber(data))
{
angleAz = atof(data);
/*Calculate the steps*/
stepAz = deg2step(angleAz);
}
/*Get the absolute value of angle*/
rawData = strtok_r(Data, " " , &Data);
if (rawData[0] == 'E' && rawData[1] == 'L')
{
strncpy(data, rawData+2, 10);
if (isNumber(data))
{
angleEl = atof(data);
/*Calculate the steps*/
stepEl = deg2step(angleEl);
}
}
}
}
/*Stop Moving*/
else if (buffer[0] == 'S' && buffer[1] == 'A' && buffer[2] == ' ' && buffer[3] == 'S' && buffer[4] == 'E')
{
/*Get position*/
Serial.print("AZ");
Serial.print(step2deg(AZstepper.currentPosition()), 1);
Serial.print(" ");
Serial.print("EL");
Serial.println(step2deg(ELstepper.currentPosition()), 1);
stepAz = AZstepper.currentPosition();
stepEl = ELstepper.currentPosition();
}
/*Reset the rotator*/
else if (buffer[0] == 'R' && buffer[1] == 'E' && buffer[2] == 'S' && buffer[3] == 'E' && buffer[4] == 'T')
{
/*Get position*/
Serial.print("AZ");
Serial.print(step2deg(AZstepper.currentPosition()), 1);
Serial.print(" ");
Serial.print("EL");
Serial.println(step2deg(ELstepper.currentPosition()), 1);
/*Move the steppers to initial position*/
Homing(deg2step(-MAX_AZ_ANGLE), deg2step(-MAX_EL_ANGLE));
/*Zero the steps*/
stepAz = 0;
stepEl = 0;
}
BufferCnt = 0;
/*Reset the disable motor time*/
t_DIS = 0;
}
/*Fill the buffer with incoming data*/
else {
buffer[BufferCnt] = incomingByte;
BufferCnt++;
}
}
}
/*Error Handling*/
void error(int num_error)
{
switch (num_error)
{
/*Azimuth error*/
case (0):
while(1)
{
Serial.println("AL001");
delay(100);
}
/*Elevation error*/
case (1):
while(1)
{
Serial.println("AL002");
delay(100);
}
default:
while(1)
{
Serial.println("AL000");
delay(100);
}
}
}
/*Send pulses to stepper motor drivers*/
void stepper_move(int stepAz, int stepEl)
{
AZstepper.moveTo(stepAz);
ELstepper.moveTo(stepEl);
AZstepper.run();
ELstepper.run();
}
/*Convert degrees to steps*/
int deg2step(double deg)
{
return(RATIO*SPR*deg/360);
}
/*Convert steps to degrees*/
double step2deg(int Step)
{
return(360.00*Step/(SPR*RATIO));
}
/*Check if is argument in number*/
boolean isNumber(char *input)
{
for (int i = 0; input[i] != '\0'; i++)
{
if (isalpha(input[i]))
return false;
}
return true;
}