diff --git a/.github/workflows/build.yaml b/.github/workflows/build.yaml index 9ed10e6..a604d88 100644 --- a/.github/workflows/build.yaml +++ b/.github/workflows/build.yaml @@ -3,8 +3,6 @@ name: Arduino Compile on: push: pull_request: - branches: - - main jobs: build: @@ -12,35 +10,33 @@ jobs: strategy: matrix: board_fqbn: [ - "arduino:avr:uno", - "arduino:avr:nano", - "STM32:stm32:GenF1:pnum=BLUEPILL_F103C8" + "nanoatmega328new", + "robotdyn_blackpill_f303cc", + "nanoatmega328", + "adafruit_itsybitsy_m4", + "program_via_AVRISP_mkII", + "robotdyn_blackpill_f103", + "pico", + "esp32doit-devkit-v1", + "pico2w" ] fail-fast: false + steps: - - name: Checkout repository - uses: actions/checkout@v4 - - name: setup path - run: | - echo "/root/.local/bin" >> $GITHUB_PATH - mkdir libs - cd libs - git clone https://github.com/mirte-robot/mirte-arduino-libraries.git - cd .. - - uses: arduino/compile-sketches@v1 - with: - cli-version: 0.13.0 - fqbn: "${{ matrix.board_fqbn }}" - platforms: | - - name: STM32:stm32 - source-url: https://raw.githubusercontent.com/koendv/stm32duino-raspberrypi/master/BoardManagerFiles/package_stm_index.json - - name: arduino:avr - libraries: | - - name: Servo - - name: Stepper - - name: DHTNEW - - name: NewPing - - source-path: ./libs/mirte-arduino-libraries/OpticalEncoder - - source-path: ./ - sketch-paths: examples/ - verbose: true + - uses: actions/checkout@v4 + with: + submodules: 'true' + - name: Set up Python + uses: actions/setup-python@v5 + with: + python-version: '3.x' + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install platformio + # It is important to first install the libraries before compiling, since otherwise compilation might fail to find the just-installed libraries + - name: Install platformIO libraries + run: pio pkg install -e ${{ matrix.board_fqbn }} + - name: Run PlatformIO + run: platformio run -e ${{ matrix.board_fqbn }} + diff --git a/.github/workflows/cpp-check.yml b/.github/workflows/cpp-check.yml new file mode 100644 index 0000000..eb9b20a --- /dev/null +++ b/.github/workflows/cpp-check.yml @@ -0,0 +1,17 @@ +name: test-clang-format + +on: [push, pull_request] + +jobs: + cpp_style_check: + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v3 + - uses: DoozyX/clang-format-lint-action@v0.14 + with: + source: '.' + # exclude: './third_party ./external' + extensions: 'h,cpp' + clangFormatVersion: 14 + style: llvm \ No newline at end of file diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..7fa5ecc --- /dev/null +++ b/.gitignore @@ -0,0 +1,2 @@ +.pio +.vscode/ diff --git a/LICENSE b/LICENSE deleted file mode 100644 index 0ad25db..0000000 --- a/LICENSE +++ /dev/null @@ -1,661 +0,0 @@ - GNU AFFERO GENERAL PUBLIC LICENSE - Version 3, 19 November 2007 - - Copyright (C) 2007 Free Software Foundation, Inc. - 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. - - - Copyright (C) - - 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 . - -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 -. diff --git a/README.md b/README.md index 13fab5f..6becf63 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,272 @@ # Telemetrix4Arduino -The Telemetrix Project Server For Arduino-Core. For instructions on use, -see the [Telemetrix User's Guide.](https://mryslab.github.io/telemetrix/) +WIP To convert to the same interface as the pico + +![](images/tmx.png) + +The Pico server code may be viewed [here.](https://github.com/mirte-robot/Telemetrix4RpiPico) + +# Interface + +Data transfers and how to communicate with telemetrix. The protocol is [length_of_msg, msg_id, msg....]. No error correction, no crc and no recovery if byte count is off. All the following messages have the length removed. Send and receive are from the computers perspective. +## Main + +### Unique ID +Arduino not implemented yet. TODO: Find way to do it. +Get a 8 byte unique id of the microcontroller. +`msg_id = 6`, both receive and send. + +Send: +```py +[REPORT_UNIQUE_ID = 6] +``` +Receive: +```py +[REPORT_UNIQUE_ID = 6, id[0], id[1], id[2], id[3],id[4],id[5],id[6],id[7] ] +``` + +### Get firmware version +Get the firmware version on the MCU with this command. Current version is 1.3. + +Send: +```py +[FIRMWARE_REPORT = 5] +``` + +Receive: +```py +[FIRMWARE_REPORT = 5, MAJOR, MINOR] +``` + +### Watchdog +NOT implemented +At first watchdog message, the watchdog is started. This message and any subsequent message will be acknowledged with the same COUNTER as the computer sent + a constant `boot_id`, that is randomly generated when the watchdog is started. The computer can check the counter to make sure no messages are lost. The constant `boot_id` is for the computer to check that the mcu did not restart. Watchdog timeout is 5s, but modules get a message after 4s to disable( we don't want rogue robots that are uncontrollable). + +`msg_id = 32`. Both send and receive. + +Send: +```py +[PING_ID = 32, COUNTER] +``` + +Receive: +```py +[PONG_ID = 32, COUNTER_FROM_COMPUTER, CONST_boot_id] +``` + +### Get saved id +NOT implemented +This id is stored on the MCU to later identify it when multiple microcontrollers are in use +Send: +```py +[GET_ID = 35 ] +``` + +Receive: +```py +[GET_ID_REPORT = 35, id ] +``` + +### Save id +NOT implemented +Save an id. This will be stored and kept between reboots + +Send: +```py +[SET_ID = 36, id] +``` + +Receive: +```py +[SET_ID_REPORT = 36, id] +``` + + +### I2C + +#### I2C start +To start an I2C bus, send this command once. Every start command will reset the bus, resetting/losing connection with previous I2C devices. +The i2c_port must be 0 or 1 for the RP2040. port 0 sda pins: ```[0, 4, 8, 12, 20, 16]```, port 1 sda pins: ```[2, 6, 10, 14, 26, 18]```. There is no check on this on the MCU side. The speed will be set to 100k and pull-ups enabled. + + +Send: +```py +[I2C_BEGIN = 10, i2c_port, sda, scl] +``` + +#### I2C write +The I2C port must be started. The ```cust_message_id``` will be sent back as acknowledge. It can be used to keep track on which message was okay. Max data length is 23 (MAX_MSG_LEN = 30 - 7 other bytes). Address must be in range [0..127]. ```no_stop``` is used to not stop the bus, just set it to 0. +The I2C write timeout is 50ms. The ```write_return_value``` is the amount of written bytes if okay (message_len) or the error value (negative or >128). + +Send: +```py +[I2C_WRITE = 12, i2c_port, address, cust_message_id, message_len, no_stop, message] +``` + +Receive: +```py +[I2C_WRITE_REPORT = 8, i2c_port, cust_message_id, write_return_value] +``` + +#### I2C read + +Register can be 0xFE + +Send +```py +[I2C_READ, i2c_port, i2c_addr, cust_message_id, register, num_bytes, no_stop] +``` + +## Sensors + +### Sonar +The sonars(hc-sr04) are time-triggered round-robin at a rate of 10Hz to not interfere with eachother. Example: 10Hz per sonar, 3 sonars, timer at 30Hz. Sonar reading is blocking by the NewPing lib. + +Max distance is 4m. Distance is reported in cm, in 2 bytes: ```distance_m = int(distance/100); distance_cm = distance%100``` + +max sonars is 6. + +Add sonar: +```py + +[SONAR_NEW = 13, trigger_pin, echo_pin] +``` + +Receive: +```py +[SONAR_REPORT = 11, trigger_pin, distance_m, distance_cm] +``` + +### Encoders +Quad is not supported! +2 types are supported, quadrature and single pin. Every edge is counted (up and down, A & B). No interrupts are used, but the encoders are checked at 10kHz. Max of 4 encoders. + +Encoder type is 1 for single pin encoder, 2 for quadrature. pin_B is always sent, but must be 0 if not used. The steps are reset on every report, you need to add them to keep a incremental value. The steps need to be interpreted as ```int8_t```, as a quadrature encoder can count down. + +Add encoder: +```py +[ENCODER_NEW = 30, encoder_type, pin_A, pin_B] +``` + +Receive: +```py +[ENCODER_REPORT = 14, pin_A, steps] +``` + +### Read pin +To read a digital/analog pin, you need to send a command to set the pin mode and then, on-change, the data will be sent. It's possible to switch modes during operation, even input <-> output. Just send a new ```SET_PIN_MODE``` message. + +#### Analog +The pin must be in range of [0..MAX_PINS], check before that it's an analog pin. differential is the minimal change for the value or it is not reported. + +Differential is ```uint16_t```, with ```diff_high = diff>>8``` and ```diff_low = diff&0xFF```. + +Set: +```py +[SET_PIN_MODE = 1, adc_pin, ANALOG_IN = 5, diff_high, diff_low, report_enable ] +``` + +Receive: +```py +[ANALOG_REPORT = 3, adc_pin, value_high, value_low] +``` + +#### Digital +Only on change, the data is sent. digital_in_type can be: +- DIGITAL_INPUT = 0 +- DIGITAL_INPUT_PULLUP = 3 +- DIGITAL_INPUT_PULLDOWN = 4 (chips without pulldown will get normal input) + +```report_enable``` can be used to enable or disable reporting. ```1``` for enable. +Set: +```py +[SET_PIN_MODE = 1, pin, digital_in_type, report_enable] +``` + +Receive: +```py +[DIGITAL_REPORT = 2, pin, value] +``` + +### Enable/disable reporting +If you want to stop receiving updates. This will also stop modules and sensors from reporting. + +Disable: +``` +[STOP_ALL_REPORTS = 15] +``` +Enable: +```py +[ENABLE_ALL_REPORTS = 16] +``` + +### Modify reporting +If you only want to en/disable a single pin or type, send this message. + +modify_type can be any of +- REPORTING_DISABLE_ALL = 0. Disable analog and digital inputs reporting. Set pin to 0. +- REPORTING_ANALOG_ENABLE = 1. Enable a single analog pin. Needs to have been set as analog pin otherwise UB. +- REPORTING_ANALOG_DISABLE = 3. Disable a single analog pin. Pin in range ```[0..MAX_PINS]``` +- REPORTING_DIGITAL_ENABLE = 2. Enable a single digital pin. Needs to have been set as digital input, otherwise UB. +- REPORTING_DIGITAL_DISABLE = 4. Disable a single digital pin. + +Send: +```py +[MODIFY_REPORTING = 4, modify_type, pin] +``` + +## Actuators + +### Digital output +First set pin once as output. Afterwards send updates to set new values. + +Set: +```py +[SET_PIN_MODE = 1, pin, DIGITAL_OUTPUT = 1] +``` +Update: +```py +[DIGITAL_WRITE = 2, pin, value] +``` + +### PWM output / Servo +The PWM mode can be used for servos, as the PWM frequency is set to 50Hz. The value must be in range ```[0, 20000]```. ```value_high = value>>8```, ```value_low = value&0xFF```. TODO: range is not correct, can change per chip. + +Setup: +```py +[SET_PIN_MODE = 1, pin, PWM_OUTPUT = 2] +``` +Update: +```py +[PWM_WRITE = 3, pin, value_high, value_low] +``` + +#### Servo specific messages +The servo messages, types 7-9, are not supported (yet), as servos can be used with the PWM messages. + + + + +## Modules +### Hiwonder: +Servos are identified based on an id. The actual servo id is only transmitted at init, after that the index of the servo in the init list is used to offload id searching from the pico to the computer. +#### Init: +```py +[ uart_id, rx_pin, tx_pin, len(servos), servo_1_id, servo_2_id, ..., servo_X_id ] +``` + +#### Set angle: +Message subtype 1 + +time in ms. +```py + [ 1, len(servos), servo_1_num, servo_1_angle_high_byte, servo_1_angle_low_byte, servo_1_time_high_byte, servo_1_time_low_byte, ..., servo_X_angle_high_byte, servo_X_angle_low_byte, servo_X_time_high_byte, servo_X_time_low_byte, ...] + ``` + +#### Set enabled: + ```py +[ 2, len(servos), enabled(1 or 0) servo_1_num, servo_X_num] +``` +#### Set all enabled: +```py +[ 2, 0, enabled] +``` diff --git a/Telemetrix4Arduino.cpp b/Telemetrix4Arduino.cpp deleted file mode 100644 index 52040ad..0000000 --- a/Telemetrix4Arduino.cpp +++ /dev/null @@ -1,3 +0,0 @@ -#include "Telemetrix4Arduino.h" - - diff --git a/Telemetrix4Arduino.h b/Telemetrix4Arduino.h deleted file mode 100644 index 4f98570..0000000 --- a/Telemetrix4Arduino.h +++ /dev/null @@ -1,9 +0,0 @@ -#ifndef _TELEMETRIX4ARDUINO_H_ -#define _TELEMETRIX4ARDUINO_H_ - -class Telemetrix4Arduino { - -public: -}; - -#endif //_TELEMETRIX4ARDUINO_H_ diff --git a/examples/Telemetrix4Arduino/Telemetrix4Arduino.ino b/examples/Telemetrix4Arduino/Telemetrix4Arduino.ino deleted file mode 100644 index 4e0e6a7..0000000 --- a/examples/Telemetrix4Arduino/Telemetrix4Arduino.ino +++ /dev/null @@ -1,1160 +0,0 @@ -#include -#include "Telemetrix4Arduino.h" -#include -#include -#include -#include -#include -/* - Copyright (c) 2020 Alan Yorinks All rights reserved. - - This program is free software; you can redistribute it and/or - modify it under the terms of the GNU AFFERO GENERAL PUBLIC LICENSE - Version 3 as published by the Free Software Foundation; either - or (at your option) any later version. - This library is distributed in the hope that it will be useful,f - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - General Public License for more details. - - You should have received a copy of the GNU AFFERO GENERAL PUBLIC LICENSEf - along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -// We define these here to provide a forward reference. -// If you add a new command, you must add the command handler -// here as well. - -extern void serial_loopback(); - -extern void set_pin_mode(); - -extern void digital_write(); - -extern void analog_write(); - -extern void modify_reporting(); - -extern void get_firmware_version(); - -extern void are_you_there(); - -extern void servo_attach(); - -extern void servo_write(); - -extern void servo_detach(); - -extern void i2c_begin(); - -extern void i2c_read(); - -extern void i2c_write(); - -extern void sonar_new(); - -extern void dht_new(); - -extern void encoder_new(); - -extern void stop_all_reports(); - -extern void set_analog_scanning_interval(); - -extern void enable_all_reports(); - -extern void reset_data(); - -extern void init_pin_structures(); - - -// uncomment out the next line to create a 2nd i2c port -//#define SECOND_I2C_PORT - -#ifdef SECOND_I2C_PORT -// Change the pins to match SDA and SCL for your board -#define SECOND_I2C_PORT_SDA PB11 -#define SECOND_I2C_PORT_SCL PB10 - -TwoWire Wire2(SECOND_I2C_PORT_SDA, SECOND_I2C_PORT_SCL); -#endif - -// a pointer to an active TwoWire object -TwoWire *current_i2c_port; - - -// This value must be the same as specified when instantiating the -// telemetrix client. The client defaults to a value of 1. -// This value is used for the client to auto-discover and to -// connect to a specific board regardless of the current com port -// it is currently connected to. -#define ARDUINO_ID 1 - -// Commands -received by this sketch -// Add commands retaining the sequential numbering. -// The order of commands here must be maintained in the command_table. -#define SERIAL_LOOP_BACK 0 -#define SET_PIN_MODE 1 -#define DIGITAL_WRITE 2 -#define ANALOG_WRITE 3 -#define MODIFY_REPORTING 4 // mode(all, analog, or digital), pin, enable or disable -#define GET_FIRMWARE_VERSION 5 -#define ARE_U_THERE 6 -#define SERVO_ATTACH 7 -#define SERVO_WRITE 8 -#define SERVO_DETACH 9 -#define I2C_BEGIN 10 -#define I2C_READ 11 -#define I2C_WRITE 12 -#define SONAR_NEW 13 -#define DHT_NEW 14 -#define STOP_ALL_REPORTS 15 -#define SET_ANALOG_SCANNING_INTERVAL 16 -#define ENABLE_ALL_REPORTS 17 -#define RESET 18 - -// Custom rotary encoder support -#define ENCODER_NEW 19 - -// When adding a new command update the command_table. -// The command length is the number of bytes that follow -// the command byte itself, and does not include the command -// byte in its length. -// The command_func is a pointer the command's function. -struct command_descriptor -{ - // a pointer to the command processing function - void (*command_func)(void); -}; - -// An array of pointers to the command functions - -// If you add new commands, make sure to extend the siz of this -// array. -command_descriptor command_table[20] = -{ - {&serial_loopback}, - {&set_pin_mode}, - {&digital_write}, - {&analog_write}, - {&modify_reporting}, - {&get_firmware_version}, - {&are_you_there}, - {&servo_attach}, - {&servo_write}, - {&servo_detach}, - {&i2c_begin}, - {&i2c_read}, - {&i2c_write}, - {&sonar_new}, - {dht_new}, - {stop_all_reports}, - {set_analog_scanning_interval}, - {enable_all_reports}, - {reset_data}, - {&encoder_new} -}; - -// Input pin reporting control sub commands (modify_reporting) -#define REPORTING_DISABLE_ALL 0 -#define REPORTING_ANALOG_ENABLE 1 -#define REPORTING_DIGITAL_ENABLE 2 -#define REPORTING_ANALOG_DISABLE 3 -#define REPORTING_DIGITAL_DISABLE 4 - -// maximum length of a command in bytes -#define MAX_COMMAND_LENGTH 30 - -// Pin mode definitions - -// INPUT defined in Arduino.h = 0 -// OUTPUT defined in Arduino.h = 1 -// INPUT_PULLUP defined in Arduino.h = 2 -// The following are defined for arduino_telemetrix (AT) -#define AT_ANALOG 3 -#define AT_MODE_NOT_SET 255 - -// maximum number of pins supported -#define MAX_DIGITAL_PINS_SUPPORTED 100 -#define MAX_ANALOG_PINS_SUPPORTED 15 - -// Reports - sent from this sketch -#define DIGITAL_REPORT DIGITAL_WRITE -#define ANALOG_REPORT ANALOG_WRITE -#define FIRMWARE_REPORT 5 -#define I_AM_HERE 6 -#define SERVO_UNAVAILABLE 7 -#define I2C_TOO_FEW_BYTES_RCVD 8 -#define I2C_TOO_MANY_BYTES_RCVD 9 -#define I2C_READ_REPORT 10 -#define SONAR_DISTANCE 11 -#define DHT_REPORT 12 -#define DEBUG_PRINT 99 - -#define ENCODER_REPORT 13 - -// DHT Report sub-types -#define DHT_DATA 0 -#define DHT_READ_ERROR 1 - -// firmware version - update this when bumping the version -#define FIRMWARE_MAJOR 1 -#define FIRMWARE_MINOR 11 - -// A buffer to hold i2c report data -byte i2c_report_message[64]; - -bool stop_reports = false; // a flag to stop sending all report messages - -// Analog input pin numbers are defined from -// A0 - A7. Since we do not know if the board -// in use also supports higher analog pin numbers -// we need to define those pin numbers to allow -// the program to compile, even though the -// pins may not exist for the board in use. - -#ifndef A8 -#define A8 2047 -#endif - -#ifndef A9 -#define A9 2047 -#endif - -#ifndef A10 -#define A10 2047 -#endif - -#ifndef PIN_A11 -#define A11 2047 -#endif - -#ifndef PIN_A12 -#define A12 2047 -#endif - -#ifndef PIN_A13 -#define A13 2047 -#endif - -#ifndef PIN_A14 -#define A14 2047 -#endif - -#ifndef PIN_A15 -#define A15 2047 -#endif - -// To translate a pin number from an integer value to its analog pin number -// equivalent, this array is used to look up the value to use for the pin. -int analog_read_pins[20] = {A0, A1, A2, A3, A4, A5, A6, A7, A8, A9, A10, A11, A12, A13, A14, A15}; - -// a descriptor for digital pins -struct pin_descriptor -{ - byte pin_number; - byte pin_mode; - bool reporting_enabled; // If true, then send reports if an input pin - int last_value; // Last value read for input mode -}; - -// an array of digital_pin_descriptors -pin_descriptor the_digital_pins[MAX_DIGITAL_PINS_SUPPORTED]; - -// a descriptor for digital pins -struct analog_pin_descriptor -{ - byte pin_number; - byte pin_mode; - bool reporting_enabled; // If true, then send reports if an input pin - int last_value; // Last value read for input mode - int differential; // difference between current and last value needed - // to generate a report -}; - -// an array of analog_pin_descriptors -analog_pin_descriptor the_analog_pins[MAX_ANALOG_PINS_SUPPORTED]; - -unsigned long current_millis; // for analog input loop -unsigned long previous_millis; // for analog input loop -uint8_t analog_sampling_interval = 19; - -// servo management -Servo servos[MAX_SERVOS]; - -// this array allows us to retrieve the servo object -// associated with a specific pin number -byte pin_to_servo_index_map[MAX_SERVOS]; - -// HC-SR04 Sonar Management -#define MAX_SONARS 6 - -struct Sonar -{ - uint8_t trigger_pin; - unsigned int last_value; - NewPing *usonic; -}; - -// an array of sonar objects -Sonar sonars[MAX_SONARS]; - -byte sonars_index = 0; // index into sonars struct - -// used for scanning the sonar devices. -byte last_sonar_visited = 0; - -unsigned long sonar_current_millis; // for analog input loop -unsigned long sonar_previous_millis; // for analog input loop -uint8_t sonar_scan_interval = 33; // Milliseconds between sensor pings -// (29ms is about the min to avoid = 19; - -// DHT Management -#define MAX_DHTS 6 // max number of devices -#define READ_FAILED_IN_SCANNER 0 // read request failed when scanning -#define READ_IN_FAILED_IN_SETUP 1 // read request failed when initially setting up - -struct DHT -{ - uint8_t pin; - unsigned int last_value; - DHTNEW *dht_sensor; -}; - -// an array of dht objects] -DHT dhts[MAX_DHTS]; - -byte dht_index = 0; // index into dht struct - -unsigned long dht_current_millis; // for analog input loop -unsigned long dht_previous_millis; // for analog input loop -unsigned int dht_scan_interval = 2000; // scan dht's every 2 seconds - - -// Optical encoder handling -struct OptEncoder -{ - uint8_t pin; - long last_value; - OpticalEncoder *optEnc_sensor; -}; - -#define MAX_ENCODERS 4 - -OptEncoder optEnc[MAX_ENCODERS]; -uint8_t optEncoder_ix = 0 ; // number of Optical Encoders attached - -typedef void (*intCB)(void); // lambda definition for interrupt callback - -intCB interruptMap[MAX_ENCODERS] = { - []{optEnc[0].optEnc_sensor->handleInterrupt();}, - []{optEnc[1].optEnc_sensor->handleInterrupt();}, - []{optEnc[2].optEnc_sensor->handleInterrupt();}, - []{optEnc[3].optEnc_sensor->handleInterrupt();} -}; - - -unsigned long optenc_current_millis; // for analog input loop -unsigned long optenc_previous_millis; // for analog input loop -unsigned int optenc_scan_interval = 10; // scan encoders every x ms - -// buffer to hold incoming command data -byte command_buffer[MAX_COMMAND_LENGTH]; - -// A method to send debug data across the serial link -void send_debug_info(byte id, int value) -{ - byte debug_buffer[5] = {(byte)4, (byte)DEBUG_PRINT, 0, 0, 0}; - debug_buffer[2] = id; - debug_buffer[3] = highByte(value); - debug_buffer[4] = lowByte(value); - Serial.write(debug_buffer, 5); -} - -// command functions -void serial_loopback() -{ - byte loop_back_buffer[3] = {2, (byte)SERIAL_LOOP_BACK, command_buffer[0]}; - Serial.write(loop_back_buffer, 3); -} - -void set_pin_mode() -{ - byte pin; - byte mode; - pin = command_buffer[0]; - mode = command_buffer[1]; - - switch (mode) - { - case INPUT: - the_digital_pins[pin].pin_mode = mode; - the_digital_pins[pin].reporting_enabled = command_buffer[2]; - the_digital_pins[pin].last_value = -1; - pinMode(pin, INPUT); - break; - case INPUT_PULLUP: - the_digital_pins[pin].pin_mode = mode; - the_digital_pins[pin].reporting_enabled = command_buffer[2]; - the_digital_pins[pin].last_value = -1; - pinMode(pin, INPUT_PULLUP); - break; - case OUTPUT: - the_digital_pins[pin].pin_mode = mode; - pinMode(pin, OUTPUT); - break; - case AT_ANALOG: - the_analog_pins[pin].pin_mode = mode; - the_analog_pins[pin].differential = (command_buffer[2] << 8) + command_buffer[3]; - the_analog_pins[pin].reporting_enabled = command_buffer[4]; - the_analog_pins[pin].last_value = -1; - break; - default: - break; - } -} - -void set_analog_scanning_interval() -{ - analog_sampling_interval = command_buffer[0]; -} - -void digital_write() -{ - byte pin; - byte value; - pin = command_buffer[0]; - value = command_buffer[1]; - digitalWrite(pin, value); -} - -void analog_write() -{ - // command_buffer[0] = PIN, command_buffer[1] = value_msb, - // command_buffer[2] = value_lsb - byte pin; // command_buffer[0] - unsigned int value; - - pin = command_buffer[0]; - - value = (command_buffer[1] << 8) + command_buffer[2]; - analogWrite(pin, value); -} - -void modify_reporting() -{ - int pin = command_buffer[1]; - - switch (command_buffer[0]) - { - case REPORTING_DISABLE_ALL: - for (int i = 0; i < MAX_DIGITAL_PINS_SUPPORTED; i++) - { - the_digital_pins[i].reporting_enabled = false; - } - for (int i = 0; i < MAX_ANALOG_PINS_SUPPORTED; i++) - { - the_analog_pins[i].reporting_enabled = false; - } - break; - case REPORTING_ANALOG_ENABLE: - if (the_analog_pins[pin].pin_mode != AT_MODE_NOT_SET) - { - the_analog_pins[pin].reporting_enabled = true; - } - break; - case REPORTING_ANALOG_DISABLE: - if (the_analog_pins[pin].pin_mode != AT_MODE_NOT_SET) - { - the_analog_pins[pin].reporting_enabled = false; - } - break; - case REPORTING_DIGITAL_ENABLE: - if (the_digital_pins[pin].pin_mode != AT_MODE_NOT_SET) - { - the_digital_pins[pin].reporting_enabled = true; - } - break; - case REPORTING_DIGITAL_DISABLE: - if (the_digital_pins[pin].pin_mode != AT_MODE_NOT_SET) - { - the_digital_pins[pin].reporting_enabled = false; - } - break; - default: - break; - } -} - -void get_firmware_version() -{ - byte report_message[4] = {3, FIRMWARE_REPORT, FIRMWARE_MAJOR, FIRMWARE_MINOR}; - Serial.write(report_message, 4); -} - -void are_you_there() -{ - byte report_message[3] = {2, I_AM_HERE, ARDUINO_ID}; - Serial.write(report_message, 3); -} - -/*************************************************** - Servo Commands - **************************************************/ - -// Find the first servo that is not attached to a pin -// This is a helper function not called directly via the API -int find_servo() -{ - int index = -1; - for (int i = 0; i < MAX_SERVOS; i++) - { - if (servos[i].attached() == false) - { - index = i; - break; - } - } - return index; -} - -void servo_attach() -{ - - byte pin = command_buffer[0]; - int servo_found = -1; - - int minpulse = (command_buffer[1] << 8) + command_buffer[2]; - int maxpulse = (command_buffer[3] << 8) + command_buffer[4]; - - // find the first available open servo - servo_found = find_servo(); - if (servo_found != -1) - { - pin_to_servo_index_map[servo_found] = pin; - servos[servo_found].attach(pin, minpulse, maxpulse); - } - else - { - // no open servos available, send a report back to client - byte report_message[2] = {SERVO_UNAVAILABLE, pin}; - Serial.write(report_message, 2); - } -} - -// set a servo to a given angle -void servo_write() -{ - byte pin = command_buffer[0]; - int angle = command_buffer[1]; - // find the servo object for the pin - for (int i = 0; i < MAX_SERVOS; i++) - { - if (pin_to_servo_index_map[i] == pin) - { - - servos[i].write(angle); - return; - } - } -} - -// detach a servo and make it available for future use -void servo_detach() -{ - byte pin = command_buffer[0]; - - // find the servo object for the pin - for (int i = 0; i < MAX_SERVOS; i++) - { - if (pin_to_servo_index_map[i] == pin) - { - - pin_to_servo_index_map[i] = -1; - servos[i].detach(); - } - } -} - -/*********************************** - i2c functions - **********************************/ - -void i2c_begin() -{ - byte i2c_port = command_buffer[0]; - if (! i2c_port) - { - Wire.begin(); -#if defined(__AVR_ATmega328P__) - Wire.setWireTimeout(10,false); - Wire.clearWireTimeoutFlag(); -#endif - } - -#ifdef SECOND_I2C_PORT - else - { - Wire2.begin(); -#if defined(__AVR_ATmega328P__) - Wire2.setWireTimeout(10,false); - Wire2.clearWireTimeoutFlag(); -#endif - } -#endif -} - -void i2c_read() -{ - // data in the incoming message: - // address, [0] - // register, [1] - // number of bytes, [2] - // stop transmitting flag [3] - // i2c port [4] - - int message_size = 0; - byte address = command_buffer[0]; - byte the_register = command_buffer[1]; - - // set the current i2c port if this is for the primary i2c - if (command_buffer[4] == 0) - { - current_i2c_port = &Wire; - } - -#ifdef SECOND_I2C_PORT - // this is for port 2 - if (command_buffer[4] == 1) - { - current_i2c_port = &Wire2; - } -#endif - - current_i2c_port->beginTransmission(address); - current_i2c_port->write((byte)the_register); - current_i2c_port->endTransmission(command_buffer[3]); // default = true - current_i2c_port->requestFrom(address, command_buffer[2]); // all bytes are returned in requestFrom - - // check to be sure correct number of bytes were returned by slave - if (command_buffer[2] < current_i2c_port->available()) - { - byte report_message[4] = {3, I2C_TOO_FEW_BYTES_RCVD, 1, address}; - Serial.write(report_message, 4); - return; - } - else if (command_buffer[2] > current_i2c_port->available()) - { - byte report_message[4] = {3, I2C_TOO_MANY_BYTES_RCVD, 1, address}; - Serial.write(report_message, 4); - return; - } - - // packet length - i2c_report_message[0] = command_buffer[2] + 5; - - // report type - i2c_report_message[1] = I2C_READ_REPORT; - - // i2c_port - i2c_report_message[2] = command_buffer[4]; - - // number of bytes read - i2c_report_message[3] = command_buffer[2]; // number of bytes - - // device address - i2c_report_message[4] = address; - - // device register - i2c_report_message[5] = the_register; - - // append the data that was read - for (message_size = 0; message_size < command_buffer[2] && current_i2c_port->available(); message_size++) - { - i2c_report_message[6 + message_size] = current_i2c_port->read(); - } - // send slave address, register and received bytes - - for (int i = 0; i < message_size + 6; i++) - { - Serial.write(i2c_report_message[i]); - } -} - -void i2c_write() -{ - // command_buffer[0] is the number of bytes to send - // command_buffer[1] is the device address - // command_buffer[2] is the i2c port - // additional bytes to write= command_buffer[3..]; - - // set the current i2c port if this is for the primary i2c - if (command_buffer[2] == 0) - { - current_i2c_port = &Wire; - } - -#ifdef SECOND_I2C_PORT - // this is for port 2 - if (command_buffer[2] == 1) - { - current_i2c_port = &Wire2; - } -#endif -#if defined(__AVR_ATmega328P__) - if (current_i2c_port->getWireTimeoutFlag()) - { - return; - } -#endif - current_i2c_port->beginTransmission(command_buffer[1]); - - // write the data to the device - for (int i = 0; i < command_buffer[0]; i++) - { - current_i2c_port->write(command_buffer[i + 3]); - } - current_i2c_port->endTransmission(); - // delayMicroseconds(70); -} - -/*********************************** - HC-SR04 adding a new device - **********************************/ - -void sonar_new() -{ - // command_buffer[0] = trigger pin, command_buffer[1] = echo pin - sonars[sonars_index].usonic = new NewPing((uint8_t)command_buffer[0], (uint8_t)command_buffer[1], - 2000); - sonars[sonars_index].trigger_pin = command_buffer[0]; - sonars_index++; -} - -/*********************************** - DHT adding a new device - **********************************/ - -void dht_new() -{ - int d_read; - // report consists of: - // 0 - byte count - // 1 - report type - // 2 - dht report subtype - // 3 - pin number - // 4 - error value - - // pre-build an error report in case of a read error - byte report_message[5] = {4, (byte)DHT_REPORT, (byte)DHT_READ_ERROR, (byte)0, (byte)0}; - - dhts[dht_index].dht_sensor = new DHTNEW((uint8_t)command_buffer[0]); - dhts[dht_index].dht_sensor->setType(); - - dhts[dht_index].pin = command_buffer[0]; - d_read = dhts[dht_index].dht_sensor->read(); - - // if read return == zero it means no errors. - if (d_read == 0) - { - dht_index++; - } - else - { - // error found - // send report and release the dht object - - report_message[3] = command_buffer[0]; // pin number - report_message[4] = d_read; - Serial.write(report_message, 5); - delete (dhts[dht_index].dht_sensor); - } -} - - -/*********************************** - Adding a new encoder device - **********************************/ -void encoder_new() -{ - // create new encoder object and get interrupt calback method from map - optEnc[optEncoder_ix].optEnc_sensor = new OpticalEncoder(); - intCB callbackMethod = interruptMap[optEncoder_ix]; - - // command_buffer[0] = encoder pin, command_buffer[1] = Interrupt trigger mode, command_buffer[2] = nr of ticks per rotation - optEnc[optEncoder_ix].optEnc_sensor->setup(command_buffer[0], callbackMethod, command_buffer[1], command_buffer[2]); - optEnc[optEncoder_ix].pin = command_buffer[0]; - optEncoder_ix++; -} - -void stop_all_reports() -{ - stop_reports = true; - delay(20); - Serial.flush(); -} - -void enable_all_reports() -{ - Serial.flush(); - stop_reports = false; - delay(20); -} - -void get_next_command() -{ - byte command; - byte packet_length; - command_descriptor command_entry; - - // clear the command buffer - memset(command_buffer, 0, sizeof(command_buffer)); - - // if there is no command waiting, then return - if (! Serial.available()) - { - return; - } - // get the packet length - packet_length = (byte)Serial.read(); - - while (! Serial.available()) - { - delay(1); - } - - // get the command byte - command = (byte)Serial.read(); - - // uncomment the next line to see the packet length and command - //send_debug_info(packet_length, command); - command_entry = command_table[command]; - - if (packet_length > 1) - { - // get the data for that command - for (int i = 0; i < packet_length - 1; i++) - { - // need this delay or data read is not correct - while (! Serial.available()) - { - delay(1); - } - command_buffer[i] = (byte)Serial.read(); - // uncomment out to see each of the bytes following the command - //send_debug_info(i, command_buffer[i]); - } - } - command_entry.command_func(); -} - -void scan_digital_inputs() -{ - byte value; - - // report message - - // byte 0 = packet length - // byte 1 = report type - // byte 2 = pin number - // byte 3 = value - byte report_message[4] = {3, DIGITAL_REPORT, 0, 0}; - - for (int i = 0; i < MAX_DIGITAL_PINS_SUPPORTED; i++) - { - if (the_digital_pins[i].pin_mode == INPUT || - the_digital_pins[i].pin_mode == INPUT_PULLUP) - { - if (the_digital_pins[i].reporting_enabled) - { - // if the value changed since last read - value = (byte)digitalRead(the_digital_pins[i].pin_number); - if (value != the_digital_pins[i].last_value) - { - the_digital_pins[i].last_value = value; - report_message[2] = (byte)i; - report_message[3] = value; - Serial.write(report_message, 4); - } - } - } - } -} - -void scan_analog_inputs() -{ - int value; - - // report message - - // byte 0 = packet length - // byte 1 = report type - // byte 2 = pin number - // byte 3 = high order byte of value - // byte 4 = low order byte of value - - byte report_message[5] = {4, ANALOG_REPORT, 0, 0, 0}; - uint8_t adjusted_pin_number; - int differential; - - current_millis = millis(); - if (current_millis - previous_millis > analog_sampling_interval) - { - previous_millis += analog_sampling_interval; - for (int i = 0; i < MAX_ANALOG_PINS_SUPPORTED; i++) - { - if (the_analog_pins[i].pin_mode == AT_ANALOG) - { - if (the_analog_pins[i].reporting_enabled) - { - // if the value changed since last read - // adjust pin number for the actual read - adjusted_pin_number = (uint8_t)(analog_read_pins[i]); - value = analogRead(adjusted_pin_number); - differential = abs(value - the_analog_pins[i].last_value); - if (differential >= the_analog_pins[i].differential) - { - //trigger value achieved, send out the report - the_analog_pins[i].last_value = value; - // input_message[1] = the_analog_pins[i].pin_number; - report_message[2] = (byte)i; - report_message[3] = highByte(value); // get high order byte - report_message[4] = lowByte(value); - Serial.write(report_message, 5); - delay(1); - } - } - } - } - } -} - -void scan_sonars() -{ - unsigned int distance; - - if (sonars_index) - { - sonar_current_millis = millis(); - if (sonar_current_millis - sonar_previous_millis > sonar_scan_interval) - { - sonar_previous_millis += sonar_scan_interval; - distance = sonars[last_sonar_visited].usonic->ping() / US_ROUNDTRIP_CM; - if (distance != sonars[last_sonar_visited].last_value) - { - sonars[last_sonar_visited].last_value = distance; - - // byte 0 = packet length - // byte 1 = report type - // byte 2 = trigger pin number - // byte 3 = distance high order byte - // byte 4 = distance low order byte - byte report_message[5] = {4, SONAR_DISTANCE, sonars[last_sonar_visited].trigger_pin, - (byte)(distance >> 8), (byte)(distance & 0xff) - }; - Serial.write(report_message, 5); - } - last_sonar_visited++; - if (last_sonar_visited == sonars_index) - { - last_sonar_visited = 0; - } - } - } -} - -void scan_dhts() -{ - // prebuild report for valid data - // reuse the report if a read command fails - - // data returned is in floating point form - 4 bytes - // each for humidity and temperature - - // byte 0 = packet length - // byte 1 = report type - // byte 2 = report sub type - DHT_DATA or DHT_ERROR - // btye 3 = pin number - // byte 4 = humidity high order byte for data or error value - // byte 5 = humidity byte 2 - // byte 6 = humidity byte 3 - // byte 7 = humidity byte 4 - // byte 8 = temperature high order byte for data or - // byte 9 = temperature byte 2 - // byte 10 = temperature byte 3 - // byte 11 = temperature byte 4 - byte report_message[12] = {11, DHT_REPORT, DHT_DATA, 0, 0, 0, 0, 0, 0, 0, 0, 0}; - - byte d_read; - - float dht_data; - - // are there any dhts to read? - if (dht_index) - { - // is it time to do the read? This should occur every 2 seconds - dht_current_millis = millis(); - if (dht_current_millis - dht_previous_millis > dht_scan_interval) - { - // update for the next scan - dht_previous_millis += dht_scan_interval; - - // read and report all the dht sensors - for (int i = 0; i < dht_index; i++) - { - report_message[3] = dhts[i].pin; - // get humidity - dht_data = dhts[i].dht_sensor->getHumidity(); - memcpy(&report_message[4], &dht_data, sizeof dht_data); - - // get temperature - dht_data = dhts[i].dht_sensor->getTemperature(); - memcpy(&report_message[8], &dht_data, sizeof dht_data); - - Serial.write(report_message, 12); - - // now read do a read for this device for next go around - d_read = dhts[i].dht_sensor->read(); - - if (d_read) - { - // error found - // send report - //send_debug_info(1, 1); - report_message[0] = 4; - report_message[1] = DHT_REPORT; - report_message[2] = DHT_READ_ERROR; - report_message[3] = dhts[i].pin; // pin number - report_message[4] = d_read; - Serial.write(report_message, 5); - } - } - } - } -} - -void scan_encoders() -{ - // byte 0 = packet length - // byte 1 = report type - // byte 2 = pin number - // byte 3 = encoder ticks high order byte for data or error value - // byte 4 = encoder ticks byte 2 - // byte 5 = encoder ticks byte 3 - // byte 6 = encoder ticks byte 4 - byte report_message[7] = {6, ENCODER_REPORT, 0, 0, 0, 0, 0}; - - long optEnc_return_val = 0; - - if (optEncoder_ix) { - optenc_current_millis = millis(); - if (optenc_current_millis - optenc_previous_millis > optenc_scan_interval) { - optenc_previous_millis += optenc_scan_interval; - - for (int i = 0; i < optEncoder_ix; ++i) { - optEnc_return_val = optEnc[i].optEnc_sensor->getPosition(); - - if (optEnc_return_val != optEnc[i].last_value) - { - optEnc[i].last_value = optEnc_return_val; - report_message[2] = optEnc[i].pin; - - //copy bytes to message - memcpy(&report_message[3], &optEnc_return_val, sizeof optEnc_return_val); - Serial.write(report_message, 7); - } - } - } - } -} - -void reset_data() { - // reset the data structures - - // fist stop all reporting - stop_all_reports(); - - current_millis = 0; // for analog input loop - previous_millis = 0; // for analog input loop - analog_sampling_interval = 19; - - // detach any attached servos - for (int i = 0; i < MAX_SERVOS; i++) - { - if (servos[i].attached() == true) - { - servos[i].detach(); - } - } - - sonars_index = 0; // reset the index into the sonars array - - sonar_current_millis = 0; // for analog input loop - sonar_previous_millis = 0; // for analog input loop - sonar_scan_interval = 33; // Milliseconds between sensor pings - - dht_index = 0; // index into dht array - - dht_current_millis = 0; // for analog input loop - dht_previous_millis = 0; // for analog input loop - dht_scan_interval = 2000; // scan dht's every 2 seconds - - // Reset optical encoder timers and index - optEncoder_ix = 0; - optenc_current_millis = 0; // for encoder input loop - optenc_previous_millis = millis(); // for encoder input loop - optenc_scan_interval = 10; // scan encoders every x ms - - init_pin_structures(); - - memset(sonars, 0, sizeof(sonars)); - memset(dhts, 0, sizeof(dhts)); - memset(optEnc, 0, sizeof(optEnc)); - enable_all_reports(); -} - -void init_pin_structures() { - // create an array of pin_descriptors for 100 pins - // establish the digital pin array - for (byte i = 0; i < MAX_DIGITAL_PINS_SUPPORTED; i++) - { - the_digital_pins[i].pin_number = i; - the_digital_pins[i].pin_mode = AT_MODE_NOT_SET; - the_digital_pins[i].reporting_enabled = false; - the_digital_pins[i].last_value = -1; - } - - // establish the analog pin array - for (byte i = 0; i < MAX_ANALOG_PINS_SUPPORTED; i++) - { - the_analog_pins[i].pin_number = i; - the_analog_pins[i].pin_mode = AT_MODE_NOT_SET; - the_analog_pins[i].reporting_enabled = false; - the_analog_pins[i].last_value = -1; - the_analog_pins[i].differential = 0; - } -} - -void setup() -{ - // initialize the servo allocation map table - init_pin_structures(); - - Serial.begin(1000000); -} - -void loop() -{ - // keep processing incoming commands - get_next_command(); - - if (!stop_reports) - { // stop reporting - scan_digital_inputs(); - scan_analog_inputs(); - scan_sonars(); - scan_dhts(); - scan_encoders(); - } -} diff --git a/include/README b/include/README new file mode 100644 index 0000000..194dcd4 --- /dev/null +++ b/include/README @@ -0,0 +1,39 @@ + +This directory is intended for project header files. + +A header file is a file containing C declarations and macro definitions +to be shared between several project source files. You request the use of a +header file in your project source file (C, C++, etc) located in `src` folder +by including it, with the C preprocessing directive `#include'. + +```src/main.c + +#include "header.h" + +int main (void) +{ + ... +} +``` + +Including a header file produces the same results as copying the header file +into each source file that needs it. Such copying would be time-consuming +and error-prone. With a header file, the related declarations appear +in only one place. If they need to be changed, they can be changed in one +place, and programs that include the header file will automatically use the +new version when next recompiled. The header file eliminates the labor of +finding and changing all the copies as well as the risk that a failure to +find one copy will result in inconsistencies within a program. + +In C, the usual convention is to give header files names that end with `.h'. +It is most portable to use only letters, digits, dashes, and underscores in +header file names, and at most one dot. + +Read more about using header files in official GCC documentation: + +* Include Syntax +* Include Operation +* Once-Only Headers +* Computed Includes + +https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html diff --git a/include/Telemetrix4Arduino.h b/include/Telemetrix4Arduino.h new file mode 100644 index 0000000..c9d85d9 --- /dev/null +++ b/include/Telemetrix4Arduino.h @@ -0,0 +1,9 @@ +#pragma once +#include +// #include +// maximum length of a command in bytes +#define MAX_COMMAND_LENGTH 30 + +extern uint8_t command_buffer[MAX_COMMAND_LENGTH]; + +template void send_message(const uint8_t (&message)[N]); \ No newline at end of file diff --git a/include/boards/esp32devkit.hpp b/include/boards/esp32devkit.hpp new file mode 100644 index 0000000..deefe35 --- /dev/null +++ b/include/boards/esp32devkit.hpp @@ -0,0 +1,17 @@ +#pragma once + +#if defined(ARDUINO_ARCH_ESP32) +#include +#include +// This board does not have a normal list of analog pins +#define A1 2047 +#define A2 2047 +#define A8 2047 +#define A9 2047 +void hw_init(); + +#define SECOND_I2C_PORT 1 +#define SECOND_I2C_PORT_SDA 16 +#define SECOND_I2C_PORT_SCL 17 +extern TwoWire Wire2; // Use GPIO 16 and 17 for I2C on ESP32 +#endif \ No newline at end of file diff --git a/include/boards/itsybitsy_m4.hpp b/include/boards/itsybitsy_m4.hpp new file mode 100644 index 0000000..607d967 --- /dev/null +++ b/include/boards/itsybitsy_m4.hpp @@ -0,0 +1,22 @@ +#pragma once + +#include + +#if defined(ARDUINO_ARCH_SAMD) && defined(ARDUINO_ITSYBITSY_M4) +const auto A7 = 2047; +const auto A8 = 2047; +const auto A9 = 2047; +const auto A10 = 2047; +const auto A11 = 2047; +const auto A12 = 2047; +const auto A13 = 2047; +const auto A14 = 2047; +const auto A15 = 2047; +const auto A16 = 2047; +const auto A17 = 2047; +const auto A18 = 2047; +const auto A19 = 2047; + +const auto MAX_SERVOS = 0; +void hw_init(); +#endif \ No newline at end of file diff --git a/include/boards/nanoatmega.hpp b/include/boards/nanoatmega.hpp new file mode 100644 index 0000000..94a771a --- /dev/null +++ b/include/boards/nanoatmega.hpp @@ -0,0 +1,20 @@ +#pragma once +#include + +#if defined(ARDUINO_ARCH_AVR) && defined(ARDUINO_AVR_NANO) + +const auto A8 = 2047; +const auto A9 = 2047; +const auto A10 = 2047; +const auto A11 = 2047; +const auto A12 = 2047; +const auto A13 = 2047; +const auto A14 = 2047; +const auto A15 = 2047; +const auto A16 = 2047; +const auto A17 = 2047; +const auto A18 = 2047; +const auto A19 = 2047; +#define MAX_SERVOS 4 // PWM pins on Nano +void hw_init(); +#endif \ No newline at end of file diff --git a/include/boards/pico.hpp b/include/boards/pico.hpp new file mode 100644 index 0000000..c61cde7 --- /dev/null +++ b/include/boards/pico.hpp @@ -0,0 +1,42 @@ +#pragma once +#include + +// Maybe some more are required, for pico2 and pico1w +#if defined(RASPBERRY_PI_PICO) || defined(ARDUINO_RASPBERRY_PI_PICO_W) || \ + defined(ARDUINO_ARCH_RP2040) + +#include +#include + +const auto A4 = 2047; +const auto A5 = 2047; +const auto A6 = 2047; +const auto A7 = 2047; +const auto A8 = 2047; +const auto A9 = 2047; +const auto A10 = 2047; +const auto A11 = 2047; +const auto A12 = 2047; +const auto A13 = 2047; +const auto A14 = 2047; +const auto A15 = 2047; +const auto A16 = 2047; +const auto A17 = 2047; +const auto A18 = 2047; +const auto A19 = 2047; +#define SECOND_I2C_PORT 1 +// Change the pins to match SDA and SCL for your board +#define SECOND_I2C_PORT_SDA 10 +#define SECOND_I2C_PORT_SCL 11 +#if !defined(ARDUINO_RASPBERRY_PI_PICO_2W) +extern TwoWire Wire2; + +#define MAX_SERVOS 12 // according to the servo lib +#else +#define MAX_SERVOS 0 +extern TwoWire Wire2; // Use GPIO 10 and 11 for I2C on Pico 2W +#endif +#define I2C_COUNT 2 +#define MAX_SONARS 6 // the current library does not work somehow on pico +void hw_init(); +#endif \ No newline at end of file diff --git a/include/boards/stm32blackpill.hpp b/include/boards/stm32blackpill.hpp new file mode 100644 index 0000000..9cfaf5b --- /dev/null +++ b/include/boards/stm32blackpill.hpp @@ -0,0 +1,27 @@ +#pragma once +#include +#if defined(ARDUINO_ARCH_STM32) && defined(ARDUINO_BLACKPILL_F103C8) + +const auto A10 = 2047; +const auto A11 = 2047; +const auto A12 = 2047; +const auto A13 = 2047; +const auto A14 = 2047; +const auto A15 = 2047; +const auto A16 = 2047; +const auto A17 = 2047; +const auto A18 = 2047; +const auto A19 = 2047; +const auto MAX_SERVOS = 8; +void hw_init(); +#endif + +#if defined(ARDUINO_ARCH_STM32) && defined(ARDUINO_BLACKPILL_F303CC) +const auto A15 = 2047; +const auto A16 = 2047; +const auto A17 = 2047; +const auto A18 = 2047; +const auto A19 = 2047; +const auto MAX_SERVOS = 8; +void hw_init(); +#endif diff --git a/include/commands.hpp b/include/commands.hpp new file mode 100644 index 0000000..8b285ab --- /dev/null +++ b/include/commands.hpp @@ -0,0 +1,63 @@ +#pragma once + +enum MESSAGE_IN_TYPE : uint8_t { + SERIAL_LOOP_BACK = 0, + SET_PIN_MODE = 1, + DIGITAL_WRITE = 2, + PWM_WRITE = 3, + MODIFY_REPORTING = 4, + GET_FIRMWARE_VERSION = 5, + GET_UNIQUE_ID = 6, + SERVO_ATTACH = 7, // = unused + SERVO_WRITE = 8, // = unused + SERVO_DETACH = 9, // = unused + I2C_BEGIN = 10, + I2C_READ = 11, + I2C_WRITE = 12, + SONAR_NEW = 13, + DHT_NEW = 14, + STOP_ALL_REPORTS = 15, + ENABLE_ALL_REPORTS = 16, + RESET_DATA = 17, + RESET_BOARD = 18, + INITIALIZE_NEO_PIXELS = 19, + SHOW_NEO_PIXELS = 20, + SET_NEO_PIXEL = 21, + CLEAR_ALL_NEO_PIXELS = 22, + FILL_NEO_PIXELS = 23, + SPI_INIT = 24, + SPI_WRITE_BLOCKING = 25, + SPI_READ_BLOCKING = 26, + SPI_SET_FORMAT = 27, + SPI_CS_CONTROL = 28, + SET_SCAN_DELAY = 29, + ENCODER_NEW = 30, + SENSOR_NEW = 31, + GET_ID = 35, + SET_ID = 36, + FEATURE_CHECK = 37, + MAX_IN_MESSAGE_TYPE +}; + +enum MESSAGE_OUT_TYPE : uint8_t { + SERIAL_LOOP_BACK_REPORT = 0, + DIGITAL_REPORT = 2, + ANALOG_REPORT = 3, + FIRMWARE_REPORT = 5, + REPORT_UNIQUE_ID = 6, + SERVO_UNAVAILABLE = 7, // for the future + I2C_WRITE_REPORT = 8, + I2C_READ_FAILED = 9, + I2C_READ_REPORT = 10, + SONAR_DISTANCE = 11, + DHT_REPORT = 12, + SPI_REPORT = 13, + ENCODER_REPORT = 14, + DEBUG_PRINT = 99, + SENSOR_REPORT = 20, + SENSOR_MAIN_REPORT = 21, + PONG_REPORT = 32, + MODULE_MAIN_REPORT = 33, + MODULE_REPORT = 34, + MAX_OUT_MESSAGE_TYPE +}; diff --git a/include/config.hpp b/include/config.hpp new file mode 100644 index 0000000..66f1ed5 --- /dev/null +++ b/include/config.hpp @@ -0,0 +1,17 @@ +#pragma once +#include "boards/esp32devkit.hpp" +#include "boards/itsybitsy_m4.hpp" +#include "boards/nanoatmega.hpp" +#include "boards/pico.hpp" +#include "boards/stm32blackpill.hpp" +#ifndef MAX_SONARS +#define MAX_SONARS 6 +#endif + +#ifndef ENABLE_ADAFRUIT_WATCHDOG +#define ENABLE_ADAFRUIT_WATCHDOG 1 +#endif + +#ifndef I2C_COUNT +#define I2C_COUNT 1 +#endif \ No newline at end of file diff --git a/include/i2c.hpp b/include/i2c.hpp new file mode 100644 index 0000000..3431ab4 --- /dev/null +++ b/include/i2c.hpp @@ -0,0 +1,54 @@ +#pragma once +#include +#include +void i2c_begin(); +void i2c_read(); +void i2c_write(); + +// i2c report buffer offsets +#define I2C_PACKET_LENGTH 0 +#define I2C_REPORT_ID 1 +#define I2C_REPORT_PORT 2 +#define I2C_REPORT_DEVICE_ADDRESS 3 +#define I2C_REPORT_READ_REGISTER 4 +#define I2C_REPORT_READ_NUMBER_DATA_BYTES 5 + +#define I2C_ERROR_REPORT_LENGTH 4 +#define I2C_ERROR_REPORT_NUM_OF_BYTE_TO_SEND 5 +// i2c_common +#define I2C_PORT 1 +#define I2C_DEVICE_ADDRESS 2 // read and write + +// i2c_init +#define I2C_SDA_GPIO_PIN 2 +#define I2C_SCL_GPIO_PIN 3 + +// i2c_read +#define I2C_READ_MESSAGE_ID 3 +#define I2C_READ_REGISTER 4 +#define I2C_READ_LENGTH 5 +#define I2C_READ_NO_STOP_FLAG 6 + +// I2c_write +#define I2C_WRITE_MESSAGE_ID 3 +#define I2C_WRITE_NUMBER_OF_BYTES 4 +#define I2C_WRITE_NO_STOP_FLAG 5 +#define I2C_WRITE_BYTES_TO_WRITE 6 + +// This defines how many bytes there are +// that precede the first byte read position +// in the i2c report message buffer. +#define I2C_READ_DATA_BASE_BYTES 6 + +// Start of i2c data read within the message buffer +#define I2C_READ_START_OF_DATA 7 + +// Indicator that no i2c register is being specified in the command +#define I2C_NO_REGISTER 254 + +extern TwoWire *i2c_buses[I2C_COUNT]; + +bool write_i2c(int i2c_port, int device_address, const uint8_t *data, + size_t length); +bool read_i2c(int i2c_port, int device_address, const uint8_t *registers, + size_t register_length, uint8_t *data, size_t data_length); \ No newline at end of file diff --git a/include/main.hpp b/include/main.hpp new file mode 100644 index 0000000..0832982 --- /dev/null +++ b/include/main.hpp @@ -0,0 +1,64 @@ +#pragma once + +#include +void get_unique_id(); + +// Old code +extern void serial_loopback(); + +extern void set_pin_mode(); + +extern void digital_write(); + +extern void pwm_write(); + +extern void modify_reporting(); + +extern void get_firmware_version(); + +extern void are_you_there(); + +extern void servo_attach(); + +extern void servo_write(); + +extern void servo_detach(); + +extern void sonar_new(); + +extern void dht_new(); + +extern void encoder_new(); + +extern void stop_all_reports(); + +extern void set_analog_scanning_interval(); + +extern void enable_all_reports(); + +extern void reset_data(); + +extern void init_pin_structures(); + +void ping(); + +void feature_detection(); + +void send_debug_info(byte id, int value); + +void module_new(); +void module_data(); +void sensor_new(); +enum PIN_MODES : uint8_t { + NOT_SET = 255, + INPUT_MODE = 0, + OUTPUT_MODE = 1, + PWM = 2, + INPUT_PULL_UP = 3, + INPUT_PULL_DOWN = 4, + ANALOG_INPUT = 5, + SONAR_MODE = 7, + DHT_MODE = 8 +}; + +void send_message(const uint8_t *message, size_t length); \ No newline at end of file diff --git a/include/modules.hpp b/include/modules.hpp new file mode 100644 index 0000000..6f03485 --- /dev/null +++ b/include/modules.hpp @@ -0,0 +1,51 @@ +#pragma once +#include +#ifndef MAX_MODULES_COUNT +#define MAX_MODULES_COUNT 4 // Max number of modules that can be added +#endif // MAX_MODULES_COUNT + +#if MAX_MODULES_COUNT > 0 +/***********************************************/ +/***************MODULES*************************/ +void module_new_i(uint8_t command_buffer[], size_t packet_size); + +void module_data_i(uint8_t command_buffer[], size_t packet_size); + +enum MODULE_TYPES : uint8_t { // Max 255 modules, but will always fit in a + // single byte! + PCA9685 = 0, // 16x 12bit PWM + HIWONDER_SERVO = 1, + SHUTDOWN_RELAY = 2, + TMX_SSD1306 = 3, + MAX_MODULES +}; + +class Module { +public: + virtual void readModule() = 0; + virtual void writeModule(uint8_t data[], size_t size) = 0; + virtual void resetModule() = 0; + bool stop = false; + void publishData(const uint8_t data[], size_t size); + + int num = 0; + MODULE_TYPES type = MODULE_TYPES::MAX_MODULES; + // called at every loop, only used when needed (Oled update) + virtual void updModule(){}; +}; +void scan_modules(); +void upd_modules(); +extern Module *modules[MAX_MODULES_COUNT]; // Array of pointers to modules +extern size_t module_count; // Number of modules in the array + +#include "modules/ssd1306.hpp" // Include the SSD1306 module header + +#else + +// No modules supported, so we define empty functions +inline void module_new_i(uint8_t command_buffer[], size_t packet_size) {} +inline void module_data_i(uint8_t command_buffer[], size_t packet_size) {} +inline void scan_modules() {} +inline void upd_modules() {} + +#endif \ No newline at end of file diff --git a/include/modules/ssd1306.hpp b/include/modules/ssd1306.hpp new file mode 100644 index 0000000..434e445 --- /dev/null +++ b/include/modules/ssd1306.hpp @@ -0,0 +1,29 @@ +#pragma once + +#include +#include +class TmxSSD1306 : public Module { +public: + TmxSSD1306(uint8_t data[], size_t packet_size) { + num = data[0]; + type = MODULE_TYPES::TMX_SSD1306; + // TODO: this is just for testing the module system. + } + void readModule() override { + // probably nothing to read + } + void writeModule(uint8_t data[], size_t size) override { + // // TODO: implement writing to the SSD1306 display + // send_debug_info(30, size); + // send_debug_info(31, data[0]); + if (data[0] == 1) { // test reply on the "booting..." text commands. + uint8_t display_data[32] = {1, 10, 10, 1}; + + this->publishData(display_data, 4); + } + } + void resetModule() override {} + void updModule() override { + // MAYBE: write a few bytes to the display, or not, depends on lib. + } +}; \ No newline at end of file diff --git a/include/sensors.hpp b/include/sensors.hpp new file mode 100644 index 0000000..3ffc56a --- /dev/null +++ b/include/sensors.hpp @@ -0,0 +1,50 @@ +#pragma once +#include +#ifndef MAX_SENSORS_COUNT +#define MAX_SENSORS_COUNT 4 // Max number of modules that can be added +#endif // MAX_MODULES_COUNT + +#if MAX_SENSORS_COUNT > 0 +/*****************************************************************************/ +/****SENSORS*/ +/*****************************************************************************/ + +enum SENSOR_TYPES : uint8_t { // Max 255 sensors, but will always fit in a + // single byte! + GPS = 0, + LOAD_CELL = 1, + MPU_9250 = 2, + TOF_VL53 = 3, + VEML6040 = 4, // Color sensor + ADXL345 = 5, // 3 axis accel + INA226a = 6, + HMC5883l = 7, + AS5600_t = 8, // Magnetic angle sensor + MAX_SENSORS +}; + +class Sensor { +public: + virtual void readSensor() = 0; + virtual void resetSensor() = 0; + bool stop = false; + void writeSensorData(const uint8_t data[], size_t size); + static Sensor *create(uint8_t *data, size_t size) { + // This function is used to create a sensor object based on the type + // and data provided. It should be overridden in derived classes. + return nullptr; + } + int num; + SENSOR_TYPES type = SENSOR_TYPES::MAX_SENSORS; +}; + +const int SENSORS_MAX_SETTINGS_A = 6; +void sensor_new_i(uint8_t command_buffer[], size_t packet_size); +void readSensors(); + +#else + +// No sensors supported, so we define empty functions +void sensor_new_i(uint8_t command_buffer[], size_t packet_size); +void readSensors(); +#endif \ No newline at end of file diff --git a/include/sensors/veml6040.hpp b/include/sensors/veml6040.hpp new file mode 100644 index 0000000..f318743 --- /dev/null +++ b/include/sensors/veml6040.hpp @@ -0,0 +1,67 @@ +#pragma once + +#include + +#if MAX_SENSORS_COUNT > 0 +#include +#include +class VEML6040_Sensor : public Sensor { +public: + VEML6040_Sensor(uint8_t settings[], size_t settings_size) { + // Initialize the sensor with the provided settings + if (settings_size > 0) { + i2c_port = settings[0]; // Assuming first byte is I2C port + } + this->i2c_addr = 0x10; // Default I2C address for VEML6040 + init_sequence(); + } + void readSensor() { + if (this->stop) { + return; + } + uint8_t data[8]; + uint8_t sensor_data[2]; + bool ok = true; + size_t data_offset = 0; + for (uint8_t reg = 0x08; reg <= 0x0B; + reg++) { // read the 4 registers and add the data to the full data + // vector + uint8_t regs[1] = {reg}; + ok &= read_i2c(this->i2c_port, this->i2c_addr, regs, 1, sensor_data, 2); + // Flip the order to make it match the rest. + data[0 + data_offset] = sensor_data[1]; + data[1 + data_offset] = sensor_data[0]; + data_offset += 2; + } + + this->writeSensorData(data, 8); + if (!ok) { + this->stop = true; + } + } + void resetSensor(){}; + static Sensor *create(uint8_t *data, size_t size) { + if (size < 1) { + return nullptr; // Not enough data to create sensor + } + return new VEML6040_Sensor(data, size); + } + +private: + void init_sequence() { + uint8_t data[2] = {0, 0x21}; + bool ok = write_i2c(this->i2c_port, this->i2c_addr, data, 2); + // send_debug_info(181, ok); + delayMicroseconds(100); + data[1] = 0x20; // 0x20 = 0b0010'0000, 100 time, no stop bit + ok &= write_i2c(this->i2c_port, this->i2c_addr, data, 2); + // send_debug_info(182, ok); + if (!ok) { + this->stop = true; + } + } + int i2c_port = 0; + int i2c_addr = 0x10; +}; + +#endif \ No newline at end of file diff --git a/lib/OpticalEncoder/OpticalEncoder.h b/lib/OpticalEncoder/OpticalEncoder.h new file mode 100644 index 0000000..adf2eb4 --- /dev/null +++ b/lib/OpticalEncoder/OpticalEncoder.h @@ -0,0 +1,88 @@ +class OpticalEncoder { + +public: + void setup(uint8_t pinNr, void (*ISR_callback)(void), int value, + int ticksPerRotation); + void handleInterrupt(void); + long getSpeed(void); + uint8_t getPin(void); + int32_t getPosition(void); + void resetPosition(void); + bool getDirection(void); + void setDirection(bool forward); + +private: + volatile long _encoder0Pos = 0; + volatile bool _movingForward = true; + uint8_t tach1Pin; + + long newposition = 0; + long oldposition = 0; + unsigned long newtime = 0; + unsigned long oldtime = 0; + long speed = 0; + int nrTicks = 20; + unsigned long prevmillis = 0; + + void (*ISR_callback)(); +}; + +void OpticalEncoder::setup(uint8_t pinNr, void (*ISR_callback)(void), int value, + int ticksPerRotation) { + tach1Pin = pinNr; + nrTicks = ticksPerRotation; + pinMode(tach1Pin, INPUT_PULLUP); + +#ifdef digitalPinToInterrupt // Use macro defined in pins_arduino.h + attachInterrupt(digitalPinToInterrupt(tach1Pin), ISR_callback, FALLING); +#elif defined(__AVR_ATmega32U4__) // Arduino Leonardo + attachInterrupt(1, ISR_callback, FALLING); // pin 2 +#else + attachInterrupt(0, ISR_callback, FALLING); // pin 2 +#endif +} + +inline void OpticalEncoder::handleInterrupt(void) { + unsigned long currmillis = millis(); + if (currmillis - prevmillis > 2) { + if (_movingForward) { + _encoder0Pos++; + } else { + _encoder0Pos--; + } + } + prevmillis = currmillis; +} + +uint8_t OpticalEncoder::getPin(void) { return tach1Pin; } + +int32_t OpticalEncoder::getPosition() { + // noInterrupts(); + newposition = _encoder0Pos; + // interrupts(); + return newposition; +} + +void OpticalEncoder::resetPosition() { + noInterrupts(); + _encoder0Pos = 0; + interrupts(); + newposition = 0; + oldposition = 0; +} + +bool OpticalEncoder::getDirection() { return _movingForward; } + +void OpticalEncoder::setDirection(bool forward) { _movingForward = forward; } + +long OpticalEncoder::getSpeed() { + newtime = millis(); + speed = (abs(getPosition()) - abs(oldposition)) * 60000 / + ((newtime - oldtime) * + nrTicks); // 1000(to conver milli sec to sec)*60(to convert sec to + // minutes)/6(total number of pulses per rotation)=10000 + // (pulses per milli sec to rpm) + oldposition = newposition; + oldtime = newtime; + return speed; +} diff --git a/lib/OpticalEncoder/examples/DoubleEncoder.ino b/lib/OpticalEncoder/examples/DoubleEncoder.ino new file mode 100644 index 0000000..00f865a --- /dev/null +++ b/lib/OpticalEncoder/examples/DoubleEncoder.ino @@ -0,0 +1,39 @@ +#include + +OpticalEncoder *encoders[2]; +uint8_t fanpins[2] = {2, 3}; +long sum_speed[2] = {0, 0}; +int nr_loops = 0; + +void setup() +{ + Serial.begin(115200); + encoders[0] = new OpticalEncoder(); + encoders[1] = new OpticalEncoder(); + encoders[0]->setup(fanpins[0], []{encoders[0]->handleInterrupt();}, FALLING, 20); + encoders[1]->setup(fanpins[1], []{encoders[1]->handleInterrupt();}, FALLING, 20); +} + +void loop() +{ + static uint32_t lastMillis = 0; + static const uint32_t minuteMillis = millis(); + if (millis() - minuteMillis < 10000UL) { + if (millis() - lastMillis > 100UL) + { + sum_speed[0] += encoders[0]->getSpeed(); + sum_speed[1] += encoders[1]->getSpeed(); + nr_loops++; + lastMillis = millis(); + } + } else { + Serial.println(F("AVG ENCODER 1: "));Serial.println(floor(sum_speed[0]/nr_loops + 0.5), 0); + Serial.println(F("Last Speed ENCODER 1: "));Serial.println(floor(encoders[0]->getSpeed() + 0.5), 0); + Serial.println(F("NrTicks ENCODER 1: "));Serial.println(encoders[0]->getPosition()); + + Serial.println(F("AVG ENCODER 2: "));Serial.println(floor(sum_speed[1]/nr_loops + 0.5), 0); + Serial.println(F("Last Speed ENCODER 2: "));Serial.println(floor(encoders[1]->getSpeed() + 0.5), 0); + Serial.println(F("NrTicks ENCODER 2: "));Serial.println(encoders[1]->getPosition()); + while(1){}; //last line of main loop + } +} diff --git a/lib/OpticalEncoder/keywords.txt b/lib/OpticalEncoder/keywords.txt new file mode 100644 index 0000000..ce6b9b4 --- /dev/null +++ b/lib/OpticalEncoder/keywords.txt @@ -0,0 +1,22 @@ +################################################ +# Syntax Coloring Map For Optical Encoder Library +################################################ + +################################################ +# Datatypes (KEYWORD1) +################################################ + +OpticalEncoder KEYWORD1 + +################################################ +# Methods and Functions (KEYWORD2) +################################################ + +setup KEYWORD2 +handleInterrupt KEYWORD2 +getSpeed KEYWORD2 +getPin KEYWORD2 +getPosition KEYWORD2 +resetPosition KEYWORD2 +getDirection KEYWORD2 +setDirection KEYWORD2 diff --git a/lib/README b/lib/README new file mode 100644 index 0000000..6debab1 --- /dev/null +++ b/lib/README @@ -0,0 +1,46 @@ + +This directory is intended for project specific (private) libraries. +PlatformIO will compile them to static libraries and link into executable file. + +The source code of each library should be placed in a an own separate directory +("lib/your_library_name/[here are source files]"). + +For example, see a structure of the following two libraries `Foo` and `Bar`: + +|--lib +| | +| |--Bar +| | |--docs +| | |--examples +| | |--src +| | |- Bar.c +| | |- Bar.h +| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html +| | +| |--Foo +| | |- Foo.c +| | |- Foo.h +| | +| |- README --> THIS FILE +| +|- platformio.ini +|--src + |- main.c + +and a contents of `src/main.c`: +``` +#include +#include + +int main (void) +{ + ... +} + +``` + +PlatformIO Library Dependency Finder will find automatically dependent +libraries scanning project source files. + +More information about PlatformIO Library Dependency Finder +- https://docs.platformio.org/page/librarymanager/ldf.html diff --git a/library.properties b/library.properties deleted file mode 100644 index caf50bf..0000000 --- a/library.properties +++ /dev/null @@ -1,10 +0,0 @@ -name=Telemetrix4Arduino -version=1.12 -author=Alan Yorinks -maintainer=https://github.com/MrYsLab/ -sentence=The server for the Telemetrix Project. -paragraph=This sketch is a server for the telemetrix and telemetrix-aio Python clients. It provides remote control and monitoring of Arduino-Core devices. -category=Device Control -url=https://github.com/MrYsLab/Telemetrix4Arduino -depends=Ultrasonic,DHTNEW -architectures=* diff --git a/out.txt b/out.txt new file mode 100644 index 0000000..9d2ab42 --- /dev/null +++ b/out.txt @@ -0,0 +1,1292 @@ +[test-clang-format/cpp_style_check] ⭐ Run Set up job +[test-clang-format/cpp_style_check] 🚀 Start image=catthehacker/ubuntu:act-latest +[Arduino Compile/build-2 ] ⭐ Run Set up job +[Arduino Compile/build-2 ] 🚀 Start image=catthehacker/ubuntu:act-latest +[Arduino Compile/build-3 ] ⭐ Run Set up job +[Arduino Compile/build-3 ] 🚀 Start image=catthehacker/ubuntu:act-latest +[Arduino Compile/build-4 ] ⭐ Run Set up job +[Arduino Compile/build-4 ] 🚀 Start image=catthehacker/ubuntu:act-latest +[Arduino Compile/build-1 ] ⭐ Run Set up job +[Arduino Compile/build-1 ] 🚀 Start image=catthehacker/ubuntu:act-latest +[Arduino Compile/build-2 ] 🐳 docker pull image=catthehacker/ubuntu:act-latest platform= username= forcePull=true +[Arduino Compile/build-4 ] 🐳 docker pull image=catthehacker/ubuntu:act-latest platform= username= forcePull=true +[Arduino Compile/build-1 ] 🐳 docker pull image=catthehacker/ubuntu:act-latest platform= username= forcePull=true +[Arduino Compile/build-3 ] 🐳 docker pull image=catthehacker/ubuntu:act-latest platform= username= forcePull=true +[test-clang-format/cpp_style_check] 🐳 docker pull image=catthehacker/ubuntu:act-latest platform= username= forcePull=true +[Arduino Compile/build-3 ] 🐳 docker create image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-1 ] 🐳 docker create image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-2 ] 🐳 docker create image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-3 ] 🐳 docker run image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-1 ] 🐳 docker run image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[test-clang-format/cpp_style_check] 🐳 docker create image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-2 ] 🐳 docker run image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[test-clang-format/cpp_style_check] 🐳 docker run image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-4 ] 🐳 docker create image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-3 ] 🐳 docker exec cmd=[node --no-warnings -e console.log(process.execPath)] user= workdir= +[Arduino Compile/build-2 ] 🐳 docker exec cmd=[node --no-warnings -e console.log(process.execPath)] user= workdir= +[Arduino Compile/build-1 ] 🐳 docker exec cmd=[node --no-warnings -e console.log(process.execPath)] user= workdir= +[Arduino Compile/build-2 ] ✅ Success - Set up job +[Arduino Compile/build-4 ] 🐳 docker run image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-2 ] ☁ git clone 'https://github.com/actions/setup-python' # ref=v5 +[Arduino Compile/build-1 ] ✅ Success - Set up job +[Arduino Compile/build-3 ] ✅ Success - Set up job +[Arduino Compile/build-1 ] ☁ git clone 'https://github.com/actions/setup-python' # ref=v5 +[Arduino Compile/build-3 ] ☁ git clone 'https://github.com/actions/setup-python' # ref=v5 +[test-clang-format/cpp_style_check] 🐳 docker exec cmd=[node --no-warnings -e console.log(process.execPath)] user= workdir= +[test-clang-format/cpp_style_check] ✅ Success - Set up job +[test-clang-format/cpp_style_check] ☁ git clone 'https://github.com/DoozyX/clang-format-lint-action' # ref=v0.14 +[Arduino Compile/build-4 ] 🐳 docker exec cmd=[node --no-warnings -e console.log(process.execPath)] user= workdir= +[Arduino Compile/build-4 ] ✅ Success - Set up job +[Arduino Compile/build-4 ] ☁ git clone 'https://github.com/actions/setup-python' # ref=v5 +[Arduino Compile/build-2 ] Non-terminating error while running 'git clone': some refs were not updated +[Arduino Compile/build-2 ] 🧪 Matrix: map[board_fqbn:robotdyn_blackpill_f303cc] +[Arduino Compile/build-2 ] ⭐ Run Main actions/checkout@v4 +[Arduino Compile/build-2 ] 🐳 docker cp src=/home/arendjan/mirte/telemetrix4arduino/. dst=/home/arendjan/mirte/telemetrix4arduino +[Arduino Compile/build-2 ] ✅ Success - Main actions/checkout@v4 +[Arduino Compile/build-2 ] ⭐ Run Main Set up Python +[Arduino Compile/build-2 ] 🐳 docker cp src=/home/arendjan/.cache/act/actions-setup-python@v5/ dst=/var/run/act/actions/actions-setup-python@v5/ +[Arduino Compile/build-2 ] 🐳 docker exec cmd=[/opt/acttoolcache/node/18.20.8/x64/bin/node /var/run/act/actions/actions-setup-python@v5/dist/setup/index.js] user= workdir= +[Arduino Compile/build-2 ] ❓ ::group::Installed versions +[Arduino Compile/build-1 ] Non-terminating error while running 'git clone': some refs were not updated +[Arduino Compile/build-1 ] 🧪 Matrix: map[board_fqbn:nanoatmega328new] +[Arduino Compile/build-2 ] | Successfully set up CPython (3.13.5) +[Arduino Compile/build-2 ] ❓ ::endgroup:: +[Arduino Compile/build-2 ] ❓ add-matcher /run/act/actions/actions-setup-python@v5/.github/python.json +[Arduino Compile/build-2 ] ✅ Success - Main Set up Python +[Arduino Compile/build-2 ] ⚙ ::set-env:: pythonLocation=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-2 ] ⚙ ::set-env:: PKG_CONFIG_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib/pkgconfig +[Arduino Compile/build-2 ] ⚙ ::set-env:: Python_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-2 ] ⚙ ::set-env:: Python2_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-2 ] ⚙ ::set-env:: Python3_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-2 ] ⚙ ::set-env:: LD_LIBRARY_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib +[Arduino Compile/build-2 ] ⚙ ::set-output:: python-version=3.13.5 +[Arduino Compile/build-2 ] ⚙ ::set-output:: python-path=/opt/hostedtoolcache/Python/3.13.5/x64/bin/python +[Arduino Compile/build-1 ] ⭐ Run Main actions/checkout@v4 +[Arduino Compile/build-2 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-2 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64/bin +[Arduino Compile/build-1 ] 🐳 docker cp src=/home/arendjan/mirte/telemetrix4arduino/. dst=/home/arendjan/mirte/telemetrix4arduino +[Arduino Compile/build-2 ] ⭐ Run Main Install dependencies +[Arduino Compile/build-1 ] ✅ Success - Main actions/checkout@v4 +[Arduino Compile/build-2 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/2] user= workdir= +[Arduino Compile/build-1 ] ⭐ Run Main Set up Python +[Arduino Compile/build-1 ] 🐳 docker cp src=/home/arendjan/.cache/act/actions-setup-python@v5/ dst=/var/run/act/actions/actions-setup-python@v5/ +[Arduino Compile/build-1 ] 🐳 docker exec cmd=[/opt/acttoolcache/node/18.20.8/x64/bin/node /var/run/act/actions/actions-setup-python@v5/dist/setup/index.js] user= workdir= +[Arduino Compile/build-3 ] Non-terminating error while running 'git clone': some refs were not updated +[Arduino Compile/build-3 ] 🧪 Matrix: map[board_fqbn:nanoatmega328] +[Arduino Compile/build-3 ] ⭐ Run Main actions/checkout@v4 +[Arduino Compile/build-1 ] ❓ ::group::Installed versions +[Arduino Compile/build-3 ] 🐳 docker cp src=/home/arendjan/mirte/telemetrix4arduino/. dst=/home/arendjan/mirte/telemetrix4arduino +[Arduino Compile/build-1 ] | Successfully set up CPython (3.13.5) +[Arduino Compile/build-1 ] ❓ ::endgroup:: +[Arduino Compile/build-1 ] ❓ add-matcher /run/act/actions/actions-setup-python@v5/.github/python.json +[Arduino Compile/build-1 ] ✅ Success - Main Set up Python +[Arduino Compile/build-1 ] ⚙ ::set-env:: Python3_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-1 ] ⚙ ::set-env:: LD_LIBRARY_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib +[Arduino Compile/build-1 ] ⚙ ::set-env:: pythonLocation=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-1 ] ⚙ ::set-env:: PKG_CONFIG_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib/pkgconfig +[Arduino Compile/build-1 ] ⚙ ::set-env:: Python_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-1 ] ⚙ ::set-env:: Python2_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-2 ] | Requirement already satisfied: pip in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (25.1.1) +[Arduino Compile/build-1 ] ⚙ ::set-output:: python-path=/opt/hostedtoolcache/Python/3.13.5/x64/bin/python +[Arduino Compile/build-1 ] ⚙ ::set-output:: python-version=3.13.5 +[Arduino Compile/build-1 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-1 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64/bin +[Arduino Compile/build-3 ] ✅ Success - Main actions/checkout@v4 +[Arduino Compile/build-1 ] ⭐ Run Main Install dependencies +[Arduino Compile/build-3 ] ⭐ Run Main Set up Python +[Arduino Compile/build-3 ] 🐳 docker cp src=/home/arendjan/.cache/act/actions-setup-python@v5/ dst=/var/run/act/actions/actions-setup-python@v5/ +[Arduino Compile/build-1 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/2] user= workdir= +[test-clang-format/cpp_style_check] Non-terminating error while running 'git clone': some refs were not updated +[test-clang-format/cpp_style_check] ⭐ Run Main actions/checkout@v3 +[Arduino Compile/build-2 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[test-clang-format/cpp_style_check] 🐳 docker cp src=/home/arendjan/mirte/telemetrix4arduino/. dst=/home/arendjan/mirte/telemetrix4arduino +[test-clang-format/cpp_style_check] ✅ Success - Main actions/checkout@v3 +[test-clang-format/cpp_style_check] ⭐ Run Main DoozyX/clang-format-lint-action@v0.14 +[test-clang-format/cpp_style_check] 🐳 docker build -t act-doozyx-clang-format-lint-action-v0-14-dockeraction:latest /home/arendjan/.cache/act/DoozyX-clang-format-lint-action@v0.14 +[Arduino Compile/build-3 ] 🐳 docker exec cmd=[/opt/acttoolcache/node/18.20.8/x64/bin/node /var/run/act/actions/actions-setup-python@v5/dist/setup/index.js] user= workdir= +[Arduino Compile/build-1 ] | Requirement already satisfied: pip in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (25.1.1) +[test-clang-format/cpp_style_check] 🐳 docker pull image=act-doozyx-clang-format-lint-action-v0-14-dockeraction:latest platform= username= forcePull=false +[test-clang-format/cpp_style_check] 🐳 docker create image=act-doozyx-clang-format-lint-action-v0-14-dockeraction:latest platform= entrypoint=[] cmd=["--clang-format-executable" "/clang-format/clang-format14" "-r" "--color" "always" "--style" "llvm" "--inplace" "False" "--extensions" "h,cpp" "--exclude" "none" "."] network="container:act-test-clang-format-cpp-style-check-326e39a0d645c808983c597b24e14296cd95459c3cd88b8c4801f7d7b725c758" +[Arduino Compile/build-3 ] ❓ ::group::Installed versions +[Arduino Compile/build-1 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[Arduino Compile/build-3 ] | Successfully set up CPython (3.13.5) +[Arduino Compile/build-3 ] ❓ ::endgroup:: +[Arduino Compile/build-3 ] ❓ add-matcher /run/act/actions/actions-setup-python@v5/.github/python.json +[Arduino Compile/build-3 ] ✅ Success - Main Set up Python +[Arduino Compile/build-3 ] ⚙ ::set-env:: PKG_CONFIG_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib/pkgconfig +[Arduino Compile/build-3 ] ⚙ ::set-env:: Python_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-3 ] ⚙ ::set-env:: Python2_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-3 ] ⚙ ::set-env:: Python3_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-3 ] ⚙ ::set-env:: LD_LIBRARY_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib +[Arduino Compile/build-3 ] ⚙ ::set-env:: pythonLocation=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-2 ] | Requirement already satisfied: platformio in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (6.1.18) +[Arduino Compile/build-3 ] ⚙ ::set-output:: python-version=3.13.5 +[Arduino Compile/build-3 ] ⚙ ::set-output:: python-path=/opt/hostedtoolcache/Python/3.13.5/x64/bin/python +[Arduino Compile/build-2 ] | Requirement already satisfied: bottle==0.13.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.13.4) +[Arduino Compile/build-3 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-3 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64/bin +[Arduino Compile/build-2 ] | Requirement already satisfied: click<8.1.8,>=8.0.4 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (8.1.7) +[Arduino Compile/build-2 ] | Requirement already satisfied: colorama in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.4.6) +[Arduino Compile/build-2 ] | Requirement already satisfied: marshmallow==3.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.26.1) +[Arduino Compile/build-2 ] | Requirement already satisfied: pyelftools<1,>=0.27 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.32) +[Arduino Compile/build-2 ] | Requirement already satisfied: pyserial==3.5.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.5) +[Arduino Compile/build-2 ] | Requirement already satisfied: requests==2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.32.4) +[Arduino Compile/build-2 ] | Requirement already satisfied: semantic_version==2.10.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.10.0) +[Arduino Compile/build-2 ] | Requirement already satisfied: tabulate==0.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.9.0) +[Arduino Compile/build-2 ] | Requirement already satisfied: ajsonrpc==1.2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-2 ] | Requirement already satisfied: starlette<0.47,>=0.19 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.46.2) +[Arduino Compile/build-2 ] | Requirement already satisfied: uvicorn<0.35,>=0.16 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.34.3) +[Arduino Compile/build-2 ] | Requirement already satisfied: wsproto==1.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-2 ] | Requirement already satisfied: packaging>=17.0 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from marshmallow==3.*->platformio) (25.0) +[Arduino Compile/build-2 ] | Requirement already satisfied: charset_normalizer<4,>=2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.4.2) +[Arduino Compile/build-2 ] | Requirement already satisfied: idna<4,>=2.5 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.10) +[Arduino Compile/build-2 ] | Requirement already satisfied: urllib3<3,>=1.21.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2.5.0) +[Arduino Compile/build-2 ] | Requirement already satisfied: certifi>=2017.4.17 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2025.6.15) +[Arduino Compile/build-2 ] | Requirement already satisfied: anyio<5,>=3.6.2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from starlette<0.47,>=0.19->platformio) (4.9.0) +[Arduino Compile/build-2 ] | Requirement already satisfied: sniffio>=1.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from anyio<5,>=3.6.2->starlette<0.47,>=0.19->platformio) (1.3.1) +[Arduino Compile/build-2 ] | Requirement already satisfied: h11>=0.8 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from uvicorn<0.35,>=0.16->platformio) (0.16.0) +[Arduino Compile/build-3 ] ⭐ Run Main Install dependencies +[Arduino Compile/build-2 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[Arduino Compile/build-3 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/2] user= workdir= +[test-clang-format/cpp_style_check] 🐳 docker run image=act-doozyx-clang-format-lint-action-v0-14-dockeraction:latest platform= entrypoint=[] cmd=["--clang-format-executable" "/clang-format/clang-format14" "-r" "--color" "always" "--style" "llvm" "--inplace" "False" "--extensions" "h,cpp" "--exclude" "none" "."] network="container:act-test-clang-format-cpp-style-check-326e39a0d645c808983c597b24e14296cd95459c3cd88b8c4801f7d7b725c758" +[Arduino Compile/build-4 ] Non-terminating error while running 'git clone': some refs were not updated +[Arduino Compile/build-4 ] 🧪 Matrix: map[board_fqbn:adafruit_itsybitsy_m4] +[Arduino Compile/build-2 ] ✅ Success - Main Install dependencies +[Arduino Compile/build-4 ] ⭐ Run Main actions/checkout@v4 +[Arduino Compile/build-4 ] 🐳 docker cp src=/home/arendjan/mirte/telemetrix4arduino/. dst=/home/arendjan/mirte/telemetrix4arduino +[Arduino Compile/build-2 ] ⭐ Run Main Install platformIO libraries +[Arduino Compile/build-4 ] ✅ Success - Main actions/checkout@v4 +[Arduino Compile/build-2 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/3] user= workdir= +[Arduino Compile/build-4 ] ⭐ Run Main Set up Python +[Arduino Compile/build-4 ] 🐳 docker cp src=/home/arendjan/.cache/act/actions-setup-python@v5/ dst=/var/run/act/actions/actions-setup-python@v5/ +[Arduino Compile/build-4 ] 🐳 docker exec cmd=[/opt/acttoolcache/node/18.20.8/x64/bin/node /var/run/act/actions/actions-setup-python@v5/dist/setup/index.js] user= workdir= +[Arduino Compile/build-2 ] | ******************************************************************************** +[Arduino Compile/build-2 ] | If you like PlatformIO, please: +[Arduino Compile/build-2 ] | - star it on GitHub > https://github.com/platformio/platformio-core +[Arduino Compile/build-2 ] | - follow us on LinkedIn to stay up-to-date on the latest project news > https://www.linkedin.com/company/platformio/ +[Arduino Compile/build-2 ] | - try PlatformIO IDE for embedded development > https://platformio.org/platformio-ide +[Arduino Compile/build-2 ] | ******************************************************************************** +[Arduino Compile/build-2 ] | +[Arduino Compile/build-2 ] | Resolving robotdyn_blackpill_f303cc dependencies... +[Arduino Compile/build-2 ] | Platform Manager: Installing ststm32 +[Arduino Compile/build-1 ] | Requirement already satisfied: platformio in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (6.1.18) +[Arduino Compile/build-1 ] | Requirement already satisfied: bottle==0.13.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.13.4) +[Arduino Compile/build-1 ] | Requirement already satisfied: click<8.1.8,>=8.0.4 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (8.1.7) +[Arduino Compile/build-1 ] | Requirement already satisfied: colorama in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.4.6) +[Arduino Compile/build-1 ] | Requirement already satisfied: marshmallow==3.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.26.1) +[Arduino Compile/build-1 ] | Requirement already satisfied: pyelftools<1,>=0.27 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.32) +[Arduino Compile/build-1 ] | Requirement already satisfied: pyserial==3.5.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.5) +[Arduino Compile/build-1 ] | Requirement already satisfied: requests==2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.32.4) +[Arduino Compile/build-1 ] | Requirement already satisfied: semantic_version==2.10.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.10.0) +[Arduino Compile/build-1 ] | Requirement already satisfied: tabulate==0.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.9.0) +[Arduino Compile/build-1 ] | Requirement already satisfied: ajsonrpc==1.2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-1 ] | Requirement already satisfied: starlette<0.47,>=0.19 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.46.2) +[Arduino Compile/build-1 ] | Requirement already satisfied: uvicorn<0.35,>=0.16 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.34.3) +[Arduino Compile/build-1 ] | Requirement already satisfied: wsproto==1.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-1 ] | Requirement already satisfied: packaging>=17.0 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from marshmallow==3.*->platformio) (25.0) +[Arduino Compile/build-1 ] | Requirement already satisfied: charset_normalizer<4,>=2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.4.2) +[Arduino Compile/build-1 ] | Requirement already satisfied: idna<4,>=2.5 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.10) +[Arduino Compile/build-1 ] | Requirement already satisfied: urllib3<3,>=1.21.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2.5.0) +[Arduino Compile/build-1 ] | Requirement already satisfied: certifi>=2017.4.17 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2025.6.15) +[Arduino Compile/build-1 ] | Requirement already satisfied: anyio<5,>=3.6.2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from starlette<0.47,>=0.19->platformio) (4.9.0) +[Arduino Compile/build-1 ] | Requirement already satisfied: sniffio>=1.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from anyio<5,>=3.6.2->starlette<0.47,>=0.19->platformio) (1.3.1) +[Arduino Compile/build-1 ] | Requirement already satisfied: h11>=0.8 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from uvicorn<0.35,>=0.16->platformio) (0.16.0) +[Arduino Compile/build-3 ] | Requirement already satisfied: pip in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (25.1.1) +[Arduino Compile/build-1 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[Arduino Compile/build-1 ] ✅ Success - Main Install dependencies +[Arduino Compile/build-3 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[Arduino Compile/build-1 ] ⭐ Run Main Install platformIO libraries +[Arduino Compile/build-4 ] ❓ ::group::Installed versions +[Arduino Compile/build-4 ] | Successfully set up CPython (3.13.5) +[Arduino Compile/build-4 ] ❓ ::endgroup:: +[Arduino Compile/build-4 ] ❓ add-matcher /run/act/actions/actions-setup-python@v5/.github/python.json +[Arduino Compile/build-1 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/3] user= workdir= +[Arduino Compile/build-4 ] ✅ Success - Main Set up Python +[Arduino Compile/build-4 ] ⚙ ::set-env:: Python2_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-4 ] ⚙ ::set-env:: Python3_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-4 ] ⚙ ::set-env:: LD_LIBRARY_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib +[Arduino Compile/build-4 ] ⚙ ::set-env:: pythonLocation=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-4 ] ⚙ ::set-env:: PKG_CONFIG_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib/pkgconfig +[Arduino Compile/build-4 ] ⚙ ::set-env:: Python_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-4 ] ⚙ ::set-output:: python-version=3.13.5 +[Arduino Compile/build-4 ] ⚙ ::set-output:: python-path=/opt/hostedtoolcache/Python/3.13.5/x64/bin/python +[Arduino Compile/build-4 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-4 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64/bin +[test-clang-format/cpp_style_check] | Processing 4 files: ./src/i2c.cpp, ./src/main.cpp, ./lib/OpticalEncoder/OpticalEncoder.h, ./include/Telemetrix4Arduino.h +[Arduino Compile/build-4 ] ⭐ Run Main Install dependencies +[test-clang-format/cpp_style_check] | --- ./src/main.cpp (original) +[test-clang-format/cpp_style_check] | +++ ./src/main.cpp (reformatted) +[test-clang-format/cpp_style_check] | @@ -630,7 +630,7 @@ +[test-clang-format/cpp_style_check] |  // send_debug_info(0, packet_length); +[test-clang-format/cpp_style_check] | auto max_wait = 10; // wait for the command to be available +[test-clang-format/cpp_style_check] | while (max_wait-- > 0 && !Serial.available()) { +[test-clang-format/cpp_style_check] | - delayMicroseconds(10); +[test-clang-format/cpp_style_check] | + delayMicroseconds(10); +[test-clang-format/cpp_style_check] |  } +[test-clang-format/cpp_style_check] | if (packet_length == 0) { +[test-clang-format/cpp_style_check] | return; // no command to process, reset bytes +[test-clang-format/cpp_style_check] | @@ -933,7 +933,7 @@ +[test-clang-format/cpp_style_check] |  // digitalWrite(LED_BUILTIN, HIGH); +[test-clang-format/cpp_style_check] | // delay(100); +[test-clang-format/cpp_style_check] | // } +[test-clang-format/cpp_style_check] | - for(auto i = 0; i < 0xFF; i++) { +[test-clang-format/cpp_style_check] | + for (auto i = 0; i < 0xFF; i++) { +[test-clang-format/cpp_style_check] |  Serial.write(0); +[test-clang-format/cpp_style_check] | } +[test-clang-format/cpp_style_check] | // get_firmware_version(); +[test-clang-format/cpp_style_check] | @@ -946,7 +946,7 @@ +[test-clang-format/cpp_style_check] |  static decltype(millis()) scan_delay = 10; +[test-clang-format/cpp_style_check] | if (!stop_reports) { // stop reporting +[test-clang-format/cpp_style_check] | if (millis() - last_scan >= (scan_delay)) { +[test-clang-format/cpp_style_check] | - digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); +[test-clang-format/cpp_style_check] | + digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); +[test-clang-format/cpp_style_check] |  // Serial.println("Scanning inputs..."); +[test-clang-format/cpp_style_check] | // send_debug_info(10, 10); +[test-clang-format/cpp_style_check] | last_scan += scan_delay; +[test-clang-format/cpp_style_check] | @@ -1008,7 +1008,7 @@ +[test-clang-format/cpp_style_check] |  +[test-clang-format/cpp_style_check] | template void send_message(const uint8_t (&message)[N]) { +[test-clang-format/cpp_style_check] | while (Serial.availableForWrite() < (int)N + 3) { +[test-clang-format/cpp_style_check] | - delayMicroseconds(10); +[test-clang-format/cpp_style_check] | + delayMicroseconds(10); +[test-clang-format/cpp_style_check] |  } +[test-clang-format/cpp_style_check] | Serial.write((uint8_t)N); // send msg len +[test-clang-format/cpp_style_check] | Serial.write(message, N); // send message +[Arduino Compile/build-4 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/2] user= workdir= +[test-clang-format/cpp_style_check] ❌ Failure - Main DoozyX/clang-format-lint-action@v0.14 +[test-clang-format/cpp_style_check] exit with `FAILURE`: 1 +[test-clang-format/cpp_style_check] ⭐ Run Complete job +[test-clang-format/cpp_style_check] ✅ Success - Complete job +[test-clang-format/cpp_style_check] 🏁 Job failed +[Arduino Compile/build-1 ] | ******************************************************************************** +[Arduino Compile/build-1 ] | If you like PlatformIO, please: +[Arduino Compile/build-1 ] | - star it on GitHub > https://github.com/platformio/platformio-core +[Arduino Compile/build-1 ] | - follow us on LinkedIn to stay up-to-date on the latest project news > https://www.linkedin.com/company/platformio/ +[Arduino Compile/build-1 ] | - try PlatformIO IDE for embedded development > https://platformio.org/platformio-ide +[Arduino Compile/build-1 ] | ******************************************************************************** +[Arduino Compile/build-1 ] | +[Arduino Compile/build-1 ] | Resolving nanoatmega328new dependencies... +[Arduino Compile/build-1 ] | Platform Manager: Installing atmelavr +[Arduino Compile/build-3 ] | Requirement already satisfied: platformio in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (6.1.18) +[Arduino Compile/build-3 ] | Requirement already satisfied: bottle==0.13.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.13.4) +[Arduino Compile/build-3 ] | Requirement already satisfied: click<8.1.8,>=8.0.4 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (8.1.7) +[Arduino Compile/build-3 ] | Requirement already satisfied: colorama in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.4.6) +[Arduino Compile/build-3 ] | Requirement already satisfied: marshmallow==3.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.26.1) +[Arduino Compile/build-3 ] | Requirement already satisfied: pyelftools<1,>=0.27 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.32) +[Arduino Compile/build-3 ] | Requirement already satisfied: pyserial==3.5.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.5) +[Arduino Compile/build-3 ] | Requirement already satisfied: requests==2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.32.4) +[Arduino Compile/build-3 ] | Requirement already satisfied: semantic_version==2.10.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.10.0) +[Arduino Compile/build-3 ] | Requirement already satisfied: tabulate==0.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.9.0) +[Arduino Compile/build-3 ] | Requirement already satisfied: ajsonrpc==1.2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-3 ] | Requirement already satisfied: starlette<0.47,>=0.19 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.46.2) +[Arduino Compile/build-3 ] | Requirement already satisfied: uvicorn<0.35,>=0.16 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.34.3) +[Arduino Compile/build-3 ] | Requirement already satisfied: wsproto==1.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-3 ] | Requirement already satisfied: packaging>=17.0 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from marshmallow==3.*->platformio) (25.0) +[Arduino Compile/build-3 ] | Requirement already satisfied: charset_normalizer<4,>=2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.4.2) +[Arduino Compile/build-3 ] | Requirement already satisfied: idna<4,>=2.5 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.10) +[Arduino Compile/build-3 ] | Requirement already satisfied: urllib3<3,>=1.21.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2.5.0) +[Arduino Compile/build-3 ] | Requirement already satisfied: certifi>=2017.4.17 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2025.6.15) +[Arduino Compile/build-3 ] | Requirement already satisfied: anyio<5,>=3.6.2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from starlette<0.47,>=0.19->platformio) (4.9.0) +[Arduino Compile/build-3 ] | Requirement already satisfied: sniffio>=1.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from anyio<5,>=3.6.2->starlette<0.47,>=0.19->platformio) (1.3.1) +[Arduino Compile/build-3 ] | Requirement already satisfied: h11>=0.8 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from uvicorn<0.35,>=0.16->platformio) (0.16.0) +[Arduino Compile/build-4 ] | Requirement already satisfied: pip in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (25.1.1) +[Arduino Compile/build-3 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[Arduino Compile/build-3 ] ✅ Success - Main Install dependencies +[Arduino Compile/build-4 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[Arduino Compile/build-3 ] ⭐ Run Main Install platformIO libraries +[Arduino Compile/build-3 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/3] user= workdir= +[Arduino Compile/build-3 ] | ******************************************************************************** +[Arduino Compile/build-3 ] | If you like PlatformIO, please: +[Arduino Compile/build-3 ] | - star it on GitHub > https://github.com/platformio/platformio-core +[Arduino Compile/build-3 ] | - follow us on LinkedIn to stay up-to-date on the latest project news > https://www.linkedin.com/company/platformio/ +[Arduino Compile/build-3 ] | - try PlatformIO IDE for embedded development > https://platformio.org/platformio-ide +[Arduino Compile/build-3 ] | ******************************************************************************** +[Arduino Compile/build-3 ] | +[Arduino Compile/build-3 ] | Resolving nanoatmega328 dependencies... +[Arduino Compile/build-3 ] | Platform Manager: Installing atmelavr +[Arduino Compile/build-4 ] | Requirement already satisfied: platformio in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (6.1.18) +[Arduino Compile/build-4 ] | Requirement already satisfied: bottle==0.13.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.13.4) +[Arduino Compile/build-4 ] | Requirement already satisfied: click<8.1.8,>=8.0.4 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (8.1.7) +[Arduino Compile/build-4 ] | Requirement already satisfied: colorama in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.4.6) +[Arduino Compile/build-4 ] | Requirement already satisfied: marshmallow==3.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.26.1) +[Arduino Compile/build-4 ] | Requirement already satisfied: pyelftools<1,>=0.27 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.32) +[Arduino Compile/build-4 ] | Requirement already satisfied: pyserial==3.5.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.5) +[Arduino Compile/build-4 ] | Requirement already satisfied: requests==2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.32.4) +[Arduino Compile/build-4 ] | Requirement already satisfied: semantic_version==2.10.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.10.0) +[Arduino Compile/build-4 ] | Requirement already satisfied: tabulate==0.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.9.0) +[Arduino Compile/build-4 ] | Requirement already satisfied: ajsonrpc==1.2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-4 ] | Requirement already satisfied: starlette<0.47,>=0.19 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.46.2) +[Arduino Compile/build-4 ] | Requirement already satisfied: uvicorn<0.35,>=0.16 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.34.3) +[Arduino Compile/build-4 ] | Requirement already satisfied: wsproto==1.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-4 ] | Requirement already satisfied: packaging>=17.0 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from marshmallow==3.*->platformio) (25.0) +[Arduino Compile/build-4 ] | Requirement already satisfied: charset_normalizer<4,>=2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.4.2) +[Arduino Compile/build-4 ] | Requirement already satisfied: idna<4,>=2.5 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.10) +[Arduino Compile/build-4 ] | Requirement already satisfied: urllib3<3,>=1.21.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2.5.0) +[Arduino Compile/build-4 ] | Requirement already satisfied: certifi>=2017.4.17 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2025.6.15) +[Arduino Compile/build-4 ] | Requirement already satisfied: anyio<5,>=3.6.2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from starlette<0.47,>=0.19->platformio) (4.9.0) +[Arduino Compile/build-4 ] | Requirement already satisfied: sniffio>=1.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from anyio<5,>=3.6.2->starlette<0.47,>=0.19->platformio) (1.3.1) +[Arduino Compile/build-4 ] | Requirement already satisfied: h11>=0.8 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from uvicorn<0.35,>=0.16->platformio) (0.16.0) +[Arduino Compile/build-1 ] | Downloading 0% 10% 20% 30% 40% 50% 60% +[Arduino Compile/build-4 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[Arduino Compile/build-4 ] ✅ Success - Main Install dependencies +[Arduino Compile/build-1 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] ⭐ Run Main Install platformIO libraries +[Arduino Compile/build-1 ] | Platform Manager: atmelavr@5.1.0 has been installed! +[Arduino Compile/build-4 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/3] user= workdir= +[Arduino Compile/build-1 ] | Tool Manager: Installing platformio/toolchain-atmelavr @ ~1.70300.0 +[Arduino Compile/build-4 ] | ******************************************************************************** +[Arduino Compile/build-4 ] | If you like PlatformIO, please: +[Arduino Compile/build-4 ] | - star it on GitHub > https://github.com/platformio/platformio-core +[Arduino Compile/build-4 ] | - follow us on LinkedIn to stay up-to-date on the latest project news > https://www.linkedin.com/company/platformio/ +[Arduino Compile/build-4 ] | - try PlatformIO IDE for embedded development > https://platformio.org/platformio-ide +[Arduino Compile/build-4 ] | ******************************************************************************** +[Arduino Compile/build-4 ] | +[Arduino Compile/build-4 ] | Resolving adafruit_itsybitsy_m4 dependencies... +[Arduino Compile/build-4 ] | Platform Manager: Installing atmelsam +[Arduino Compile/build-3 ] | Downloading 0% 10% 20% 30% 40% 50% 60% +[Arduino Compile/build-3 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Platform Manager: atmelavr@5.1.0 has been installed! +[Arduino Compile/build-3 ] | Tool Manager: Installing platformio/toolchain-atmelavr @ ~1.70300.0 +[Arduino Compile/build-4 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Platform Manager: atmelsam@8.3.0 has been installed! +[Arduino Compile/build-4 ] | Tool Manager: Installing platformio/toolchain-gccarmnoneeabi @ ~1.90301.0 +[Arduino Compile/build-2 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-2 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-2 ] | Platform Manager: ststm32@19.2.0 has been installed! +[Arduino Compile/build-2 ] | Tool Manager: Installing platformio/toolchain-gccarmnoneeabi @ * +[Arduino Compile/build-1 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Tool Manager: toolchain-atmelavr@1.70300.191015 has been installed! +[Arduino Compile/build-1 ] | Tool Manager: Installing platformio/framework-arduino-avr @ ~5.2.0 +[Arduino Compile/build-3 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Tool Manager: toolchain-atmelavr@1.70300.191015 has been installed! +[Arduino Compile/build-3 ] | Tool Manager: Installing platformio/framework-arduino-avr @ ~5.2.0 +[Arduino Compile/build-3 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Tool Manager: framework-arduino-avr@5.2.0 has been installed! +[Arduino Compile/build-3 ] | Tool Manager: Installing platformio/tool-scons @ ~4.40801.0 +[Arduino Compile/build-3 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Tool Manager: tool-scons@4.40801.0 has been installed! +[Arduino Compile/build-3 ] | Library Manager: Installing teckel12/NewPing @ ^1.9.7 +[Arduino Compile/build-4 ] | Tool Manager: toolchain-gccarmnoneeabi@1.90301.200702 has been installed! +[Arduino Compile/build-4 ] | Tool Manager: Installing platformio/framework-arduino-samd-adafruit @ ~1.10716.0 +[Arduino Compile/build-2 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Downloading 0% 10% 20% +[Arduino Compile/build-3 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Library Manager: NewPing@1.9.7 has been installed! +[Arduino Compile/build-3 ] | Library Manager: Installing arduino-libraries/Stepper @ ^1.1.3 +[Arduino Compile/build-1 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Tool Manager: framework-arduino-avr@5.2.0 has been installed! +[Arduino Compile/build-1 ] | Tool Manager: Installing platformio/tool-scons @ ~4.40801.0 +[Arduino Compile/build-4 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Downloading 0% 10% +[Arduino Compile/build-3 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% +[Arduino Compile/build-3 ] | Library Manager: Stepper@1.1.3 has been installed! +[Arduino Compile/build-3 ] | Library Manager: Installing arduino-libraries/Servo @ ^1.2.0 +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Tool Manager: framework-arduino-samd-adafruit@1.10716.0 has been installed! +[Arduino Compile/build-4 ] | Tool Manager: Installing platformio/framework-cmsis @ ~2.50400.0 +[Arduino Compile/build-1 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Tool Manager: tool-scons@4.40801.0 has been installed! +[Arduino Compile/build-1 ] | Library Manager: Installing teckel12/NewPing @ ^1.9.7 +[Arduino Compile/build-3 ] | Downloading 0% 10% 20% 30% 40% 50% +[Arduino Compile/build-3 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Library Manager: Servo@1.2.2 has been installed! +[Arduino Compile/build-3 ] | Library Manager: Installing robtillaart/DHTNEW @ ^0.4.18 +[Arduino Compile/build-1 ] | Downloading 0% 10% 20% +[Arduino Compile/build-1 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Library Manager: NewPing@1.9.7 has been installed! +[Arduino Compile/build-1 ] | Library Manager: Installing arduino-libraries/Stepper @ ^1.1.3 +[Arduino Compile/build-4 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Downloading 0% 10% 20% 30% +[Arduino Compile/build-3 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Library Manager: DHTNEW@0.4.21 has been installed! +[Arduino Compile/build-3 ] | Library Manager: Installing adafruit/Adafruit SleepyDog Library @ ^1.6.5 +[Arduino Compile/build-1 ] | Downloading 0% 10% +[Arduino Compile/build-1 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% +[Arduino Compile/build-1 ] | Library Manager: Stepper@1.1.3 has been installed! +[Arduino Compile/build-1 ] | Library Manager: Installing arduino-libraries/Servo @ ^1.2.0 +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Tool Manager: framework-cmsis@2.50400.181126 has been installed! +[Arduino Compile/build-4 ] | Tool Manager: Installing platformio/framework-cmsis-atmel @ ~1.2.2 +[Arduino Compile/build-3 ] | Downloading 0% 10% 20% +[Arduino Compile/build-3 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Library Manager: Adafruit SleepyDog Library@1.6.5 has been installed! +[Arduino Compile/build-3 ] ✅ Success - Main Install platformIO libraries +[Arduino Compile/build-3 ] ⭐ Run Main Run PlatformIO +[Arduino Compile/build-3 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/4] user= workdir= +[Arduino Compile/build-3 ] | Processing nanoatmega328 (platform: atmelavr; board: nanoatmega328; framework: arduino) +[Arduino Compile/build-3 ] | -------------------------------------------------------------------------------- +[Arduino Compile/build-1 ] | Downloading 0% 10% 20% 30% 40% 50% +[Arduino Compile/build-1 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Library Manager: Servo@1.2.2 has been installed! +[Arduino Compile/build-1 ] | Library Manager: Installing robtillaart/DHTNEW @ ^0.4.18 +[Arduino Compile/build-3 ] | Verbose mode can be enabled via `-v, --verbose` option +[Arduino Compile/build-3 ] | CONFIGURATION: https://docs.platformio.org/page/boards/atmelavr/nanoatmega328.html +[Arduino Compile/build-3 ] | PLATFORM: Atmel AVR (5.1.0) > Arduino Nano ATmega328 +[Arduino Compile/build-3 ] | HARDWARE: ATMEGA328P 16MHz, 2KB RAM, 30KB Flash +[Arduino Compile/build-3 ] | DEBUG: Current (avr-stub) External (avr-stub, simavr) +[Arduino Compile/build-3 ] | PACKAGES: +[Arduino Compile/build-3 ] | - framework-arduino-avr @ 5.2.0 +[Arduino Compile/build-3 ] | - toolchain-atmelavr @ 1.70300.191015 (7.3.0) +[Arduino Compile/build-3 ] | LDF: Library Dependency Finder -> https://bit.ly/configure-pio-ldf +[Arduino Compile/build-3 ] | LDF Modes: Finder ~ chain, Compatibility ~ soft +[Arduino Compile/build-3 ] | Found 11 compatible libraries +[Arduino Compile/build-3 ] | Scanning dependencies... +[Arduino Compile/build-3 ] | Dependency Graph +[Arduino Compile/build-3 ] | |-- NewPing @ 1.9.7 +[Arduino Compile/build-3 ] | |-- Stepper @ 1.1.3 +[Arduino Compile/build-3 ] | |-- Servo @ 1.2.2 +[Arduino Compile/build-3 ] | |-- DHTNEW @ 0.4.21 +[Arduino Compile/build-3 ] | |-- Adafruit SleepyDog Library @ 1.6.5 +[Arduino Compile/build-3 ] | |-- Wire @ 1.0 +[Arduino Compile/build-3 ] | |-- OpticalEncoder +[Arduino Compile/build-3 ] | Building in release mode +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/src/i2c.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/src/main.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib6de/NewPing/NewPing.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib227/Stepper/Stepper.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5f8/Servo/avr/Servo.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5f8/Servo/mbed/Servo.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5f8/Servo/megaavr/Servo.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5f8/Servo/nrf52/Servo.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5f8/Servo/renesas/Servo.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5f8/Servo/sam/Servo.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5f8/Servo/samd/Servo.cpp.o +[Arduino Compile/build-3 ] | Archiving .pio/build/nanoatmega328/lib227/libStepper.a +[Arduino Compile/build-3 ] | Archiving .pio/build/nanoatmega328/lib6de/libNewPing.a +[Arduino Compile/build-3 ] | Indexing .pio/build/nanoatmega328/lib227/libStepper.a +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5f8/Servo/stm32f4/Servo.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5f8/Servo/xmc/Servo.cpp.o +[Arduino Compile/build-3 ] | Indexing .pio/build/nanoatmega328/lib6de/libNewPing.a +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib5be/DHTNEW/dhtnew.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/libcc5/Adafruit SleepyDog Library/Adafruit_SleepyDog.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/libcc5/Adafruit SleepyDog Library/utility/WatchdogAVR.cpp.o +[Arduino Compile/build-3 ] | Archiving .pio/build/nanoatmega328/lib5f8/libServo.a +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/libcc5/Adafruit SleepyDog Library/utility/WatchdogESP32.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/libcc5/Adafruit SleepyDog Library/utility/WatchdogESP8266.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/libcc5/Adafruit SleepyDog Library/utility/WatchdogKinetisK.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/libcc5/Adafruit SleepyDog Library/utility/WatchdogKinetisL.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/libcc5/Adafruit SleepyDog Library/utility/WatchdogNRF.cpp.o +[Arduino Compile/build-3 ] | Indexing .pio/build/nanoatmega328/lib5f8/libServo.a +[Arduino Compile/build-3 ] | Archiving .pio/build/nanoatmega328/lib5be/libDHTNEW.a +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/libcc5/Adafruit SleepyDog Library/utility/WatchdogRP2040.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/libcc5/Adafruit SleepyDog Library/utility/WatchdogSAMD.cpp.o +[Arduino Compile/build-3 ] | Indexing .pio/build/nanoatmega328/lib5be/libDHTNEW.a +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib143/Wire/Wire.cpp.o +[Arduino Compile/build-4 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/lib143/Wire/utility/twi.c.o +[Arduino Compile/build-3 ] | Archiving .pio/build/nanoatmega328/libcc5/libAdafruit SleepyDog Library.a +[Arduino Compile/build-3 ] | Archiving .pio/build/nanoatmega328/libFrameworkArduinoVariant.a +[Arduino Compile/build-3 ] | Indexing .pio/build/nanoatmega328/libcc5/libAdafruit SleepyDog Library.a +[Arduino Compile/build-3 ] | Indexing .pio/build/nanoatmega328/libFrameworkArduinoVariant.a +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/CDC.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/HardwareSerial.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/HardwareSerial0.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/HardwareSerial1.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/HardwareSerial2.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/HardwareSerial3.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/IPAddress.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/PluggableUSB.cpp.o +[Arduino Compile/build-3 ] | Archiving .pio/build/nanoatmega328/lib143/libWire.a +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/Print.cpp.o +[Arduino Compile/build-3 ] | Indexing .pio/build/nanoatmega328/lib143/libWire.a +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/Stream.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/Tone.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/USBCore.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/WInterrupts.c.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/WMath.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/WString.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/abi.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/hooks.c.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/main.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/new.cpp.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/wiring.c.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/wiring_analog.c.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/wiring_digital.c.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/wiring_pulse.S.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/wiring_pulse.c.o +[Arduino Compile/build-3 ] | Compiling .pio/build/nanoatmega328/FrameworkArduino/wiring_shift.c.o +[Arduino Compile/build-3 ] | Archiving .pio/build/nanoatmega328/libFrameworkArduino.a +[Arduino Compile/build-3 ] | Indexing .pio/build/nanoatmega328/libFrameworkArduino.a +[Arduino Compile/build-3 ] | Linking .pio/build/nanoatmega328/firmware.elf +[Arduino Compile/build-1 ] | Downloading 0% 10% 20% 30% +[Arduino Compile/build-1 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Library Manager: DHTNEW@0.4.21 has been installed! +[Arduino Compile/build-1 ] | Library Manager: Installing adafruit/Adafruit SleepyDog Library @ ^1.6.5 +[Arduino Compile/build-3 ] | Checking size .pio/build/nanoatmega328/firmware.elf +[Arduino Compile/build-3 ] | Advanced Memory Usage is available via "PlatformIO Home > Project Inspect" +[Arduino Compile/build-3 ] | RAM: [==== ] 40.9% (used 838 bytes from 2048 bytes) +[Arduino Compile/build-3 ] | Flash: [==== ] 40.9% (used 12560 bytes from 30720 bytes) +[Arduino Compile/build-3 ] | Building .pio/build/nanoatmega328/firmware.hex +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-3 ] | ========================= [SUCCESS] Took 2.69 seconds ========================= +[Arduino Compile/build-3 ] | +[Arduino Compile/build-3 ] | Environment Status Duration +[Arduino Compile/build-3 ] | ------------- -------- ------------ +[Arduino Compile/build-3 ] | nanoatmega328 SUCCESS 00:00:02.692 +[Arduino Compile/build-3 ] | ========================= 1 succeeded in 00:00:02.692 ========================= +[Arduino Compile/build-3 ] ✅ Success - Main Run PlatformIO +[Arduino Compile/build-3 ] ⭐ Run Post Set up Python +[Arduino Compile/build-3 ] 🐳 docker exec cmd=[/opt/acttoolcache/node/18.20.8/x64/bin/node /var/run/act/actions/actions-setup-python@v5/dist/cache-save/index.js] user= workdir= +[Arduino Compile/build-4 ] | Tool Manager: framework-cmsis-atmel@1.2.2 has been installed! +[Arduino Compile/build-4 ] | Tool Manager: Installing platformio/tool-scons @ ~4.40801.0 +[Arduino Compile/build-3 ] ✅ Success - Post Set up Python +[Arduino Compile/build-3 ] ⭐ Run Complete job +[Arduino Compile/build-3 ] Cleaning up container for job build +[Arduino Compile/build-3 ] ✅ Success - Complete job +[Arduino Compile/build-3 ] 🏁 Job succeeded +[Arduino Compile/build-5 ] ⭐ Run Set up job +[Arduino Compile/build-5 ] 🚀 Start image=catthehacker/ubuntu:act-latest +[Arduino Compile/build-5 ] 🐳 docker pull image=catthehacker/ubuntu:act-latest platform= username= forcePull=true +[Arduino Compile/build-2 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Downloading 0% 10% 20% +[Arduino Compile/build-1 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Library Manager: Adafruit SleepyDog Library@1.6.5 has been installed! +[Arduino Compile/build-1 ] ✅ Success - Main Install platformIO libraries +[Arduino Compile/build-1 ] ⭐ Run Main Run PlatformIO +[Arduino Compile/build-1 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/4] user= workdir= +[Arduino Compile/build-5 ] 🐳 docker create image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-4 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-1 ] | Processing nanoatmega328new (platform: atmelavr; board: nanoatmega328new; framework: arduino) +[Arduino Compile/build-1 ] | -------------------------------------------------------------------------------- +[Arduino Compile/build-5 ] 🐳 docker run image=catthehacker/ubuntu:act-latest platform= entrypoint=["tail" "-f" "/dev/null"] cmd=[] network="host" +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Tool Manager: tool-scons@4.40801.0 has been installed! +[Arduino Compile/build-4 ] | Library Manager: Installing teckel12/NewPing @ ^1.9.7 +[Arduino Compile/build-5 ] 🐳 docker exec cmd=[node --no-warnings -e console.log(process.execPath)] user= workdir= +[Arduino Compile/build-5 ] ✅ Success - Set up job +[Arduino Compile/build-5 ] ☁ git clone 'https://github.com/actions/setup-python' # ref=v5 +[Arduino Compile/build-1 ] | Verbose mode can be enabled via `-v, --verbose` option +[Arduino Compile/build-1 ] | CONFIGURATION: https://docs.platformio.org/page/boards/atmelavr/nanoatmega328new.html +[Arduino Compile/build-1 ] | PLATFORM: Atmel AVR (5.1.0) > Arduino Nano ATmega328 (New Bootloader) +[Arduino Compile/build-1 ] | HARDWARE: ATMEGA328P 16MHz, 2KB RAM, 30KB Flash +[Arduino Compile/build-1 ] | DEBUG: Current (avr-stub) External (avr-stub, simavr) +[Arduino Compile/build-1 ] | PACKAGES: +[Arduino Compile/build-1 ] | - framework-arduino-avr @ 5.2.0 +[Arduino Compile/build-1 ] | - toolchain-atmelavr @ 1.70300.191015 (7.3.0) +[Arduino Compile/build-1 ] | LDF: Library Dependency Finder -> https://bit.ly/configure-pio-ldf +[Arduino Compile/build-1 ] | LDF Modes: Finder ~ chain, Compatibility ~ soft +[Arduino Compile/build-1 ] | Found 11 compatible libraries +[Arduino Compile/build-1 ] | Scanning dependencies... +[Arduino Compile/build-1 ] | Dependency Graph +[Arduino Compile/build-1 ] | |-- NewPing @ 1.9.7 +[Arduino Compile/build-1 ] | |-- Stepper @ 1.1.3 +[Arduino Compile/build-1 ] | |-- Servo @ 1.2.2 +[Arduino Compile/build-1 ] | |-- DHTNEW @ 0.4.21 +[Arduino Compile/build-1 ] | |-- Adafruit SleepyDog Library @ 1.6.5 +[Arduino Compile/build-1 ] | |-- Wire @ 1.0 +[Arduino Compile/build-1 ] | |-- OpticalEncoder +[Arduino Compile/build-2 ] | Tool Manager: toolchain-gccarmnoneeabi@1.140201.0 has been installed! +[Arduino Compile/build-2 ] | Tool Manager: Installing platformio/framework-cmsis @ ~2.50900.0 +[Arduino Compile/build-1 ] | Building in release mode +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/src/i2c.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/src/main.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/libb7f/NewPing/NewPing.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib88e/Stepper/Stepper.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/liba34/Servo/avr/Servo.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/liba34/Servo/mbed/Servo.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/liba34/Servo/megaavr/Servo.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/liba34/Servo/nrf52/Servo.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/liba34/Servo/renesas/Servo.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/liba34/Servo/sam/Servo.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/liba34/Servo/samd/Servo.cpp.o +[Arduino Compile/build-1 ] | Archiving .pio/build/nanoatmega328new/lib88e/libStepper.a +[Arduino Compile/build-1 ] | Archiving .pio/build/nanoatmega328new/libb7f/libNewPing.a +[Arduino Compile/build-1 ] | Indexing .pio/build/nanoatmega328new/lib88e/libStepper.a +[Arduino Compile/build-1 ] | Indexing .pio/build/nanoatmega328new/libb7f/libNewPing.a +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/liba34/Servo/stm32f4/Servo.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/liba34/Servo/xmc/Servo.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/libe9a/DHTNEW/dhtnew.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib2f2/Adafruit SleepyDog Library/Adafruit_SleepyDog.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib2f2/Adafruit SleepyDog Library/utility/WatchdogAVR.cpp.o +[Arduino Compile/build-1 ] | Archiving .pio/build/nanoatmega328new/liba34/libServo.a +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib2f2/Adafruit SleepyDog Library/utility/WatchdogESP32.cpp.o +[Arduino Compile/build-1 ] | Indexing .pio/build/nanoatmega328new/liba34/libServo.a +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib2f2/Adafruit SleepyDog Library/utility/WatchdogESP8266.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib2f2/Adafruit SleepyDog Library/utility/WatchdogKinetisK.cpp.o +[Arduino Compile/build-5 ] Non-terminating error while running 'git clone': some refs were not updated +[Arduino Compile/build-5 ] 🧪 Matrix: map[board_fqbn:program_via_AVRISP_mkII] +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib2f2/Adafruit SleepyDog Library/utility/WatchdogKinetisL.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib2f2/Adafruit SleepyDog Library/utility/WatchdogNRF.cpp.o +[Arduino Compile/build-1 ] | Archiving .pio/build/nanoatmega328new/libe9a/libDHTNEW.a +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib2f2/Adafruit SleepyDog Library/utility/WatchdogRP2040.cpp.o +[Arduino Compile/build-5 ] ⭐ Run Main actions/checkout@v4 +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib2f2/Adafruit SleepyDog Library/utility/WatchdogSAMD.cpp.o +[Arduino Compile/build-1 ] | Indexing .pio/build/nanoatmega328new/libe9a/libDHTNEW.a +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib143/Wire/Wire.cpp.o +[Arduino Compile/build-5 ] 🐳 docker cp src=/home/arendjan/mirte/telemetrix4arduino/. dst=/home/arendjan/mirte/telemetrix4arduino +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/lib143/Wire/utility/twi.c.o +[Arduino Compile/build-1 ] | Archiving .pio/build/nanoatmega328new/lib2f2/libAdafruit SleepyDog Library.a +[Arduino Compile/build-1 ] | Archiving .pio/build/nanoatmega328new/libFrameworkArduinoVariant.a +[Arduino Compile/build-5 ] ✅ Success - Main actions/checkout@v4 +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/CDC.cpp.o +[Arduino Compile/build-1 ] | Indexing .pio/build/nanoatmega328new/lib2f2/libAdafruit SleepyDog Library.a +[Arduino Compile/build-1 ] | Indexing .pio/build/nanoatmega328new/libFrameworkArduinoVariant.a +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/HardwareSerial.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/HardwareSerial0.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/HardwareSerial1.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/HardwareSerial2.cpp.o +[Arduino Compile/build-1 ] | Archiving .pio/build/nanoatmega328new/lib143/libWire.a +[Arduino Compile/build-5 ] ⭐ Run Main Set up Python +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/HardwareSerial3.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/IPAddress.cpp.o +[Arduino Compile/build-1 ] | Indexing .pio/build/nanoatmega328new/lib143/libWire.a +[Arduino Compile/build-5 ] 🐳 docker cp src=/home/arendjan/.cache/act/actions-setup-python@v5/ dst=/var/run/act/actions/actions-setup-python@v5/ +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/PluggableUSB.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/Print.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/Stream.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/Tone.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/USBCore.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/WInterrupts.c.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/WMath.cpp.o +[Arduino Compile/build-4 ] | Downloading 0% 10% 20% +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Library Manager: NewPing@1.9.7 has been installed! +[Arduino Compile/build-4 ] | Library Manager: Installing arduino-libraries/Stepper @ ^1.1.3 +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/WString.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/abi.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/hooks.c.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/main.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/new.cpp.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/wiring.c.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/wiring_analog.c.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/wiring_digital.c.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/wiring_pulse.S.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/wiring_pulse.c.o +[Arduino Compile/build-1 ] | Compiling .pio/build/nanoatmega328new/FrameworkArduino/wiring_shift.c.o +[Arduino Compile/build-1 ] | Archiving .pio/build/nanoatmega328new/libFrameworkArduino.a +[Arduino Compile/build-1 ] | Indexing .pio/build/nanoatmega328new/libFrameworkArduino.a +[Arduino Compile/build-1 ] | Linking .pio/build/nanoatmega328new/firmware.elf +[Arduino Compile/build-5 ] 🐳 docker exec cmd=[/opt/acttoolcache/node/18.20.8/x64/bin/node /var/run/act/actions/actions-setup-python@v5/dist/setup/index.js] user= workdir= +[Arduino Compile/build-1 ] | Checking size .pio/build/nanoatmega328new/firmware.elf +[Arduino Compile/build-1 ] | Advanced Memory Usage is available via "PlatformIO Home > Project Inspect" +[Arduino Compile/build-1 ] | RAM: [==== ] 40.9% (used 838 bytes from 2048 bytes) +[Arduino Compile/build-1 ] | Flash: [==== ] 40.9% (used 12560 bytes from 30720 bytes) +[Arduino Compile/build-1 ] | Building .pio/build/nanoatmega328new/firmware.hex +[Arduino Compile/build-5 ] ❓ ::group::Installed versions +[Arduino Compile/build-5 ] | Successfully set up CPython (3.13.5) +[Arduino Compile/build-5 ] ❓ ::endgroup:: +[Arduino Compile/build-5 ] ❓ add-matcher /run/act/actions/actions-setup-python@v5/.github/python.json +[Arduino Compile/build-5 ] ✅ Success - Main Set up Python +[Arduino Compile/build-5 ] ⚙ ::set-env:: Python_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-5 ] ⚙ ::set-env:: Python2_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-5 ] ⚙ ::set-env:: Python3_ROOT_DIR=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-5 ] ⚙ ::set-env:: LD_LIBRARY_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib +[Arduino Compile/build-5 ] ⚙ ::set-env:: pythonLocation=/opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-5 ] ⚙ ::set-env:: PKG_CONFIG_PATH=/opt/hostedtoolcache/Python/3.13.5/x64/lib/pkgconfig +[Arduino Compile/build-5 ] ⚙ ::set-output:: python-version=3.13.5 +[Arduino Compile/build-5 ] ⚙ ::set-output:: python-path=/opt/hostedtoolcache/Python/3.13.5/x64/bin/python +[Arduino Compile/build-5 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64 +[Arduino Compile/build-5 ] ⚙ ::add-path:: /opt/hostedtoolcache/Python/3.13.5/x64/bin +[Arduino Compile/build-1 ] | ========================= [SUCCESS] Took 2.62 seconds ========================= +[Arduino Compile/build-1 ] | +[Arduino Compile/build-1 ] | Environment Status Duration +[Arduino Compile/build-1 ] | ---------------- -------- ------------ +[Arduino Compile/build-1 ] | nanoatmega328new SUCCESS 00:00:02.624 +[Arduino Compile/build-1 ] | ========================= 1 succeeded in 00:00:02.624 ========================= +[Arduino Compile/build-5 ] ⭐ Run Main Install dependencies +[Arduino Compile/build-1 ] ✅ Success - Main Run PlatformIO +[Arduino Compile/build-5 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/2] user= workdir= +[Arduino Compile/build-1 ] ⭐ Run Post Set up Python +[Arduino Compile/build-1 ] 🐳 docker exec cmd=[/opt/acttoolcache/node/18.20.8/x64/bin/node /var/run/act/actions/actions-setup-python@v5/dist/cache-save/index.js] user= workdir= +[Arduino Compile/build-1 ] ✅ Success - Post Set up Python +[Arduino Compile/build-1 ] ⭐ Run Complete job +[Arduino Compile/build-1 ] Cleaning up container for job build +[Arduino Compile/build-1 ] ✅ Success - Complete job +[Arduino Compile/build-1 ] 🏁 Job succeeded +[Arduino Compile/build-5 ] | Requirement already satisfied: pip in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (25.1.1) +[Arduino Compile/build-2 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[Arduino Compile/build-4 ] | Downloading 0% 10% +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% +[Arduino Compile/build-4 ] | Library Manager: Stepper@1.1.3 has been installed! +[Arduino Compile/build-4 ] | Library Manager: Installing robtillaart/DHTNEW @ ^0.4.18 +[Arduino Compile/build-2 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Requirement already satisfied: platformio in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (6.1.18) +[Arduino Compile/build-5 ] | Requirement already satisfied: bottle==0.13.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.13.4) +[Arduino Compile/build-5 ] | Requirement already satisfied: click<8.1.8,>=8.0.4 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (8.1.7) +[Arduino Compile/build-5 ] | Requirement already satisfied: colorama in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.4.6) +[Arduino Compile/build-5 ] | Requirement already satisfied: marshmallow==3.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.26.1) +[Arduino Compile/build-5 ] | Requirement already satisfied: pyelftools<1,>=0.27 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.32) +[Arduino Compile/build-5 ] | Requirement already satisfied: pyserial==3.5.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (3.5) +[Arduino Compile/build-5 ] | Requirement already satisfied: requests==2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.32.4) +[Arduino Compile/build-5 ] | Requirement already satisfied: semantic_version==2.10.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (2.10.0) +[Arduino Compile/build-5 ] | Requirement already satisfied: tabulate==0.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.9.0) +[Arduino Compile/build-5 ] | Requirement already satisfied: ajsonrpc==1.2.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-5 ] | Requirement already satisfied: starlette<0.47,>=0.19 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.46.2) +[Arduino Compile/build-5 ] | Requirement already satisfied: uvicorn<0.35,>=0.16 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (0.34.3) +[Arduino Compile/build-5 ] | Requirement already satisfied: wsproto==1.* in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from platformio) (1.2.0) +[Arduino Compile/build-5 ] | Requirement already satisfied: packaging>=17.0 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from marshmallow==3.*->platformio) (25.0) +[Arduino Compile/build-5 ] | Requirement already satisfied: charset_normalizer<4,>=2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.4.2) +[Arduino Compile/build-5 ] | Requirement already satisfied: idna<4,>=2.5 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (3.10) +[Arduino Compile/build-5 ] | Requirement already satisfied: urllib3<3,>=1.21.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2.5.0) +[Arduino Compile/build-5 ] | Requirement already satisfied: certifi>=2017.4.17 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from requests==2.*->platformio) (2025.6.15) +[Arduino Compile/build-2 ] | Tool Manager: framework-cmsis@2.50900.0 has been installed! +[Arduino Compile/build-2 ] | Tool Manager: Installing platformio/framework-arduinoststm32 @ ~4.21001.0 +[Arduino Compile/build-5 ] | Requirement already satisfied: anyio<5,>=3.6.2 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from starlette<0.47,>=0.19->platformio) (4.9.0) +[Arduino Compile/build-5 ] | Requirement already satisfied: sniffio>=1.1 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from anyio<5,>=3.6.2->starlette<0.47,>=0.19->platformio) (1.3.1) +[Arduino Compile/build-5 ] | Requirement already satisfied: h11>=0.8 in /opt/hostedtoolcache/Python/3.13.5/x64/lib/python3.13/site-packages (from uvicorn<0.35,>=0.16->platformio) (0.16.0) +[Arduino Compile/build-5 ] | WARNING: Running pip as the 'root' user can result in broken permissions and conflicting behaviour with the system package manager, possibly rendering your system unusable. It is recommended to use a virtual environment instead: https://pip.pypa.io/warnings/venv. Use the --root-user-action option if you know what you are doing and want to suppress this warning. +[Arduino Compile/build-5 ] ✅ Success - Main Install dependencies +[Arduino Compile/build-5 ] ⭐ Run Main Install platformIO libraries +[Arduino Compile/build-5 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/3] user= workdir= +[Arduino Compile/build-5 ] | ******************************************************************************** +[Arduino Compile/build-5 ] | If you like PlatformIO, please: +[Arduino Compile/build-5 ] | - star it on GitHub > https://github.com/platformio/platformio-core +[Arduino Compile/build-5 ] | - follow us on LinkedIn to stay up-to-date on the latest project news > https://www.linkedin.com/company/platformio/ +[Arduino Compile/build-5 ] | - try PlatformIO IDE for embedded development > https://platformio.org/platformio-ide +[Arduino Compile/build-5 ] | ******************************************************************************** +[Arduino Compile/build-5 ] | +[Arduino Compile/build-5 ] | Resolving program_via_AVRISP_mkII dependencies... +[Arduino Compile/build-5 ] | Platform Manager: Installing atmelavr +[Arduino Compile/build-4 ] | Downloading 0% 10% 20% 30% +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Library Manager: DHTNEW@0.4.21 has been installed! +[Arduino Compile/build-4 ] | Library Manager: Installing adafruit/Adafruit SleepyDog Library @ ^1.6.5 +[Arduino Compile/build-5 ] | Downloading 0% 10% 20% 30% 40% 50% 60% +[Arduino Compile/build-5 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Platform Manager: atmelavr@5.1.0 has been installed! +[Arduino Compile/build-5 ] | Tool Manager: Installing platformio/toolchain-atmelavr @ ~1.70300.0 +[Arduino Compile/build-4 ] | Downloading 0% 10% 20% +[Arduino Compile/build-4 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Library Manager: Adafruit SleepyDog Library@1.6.5 has been installed! +[Arduino Compile/build-4 ] ✅ Success - Main Install platformIO libraries +[Arduino Compile/build-4 ] ⭐ Run Main Run PlatformIO +[Arduino Compile/build-4 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/4] user= workdir= +[Arduino Compile/build-2 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Processing adafruit_itsybitsy_m4 (platform: atmelsam; board: adafruit_itsybitsy_m4; framework: arduino) +[Arduino Compile/build-4 ] | -------------------------------------------------------------------------------- +[Arduino Compile/build-4 ] | Verbose mode can be enabled via `-v, --verbose` option +[Arduino Compile/build-4 ] | CONFIGURATION: https://docs.platformio.org/page/boards/atmelsam/adafruit_itsybitsy_m4.html +[Arduino Compile/build-4 ] | PLATFORM: Atmel SAM (8.3.0) > Adafruit ItsyBitsy M4 +[Arduino Compile/build-4 ] | HARDWARE: SAMD51G19A 120MHz, 192KB RAM, 512KB Flash +[Arduino Compile/build-4 ] | DEBUG: Current (atmel-ice) External (atmel-ice, jlink) +[Arduino Compile/build-4 ] | PACKAGES: +[Arduino Compile/build-4 ] | - framework-arduino-samd-adafruit @ 1.10716.0 (1.7.16) +[Arduino Compile/build-4 ] | - framework-cmsis @ 2.50400.181126 (5.4.0) +[Arduino Compile/build-4 ] | - framework-cmsis-atmel @ 1.2.2 +[Arduino Compile/build-4 ] | - toolchain-gccarmnoneeabi @ 1.90301.200702 (9.3.1) +[Arduino Compile/build-4 ] | LDF: Library Dependency Finder -> https://bit.ly/configure-pio-ldf +[Arduino Compile/build-4 ] | LDF Modes: Finder ~ chain, Compatibility ~ soft +[Arduino Compile/build-4 ] | Found 16 compatible libraries +[Arduino Compile/build-4 ] | Scanning dependencies... +[Arduino Compile/build-4 ] | Dependency Graph +[Arduino Compile/build-4 ] | |-- NewPing @ 1.9.7 +[Arduino Compile/build-4 ] | |-- Stepper @ 1.1.3 +[Arduino Compile/build-4 ] | |-- DHTNEW @ 0.4.21 +[Arduino Compile/build-4 ] | |-- Adafruit SleepyDog Library @ 1.6.5 +[Arduino Compile/build-4 ] | |-- Wire @ 1.0 +[Arduino Compile/build-4 ] | |-- OpticalEncoder +[Arduino Compile/build-4 ] | |-- Servo @ 1.1.4 +[Arduino Compile/build-4 ] | Building in release mode +[Arduino Compile/build-4 ] | Compiling .pio/build/adafruit_itsybitsy_m4/src/i2c.cpp.o +[Arduino Compile/build-4 ] | Compiling .pio/build/adafruit_itsybitsy_m4/src/main.cpp.o +[Arduino Compile/build-5 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-4 ] | Compiling .pio/build/adafruit_itsybitsy_m4/lib13f/NewPing/NewPing.cpp.o +[Arduino Compile/build-4 ] | Compiling .pio/build/adafruit_itsybitsy_m4/lib924/Stepper/Stepper.cpp.o +[Arduino Compile/build-4 ] | src/main.cpp: In function 'void modify_reporting()': +[Arduino Compile/build-4 ] | src/main.cpp:414:23: warning: comparison of integer expressions of different signedness: 'int' and 'const unsigned int' [-Wsign-compare] +[Arduino Compile/build-4 ] | 414 | for (int i = 0; i < MAX_DIGITAL_PINS_SUPPORTED; i++) { +[Arduino Compile/build-4 ] | | ~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~ +[Arduino Compile/build-4 ] | src/main.cpp: In function 'void scan_digital_inputs()': +[Arduino Compile/build-4 ] | src/main.cpp:679:21: warning: comparison of integer expressions of different signedness: 'int' and 'const unsigned int' [-Wsign-compare] +[Arduino Compile/build-4 ] | 679 | for (int i = 0; i < MAX_DIGITAL_PINS_SUPPORTED; i++) { +[Arduino Compile/build-4 ] | | ~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~ +[Arduino Compile/build-4 ] | src/main.cpp: In function 'void setup()': +[Arduino Compile/build-4 ] | src/main.cpp:937:19: error: call of overloaded 'write(int)' is ambiguous +[Arduino Compile/build-4 ] | 937 | Serial.write(0); +[Arduino Compile/build-4 ] | | ^ +[Arduino Compile/build-4 ] | In file included from /root/.platformio/packages/framework-arduino-samd-adafruit/cores/arduino/Arduino.h:158, +[Arduino Compile/build-4 ] | from include/Telemetrix4Arduino.h:2, +[Arduino Compile/build-4 ] | from src/main.cpp:3: +[Arduino Compile/build-4 ] | /root/.platformio/packages/framework-arduino-samd-adafruit/cores/arduino/USB/USBAPI.h:136:17: note: candidate: 'virtual size_t Serial_::write(uint8_t)' +[Arduino Compile/build-4 ] | 136 | virtual size_t write(uint8_t); +[Arduino Compile/build-4 ] | | ^~~~~ +[Arduino Compile/build-4 ] | In file included from /root/.platformio/packages/framework-arduino-samd-adafruit/cores/arduino/Stream.h:26, +[Arduino Compile/build-4 ] | from /root/.platformio/packages/framework-arduino-samd-adafruit/cores/arduino/HardwareSerial.h:24, +[Arduino Compile/build-4 ] | from /root/.platformio/packages/framework-arduino-samd-adafruit/cores/arduino/Arduino.h:77, +[Arduino Compile/build-4 ] | from include/Telemetrix4Arduino.h:2, +[Arduino Compile/build-4 ] | from src/main.cpp:3: +[Arduino Compile/build-4 ] | /root/.platformio/packages/framework-arduino-samd-adafruit/cores/arduino/Print.h:51:12: note: candidate: 'size_t Print::write(const char*)' +[Arduino Compile/build-4 ] | 51 | size_t write(const char *str) { +[Arduino Compile/build-4 ] | | ^~~~~ +[Arduino Compile/build-4 ] | Compiling .pio/build/adafruit_itsybitsy_m4/lib6d7/DHTNEW/dhtnew.cpp.o +[Arduino Compile/build-4 ] | *** [.pio/build/adafruit_itsybitsy_m4/src/main.cpp.o] Error 1 +[Arduino Compile/build-4 ] | ========================== [FAILED] Took 2.47 seconds ========================== +[Arduino Compile/build-4 ] | +[Arduino Compile/build-4 ] | Environment Status Duration +[Arduino Compile/build-4 ] | --------------------- -------- ------------ +[Arduino Compile/build-4 ] | adafruit_itsybitsy_m4 FAILED 00:00:02.473 +[Arduino Compile/build-4 ] | ==================== 1 failed, 0 succeeded in 00:00:02.473 ==================== +[Arduino Compile/build-4 ] ❌ Failure - Main Run PlatformIO +[Arduino Compile/build-4 ] exitcode '1': failure +[Arduino Compile/build-4 ] ⭐ Run Complete job +[Arduino Compile/build-4 ] ✅ Success - Complete job +[Arduino Compile/build-4 ] 🏁 Job failed +[Arduino Compile/build-5 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Tool Manager: toolchain-atmelavr@1.70300.191015 has been installed! +[Arduino Compile/build-5 ] | Tool Manager: Installing platformio/framework-arduino-avr @ ~5.2.0 +[Arduino Compile/build-2 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Tool Manager: framework-arduino-avr@5.2.0 has been installed! +[Arduino Compile/build-5 ] | Tool Manager: Installing platformio/tool-scons @ ~4.40801.0 +[Arduino Compile/build-2 ] | Tool Manager: framework-arduinoststm32@4.21001.250617 has been installed! +[Arduino Compile/build-2 ] | Tool Manager: Installing platformio/tool-scons @ ~4.40801.0 +[Arduino Compile/build-5 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Tool Manager: tool-scons@4.40801.0 has been installed! +[Arduino Compile/build-5 ] | Library Manager: Installing teckel12/NewPing @ ^1.9.7 +[Arduino Compile/build-2 ] | Downloading 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-2 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-2 ] | Tool Manager: tool-scons@4.40801.0 has been installed! +[Arduino Compile/build-2 ] | Library Manager: Installing teckel12/NewPing @ ^1.9.7 +[Arduino Compile/build-5 ] | Downloading 0% 10% 20% +[Arduino Compile/build-5 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Library Manager: NewPing@1.9.7 has been installed! +[Arduino Compile/build-5 ] | Library Manager: Installing arduino-libraries/Stepper @ ^1.1.3 +[Arduino Compile/build-2 ] | Downloading 0% 10% 20% +[Arduino Compile/build-2 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-2 ] | Library Manager: NewPing@1.9.7 has been installed! +[Arduino Compile/build-2 ] | Library Manager: Installing arduino-libraries/Stepper @ ^1.1.3 +[Arduino Compile/build-5 ] | Downloading 0% 10% +[Arduino Compile/build-5 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% +[Arduino Compile/build-5 ] | Library Manager: Stepper@1.1.3 has been installed! +[Arduino Compile/build-5 ] | Library Manager: Installing arduino-libraries/Servo @ ^1.2.0 +[Arduino Compile/build-2 ] | Downloading 0% 10% +[Arduino Compile/build-2 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% +[Arduino Compile/build-2 ] | Library Manager: Stepper@1.1.3 has been installed! +[Arduino Compile/build-2 ] | Library Manager: Installing robtillaart/DHTNEW @ ^0.4.18 +[Arduino Compile/build-5 ] | Downloading 0% 10% 20% 30% 40% 50% +[Arduino Compile/build-5 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Library Manager: Servo@1.2.2 has been installed! +[Arduino Compile/build-5 ] | Library Manager: Installing robtillaart/DHTNEW @ ^0.4.18 +[Arduino Compile/build-2 ] | Downloading 0% 10% 20% 30% +[Arduino Compile/build-2 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-2 ] | Library Manager: DHTNEW@0.4.21 has been installed! +[Arduino Compile/build-2 ] ✅ Success - Main Install platformIO libraries +[Arduino Compile/build-2 ] ⭐ Run Main Run PlatformIO +[Arduino Compile/build-2 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/4] user= workdir= +[Arduino Compile/build-2 ] | Processing robotdyn_blackpill_f303cc (platform: ststm32; board: robotdyn_blackpill_f303cc; framework: arduino) +[Arduino Compile/build-2 ] | -------------------------------------------------------------------------------- +[Arduino Compile/build-5 ] | Downloading 0% 10% 20% 30% +[Arduino Compile/build-5 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-5 ] | Library Manager: DHTNEW@0.4.21 has been installed! +[Arduino Compile/build-5 ] | Library Manager: Installing adafruit/Adafruit SleepyDog Library @ ^1.6.5 +[Arduino Compile/build-2 ] | Verbose mode can be enabled via `-v, --verbose` option +[Arduino Compile/build-2 ] | CONFIGURATION: https://docs.platformio.org/page/boards/ststm32/robotdyn_blackpill_f303cc.html +[Arduino Compile/build-2 ] | PLATFORM: ST STM32 (19.2.0) > BlackPill F303CC +[Arduino Compile/build-2 ] | HARDWARE: STM32F303CCT6 72MHz, 40KB RAM, 256KB Flash +[Arduino Compile/build-2 ] | DEBUG: Current (blackmagic) External (blackmagic, cmsis-dap, jlink, stlink) +[Arduino Compile/build-2 ] | PACKAGES: +[Arduino Compile/build-2 ] | - framework-arduinoststm32 @ 4.21001.250617 (2.10.1) +[Arduino Compile/build-2 ] | - framework-cmsis @ 2.50900.0 (5.9.0) +[Arduino Compile/build-2 ] | - toolchain-gccarmnoneeabi @ 1.140201.0 (14.2.1) +[Arduino Compile/build-2 ] | LDF: Library Dependency Finder -> https://bit.ly/configure-pio-ldf +[Arduino Compile/build-2 ] | LDF Modes: Finder ~ chain, Compatibility ~ soft +[Arduino Compile/build-2 ] | Found 18 compatible libraries +[Arduino Compile/build-2 ] | Scanning dependencies... +[Arduino Compile/build-2 ] | Dependency Graph +[Arduino Compile/build-2 ] | |-- NewPing @ 1.9.7 +[Arduino Compile/build-2 ] | |-- Stepper @ 1.1.3 +[Arduino Compile/build-2 ] | |-- DHTNEW @ 0.4.21 +[Arduino Compile/build-2 ] | |-- Wire @ 1.0.0 +[Arduino Compile/build-2 ] | |-- OpticalEncoder +[Arduino Compile/build-2 ] | |-- Servo @ 1.1.2 +[Arduino Compile/build-2 ] | Building in release mode +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduinoVariant/PeripheralPins.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduinoVariant/PeripheralPins_SPARKY_F303CC.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduinoVariant/generic_clock.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduinoVariant/variant_BLACKPILL_F303CC.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduinoVariant/variant_SPARKY_F303CC.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduinoVariant/variant_generic.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_adc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_adc_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_can.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_ccb.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_cec.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_comp.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_comp_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_cordic.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_cortex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_crc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_crc_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_cryp.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_cryp_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dac.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dac_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dcache.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dcmi.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dcmi_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dfsdm.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dfsdm_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dma.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dma2d.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dma_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dsi.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_dts.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_eth.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_eth_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_exti.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_fdcan.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_firewall.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_flash.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_flash_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_flash_ramfunc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_fmac.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_fmpi2c.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_fmpi2c_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_fmpsmbus.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_fmpsmbus_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_gfxmmu.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_gfxtim.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_gpio.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_gpio_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_gpu2d.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_gtzc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_hash.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_hash_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_hcd.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_hrtim.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_hsem.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_i2c.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_i2c_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_i2s.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_i2s_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_i3c.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_icache.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_ipcc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_irda.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_iwdg.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_jpeg.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_lcd.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_lptim.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_ltdc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_ltdc_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_mdf.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_mdios.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_mdma.c.o +[Arduino Compile/build-5 ] | Downloading 0% 10% 20% +[Arduino Compile/build-5 ] | Unpacking 0% 10% 20% 30% 40% 50% 60% 70% 80% 90% 100% +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_mmc.c.o +[Arduino Compile/build-5 ] | Library Manager: Adafruit SleepyDog Library@1.6.5 has been installed! +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_mmc_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_nand.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_nor.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_opamp.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_opamp_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_ospi.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_otfdec.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_pccard.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_pcd.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_pcd_ex.c.o +[Arduino Compile/build-5 ] ✅ Success - Main Install platformIO libraries +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_pka.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_pssi.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_pwr.c.o +[Arduino Compile/build-5 ] ⭐ Run Main Run PlatformIO +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_pwr_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_qspi.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_ramcfg.c.o +[Arduino Compile/build-5 ] 🐳 docker exec cmd=[bash -e /var/run/act/workflow/4] user= workdir= +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_ramecc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_rcc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_rcc_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_rng.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_rng_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_rtc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_rtc_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_sai.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_sai_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_sd.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_sd_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_sdadc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_sdio.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_sdram.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_smartcard.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_smartcard_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_smbus.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_smbus_ex.c.o +[Arduino Compile/build-5 ] | Processing program_via_AVRISP_mkII (platform: atmelavr; board: nanoatmega328new; framework: arduino) +[Arduino Compile/build-5 ] | -------------------------------------------------------------------------------- +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_spdifrx.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_spi.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_spi_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_sram.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_subghz.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_swpmi.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_tim.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_tim_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_tsc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_uart.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_uart_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_usart.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_usart_ex.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_wwdg.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HAL/stm32yyxx_hal_xspi.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/HardwareTimer.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_adc.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_bdma.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_comp.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_cordic.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_crc.c.o +[Arduino Compile/build-5 ] | Verbose mode can be enabled via `-v, --verbose` option +[Arduino Compile/build-5 ] | CONFIGURATION: https://docs.platformio.org/page/boards/atmelavr/nanoatmega328new.html +[Arduino Compile/build-5 ] | PLATFORM: Atmel AVR (5.1.0) > Arduino Nano ATmega328 (New Bootloader) +[Arduino Compile/build-5 ] | HARDWARE: ATMEGA328P 16MHz, 2KB RAM, 30KB Flash +[Arduino Compile/build-5 ] | DEBUG: Current (avr-stub) External (avr-stub, simavr) +[Arduino Compile/build-5 ] | PACKAGES: +[Arduino Compile/build-5 ] | - framework-arduino-avr @ 5.2.0 +[Arduino Compile/build-5 ] | - toolchain-atmelavr @ 1.70300.191015 (7.3.0) +[Arduino Compile/build-5 ] | LDF: Library Dependency Finder -> https://bit.ly/configure-pio-ldf +[Arduino Compile/build-5 ] | LDF Modes: Finder ~ chain, Compatibility ~ soft +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_crs.c.o +[Arduino Compile/build-5 ] | Found 11 compatible libraries +[Arduino Compile/build-5 ] | Scanning dependencies... +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_dac.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_delayblock.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_dlyb.c.o +[Arduino Compile/build-5 ] | Dependency Graph +[Arduino Compile/build-5 ] | |-- NewPing @ 1.9.7 +[Arduino Compile/build-5 ] | |-- Stepper @ 1.1.3 +[Arduino Compile/build-5 ] | |-- Servo @ 1.2.2 +[Arduino Compile/build-5 ] | |-- DHTNEW @ 0.4.21 +[Arduino Compile/build-5 ] | |-- Adafruit SleepyDog Library @ 1.6.5 +[Arduino Compile/build-5 ] | |-- Wire @ 1.0 +[Arduino Compile/build-5 ] | |-- OpticalEncoder +[Arduino Compile/build-5 ] | Building in release mode +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_dma.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_dma2d.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_exti.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/src/i2c.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_fmac.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/src/main.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_fmc.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libf60/NewPing/NewPing.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_fmpi2c.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libb59/Stepper/Stepper.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libe88/Servo/avr/Servo.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libe88/Servo/mbed/Servo.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_fsmc.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libe88/Servo/megaavr/Servo.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libe88/Servo/nrf52/Servo.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libe88/Servo/renesas/Servo.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_gpio.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libe88/Servo/sam/Servo.cpp.o +[Arduino Compile/build-5 ] | Archiving .pio/build/program_via_AVRISP_mkII/libf60/libNewPing.a +[Arduino Compile/build-5 ] | Archiving .pio/build/program_via_AVRISP_mkII/libb59/libStepper.a +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libe88/Servo/samd/Servo.cpp.o +[Arduino Compile/build-5 ] | Indexing .pio/build/program_via_AVRISP_mkII/libf60/libNewPing.a +[Arduino Compile/build-5 ] | Indexing .pio/build/program_via_AVRISP_mkII/libb59/libStepper.a +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libe88/Servo/stm32f4/Servo.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_hrtim.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/libe88/Servo/xmc/Servo.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_i2c.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib356/DHTNEW/dhtnew.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib654/Adafruit SleepyDog Library/Adafruit_SleepyDog.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_i3c.c.o +[Arduino Compile/build-5 ] | Archiving .pio/build/program_via_AVRISP_mkII/libe88/libServo.a +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib654/Adafruit SleepyDog Library/utility/WatchdogAVR.cpp.o +[Arduino Compile/build-5 ] | Indexing .pio/build/program_via_AVRISP_mkII/libe88/libServo.a +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib654/Adafruit SleepyDog Library/utility/WatchdogESP32.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib654/Adafruit SleepyDog Library/utility/WatchdogESP8266.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib654/Adafruit SleepyDog Library/utility/WatchdogKinetisK.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib654/Adafruit SleepyDog Library/utility/WatchdogKinetisL.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_icache.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib654/Adafruit SleepyDog Library/utility/WatchdogNRF.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib654/Adafruit SleepyDog Library/utility/WatchdogRP2040.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib654/Adafruit SleepyDog Library/utility/WatchdogSAMD.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_lpgpio.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib143/Wire/Wire.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_lptim.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/lib143/Wire/utility/twi.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_lpuart.c.o +[Arduino Compile/build-5 ] | Archiving .pio/build/program_via_AVRISP_mkII/libFrameworkArduinoVariant.a +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_mdma.c.o +[Arduino Compile/build-5 ] | Indexing .pio/build/program_via_AVRISP_mkII/libFrameworkArduinoVariant.a +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/CDC.cpp.o +[Arduino Compile/build-5 ] | Archiving .pio/build/program_via_AVRISP_mkII/lib356/libDHTNEW.a +[Arduino Compile/build-5 ] | Archiving .pio/build/program_via_AVRISP_mkII/lib654/libAdafruit SleepyDog Library.a +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_opamp.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_pka.c.o +[Arduino Compile/build-5 ] | Indexing .pio/build/program_via_AVRISP_mkII/lib654/libAdafruit SleepyDog Library.a +[Arduino Compile/build-5 ] | Indexing .pio/build/program_via_AVRISP_mkII/lib356/libDHTNEW.a +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/HardwareSerial.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_pwr.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/HardwareSerial0.cpp.o +[Arduino Compile/build-5 ] | Archiving .pio/build/program_via_AVRISP_mkII/lib143/libWire.a +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_rcc.c.o +[Arduino Compile/build-5 ] | Indexing .pio/build/program_via_AVRISP_mkII/lib143/libWire.a +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/HardwareSerial1.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/HardwareSerial2.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_rng.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/HardwareSerial3.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_rtc.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/IPAddress.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_sdmmc.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/PluggableUSB.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/Print.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/Stream.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_spi.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/Tone.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/USBCore.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_swpmi.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/WInterrupts.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_tim.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/WMath.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/WString.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_ucpd.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/abi.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/hooks.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_usart.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/main.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/new.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/wiring.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_usb.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/LL/stm32yyxx_ll_utils.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/wiring_analog.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/new.cpp.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/wiring_digital.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/wiring_pulse.S.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/wiring_pulse.c.o +[Arduino Compile/build-5 ] | Compiling .pio/build/program_via_AVRISP_mkII/FrameworkArduino/wiring_shift.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/PortNames.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/analog.cpp.o +[Arduino Compile/build-5 ] | Archiving .pio/build/program_via_AVRISP_mkII/libFrameworkArduino.a +[Arduino Compile/build-5 ] | Indexing .pio/build/program_via_AVRISP_mkII/libFrameworkArduino.a +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/bootloader.c.o +[Arduino Compile/build-5 ] | Linking .pio/build/program_via_AVRISP_mkII/firmware.elf +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/clock.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/core_callback.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/dwt.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/hw_config.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/interrupt.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/otp.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/pinmap.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/stm32_def.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/system_stm32yyxx.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/timer.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/stm32/uart.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/SrcWrapper/src/syscalls.c.o +[Arduino Compile/build-5 ] | Checking size .pio/build/program_via_AVRISP_mkII/firmware.elf +[Arduino Compile/build-5 ] | Advanced Memory Usage is available via "PlatformIO Home > Project Inspect" +[Arduino Compile/build-5 ] | RAM: [==== ] 40.9% (used 838 bytes from 2048 bytes) +[Arduino Compile/build-5 ] | Flash: [==== ] 40.9% (used 12560 bytes from 30720 bytes) +[Arduino Compile/build-5 ] | Building .pio/build/program_via_AVRISP_mkII/firmware.hex +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/src/i2c.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/src/main.cpp.o +[Arduino Compile/build-5 ] | ========================= [SUCCESS] Took 4.06 seconds ========================= +[Arduino Compile/build-5 ] | +[Arduino Compile/build-5 ] | Environment Status Duration +[Arduino Compile/build-5 ] | ----------------------- -------- ------------ +[Arduino Compile/build-5 ] | program_via_AVRISP_mkII SUCCESS 00:00:04.060 +[Arduino Compile/build-5 ] | ========================= 1 succeeded in 00:00:04.060 ========================= +[Arduino Compile/build-5 ] ✅ Success - Main Run PlatformIO +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/libd2e/NewPing/NewPing.cpp.o +[Arduino Compile/build-5 ] ⭐ Run Post Set up Python +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/lib77c/Stepper/Stepper.cpp.o +[Arduino Compile/build-5 ] 🐳 docker exec cmd=[/opt/acttoolcache/node/18.20.8/x64/bin/node /var/run/act/actions/actions-setup-python@v5/dist/cache-save/index.js] user= workdir= +[Arduino Compile/build-2 ] | src/main.cpp:1032:2: warning: #warning "Watchdog not enabled, please enable it in the code" [-Wcpp] +[Arduino Compile/build-2 ] | 1032 | #warning "Watchdog not enabled, please enable it in the code" +[Arduino Compile/build-2 ] | | ^~~~~~~ +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/libcc9/DHTNEW/dhtnew.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/libfde/Wire/Wire.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/libfde/Wire/utility/twi.c.o +[Arduino Compile/build-5 ] ✅ Success - Post Set up Python +[Arduino Compile/build-5 ] ⭐ Run Complete job +[Arduino Compile/build-5 ] Cleaning up container for job build +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/libc95/Servo/stm32/Servo.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/HardwareSerial.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/IPAddress.cpp.o +[Arduino Compile/build-2 ] | In file included from src/main.cpp:8: +[Arduino Compile/build-2 ] | .pio/libdeps/robotdyn_blackpill_f303cc/NewPing/src/NewPing.h:253:46: warning: 'boolean' is deprecated [-Wdeprecated-declarations] +[Arduino Compile/build-2 ] | 253 | boolean ping_trigger(); +[Arduino Compile/build-2 ] | | ^ +[Arduino Compile/build-2 ] | In file included from /root/.platformio/packages/framework-arduinoststm32/cores/arduino/wiring.h:34, +[Arduino Compile/build-2 ] | from /root/.platformio/packages/framework-arduinoststm32/cores/arduino/Arduino.h:36, +[Arduino Compile/build-2 ] | from include/Telemetrix4Arduino.h:2, +[Arduino Compile/build-2 ] | from src/main.cpp:3: +[Arduino Compile/build-2 ] | /root/.platformio/packages/framework-arduinoststm32/cores/arduino/wiring_constants.h:110:14: note: declared here +[Arduino Compile/build-2 ] | 110 | typedef bool boolean __attribute__((deprecated)); +[Arduino Compile/build-2 ] | | ^~~~~~~ +[Arduino Compile/build-5 ] ✅ Success - Complete job +[Arduino Compile/build-5 ] 🏁 Job failed +[Arduino Compile/build-2 ] | In file included from .pio/libdeps/robotdyn_blackpill_f303cc/NewPing/src/NewPing.cpp:7: +[Arduino Compile/build-2 ] | .pio/libdeps/robotdyn_blackpill_f303cc/NewPing/src/NewPing.h:253:46: warning: 'boolean' is deprecated [-Wdeprecated-declarations] +[Arduino Compile/build-2 ] | 253 | boolean ping_trigger(); +[Arduino Compile/build-2 ] | | ^ +[Arduino Compile/build-2 ] | In file included from /root/.platformio/packages/framework-arduinoststm32/cores/arduino/wiring.h:34, +[Arduino Compile/build-2 ] | from /root/.platformio/packages/framework-arduinoststm32/cores/arduino/Arduino.h:36, +[Arduino Compile/build-2 ] | from .pio/libdeps/robotdyn_blackpill_f303cc/NewPing/src/NewPing.h:166: +[Arduino Compile/build-2 ] | /root/.platformio/packages/framework-arduinoststm32/cores/arduino/wiring_constants.h:110:14: note: declared here +[Arduino Compile/build-2 ] | 110 | typedef bool boolean __attribute__((deprecated)); +[Arduino Compile/build-2 ] | | ^~~~~~~ +[Arduino Compile/build-2 ] | .pio/libdeps/robotdyn_blackpill_f303cc/NewPing/src/NewPing.cpp:127:31: warning: 'boolean' is deprecated [-Wdeprecated-declarations] +[Arduino Compile/build-2 ] | 127 | boolean NewPing::ping_trigger() { +[Arduino Compile/build-2 ] | | ^ +[Arduino Compile/build-2 ] | /root/.platformio/packages/framework-arduinoststm32/cores/arduino/wiring_constants.h:110:14: note: declared here +[Arduino Compile/build-2 ] | 110 | typedef bool boolean __attribute__((deprecated)); +[Arduino Compile/build-2 ] | | ^~~~~~~ +[Arduino Compile/build-2 ] | Archiving .pio/build/robotdyn_blackpill_f303cc/libd2e/libNewPing.a +[Arduino Compile/build-2 ] | Archiving .pio/build/robotdyn_blackpill_f303cc/lib77c/libStepper.a +[Arduino Compile/build-2 ] | Indexing .pio/build/robotdyn_blackpill_f303cc/libd2e/libNewPing.a +[Arduino Compile/build-2 ] | Indexing .pio/build/robotdyn_blackpill_f303cc/lib77c/libStepper.a +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/Print.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/RingBuffer.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/Stream.cpp.o +[Arduino Compile/build-2 ] | Archiving .pio/build/robotdyn_blackpill_f303cc/libcc9/libDHTNEW.a +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/Tone.cpp.o +[Arduino Compile/build-2 ] | Indexing .pio/build/robotdyn_blackpill_f303cc/libcc9/libDHTNEW.a +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/WInterrupts.cpp.o +[Arduino Compile/build-2 ] | Archiving .pio/build/robotdyn_blackpill_f303cc/libfde/libWire.a +[Arduino Compile/build-2 ] | Indexing .pio/build/robotdyn_blackpill_f303cc/libfde/libWire.a +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/WMath.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/WSerial.cpp.o +[Arduino Compile/build-2 ] | Archiving .pio/build/robotdyn_blackpill_f303cc/libc95/libServo.a +[Arduino Compile/build-2 ] | Indexing .pio/build/robotdyn_blackpill_f303cc/libc95/libServo.a +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/WString.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/abi.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/avr/dtostrf.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/board.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/core_debug.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/hooks.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/itoa.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/main.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/pins_arduino.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/stm32/startup_stm32yyxx.S.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/wiring_analog.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/wiring_digital.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/wiring_pulse.cpp.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/wiring_shift.c.o +[Arduino Compile/build-2 ] | Compiling .pio/build/robotdyn_blackpill_f303cc/FrameworkArduino/wiring_time.c.o +[Arduino Compile/build-2 ] | Archiving .pio/build/robotdyn_blackpill_f303cc/libFrameworkArduino.a +[Arduino Compile/build-2 ] | Indexing .pio/build/robotdyn_blackpill_f303cc/libFrameworkArduino.a +[Arduino Compile/build-2 ] | Linking .pio/build/robotdyn_blackpill_f303cc/firmware.elf +[Arduino Compile/build-2 ] | Checking size .pio/build/robotdyn_blackpill_f303cc/firmware.elf +[Arduino Compile/build-2 ] | Advanced Memory Usage is available via "PlatformIO Home > Project Inspect" +[Arduino Compile/build-2 ] | RAM: [= ] 6.1% (used 2512 bytes from 40960 bytes) +[Arduino Compile/build-2 ] | Flash: [== ] 17.4% (used 45732 bytes from 262144 bytes) +[Arduino Compile/build-2 ] | Building .pio/build/robotdyn_blackpill_f303cc/firmware.bin +[Arduino Compile/build-2 ] | ========================= [SUCCESS] Took 12.38 seconds ========================= +[Arduino Compile/build-2 ] | +[Arduino Compile/build-2 ] | Environment Status Duration +[Arduino Compile/build-2 ] | ------------------------- -------- ------------ +[Arduino Compile/build-2 ] | robotdyn_blackpill_f303cc SUCCESS 00:00:12.381 +[Arduino Compile/build-2 ] | ========================= 1 succeeded in 00:00:12.381 ========================= +[Arduino Compile/build-2 ] ✅ Success - Main Run PlatformIO +[Arduino Compile/build-2 ] ⭐ Run Post Set up Python +[Arduino Compile/build-2 ] 🐳 docker exec cmd=[/opt/acttoolcache/node/18.20.8/x64/bin/node /var/run/act/actions/actions-setup-python@v5/dist/cache-save/index.js] user= workdir= +[Arduino Compile/build-2 ] ✅ Success - Post Set up Python +[Arduino Compile/build-2 ] ⭐ Run Complete job +[Arduino Compile/build-2 ] Cleaning up container for job build +[Arduino Compile/build-2 ] ✅ Success - Complete job +[Arduino Compile/build-2 ] 🏁 Job failed diff --git a/platformio.ini b/platformio.ini new file mode 100644 index 0000000..6c48670 --- /dev/null +++ b/platformio.ini @@ -0,0 +1,138 @@ +[env:nanoatmega328new] +platform = atmelavr +board = nanoatmega328new +framework = arduino +lib_deps = + teckel12/NewPing@^1.9.7 + arduino-libraries/Stepper@^1.1.3 + arduino-libraries/Servo@^1.2.0 + robtillaart/DHTNEW@^0.4.18 + ; silver-fang/Cpp_Standard_Library @ ^2.0.0 + adafruit/Adafruit SleepyDog Library@^1.6.5 + + +[env:nanoatmega328] +platform = atmelavr +board = nanoatmega328 +framework = arduino +; build_flags = -std=c++17 +lib_deps = + teckel12/NewPing@^1.9.7 + arduino-libraries/Stepper@^1.1.3 + arduino-libraries/Servo@^1.2.0 + robtillaart/DHTNEW@^0.4.18 + adafruit/Adafruit SleepyDog Library@^1.6.5 + +[env:robotdyn_blackpill_f303cc] +platform = ststm32 +board = robotdyn_blackpill_f303cc +framework = arduino +lib_deps = + teckel12/NewPing@^1.9.7 + arduino-libraries/Stepper@^1.1.3 + robtillaart/DHTNEW@^0.4.18 +build_flags = -DENABLE_ADAFRUIT_WATCHDOG=0 +platform_packages = + toolchain-gccarmnoneeabi + +[env:robotdyn_blackpill_f103] +platform = ststm32 +board = blackpill_f103c8 + +; change microcontroller +board_build.mcu = stm32f103c8t6 +board_build.f_cpu = 72000000L +upload_protocol = dfu +framework = arduino +lib_deps = + teckel12/NewPing@^1.9.7 + arduino-libraries/Stepper@^1.1.3 + robtillaart/DHTNEW@^0.4.18 +build_flags = -DENABLE_ADAFRUIT_WATCHDOG=0 -DPIO_FRAMEWORK_ARDUINO_ENABLE_CDC + +platform_packages = + toolchain-gccarmnoneeabi + +[env:adafruit_itsybitsy_m4] +platform = atmelsam +board = adafruit_itsybitsy_m4 +framework = arduino +build_flags = -std=c++2a +lib_deps = + teckel12/NewPing@^1.9.7 + arduino-libraries/Stepper@^1.1.3 + ; arduino-libraries/Servo@^1.2.0 ; No support yet for the M4 + robtillaart/DHTNEW@^0.4.18 + adafruit/Adafruit SleepyDog Library@^1.6.5 + + + +[env:program_via_AVRISP_mkII] # To flash the Arduino Nano with the new bootloader +platform = atmelavr +board = nanoatmega328new +framework = arduino +upload_protocol = custom +upload_port = usb +upload_flags = + -p$BOARD_MCU + -cavrispmkII +upload_command = avrdude $UPLOAD_FLAGS -U flash:w:$SOURCE:i +lib_deps = + teckel12/NewPing@^1.9.7 + arduino-libraries/Stepper@^1.1.3 + arduino-libraries/Servo@^1.2.0 + robtillaart/DHTNEW@^0.4.18 + ; silver-fang/Cpp_Standard_Library @ ^2.0.0 + adafruit/Adafruit SleepyDog Library@^1.6.5 + +[env:esp32doit-devkit-v1] +platform = espressif32 +board = esp32doit-devkit-v1 +build_type = debug +framework = arduino +lib_deps = + teckel12/NewPing@^1.9.7 + arduino-libraries/Stepper@^1.1.3 + ; arduino-libraries/Servo@^1.2.0 + robtillaart/DHTNEW@^0.4.18 + adafruit/Adafruit SleepyDog Library@^1.6.5 +build_flags = -std=c++2a -DMAX_SERVOS=0 -DENABLE_ADAFRUIT_WATCHDOG=0 -DENABLE_WATCHDOG=0 + +; [env:pico] +; platform = raspberrypi # official platform, but unsupported as RPi is skeer +; board = pico +; framework = arduino +; lib_deps = +; teckel12/NewPing@^1.9.7 +; arduino-libraries/Stepper@^1.1.3 +; arduino-libraries/Servo@^1.2.0 ; No support yet for the Pico +; robtillaart/DHTNEW@^0.4.18 +; adafruit/Adafruit SleepyDog Library@^1.6.5 +; adafruit/Adafruit SSD1306 @ ^2.5.15 +; build_flags = -std=c++2a -DENABLE_ADAFRUIT_WATCHDOG=1 + +[env:pico] # Alternative platform for Raspberry Pi Pico, without the MBED layer, fixes sonar issue +platform = https://github.com/maxgerhardt/platform-raspberrypi.git +board = pico +framework = arduino +lib_deps = + teckel12/NewPing@^1.9.7 + arduino-libraries/Stepper@^1.1.3 + arduino-libraries/Servo@^1.2.0 ; No support yet for the Pico + robtillaart/DHTNEW@^0.4.18 + adafruit/Adafruit SleepyDog Library@^1.6.5 + adafruit/Adafruit SSD1306 @ ^2.5.15 + +build_flags = -std=c++2a -DENABLE_ADAFRUIT_WATCHDOG=1 + +[env:pico2w] +platform = https://github.com/maxgerhardt/platform-raspberrypi.git +board = rpipico2w +framework = arduino +lib_deps = + teckel12/NewPing@^1.9.7 + arduino-libraries/Stepper@^1.1.3 + arduino-libraries/Servo@^1.2.0 ; No support yet for the Pico + robtillaart/DHTNEW@^0.4.18 + adafruit/Adafruit SleepyDog Library@^1.6.5 +build_flags = -std=c++2a -DENABLE_ADAFRUIT_WATCHDOG=1 diff --git a/src/boards/esp32devkit.cpp b/src/boards/esp32devkit.cpp new file mode 100644 index 0000000..d87db32 --- /dev/null +++ b/src/boards/esp32devkit.cpp @@ -0,0 +1,12 @@ +#include + +#if defined(ARDUINO_ARCH_ESP32) +void hw_init() { + + analogWriteResolution(8); + analogReadResolution(10); + Wire1.setPins(SECOND_I2C_PORT_SDA, SECOND_I2C_PORT_SCL); +} + +TwoWire Wire2 = Wire1; // Use GPIO 16 and 17 for I2C on ESP32 +#endif \ No newline at end of file diff --git a/src/boards/itsybitsy_m4.cpp b/src/boards/itsybitsy_m4.cpp new file mode 100644 index 0000000..d17f9b8 --- /dev/null +++ b/src/boards/itsybitsy_m4.cpp @@ -0,0 +1,9 @@ +#include + +#if defined(ARDUINO_ARCH_SAMD) && defined(ARDUINO_ITSYBITSY_M4) +void hw_init() { + analogWriteResolution(8); // Set default PWM resolution to 8 bits + analogReadResolution(10); // Set default ADC resolution to 10 bits +} + +#endif \ No newline at end of file diff --git a/src/boards/nanoatmega.cpp b/src/boards/nanoatmega.cpp new file mode 100644 index 0000000..74ae61b --- /dev/null +++ b/src/boards/nanoatmega.cpp @@ -0,0 +1,9 @@ +#include + +#if defined(ARDUINO_ARCH_AVR) && defined(ARDUINO_AVR_NANO) +void hw_init() { + // No specific hardware initialization needed for Nano + // This is a placeholder for future use if needed +} + +#endif \ No newline at end of file diff --git a/src/boards/pico.cpp b/src/boards/pico.cpp new file mode 100644 index 0000000..09d2299 --- /dev/null +++ b/src/boards/pico.cpp @@ -0,0 +1,17 @@ +#include + +#if defined(ARDUINO_RASPBERRY_PI_PICO_2W) || \ + defined(ARDUINO_RASPBERRY_PI_PICO_2) +TwoWire Wire2(i2c1, SECOND_I2C_PORT_SDA, SECOND_I2C_PORT_SCL); +#endif + +#if defined(ARDUINO_RASPBERRY_PI_PICO) +TwoWire Wire2(SECOND_I2C_PORT_SDA, SECOND_I2C_PORT_SCL); +#endif + +#if defined(ARDUINO_ARCH_RP2040) +void hw_init() { + analogWriteResolution(8); + analogReadResolution(10); +} +#endif diff --git a/src/boards/stm32blackpill.cpp b/src/boards/stm32blackpill.cpp new file mode 100644 index 0000000..19442ff --- /dev/null +++ b/src/boards/stm32blackpill.cpp @@ -0,0 +1,16 @@ + +#include +#if defined(ARDUINO_ARCH_STM32) && defined(ARDUINO_BLACKPILL_F103C8) + +void hw_init() { + analogWriteResolution(8); + analogReadResolution(10); +} +#endif + +#if defined(ARDUINO_ARCH_STM32) && defined(ARDUINO_BLACKPILL_F303CC) +void hw_init() { + analogWriteResolution(8); + analogReadResolution(10); +} +#endif diff --git a/src/i2c.cpp b/src/i2c.cpp new file mode 100644 index 0000000..b41f9ad --- /dev/null +++ b/src/i2c.cpp @@ -0,0 +1,184 @@ +#include "i2c.hpp" +#include "Telemetrix4Arduino.h" +#include "commands.hpp" +#include "config.hpp" +#include +#include + +/*********************************** + i2c functions + **********************************/ + +TwoWire *i2c_buses[I2C_COUNT] = { + &Wire, +#if I2C_COUNT > 1 + &Wire2 +#endif +#if I2C_COUNT > 2 + &Wire3 +#endif + // Add more TwoWire instances if needed +}; + +void i2c_begin() { + + byte i2c_port = command_buffer[0]; + if (i2c_port >= I2C_COUNT) { + // Invalid I2C port requested, return without initializing + // Serial.println("Invalid I2C port requested"); + return; + } + auto ¤t_i2c_port = *i2c_buses[i2c_port]; + // Initialize the I2C port + current_i2c_port.begin(); + +#if defined(__AVR_ATmega328P__) + current_i2c_port.setWireTimeout(10, false); + current_i2c_port.clearWireTimeoutFlag(); +#endif +} + +void i2c_read() { + + // data in the incoming message: + // address, [0] + // register, [1] + // number of bytes, [2] + // stop transmitting flag [3] + // i2c port [4] + + int message_size = 0; + byte address = command_buffer[0]; + byte the_register = command_buffer[1]; + uint8_t message_id = command_buffer[I2C_READ_MESSAGE_ID]; + uint8_t port = command_buffer[I2C_PORT]; + if (port >= I2C_COUNT) { + // Invalid I2C port requested, return without processing + // Serial.println("Invalid I2C port requested"); + return; + } + auto ¤t_i2c_port = i2c_buses[port]; + uint8_t i2c_report_message[64]; + + current_i2c_port->beginTransmission(address); + current_i2c_port->write((byte)the_register); + current_i2c_port->endTransmission(command_buffer[3]); // default = true + current_i2c_port->requestFrom( + address, command_buffer[2]); // all bytes are returned in requestFrom + // check to be sure correct number of bytes were returned by slave + auto bytes = command_buffer[2]; + if (bytes != current_i2c_port->available()) { + i2c_report_message[I2C_PACKET_LENGTH] = + I2C_ERROR_REPORT_LENGTH; // length of the packet + i2c_report_message[I2C_REPORT_ID] = I2C_READ_FAILED; // report ID + i2c_report_message[I2C_REPORT_PORT] = command_buffer[4]; + i2c_report_message[I2C_REPORT_DEVICE_ADDRESS] = address; + Serial.write(i2c_report_message, I2C_ERROR_REPORT_LENGTH); + return; + } + for (int i = 0; i < bytes; i++) { + i2c_report_message[i + I2C_READ_START_OF_DATA] = current_i2c_port->read(); + } + // length of the packet + i2c_report_message[I2C_PACKET_LENGTH] = + (uint8_t)(bytes + I2C_READ_DATA_BASE_BYTES); + + i2c_report_message[I2C_REPORT_ID] = I2C_READ_REPORT; + + // i2c_port + i2c_report_message[I2C_REPORT_PORT] = command_buffer[I2C_PORT]; + + // i2c_address + i2c_report_message[I2C_REPORT_DEVICE_ADDRESS] = + command_buffer[I2C_DEVICE_ADDRESS]; + + // i2c register + i2c_report_message[I2C_REPORT_READ_REGISTER] = + command_buffer[I2C_READ_REGISTER]; + + // number of bytes read from i2c device + i2c_report_message[I2C_REPORT_READ_NUMBER_DATA_BYTES] = (uint8_t)bytes; + + i2c_report_message[I2C_READ_MESSAGE_ID] = message_id; + + for (int i = 0; i < message_size + 6; i++) { + Serial.write(i2c_report_message[i]); + } +} + +void i2c_write() { + + // command_buffer[0] is the number of bytes to send + // command_buffer[1] is the device address + // command_buffer[2] is the i2c port + // additional bytes to write= command_buffer[3..]; + + // set the current i2c port if this is for the primary i2c + uint8_t i2c_port = command_buffer[I2C_PORT]; + if (i2c_port >= I2C_COUNT) { + // Invalid I2C port requested, return without processing + // Serial.println("Invalid I2C port requested"); + return; + } + auto ¤t_i2c_port = i2c_buses[i2c_port]; +#if defined(__AVR_ATmega328P__) + if (current_i2c_port->getWireTimeoutFlag()) { + return; + } +#endif + current_i2c_port->beginTransmission(command_buffer[1]); + + // write the data to the device + for (int i = 0; i < command_buffer[0]; i++) { + current_i2c_port->write(command_buffer[i + 3]); + } + current_i2c_port->endTransmission(); + // delayMicroseconds(70); +} + +bool write_i2c(int i2c_port, int device_address, const uint8_t *data, + size_t length) { + if (i2c_port < 0 || i2c_port >= I2C_COUNT) { + return false; // Invalid I2C port + } + TwoWire *wire = i2c_buses[i2c_port]; + if (wire == nullptr) { + return false; // I2C bus not initialized + } + wire->beginTransmission(device_address); + for (size_t i = 0; i < length; i++) { + wire->write(data[i]); + } + return wire->endTransmission() == 0; // Return true if successful +} + +bool read_i2c(int i2c_port, int device_address, const uint8_t *registers, + size_t register_length, uint8_t *data, size_t data_length) { + if (i2c_port < 0 || i2c_port >= I2C_COUNT) { + return false; // Invalid I2C port + } + TwoWire *wire = i2c_buses[i2c_port]; + if (wire == nullptr) { + return false; // I2C bus not initialized + } + + wire->beginTransmission(device_address); + for (size_t i = 0; i < register_length; i++) { + wire->write(registers[i]); + } + + if (wire->endTransmission() != 0) { + return false; // Transmission failed + } + + size_t bytesRead = wire->requestFrom(device_address, data_length); + if (bytesRead != data_length) { + return false; // Not enough data read + } + + for (size_t i = 0; i < bytesRead; i++) { + data[i] = wire->read(); + } + + return true; // Read successful +} \ No newline at end of file diff --git a/src/main.cpp b/src/main.cpp new file mode 100644 index 0000000..97cea0f --- /dev/null +++ b/src/main.cpp @@ -0,0 +1,1120 @@ +// #include "Telemetrix4Arduino.h" +// #include +#include "main.hpp" +#include "Telemetrix4Arduino.h" +#include "commands.hpp" +#include "config.hpp" +#include "i2c.hpp" +#include "modules.hpp" +#include +#include +#include +#if MAX_SERVOS > 0 +#include +#endif +#include "sensors.hpp" +#include +#include +// #include +/* + Copyright (c) 2020 Alan Yorinks All rights reserved. + + This program is free software; you can redistribute it and/or + modify it under the terms of the GNU AFFERO GENERAL PUBLIC LICENSE + Version 3 as published by the Free Software Foundation; either + or (at your option) any later version. + This library is distributed in the hope that it will be useful,f + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + General Public License for more details. + + You should have received a copy of the GNU AFFERO GENERAL PUBLIC LICENSEf + along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +// We define these here to provide a forward reference. +// If you add a new command, you must add the command handler +// here as well. + +// #include +template void send_message(const uint8_t (&message)[N]); +// uncomment out the next line to create a 2nd i2c port + +// This value must be the same as specified when instantiating the +// telemetrix client. The client defaults to a value of 1. +// This value is used for the client to auto-discover and to +// connect to a specific board regardless of the current com port +// it is currently connected to. +#define ARDUINO_ID 1 + +// When adding a new command update the command_table. +// The command length is the number of bytes that follow +// the command byte itself, and does not include the command +// byte in its length. +// The command_func is a pointer the command's function. +// using command_descriptor = void *(void); +typedef void (*command_descriptor)(); +// not implemented functions +// auto pwm_write = nullptr; +// auto get_unique_id = nullptr; +auto reset_board = nullptr; +auto init_neo_pixels = nullptr; +auto show_neo_pixels = nullptr; +auto set_neo_pixel = nullptr; +auto clear_all_neo_pixels = nullptr; +auto fill_neo_pixels = nullptr; +auto init_spi = nullptr; +auto write_blocking_spi = nullptr; +auto read_blocking_spi = nullptr; +auto set_format_spi = nullptr; +auto spi_cs_control = nullptr; +auto set_scan_delay = nullptr; +// auto sensor_new = ; +// auto ping = nullptr; +// auto module_new = module_new; +// auto module_data = module_data; +auto get_id = nullptr; +auto set_id = nullptr; +// If you add new commands, make sure to extend the siz of this +// array. +constexpr command_descriptor command_table[] = { + &serial_loopback, // 0 + &set_pin_mode, // 1 + &digital_write, // 2, checked + pwm_write, // 3 + &modify_reporting, // 4, checked + &get_firmware_version, // 5, checked + &get_unique_id, // 6, checked + &servo_attach, // 7 + &servo_write, // 8 + &servo_detach, // 9 + &i2c_begin, + &i2c_read, + &i2c_write, + &sonar_new, // 13, checked + &dht_new, + &stop_all_reports, // 15, checked + &enable_all_reports, // 16, checked + &reset_data, + reset_board, + init_neo_pixels, + show_neo_pixels, + set_neo_pixel, + clear_all_neo_pixels, + fill_neo_pixels, + init_spi, + write_blocking_spi, + read_blocking_spi, + set_format_spi, + spi_cs_control, + set_scan_delay, + &encoder_new, // 30, checked + &sensor_new, + ping, // 32, checked, not impelemented + &module_new, + &module_data, + get_id, + set_id, + &feature_detection}; +const size_t command_table_size = + sizeof(command_table) / sizeof(command_descriptor); +// Input pin reporting control sub commands (modify_reporting) +#define REPORTING_DISABLE_ALL 0 +#define REPORTING_ANALOG_ENABLE 1 +#define REPORTING_DIGITAL_ENABLE 2 +#define REPORTING_ANALOG_DISABLE 3 +#define REPORTING_DIGITAL_DISABLE 4 + +// Pin mode definitions + +// INPUT defined in Arduino.h = 0 +// OUTPUT defined in Arduino.h = 1 +// INPUT_PULLUP defined in Arduino.h = 2 +// The following are defined for arduino_telemetrix (AT) +// #define AT_ANALOG 3 +// #define NOT_SET 255 + +// Reports - sent from this sketch +// #define DIGITAL_REPORT DIGITAL_WRITE +// #define ANALOG_REPORT ANALOG_WRITE +// #define FIRMWARE_REPORT 5 +// #define I_AM_HERE 6 +// #define SERVO_UNAVAILABLE 7 +// #define I2C_TOO_FEW_BYTES_RCVD 8 +// #define I2C_TOO_MANY_BYTES_RCVD 9 +// #define I2C_READ_REPORT 10 +// #define SONAR_DISTANCE 11 +// #define DHT_REPORT 12 +// #define DEBUG_PRINT 99 + +// #define ENCODER_REPORT 13 + +// DHT Report sub-types +#define DHT_DATA 0 +#define DHT_READ_ERROR 1 + +// firmware version - update this when bumping the version +#define FIRMWARE_MAJOR 1 +#define FIRMWARE_MINOR 11 + +// A buffer to hold i2c report data +byte i2c_report_message[64]; + +bool stop_reports = false; // a flag to stop sending all report messages + +// Analog input pin numbers are defined from +// A0 - A7. Since we do not know if the board +// in use also supports higher analog pin numbers +// we need to define those pin numbers to allow +// the program to compile, even though the +// pins may not exist for the board in use. +// The boards header file defines the analog pins that are not available +// To translate a pin number from an integer value to its analog pin number +// equivalent, this array is used to look up the value to use for the pin. +constexpr int analog_read_pins[20] = {A0, A1, A2, A3, A4, A5, A6, + A7, A8, A9, A10, A11, A12, A13, + A14, A15, A16, A17, A18, A19}; +constexpr int analog_read_pins_size = + sizeof(analog_read_pins) / sizeof(analog_read_pins[0]); +constexpr int ANALOG_PIN_OFFSET = A0; +constexpr int get_total_pins_not(const int *pins, int size, int not_value) { + return size > 0 ? (pins[size - 1] != not_value + ? get_total_pins_not(pins, size - 1, not_value) + 1 + : get_total_pins_not(pins, size - 1, not_value)) + : 0; +} + +constexpr int +max_i(int a, int b) { // some board have an old stdlib without constexpr max + return a < b ? b : a; +} + +constexpr int get_highest_analog_pin(const int *pins, int size, int not_value) { + return size > 0 + ? (pins[size - 1] != not_value + ? max_i(get_highest_analog_pin(pins, size - 1, not_value), + pins[size - 1]) + : get_highest_analog_pin(pins, size - 1, not_value)) + : 0; +} + +constexpr auto MAX_ANALOG_PINS_SUPPORTED = + get_total_pins_not(analog_read_pins, analog_read_pins_size, 2047); + +// maximum number of pins supported +// some boards (stm32f103) put analog pins in the 0xC0 range +// wastes some memory space, but is easier to use. +constexpr auto MAX_PINS_SUPPORTED = + max_i(NUM_DIGITAL_PINS + MAX_ANALOG_PINS_SUPPORTED, + get_highest_analog_pin(analog_read_pins, analog_read_pins_size, + 2047)); // probably too high but good enough +// #define +// a descriptor for digital pins +struct pin_descriptor { + byte pin_number; + PIN_MODES pin_mode; + bool digital_reporting_enabled; // If true, then send reports if an input pin + bool analog_reporting_enabled; // If true, then send reports if an input pin + int last_value; // Last value read for input mode + int differential; // difference between current and last value needed + // to generate a report +}; + +// an array of digital_pin_descriptors +pin_descriptor the_digital_pins[MAX_PINS_SUPPORTED]; + +// a descriptor for digital pins +// struct analog_pin_descriptor { +// byte pin_number; +// PIN_MODES pin_mode; +// bool reporting_enabled; // If true, then send reports if an input pin +// int last_value; // Last value read for input mode +// }; + +// // an array of analog_pin_descriptors +// analog_pin_descriptor the_analog_pins[40]; + +unsigned long current_millis; // for analog input loop +unsigned long previous_millis; // for analog input loop +uint8_t analog_sampling_interval = 19; + +#if MAX_SERVOS > 0 +// servo management +Servo servos[MAX_SERVOS]; // max set by servo library +// this array allows us to retrieve the servo object +// associated with a specific pin number +byte servo_index_to_pin_map[MAX_SERVOS]; +#endif +// HC-SR04 Sonar Management + +struct Sonar { + uint8_t trigger_pin; + unsigned int last_value; + NewPing *usonic; +}; + +// an array of sonar objects +Sonar sonars[MAX_SONARS]; + +byte sonars_index = 0; // index into sonars struct + +// used for scanning the sonar devices. +byte last_sonar_visited = 0; + +unsigned long sonar_current_millis; // for analog input loop +unsigned long sonar_previous_millis; // for analog input loop +uint8_t sonar_scan_interval = 33; // Milliseconds between sensor pings +// (29ms is about the min to avoid = 19; + +// DHT Management +#define MAX_DHTS 6 // max number of devices +#define READ_FAILED_IN_SCANNER 0 // read request failed when scanning +#define READ_IN_FAILED_IN_SETUP \ + 1 // read request failed when initially setting up + +struct DHT { + uint8_t pin; + unsigned int last_value; + DHTNEW *dht_sensor; +}; + +// an array of dht objects] +DHT dhts[MAX_DHTS]; + +byte dht_index = 0; // index into dht struct + +unsigned long dht_current_millis; // for analog input loop +unsigned long dht_previous_millis; // for analog input loop +unsigned int dht_scan_interval = 2000; // scan dht's every 2 seconds + +// Optical encoder handling +struct OptEncoder { + uint8_t pin; + long last_value; + OpticalEncoder *optEnc_sensor; +}; + +#define MAX_ENCODERS 2 + +OptEncoder optEnc[MAX_ENCODERS]; +uint8_t optEncoder_ix = 0; // number of Optical Encoders attached + +typedef void (*intCB)(void); // lambda definition for interrupt callback + +intCB interruptMap[MAX_ENCODERS] = { + [] { optEnc[0].optEnc_sensor->handleInterrupt(); }, + [] { optEnc[1].optEnc_sensor->handleInterrupt(); }, + // [] { optEnc[2].optEnc_sensor->handleInterrupt(); }, + // [] { optEnc[3].optEnc_sensor->handleInterrupt(); } +}; + +unsigned long optenc_current_millis; // for encoder input loop +unsigned long optenc_previous_millis; // for encoder input loop +unsigned int optenc_scan_interval = 10; // scan encoders every x ms + +// buffer to hold incoming command data +uint8_t command_buffer[MAX_COMMAND_LENGTH]; + +// A method to send debug data across the serial link +void send_debug_info(byte id, int value) { + byte debug_buffer[] = {(byte)DEBUG_PRINT, 0, 0, 0}; + debug_buffer[1] = id; + debug_buffer[2] = highByte(value); + debug_buffer[3] = lowByte(value); + // while(Serial.availableForWrite() < 5) { + // delay(1); + // } + // Serial.write(debug_buffer, 5); + send_message(debug_buffer); +} + +// command functions +void serial_loopback() { + byte loop_back_buffer[] = {(byte)SERIAL_LOOP_BACK, command_buffer[0]}; + // Serial.write(loop_back_buffer, 3); + send_message(loop_back_buffer); +} + +void set_pin_mode() { + byte pin; + PIN_MODES mode; + pin = command_buffer[0]; + mode = (PIN_MODES)command_buffer[1]; + // Serial2.println("Setting pin mode: " + String(pin) + " to " + + // String(mode)); + switch (mode) { + case INPUT_PULL_DOWN: + the_digital_pins[pin].pin_mode = mode; + the_digital_pins[pin].digital_reporting_enabled = command_buffer[2]; + the_digital_pins[pin].last_value = -1; +#ifndef INPUT_PULLDOWN // for boards that do not support INPUT_PULLDOWN, fall + // back to INPUT +#define INPUT_PULLDOWN INPUT +#endif + pinMode(pin, INPUT_PULLDOWN); + break; + case INPUT_MODE: //[SET_PIN_MODE = 1, pin, digital_in_type, report_enable] + the_digital_pins[pin].pin_mode = mode; + the_digital_pins[pin].digital_reporting_enabled = command_buffer[2]; + the_digital_pins[pin].last_value = -1; + pinMode(pin, INPUT); + break; + case INPUT_PULL_UP: + the_digital_pins[pin].pin_mode = mode; + the_digital_pins[pin].digital_reporting_enabled = command_buffer[2]; + the_digital_pins[pin].last_value = -1; + pinMode(pin, INPUT_PULLUP); + break; + case OUTPUT_MODE: + the_digital_pins[pin].pin_mode = mode; + pinMode(pin, OUTPUT); + break; + case ANALOG_INPUT: // [SET_PIN_MODE = 1, adc_pin, ANALOG_IN = 5, diff_high, + // diff_low, report_enable ] + pinMode(pin, INPUT); + the_digital_pins[pin].pin_mode = mode; + the_digital_pins[pin].differential = + (command_buffer[2] << 8) + command_buffer[3]; + the_digital_pins[pin].analog_reporting_enabled = command_buffer[4]; + the_digital_pins[pin].last_value = -1; + send_debug_info(pin, the_digital_pins[pin].differential); + break; + case PWM: + pinMode(pin, OUTPUT); + break; + default: + break; + } +} + +void set_analog_scanning_interval() { + analog_sampling_interval = command_buffer[0]; +} + +void digital_write() { + byte pin; + byte value; + pin = command_buffer[0]; + value = command_buffer[1]; + digitalWrite(pin, value); +} + +void pwm_write() { + // [PWM_WRITE = 3, pin, value_high, value_low] + + // command_buffer[0] = PIN, command_buffer[1] = value_msb, + // command_buffer[2] = value_lsb + byte pin; // command_buffer[0] + unsigned int value; + pin = command_buffer[0]; + + value = (command_buffer[1] << 8) + command_buffer[2]; + + send_debug_info(3, pin); + send_debug_info(4, value); + analogWrite(pin, value); +} + +void modify_reporting() { + // [MODIFY_REPORTING = 4, modify_type, pin] + + int pin = command_buffer[1]; + + switch (command_buffer[0]) { + case REPORTING_DISABLE_ALL: + for (uint8_t i = 0; i < MAX_PINS_SUPPORTED; i++) { + the_digital_pins[i].digital_reporting_enabled = false; + the_digital_pins[i].analog_reporting_enabled = false; + } + break; + case REPORTING_ANALOG_ENABLE: + if (the_digital_pins[pin].pin_mode != NOT_SET) { + the_digital_pins[pin].analog_reporting_enabled = true; + } + break; + case REPORTING_ANALOG_DISABLE: + if (the_digital_pins[pin].pin_mode != NOT_SET) { + the_digital_pins[pin].analog_reporting_enabled = false; + } + break; + case REPORTING_DIGITAL_ENABLE: + if (the_digital_pins[pin].pin_mode != NOT_SET) { + the_digital_pins[pin].digital_reporting_enabled = true; + } + break; + case REPORTING_DIGITAL_DISABLE: + if (the_digital_pins[pin].pin_mode != NOT_SET) { + the_digital_pins[pin].digital_reporting_enabled = false; + } + break; + default: + break; + } +} + +void get_firmware_version() { + byte report_message[] = {FIRMWARE_REPORT, FIRMWARE_MAJOR, FIRMWARE_MINOR}; + pinMode(LED_BUILTIN, OUTPUT); + digitalWrite(LED_BUILTIN, HIGH); + // Serial.write(report_message, 4); + send_message<3>(report_message); +} + +// void are_you_there() { +// byte report_message[3] = {2, I_AM_HERE, ARDUINO_ID}; +// Serial.write(report_message, 3); +// } + +/*************************************************** + Servo Commands + **************************************************/ + +// Find the first servo that is not attached to a pin +// This is a helper function not called directly via the API +int find_servo() { +#if MAX_SERVOS > 0 + int index = -1; + for (int i = 0; i < MAX_SERVOS; i++) { + if (servos[i].attached() == false) { + index = i; + break; + } + } + return index; +#else + return -1; // no servos supported +#endif +} + +void servo_attach() { +#if MAX_SERVOS > 0 + byte pin = command_buffer[0]; + int servo_found = -1; + + int minpulse = (command_buffer[1] << 8) + command_buffer[2]; + int maxpulse = (command_buffer[3] << 8) + command_buffer[4]; + + // find the first available open servo + servo_found = find_servo(); + if (servo_found != -1) { + servo_index_to_pin_map[servo_found] = pin; + servos[servo_found].attach(pin, minpulse, maxpulse); + } else { + // no open servos available, send a report back to client + byte report_message[] = {SERVO_UNAVAILABLE, pin}; + // Serial.write(report_message, 2); + send_message(report_message); + } +#endif +} + +// set a servo to a given angle +void servo_write() { +#if MAX_SERVOS > 0 + byte pin = command_buffer[0]; + int angle = command_buffer[1] << 8 | command_buffer[2]; + // find the servo object for the pin + for (int i = 0; i < MAX_SERVOS; i++) { + if (servo_index_to_pin_map[i] == pin) { + servos[i].write(angle); + return; + } + } +#endif +} + +// detach a servo and make it available for future use +void servo_detach() { +#if MAX_SERVOS > 0 + byte pin = command_buffer[0]; + + // find the servo object for the pin + for (int i = 0; i < MAX_SERVOS; i++) { + if (servo_index_to_pin_map[i] == pin) { + + servo_index_to_pin_map[i] = -1; + servos[i].detach(); + } + } +#else +#warning "No servos supported, servos will not do anything" +#endif +} + +/*********************************** + HC-SR04 adding a new device + **********************************/ + +void sonar_new() { + send_debug_info(9, sonars_index); + // [SONAR_NEW = 13, trigger_pin, echo_pin] + if (sonars_index >= MAX_SONARS) { + return; + } + send_debug_info(130, command_buffer[0]); + send_debug_info(131, command_buffer[1]); + sonars[sonars_index].usonic = + new NewPing((uint8_t)command_buffer[0], (uint8_t)command_buffer[1], 400); + sonars[sonars_index].trigger_pin = command_buffer[0]; + sonars_index++; // next index, so it is the number of sonars + sonar_scan_interval = 100 / sonars_index; // always scan all sonars in 100ms +} + +/*********************************** + DHT adding a new device + **********************************/ + +void dht_new() { + int d_read; + // report consists of: + // 0 - byte count + // 1 - report type + // 2 - dht report subtype + // 3 - pin number + // 4 - error value + + // pre-build an error report in case of a read error + byte report_message[] = {(byte)DHT_REPORT, (byte)DHT_READ_ERROR, (byte)0, + (byte)0}; + + dhts[dht_index].dht_sensor = new DHTNEW((uint8_t)command_buffer[0]); + dhts[dht_index].dht_sensor->setType(); + + dhts[dht_index].pin = command_buffer[0]; + d_read = dhts[dht_index].dht_sensor->read(); + + // if read return == zero it means no errors. + if (d_read == 0) { + dht_index++; + } else { + // error found + // send report and release the dht object + + report_message[2] = command_buffer[0]; // pin number + report_message[3] = d_read; + // Serial.write(report_message, 5); + send_message(report_message); + delete (dhts[dht_index].dht_sensor); + } +} + +/*********************************** + Adding a new encoder device + **********************************/ +void encoder_new() { + // [ENCODER_NEW = 30, encoder_type, pin_A, pin_B] + // TODO: encoder_type is ignored for now, only single encoder for now. + // TODO: convert this to a time triggered encoder system. + // create new encoder object and get interrupt calback method from map + auto pinA = command_buffer[1]; + optEnc[optEncoder_ix].optEnc_sensor = new OpticalEncoder(); + intCB callbackMethod = interruptMap[optEncoder_ix]; + optEnc[optEncoder_ix].optEnc_sensor->setup(pinA, callbackMethod, 0, 0); + optEnc[optEncoder_ix].pin = pinA; + optEncoder_ix++; +} + +void stop_all_reports() { + stop_reports = true; + // delay(20); + // Serial.flush(); +} + +void enable_all_reports() { + // Serial.flush(); + stop_reports = false; + // delay(20); +} + +byte packet_length; +void get_next_command() { + byte command; + command_descriptor command_entry; + + // clear the command buffer + memset(command_buffer, 0, sizeof(command_buffer)); + + // if there is no command waiting, then return + if (!Serial.available()) { + return; + } + // get the packet length + packet_length = (byte)Serial.read(); + // send_debug_info(0, packet_length); + auto max_wait = 10; // wait for the command to be available + while (max_wait-- > 0 && !Serial.available()) { + delayMicroseconds(10); + } + if (packet_length == 0) { + return; // no command to process, reset bytes + } + // get the command byte + command = (byte)Serial.read(); + + if (command >= command_table_size) { // discard the command + for (auto i = 0; i < packet_length - 1; i++) { + max_wait = 10; // wait for the next byte to be available + while (max_wait-- > 0 && !Serial.available()) { + delayMicroseconds(10); + } + Serial.read(); + } + // TODO: send a message to the client that the command is not supported + return; + } + command_entry = command_table[command]; + // Serial2.print("Command: "); + // Serial2.println(command); + if (packet_length > 1) { + // get the data for that command + for (int i = 0; i < packet_length - 1; i++) { + max_wait = 10; // wait for the next byte to be available + // need this delay or data read is not correct + while (max_wait-- > 0 && !Serial.available()) { + delayMicroseconds(10); + } + command_buffer[i] = (byte)Serial.read(); + // uncomment out to see each of the bytes following the command + // send_debug_info(i, command_buffer[i]); + } + } + command_entry(); +} + +void scan_digital_inputs() { + byte value; + + // report message + + // [DIGITAL_REPORT = 2, pin, value] + + byte report_message[4] = {DIGITAL_REPORT, 0, 0}; + + for (uint8_t i = 0; i < MAX_PINS_SUPPORTED; i++) { + if (the_digital_pins[i].pin_mode == INPUT_MODE || + the_digital_pins[i].pin_mode == INPUT_PULL_UP || + the_digital_pins[i].pin_mode == INPUT_PULL_DOWN) { + if (the_digital_pins[i].digital_reporting_enabled) { + // if the value changed since last read + value = (byte)digitalRead(the_digital_pins[i].pin_number); + if (value != the_digital_pins[i].last_value) { + the_digital_pins[i].last_value = value; + report_message[1] = (byte)i; + report_message[2] = value; + // Serial.write(report_message, 4); + send_message(report_message); + } + } + } + } +} + +void scan_analog_inputs() { + int value; + + // report message + + // byte 0 = packet length + // byte 1 = report type + // byte 2 = pin number + // byte 3 = high order byte of value + // byte 4 = low order byte of value + // [ANALOG_REPORT = 3, adc_pin, value_high, value_low] + + byte report_message[] = {ANALOG_REPORT, 0, 0, 0}; + uint8_t adjusted_pin_number; + int differential; + + current_millis = millis(); + if (current_millis - previous_millis > analog_sampling_interval) { + previous_millis += analog_sampling_interval; + for (uint8_t i = 0; i < MAX_PINS_SUPPORTED; i++) { + if (the_digital_pins[i].pin_mode == ANALOG_INPUT) { + if (the_digital_pins[i].analog_reporting_enabled) { + // if the value changed since last read + // adjust pin number for the actual read + adjusted_pin_number = i; // (uint8_t)(analog_read_pins[i]); + value = analogRead(adjusted_pin_number); + differential = abs(value - the_digital_pins[i].last_value); + if (differential >= the_digital_pins[i].differential) { + // trigger value achieved, send out the report + the_digital_pins[i].last_value = value; + report_message[1] = (byte)adjusted_pin_number; + report_message[2] = highByte(value); // get high order byte + report_message[3] = lowByte(value); + send_message(report_message); + } + } + } + } + } +} + +void scan_sonars() { + unsigned int distance; + + if (sonars_index) { + sonar_current_millis = millis(); + if (sonar_current_millis - sonar_previous_millis > sonar_scan_interval) { + // send_debug_info(10, sonar_current_millis); + sonar_previous_millis += sonar_scan_interval; + auto ping = sonars[last_sonar_visited].usonic->ping(); + distance = ping / US_ROUNDTRIP_CM; + if (ping == 0) { + distance = 0xFFFE; + } + if (distance != sonars[last_sonar_visited].last_value || true) { + sonars[last_sonar_visited].last_value = distance; + + // [SONAR_REPORT = 11, trigger_pin, distance_m, distance_cm] + + byte report_message[] = { + SONAR_DISTANCE, sonars[last_sonar_visited].trigger_pin, + (byte)(distance >> 8), (byte)(distance % 0xFF)}; + // Serial.write(report_message, 5); + // send_debug_info(0, distance); + send_message(report_message); + } + last_sonar_visited++; + if (last_sonar_visited == sonars_index) { + last_sonar_visited = 0; + } + } + } +} + +void scan_dhts() { + // prebuild report for valid data + // reuse the report if a read command fails + + // data returned is in floating point form - 4 bytes + // each for humidity and temperature + + // byte 0 = packet length + // byte 1 = report type + // byte 2 = report sub type - DHT_DATA or DHT_ERROR + // btye 3 = pin number + // byte 4 = humidity high order byte for data or error value + // byte 5 = humidity byte 2 + // byte 6 = humidity byte 3 + // byte 7 = humidity byte 4 + // byte 8 = temperature high order byte for data or + // byte 9 = temperature byte 2 + // byte 10 = temperature byte 3 + // byte 11 = temperature byte 4 + byte report_message[] = {DHT_REPORT, DHT_DATA, 0, 0, 0, 0, 0, 0, 0, 0, 0}; + + byte d_read; + + float dht_data; + + // are there any dhts to read? + if (dht_index) { + // is it time to do the read? This should occur every 2 seconds + dht_current_millis = millis(); + if (dht_current_millis - dht_previous_millis > dht_scan_interval) { + // update for the next scan + dht_previous_millis += dht_scan_interval; + + // read and report all the dht sensors + for (int i = 0; i < dht_index; i++) { + report_message[2] = dhts[i].pin; + // get humidity + dht_data = dhts[i].dht_sensor->getHumidity(); + memcpy(&report_message[3], &dht_data, sizeof dht_data); + + // get temperature + dht_data = dhts[i].dht_sensor->getTemperature(); + memcpy(&report_message[6], &dht_data, sizeof dht_data); + + // Serial.write(report_message, 12); + send_message(report_message); + + // now read do a read for this device for next go around + d_read = dhts[i].dht_sensor->read(); + + if (d_read) { + // error found + // send report + // send_debug_info(1, 1); + // report_message[0] = 4; + // report_message[1] = DHT_REPORT; + report_message[1] = DHT_READ_ERROR; + report_message[2] = dhts[i].pin; // pin number + report_message[3] = d_read; + // Serial.write(report_message, 5); + send_message(report_message); + } + } + } + } +} + +void scan_encoders() { + // [ENCODER_REPORT = 14, pin_A, steps] + + byte report_message[] = {ENCODER_REPORT, 0, 0}; + + long optEnc_return_val = 0; + + if (optEncoder_ix) { + + for (int i = 0; i < optEncoder_ix; ++i) { + auto enc = optEnc[i].optEnc_sensor; + optEnc_return_val = enc->getPosition(); + + if (optEnc_return_val != 0) { + enc->resetPosition(); + report_message[1] = optEnc[i].pin; + report_message[2] = optEnc_return_val & 0xFF; + + // Serial.write(report_message, 4); + send_message(report_message); + } + } + } +} + +void reset_data() { + // reset the data structures + + // fist stop all reporting + stop_all_reports(); + + current_millis = 0; // for analog input loop + previous_millis = 0; // for analog input loop + analog_sampling_interval = 19; + +// detach any attached servos +#if MAX_SERVOS > 0 + for (int i = 0; i < MAX_SERVOS; i++) { + if (servos[i].attached() == true) { + servos[i].detach(); + } + } +#endif + sonars_index = 0; // reset the index into the sonars array + + sonar_current_millis = 0; // for analog input loop + sonar_previous_millis = 0; // for analog input loop + sonar_scan_interval = 33; // Milliseconds between sensor pings + + dht_index = 0; // index into dht array + + dht_current_millis = 0; // for analog input loop + dht_previous_millis = 0; // for analog input loop + dht_scan_interval = 2000; // scan dht's every 2 seconds + + // Reset optical encoder timers and index + optEncoder_ix = 0; + optenc_current_millis = 0; // for analog input loop + optenc_previous_millis = 0; // for analog input loop + optenc_scan_interval = 10; // scan encoders every x ms + + init_pin_structures(); + + memset(sonars, 0, sizeof(sonars)); + memset(dhts, 0, sizeof(dhts)); + memset(optEnc, 0, sizeof(optEnc)); + enable_all_reports(); +} + +void init_pin_structures() { + // create an array of pin_descriptors for 100 pins + // establish the digital pin array + for (byte i = 0; i < MAX_PINS_SUPPORTED; i++) { + the_digital_pins[i].pin_number = i; + the_digital_pins[i].pin_mode = NOT_SET; + the_digital_pins[i].digital_reporting_enabled = false; + the_digital_pins[i].analog_reporting_enabled = false; + the_digital_pins[i].last_value = -1; + the_digital_pins[i].differential = 0; // no differential by default + } +} +#define RXD2 16 +#define TXD2 17 + +void setup() { + Serial.begin(115200); + init_pin_structures(); + hw_init(); + for (auto i = 0; i < 0xFF; i++) { + Serial.write((uint8_t)0); + } + pinMode(LED_BUILTIN, OUTPUT); + digitalWrite(LED_BUILTIN, LOW); // turn off the LED + for (auto i = 0; i < 4; i++) { + digitalWrite(LED_BUILTIN, HIGH); + delay(100); + digitalWrite(LED_BUILTIN, LOW); + delay(100); + } + // get_firmware_version(); +} + +void loop() { + // keep processing incoming commands + get_next_command(); + upd_modules(); + readSensors(); + static decltype(millis()) last_scan = 0; + static decltype(millis()) scan_delay = 10; + if (!stop_reports) { // stop reporting + if (millis() - last_scan >= (scan_delay)) { + static int x = 0; + x++; + // send_debug_info(100, x++); + // send_debug_info(101, Serial.available()); + digitalWrite(LED_BUILTIN, x % 2); + // Serial.println("Scanning inputs..."); + // send_debug_info(10, 10); + last_scan += scan_delay; + + scan_digital_inputs(); + scan_analog_inputs(); + scan_sonars(); + scan_dhts(); + scan_encoders(); + scan_modules(); + } + } +} +static_assert(command_table[32] == &ping, "command_table[32] must be ping"); +static_assert(sizeof(command_buffer) == MAX_COMMAND_LENGTH, + "command_buffer size must be equal to MAX_COMMAND_LENGTH"); +static_assert(command_table[37] == &feature_detection, + "command_table[37] must be feature_detection"); + +void feature_detection() { + send_debug_info(201, 1); + // in message: [FEATURE_CHECK = 37, message_type_to_check] + // out message: [3, FEATURE_CHECK, 0/1] + uint8_t report_message[7 + analog_read_pins_size] = { + FEATURE_CHECK, 0, 0, 0, 0, 0, 0}; + // byte report_message[3] = {2, FEATURE_CHECK, 0}; + auto message_type = command_buffer[0]; + report_message[1] = message_type; + if (command_table_size <= message_type) { + report_message[2] = 0; + } else { + auto cmd = command_table[message_type]; + if (cmd != nullptr) { + report_message[2] = 1; + if (cmd == &encoder_new) { + report_message[3] = MAX_ENCODERS; // encoder + report_message[4] = 1; // single encoder + } else if (cmd == &sonar_new) { + report_message[3] = MAX_SONARS; // sonar + } else if (cmd == &set_pin_mode) { + report_message[3] = NUM_DIGITAL_PINS; + report_message[4] = 10; // analog input resolution + report_message[5] = 8; // PWM resolution + report_message[6] = MAX_ANALOG_PINS_SUPPORTED; + // report_message[5] = ADC_RESOLUTION; // ADC resolution + // report_message[6] = PWM_RESOLUTION; // PWM resolution + // report_message[5] = ANALOG_PIN_OFFSET; + for (auto i = 0; i < MAX_ANALOG_PINS_SUPPORTED; i++) { + report_message[7 + i] = (uint8_t)analog_read_pins[i]; + } + } else if (cmd == &servo_attach) { + report_message[3] = MAX_SERVOS; + } else if (cmd == &dht_new) { + report_message[3] = MAX_DHTS; + } else if (cmd == &get_firmware_version) { + report_message[3] = FIRMWARE_MAJOR; + report_message[4] = FIRMWARE_MINOR; + } else if (cmd == &get_unique_id) { + report_message[3] = 0; // TODO: implement + } else if (cmd == &i2c_begin) { + report_message[3] = I2C_COUNT; + } + } else { + report_message[2] = 0; // command not supported + } + } + send_message(report_message); + send_debug_info(200, message_type); +} + +template void send_message(const uint8_t (&message)[N]) { + // while (Serial.availableForWrite() < (int)N + 3) { + // Serial.println("Waiting for serial write..."); + // delayMicroseconds(10); + // } + Serial.write((uint8_t)N); // send msg len + for (size_t i = 0; i < N; i++) { + Serial.write((uint8_t)message[i]); // send msg len + } + // Serial.write(message, N); // send message +} + +void send_message(const uint8_t *message, size_t length) { + // while (Serial.availableForWrite() < (int)length + 3) { + // Serial.println("Waiting for serial write..."); + // delayMicroseconds(10); + // } + Serial.write((uint8_t)(length)); // send msg len + for (size_t i = 0; i < length; i++) { + Serial.write((uint8_t)message[i]); // send msg len + } +} + +void get_unique_id() { + // in message: [GET_UNIQUE_ID = 6] + // out message: [REPORT_UNIQUE_ID = 6, id[0], id[1], id[2], + // id[3],id[4],id[5],id[6],id[7] ] + uint8_t report_message[] = {GET_UNIQUE_ID, 0}; // TODO: implement + send_message(report_message); +} + +#if ENABLE_ADAFRUIT_WATCHDOG +#include +#define ENABLE_WATCHDOG 1 +#endif +// TODO: other watchdog implementations + +#if ENABLE_WATCHDOG == 0 +#warning "Watchdog not enabled, please enable it in the code" +#endif +bool watchdog_enabled = false; +uint32_t last_ping = 0; +void ping() { + static uint8_t random = -1; + // digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); + auto special_num = command_buffer[0]; + if (!watchdog_enabled) { +#if ENABLE_ADAFRUIT_WATCHDOG + + Watchdog.enable(4000); +#endif + // watchdog_enable(WATCHDOG_TIME, + // 1); // Add watchdog requiring trigger every 5s + watchdog_enabled = true; + // srand(millis()); + // random = rand() % 100; // create some random number to let computer side + // // know it is the same run + random = 0x1B; + } + uint8_t out[] = {PONG_REPORT, // write type + special_num, random, 0, 0, 0, 0}; + // out[0] = out.size() - 1; // dont count the packet length + // send_debug_info(1, special_num); + // // Serial2.println("Pinging..."); + + send_message(out); + if (true) { + // watchdog_update(); +#if ENABLE_ADAFRUIT_WATCHDOG + Watchdog.reset(); +#endif + + last_ping = millis(); + } +} + +void module_new() { module_new_i(command_buffer, packet_length); } + +void module_data() { module_data_i(command_buffer, packet_length); } + +void sensor_new() { sensor_new_i(command_buffer, packet_length); } \ No newline at end of file diff --git a/src/modules.cpp b/src/modules.cpp new file mode 100644 index 0000000..d0967a9 --- /dev/null +++ b/src/modules.cpp @@ -0,0 +1,110 @@ +#include "modules.hpp" +#include "commands.hpp" +#include "main.hpp" + +typedef Module *(*ModuleFunc)(uint8_t[], size_t); + +Module *create_ssd1306_module(uint8_t data[], size_t packet_size) { + return new TmxSSD1306(data, packet_size); +} + +size_t module_count = 0; // Initialize module count +Module *modules[MAX_MODULES_COUNT] = {nullptr}; // Array of pointers to modules + +void module_new_i(uint8_t command_buffer[], size_t packet_size) { + + const auto msg_type = command_buffer[0]; + const ModuleFunc module_funcs[] = { + nullptr, // {MODULE_TYPES::PCA9685, [](std::vector& data) { + // return new PCA9685_Module(data); }}, + nullptr, // {MODULE_TYPES::HIWONDER_SERVO, []( std::vector& + // data) { return new Hiwonder_Servo(data); }}, + nullptr, // {MODULE_TYPES::SHUTDOWN_RELAY, [](const std::vector& + // data) { return nullptr; /* not implemented */ }}, + create_ssd1306_module, // {MODULE_TYPES::TMX_SSD1306, + // create_ssd1306_module}, + }; + if (module_count >= MAX_MODULES_COUNT) { + return; // no more modules can be added + } + if (msg_type == 1) { + const MODULE_TYPES type = (MODULE_TYPES)command_buffer[2]; + const uint8_t module_num = command_buffer[1]; + // std::vector data; + + // data.insert(data.end(), &command_buffer[4], + // &command_buffer[packet_size]); + + if (type >= MODULE_TYPES::MAX_MODULES) { + return; + } + Module *module = nullptr; + auto func = module_funcs[type]; + if (func == nullptr) { + module_count++; // Just increment counter, to keep the same index on mcu + // and computer. + return; // module type not supported + } + module = func(command_buffer + 3, packet_size - 3); + module->type = type; + module->num = module_num; + + modules[module_num] = module; + module_count++; + } else if (msg_type == 0) { // check module type feature detection + bool found = false; + const uint8_t module_type_target = command_buffer[1]; + if (module_type_target < MODULE_TYPES::MAX_MODULES) { + found = (module_funcs[module_type_target] != nullptr); + } + uint8_t message[4] = { + MODULE_MAIN_REPORT, // message type + 0, // feature check + module_type_target, // module type + (uint8_t)(found ? 1u : 0u) // found or not + }; + send_message(message, 4); + } +} + +void module_data_i(uint8_t command_buffer[], size_t packet_size) { + const uint8_t module_num = command_buffer[0]; + if (module_num > module_count || module_num >= MAX_MODULES_COUNT) { + return; + } + // std::vector data; + // data.insert(data.end(), &command_buffer[2], + // &command_buffer[packet_size]); + modules[module_num]->writeModule(command_buffer + 1, packet_size - 1); +} + +void Module::publishData(const uint8_t data[], size_t size) { + uint8_t out[30] = { + // 0, // write len + MODULE_REPORT, // write type + (uint8_t)this->num, // write num + this->type, // write sensor type + }; + for (size_t i = 0; i < size && i < sizeof(out) - 4; i++) { + out[i + 3] = data[i]; // copy data to the output buffer + } + + send_message(out, size + 4); // send the message with the data + // TODO: check dit +} + +void scan_modules() { + for (size_t i = 0; i < module_count; i++) { + if (modules[i] != nullptr && !modules[i]->stop) { + modules[i]->readModule(); + } + } +} + +void upd_modules() { + for (size_t i = 0; i < module_count; i++) { + if (modules[i] != nullptr && !modules[i]->stop) { + modules[i]->updModule(); + } + } +} \ No newline at end of file diff --git a/src/sensors.cpp b/src/sensors.cpp new file mode 100644 index 0000000..e5f6bb4 --- /dev/null +++ b/src/sensors.cpp @@ -0,0 +1,96 @@ +#include "sensors.hpp" +#if MAX_SENSORS_COUNT > 0 +#include "commands.hpp" +#include "main.hpp" +#include "sensors/veml6040.hpp" // Include the VEML6040 + +void Sensor::writeSensorData(const uint8_t data[], size_t size) { + uint8_t out[30] = { + SENSOR_REPORT, // write type + (uint8_t)this->num, // write num + this->type, // write sensor type + }; + for (size_t i = 0; i < size && i < sizeof(out) - 3; i++) { + out[i + 3] = data[i]; // copy data to the output buffer + } + send_message(out, size + 3); +} +Sensor *sensors[MAX_SENSORS_COUNT] = {}; // Array of pointers to sensors +size_t sensors_count = 0; // Number of sensors in the array + +typedef Sensor *(*SensorFunc)(uint8_t[], size_t); + +SensorFunc sensor_funcs[] = { + nullptr, // 0 - GPS + nullptr, // 1 - LOAD_CELL + nullptr, // 2 - MPU_9250 + nullptr, // 3 - TOF_VL53 + VEML6040_Sensor::create, // 4 - VEML6040 + nullptr, // 5 - ADXL345 + nullptr, // 6 - INA226a + nullptr, // 7 - HMC5883l + nullptr, // 8 - AS5600_t +}; + +void sensor_new_i(uint8_t command_buffer[], size_t packet_size) { + const uint8_t sensor_cmd = command_buffer[0]; + + if (sensor_cmd == 1) { + const SENSOR_TYPES type = (SENSOR_TYPES)command_buffer[2]; + const uint8_t sensor_num = command_buffer[1]; + + uint8_t *sensor_data = command_buffer + 3; // data starts after type and num + size_t sensor_data_size = packet_size - 3; // size of the data + if (type >= SENSOR_TYPES::MAX_SENSORS) { + return; + } + Sensor *sensor = nullptr; + if (sensor_funcs[type] != nullptr) { + sensor = sensor_funcs[type](sensor_data, sensor_data_size); + if (sensor == nullptr) { + // If sensor creation failed, we just increment the count and return + sensors_count++; + return; + } + } else { + sensors_count++; // Just increment counter, to keep the same index on mcu + // and computer. + return; + } + sensor->type = type; + sensor->num = sensor_num; + + sensors[sensor_num] = sensor; + sensors_count++; + } else if (sensor_cmd == 0) { + // This is a feature detection command, check if the sensor type is + // supported + const SENSOR_TYPES type = (SENSOR_TYPES)command_buffer[1]; + uint8_t found = + (type < SENSOR_TYPES::MAX_SENSORS && sensor_funcs[type] != nullptr); + + uint8_t message[4] = { + SENSOR_MAIN_REPORT, // message type + 0, // feature check + (uint8_t)type, // sensor type + found // found or not + }; + send_message(message, 4); + } +} + +void readSensors() { + for (size_t i = 0; i < sensors_count; i++) { + if (sensors[i] == nullptr || sensors[i]->stop) { + continue; // skip if sensor is not initialized or stopped + } + sensors[i]->readSensor(); + } +} + +#else +// No sensors supported, so we define empty functions +void sensor_new_i(uint8_t command_buffer[], size_t packet_size) {} +void readSensors() {} + +#endif // MAX_SENSORS_COUNT > 0 \ No newline at end of file diff --git a/test/README b/test/README new file mode 100644 index 0000000..9b1e87b --- /dev/null +++ b/test/README @@ -0,0 +1,11 @@ + +This directory is intended for PlatformIO Test Runner and project tests. + +Unit Testing is a software testing method by which individual units of +source code, sets of one or more MCU program modules together with associated +control data, usage procedures, and operating procedures, are tested to +determine whether they are fit for use. Unit testing finds problems early +in the development cycle. + +More information about PlatformIO Unit Testing: +- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html