Showing preview only (2,268K chars total). Download the full file or copy to clipboard to get everything.
Repository: purduesigbots/pros
Branch: develop-pros-4
Commit: c0897ad1f709
Files: 204
Total size: 2.1 MB
Directory structure:
gitextract_74vec5n_/
├── .arcconfig
├── .arclint
├── .clang-format
├── .github/
│ ├── CONTRIBUTING.md
│ ├── ISSUE_TEMPLATE.md
│ └── PULL_REQUEST_TEMPLATE.md
├── .gitignore
├── .gitmodules
├── .vs/
│ └── pros/
│ └── v16/
│ └── .suo
├── LICENSE
├── Makefile
├── README.md
├── STYLEGUIDE.md
├── VSCode.md
├── azure-build-libc.yaml
├── azure-pipelines.yml
├── common.mk
├── firmware/
│ ├── libc.a
│ ├── libm.a
│ ├── v5-common.ld
│ ├── v5-hot.ld
│ └── v5.ld
├── include/
│ ├── api.h
│ ├── common/
│ │ ├── cobs.h
│ │ ├── gid.h
│ │ ├── linkedlist.h
│ │ ├── set.h
│ │ └── string.h
│ ├── kapi.h
│ ├── main.h
│ ├── pros/
│ │ ├── abstract_motor.hpp
│ │ ├── adi.h
│ │ ├── adi.hpp
│ │ ├── ai_vision.h
│ │ ├── ai_vision.hpp
│ │ ├── apix.h
│ │ ├── colors.h
│ │ ├── colors.hpp
│ │ ├── device.h
│ │ ├── device.hpp
│ │ ├── distance.h
│ │ ├── distance.hpp
│ │ ├── error.h
│ │ ├── ext_adi.h
│ │ ├── gps.h
│ │ ├── gps.hpp
│ │ ├── imu.h
│ │ ├── imu.hpp
│ │ ├── link.h
│ │ ├── link.hpp
│ │ ├── llemu.h
│ │ ├── llemu.hpp
│ │ ├── misc.h
│ │ ├── misc.hpp
│ │ ├── motor_group.hpp
│ │ ├── motors.h
│ │ ├── motors.hpp
│ │ ├── optical.h
│ │ ├── optical.hpp
│ │ ├── rotation.h
│ │ ├── rotation.hpp
│ │ ├── rtos.h
│ │ ├── rtos.hpp
│ │ ├── screen.h
│ │ ├── screen.hpp
│ │ ├── serial.h
│ │ ├── serial.hpp
│ │ ├── version.h
│ │ ├── vision.h
│ │ └── vision.hpp
│ ├── rtos/
│ │ ├── FreeRTOS.h
│ │ ├── FreeRTOSConfig.h
│ │ ├── StackMacros.h
│ │ ├── list.h
│ │ ├── message_buffer.h
│ │ ├── portable.h
│ │ ├── portmacro.h
│ │ ├── projdefs.h
│ │ ├── queue.h
│ │ ├── semphr.h
│ │ ├── stack_macros.h
│ │ ├── stream_buffer.h
│ │ ├── task.h
│ │ ├── tcb.h
│ │ └── timers.h
│ ├── system/
│ │ ├── dev/
│ │ │ ├── banners.h
│ │ │ ├── dev.h
│ │ │ ├── ser.h
│ │ │ ├── usd.h
│ │ │ └── vfs.h
│ │ ├── hot.h
│ │ ├── optimizers.h
│ │ ├── user_functions/
│ │ │ ├── c_list.h
│ │ │ ├── cpp_list.h
│ │ │ └── list.h
│ │ └── user_functions.h
│ └── vdml/
│ ├── port.h
│ ├── registry.h
│ └── vdml.h
├── libv5rts-strip-options.txt
├── patch_headers.py
├── project.pros
├── public_symbols.txt
├── src/
│ ├── common/
│ │ ├── README.md
│ │ ├── cobs.c
│ │ ├── gid.c
│ │ ├── linkedlist.c
│ │ ├── set.c
│ │ └── string.c
│ ├── devices/
│ │ ├── README.md
│ │ ├── battery.c
│ │ ├── battery.cpp
│ │ ├── controller.c
│ │ ├── controller.cpp
│ │ ├── registry.c
│ │ ├── screen.c
│ │ ├── screen.cpp
│ │ ├── vdml.c
│ │ ├── vdml_adi.c
│ │ ├── vdml_adi.cpp
│ │ ├── vdml_ai_vision.c
│ │ ├── vdml_ai_vision.cpp
│ │ ├── vdml_device.c
│ │ ├── vdml_device.cpp
│ │ ├── vdml_distance.c
│ │ ├── vdml_distance.cpp
│ │ ├── vdml_ext_adi.c
│ │ ├── vdml_gps.c
│ │ ├── vdml_gps.cpp
│ │ ├── vdml_imu.c
│ │ ├── vdml_imu.cpp
│ │ ├── vdml_link.c
│ │ ├── vdml_link.cpp
│ │ ├── vdml_motorgroup.cpp
│ │ ├── vdml_motors.c
│ │ ├── vdml_motors.cpp
│ │ ├── vdml_optical.c
│ │ ├── vdml_optical.cpp
│ │ ├── vdml_rotation.c
│ │ ├── vdml_rotation.cpp
│ │ ├── vdml_serial.c
│ │ ├── vdml_serial.cpp
│ │ ├── vdml_usd.c
│ │ ├── vdml_usd.cpp
│ │ ├── vdml_vision.c
│ │ └── vdml_vision.cpp
│ ├── main.cpp
│ ├── rtos/
│ │ ├── LICENSE
│ │ ├── README.md
│ │ ├── heap_4.c
│ │ ├── list.c
│ │ ├── port.c
│ │ ├── portASM.S
│ │ ├── portmacro.h
│ │ ├── queue.c
│ │ ├── refactor.sh
│ │ ├── refactor.tsv
│ │ ├── rtos.cpp
│ │ ├── semphr.c
│ │ ├── stream_buffer.c
│ │ ├── task_notify_when_deleting.c
│ │ ├── tasks.c
│ │ └── timers.c
│ ├── system/
│ │ ├── cpp_support.cpp
│ │ ├── dev/
│ │ │ ├── dev_driver.c
│ │ │ ├── file_system_stubs.c
│ │ │ ├── ser_daemon.c
│ │ │ ├── ser_driver.c
│ │ │ ├── usd_driver.c
│ │ │ └── vfs.c
│ │ ├── envlock.c
│ │ ├── hot.c
│ │ ├── mlock.c
│ │ ├── newlib_stubs.c
│ │ ├── newlib_stubs_support.cpp
│ │ ├── rtos_hooks.c
│ │ ├── startup.c
│ │ ├── system_daemon.c
│ │ ├── unwind.c
│ │ ├── user_functions.c
│ │ └── xilinx_vectors.s
│ └── tests/
│ ├── adi.cpp
│ ├── basic_test.c
│ ├── basic_test.cpp
│ ├── errno_reentrancy.c
│ ├── exceptions.cpp
│ ├── ext_adi.cpp
│ ├── generic_serial.cpp
│ ├── generic_serial_file.cpp
│ ├── gyro.c
│ ├── gyro.cpp
│ ├── mutexes.c
│ ├── pnuematics.cpp
│ ├── rtos_function_linking.c
│ ├── segfault.cpp
│ ├── simple_names.c
│ ├── simple_names.cpp
│ ├── static_tast_states.c
│ ├── task_notify_when_deleting.c
│ └── vision_test.cpp
├── template-Makefile
├── template-gitignore
├── verify-symbols.sh
└── version.py
================================================
FILE CONTENTS
================================================
================================================
FILE: .arcconfig
================================================
{
"phabricator.uri": "https://phabricator.purduesigbots.com/",
"repoistory.callsign": "rRESTRICTEDPROS",
"lint.engine": "ArcanistConfigurationDrivenLintEngine",
"default-reviewers": "berman5 jhabibi jbuschjr",
"load": [
"clang-format-linter"
]
}
================================================
FILE: .arclint
================================================
{
"linters": {
"clang-format": {
"type": "clang-format",
"include": "(.*\\.(c|cpp|h|hpp)$)",
"exclude": "(^(src|include)/(rtos/|display/lv_.+))"
},
"spelling": {
"type": "spelling",
"include": "(.*)",
"exclude": "(^(src|include)|(rtos/|display/lv_.*))"
},
"text": {
"type": "text",
"include": "(.*)",
"exclude": "(^(src|include)/(((rtos)/)|(system/dev/banners.h)|(display/((lv_.+)|(licence.txt)))))",
"severity": {
"2": "disabled",
"3": "disabled"
}
}
}
}
================================================
FILE: .clang-format
================================================
BasedOnStyle: Google
TabWidth: 2
Language: Cpp
UseTab: ForIndentation
ColumnLimit: 120
Standard: Cpp11
DerivePointerAlignment: false
PointerAlignment: Left
FixNamespaceComments: true
ReflowComments: true
SortIncludes: true
AccessModifierOffset: 0
AllowShortBlocksOnASingleLine: false
AllowShortCaseLabelsOnASingleLine: false
AllowShortFunctionsOnASingleLine: Empty
================================================
FILE: .github/CONTRIBUTING.md
================================================
# Contributing to PROS
:tada: :+1: :steam_locomotive: Thanks for taking the time to contribute! :steam_locomotive: :+1: :tada:
**Did you find a bug?**
- **Before opening an issue, make sure you are in the right repository!**
purduesigbots maintains four repositories related to PROS:
- [purduesigbots/pros](https://github.com/purduesigbots/pros): the repository containing the source code for the kernel the user-facing API. Issues should be opened here if they affect the code you write (e.g., "I would like to be able to do X with PROS," or "when I call <PROS function> X doesn't work as I expect")
- [purduesigbots/pros-cli](https://github.com/purduesigbots/pros-cli): the repository containing the source code for the command line interface (CLI). Issues should be opened here if they concern the PROS CLI (e.g., problems with commands like `pros make`), as well as project creation and management.
- [purduesigbots/pros-atom](https://github.com/purduesigbots/pros-vsc): the repository containing the source code for the VSCode extension. Issues should be opened here if they concern the coding experience within VSCode (e.g., "there is no button to do X," or "the linter is spamming my interface with errors").
- [purduesigbots/pros-docs](https://github.com/purduesigbots/pros-docs): the repository containing the source code for [our documentation website](https://pros.cs.purdue.edu). Issues should be opened here if they concern available documentation (e.g., "there is not guide on using <PROS feature>," or "the documentation says to do X, but only Y works")
- **Verify the bug lies in PROS.** We receive quite a few reports that are due to bugs in user code, not the kernel.
- Ensure the bug wasn't already reported by searching GitHub [issues](https://github.com/purduesigbots/pros/issues)
- If you're unable to find an issue, [open](https://github.com/purduesigbots/pros/issues/new) a new one.
**Did you patch a bug or add a new feature?**
1. [Fork](https://github.com/purduesigbots/pros/fork) and clone the repository
2. Create a new branch: `git checkout -b my-branch-name`
3. Make your changes.
4. Push to your fork and submit a pull request.
5. Wait for your pull request to be reviewed. In order to ensure that the PROS kernel is stable, we take extra time to test pull requests. As a result, your pull request may take some time to be merged into master.
Here are a few tips that can help expedite your pull request being accepted:
- Follow existing code's style.
- Document why you made the changes you did.
- Keep your change as focused as possible. If you have multiple independent changes, make a pull request for each.
- If you did some testing, describe your procedure and results.
- If you're fixing an issue, reference it by number.
================================================
FILE: .github/ISSUE_TEMPLATE.md
================================================
#### Expected Behavior:
<!-- Describe what you expected to happen -->
#### Actual Behavior:
<!-- Describe what actually happened -->
#### Steps to reproduce:
<!-- Is the observed behavior repeatable? If so, describe the steps needed to reproduce it. -->
#### System information:
Platform: <!-- e.g. V5 or Cortex -->
PROS Kernel Version: <!-- run `prosv5 conduct info-project` in the project root -->
#### Additional Information
<!-- Is there any additional information you think is relevant? -->
#### Screenshots/Output Dumps/Stack Traces
================================================
FILE: .github/PULL_REQUEST_TEMPLATE.md
================================================
#### Summary:
<!-- Provide a concise description of your changes -->
#### Motivation:
<!-- Provide a brief description of why you think these changes need to be made -->
##### References (optional):
<!-- If this PR is related to an issue or task, reference it here (e.g. closes #1) -->
#### Test Plan:
<!-- Provide a list of steps that can be taken to verify these changes work as intended -->
- [ ] test item
================================================
FILE: .gitignore
================================================
.vscode/
.idea/
bin/
.*.sw*
template/
version
cquery_log.txt
compile_commands.json
.ccls-cache/
.ccls
temp.log
temp.errors
.d/
.clangd/
.cache/
.DS_Store
================================================
FILE: .gitmodules
================================================
[submodule "firmware/libv5rts"]
path = firmware/libv5rts
url = git@github.com:purduesigbots/libv5rts.git
ignore = dirty
================================================
FILE: LICENSE
================================================
PROS 4.0 contains modified or linked source code from the following packages:
- FreeRTOS (src/rtos/LICENSE)
Unless otherwise specified, PROS 4.0 is distributed under the Mozilla Public
License Version 2.0, reproduced below:
Mozilla Public License Version 2.0
==================================
1. Definitions
--------------
1.1. "Contributor"
means each individual or legal entity that creates, contributes to
the creation of, or owns Covered Software.
1.2. "Contributor Version"
means the combination of the Contributions of others (if any) used
by a Contributor and that particular Contributor's Contribution.
1.3. "Contribution"
means Covered Software of a particular Contributor.
1.4. "Covered Software"
means Source Code Form to which the initial Contributor has attached
the notice in Exhibit A, the Executable Form of such Source Code
Form, and Modifications of such Source Code Form, in each case
including portions thereof.
1.5. "Incompatible With Secondary Licenses"
means
(a) that the initial Contributor has attached the notice described
in Exhibit B to the Covered Software; or
(b) that the Covered Software was made available under the terms of
version 1.1 or earlier of the License, but not also under the
terms of a Secondary License.
1.6. "Executable Form"
means any form of the work other than Source Code Form.
1.7. "Larger Work"
means a work that combines Covered Software with other material, in
a separate file or files, that is not Covered Software.
1.8. "License"
means this document.
1.9. "Licensable"
means having the right to grant, to the maximum extent possible,
whether at the time of the initial grant or subsequently, any and
all of the rights conveyed by this License.
1.10. "Modifications"
means any of the following:
(a) any file in Source Code Form that results from an addition to,
deletion from, or modification of the contents of Covered
Software; or
(b) any new file in Source Code Form that contains any Covered
Software.
1.11. "Patent Claims" of a Contributor
means any patent claim(s), including without limitation, method,
process, and apparatus claims, in any patent Licensable by such
Contributor that would be infringed, but for the grant of the
License, by the making, using, selling, offering for sale, having
made, import, or transfer of either its Contributions or its
Contributor Version.
1.12. "Secondary License"
means either the GNU General Public License, Version 2.0, the GNU
Lesser General Public License, Version 2.1, the GNU Affero General
Public License, Version 3.0, or any later versions of those
licenses.
1.13. "Source Code Form"
means the form of the work preferred for making modifications.
1.14. "You" (or "Your")
means an individual or a legal entity exercising rights under this
License. For legal entities, "You" includes any entity that
controls, is controlled by, or is under common control with You. For
purposes of this definition, "control" means (a) the power, direct
or indirect, to cause the direction or management of such entity,
whether by contract or otherwise, or (b) ownership of more than
fifty percent (50%) of the outstanding shares or beneficial
ownership of such entity.
2. License Grants and Conditions
--------------------------------
2.1. Grants
Each Contributor hereby grants You a world-wide, royalty-free,
non-exclusive license:
(a) under intellectual property rights (other than patent or trademark)
Licensable by such Contributor to use, reproduce, make available,
modify, display, perform, distribute, and otherwise exploit its
Contributions, either on an unmodified basis, with Modifications, or
as part of a Larger Work; and
(b) under Patent Claims of such Contributor to make, use, sell, offer
for sale, have made, import, and otherwise transfer either its
Contributions or its Contributor Version.
2.2. Effective Date
The licenses granted in Section 2.1 with respect to any Contribution
become effective for each Contribution on the date the Contributor first
distributes such Contribution.
2.3. Limitations on Grant Scope
The licenses granted in this Section 2 are the only rights granted under
this License. No additional rights or licenses will be implied from the
distribution or licensing of Covered Software under this License.
Notwithstanding Section 2.1(b) above, no patent license is granted by a
Contributor:
(a) for any code that a Contributor has removed from Covered Software;
or
(b) for infringements caused by: (i) Your and any other third party's
modifications of Covered Software, or (ii) the combination of its
Contributions with other software (except as part of its Contributor
Version); or
(c) under Patent Claims infringed by Covered Software in the absence of
its Contributions.
This License does not grant any rights in the trademarks, service marks,
or logos of any Contributor (except as may be necessary to comply with
the notice requirements in Section 3.4).
2.4. Subsequent Licenses
No Contributor makes additional grants as a result of Your choice to
distribute the Covered Software under a subsequent version of this
License (see Section 10.2) or under the terms of a Secondary License (if
permitted under the terms of Section 3.3).
2.5. Representation
Each Contributor represents that the Contributor believes its
Contributions are its original creation(s) or it has sufficient rights
to grant the rights to its Contributions conveyed by this License.
2.6. Fair Use
This License is not intended to limit any rights You have under
applicable copyright doctrines of fair use, fair dealing, or other
equivalents.
2.7. Conditions
Sections 3.1, 3.2, 3.3, and 3.4 are conditions of the licenses granted
in Section 2.1.
3. Responsibilities
-------------------
3.1. Distribution of Source Form
All distribution of Covered Software in Source Code Form, including any
Modifications that You create or to which You contribute, must be under
the terms of this License. You must inform recipients that the Source
Code Form of the Covered Software is governed by the terms of this
License, and how they can obtain a copy of this License. You may not
attempt to alter or restrict the recipients' rights in the Source Code
Form.
3.2. Distribution of Executable Form
If You distribute Covered Software in Executable Form then:
(a) such Covered Software must also be made available in Source Code
Form, as described in Section 3.1, and You must inform recipients of
the Executable Form how they can obtain a copy of such Source Code
Form by reasonable means in a timely manner, at a charge no more
than the cost of distribution to the recipient; and
(b) You may distribute such Executable Form under the terms of this
License, or sublicense it under different terms, provided that the
license for the Executable Form does not attempt to limit or alter
the recipients' rights in the Source Code Form under this License.
3.3. Distribution of a Larger Work
You may create and distribute a Larger Work under terms of Your choice,
provided that You also comply with the requirements of this License for
the Covered Software. If the Larger Work is a combination of Covered
Software with a work governed by one or more Secondary Licenses, and the
Covered Software is not Incompatible With Secondary Licenses, this
License permits You to additionally distribute such Covered Software
under the terms of such Secondary License(s), so that the recipient of
the Larger Work may, at their option, further distribute the Covered
Software under the terms of either this License or such Secondary
License(s).
3.4. Notices
You may not remove or alter the substance of any license notices
(including copyright notices, patent notices, disclaimers of warranty,
or limitations of liability) contained within the Source Code Form of
the Covered Software, except that You may alter any license notices to
the extent required to remedy known factual inaccuracies.
3.5. Application of Additional Terms
You may choose to offer, and to charge a fee for, warranty, support,
indemnity or liability obligations to one or more recipients of Covered
Software. However, You may do so only on Your own behalf, and not on
behalf of any Contributor. You must make it absolutely clear that any
such warranty, support, indemnity, or liability obligation is offered by
You alone, and You hereby agree to indemnify every Contributor for any
liability incurred by such Contributor as a result of warranty, support,
indemnity or liability terms You offer. You may include additional
disclaimers of warranty and limitations of liability specific to any
jurisdiction.
4. Inability to Comply Due to Statute or Regulation
---------------------------------------------------
If it is impossible for You to comply with any of the terms of this
License with respect to some or all of the Covered Software due to
statute, judicial order, or regulation then You must: (a) comply with
the terms of this License to the maximum extent possible; and (b)
describe the limitations and the code they affect. Such description must
be placed in a text file included with all distributions of the Covered
Software under this License. Except to the extent prohibited by statute
or regulation, such description must be sufficiently detailed for a
recipient of ordinary skill to be able to understand it.
5. Termination
--------------
5.1. The rights granted under this License will terminate automatically
if You fail to comply with any of its terms. However, if You become
compliant, then the rights granted under this License from a particular
Contributor are reinstated (a) provisionally, unless and until such
Contributor explicitly and finally terminates Your grants, and (b) on an
ongoing basis, if such Contributor fails to notify You of the
non-compliance by some reasonable means prior to 60 days after You have
come back into compliance. Moreover, Your grants from a particular
Contributor are reinstated on an ongoing basis if such Contributor
notifies You of the non-compliance by some reasonable means, this is the
first time You have received notice of non-compliance with this License
from such Contributor, and You become compliant prior to 30 days after
Your receipt of the notice.
5.2. If You initiate litigation against any entity by asserting a patent
infringement claim (excluding declaratory judgment actions,
counter-claims, and cross-claims) alleging that a Contributor Version
directly or indirectly infringes any patent, then the rights granted to
You by any and all Contributors for the Covered Software under Section
2.1 of this License shall terminate.
5.3. In the event of termination under Sections 5.1 or 5.2 above, all
end user license agreements (excluding distributors and resellers) which
have been validly granted by You or Your distributors under this License
prior to termination shall survive termination.
************************************************************************
* *
* 6. Disclaimer of Warranty *
* ------------------------- *
* *
* Covered Software is provided under this License on an "as is" *
* basis, without warranty of any kind, either expressed, implied, or *
* statutory, including, without limitation, warranties that the *
* Covered Software is free of defects, merchantable, fit for a *
* particular purpose or non-infringing. The entire risk as to the *
* quality and performance of the Covered Software is with You. *
* Should any Covered Software prove defective in any respect, You *
* (not any Contributor) assume the cost of any necessary servicing, *
* repair, or correction. This disclaimer of warranty constitutes an *
* essential part of this License. No use of any Covered Software is *
* authorized under this License except under this disclaimer. *
* *
************************************************************************
************************************************************************
* *
* 7. Limitation of Liability *
* -------------------------- *
* *
* Under no circumstances and under no legal theory, whether tort *
* (including negligence), contract, or otherwise, shall any *
* Contributor, or anyone who distributes Covered Software as *
* permitted above, be liable to You for any direct, indirect, *
* special, incidental, or consequential damages of any character *
* including, without limitation, damages for lost profits, loss of *
* goodwill, work stoppage, computer failure or malfunction, or any *
* and all other commercial damages or losses, even if such party *
* shall have been informed of the possibility of such damages. This *
* limitation of liability shall not apply to liability for death or *
* personal injury resulting from such party's negligence to the *
* extent applicable law prohibits such limitation. Some *
* jurisdictions do not allow the exclusion or limitation of *
* incidental or consequential damages, so this exclusion and *
* limitation may not apply to You. *
* *
************************************************************************
8. Litigation
-------------
Any litigation relating to this License may be brought only in the
courts of a jurisdiction where the defendant maintains its principal
place of business and such litigation shall be governed by laws of that
jurisdiction, without reference to its conflict-of-law provisions.
Nothing in this Section shall prevent a party's ability to bring
cross-claims or counter-claims.
9. Miscellaneous
----------------
This License represents the complete agreement concerning the subject
matter hereof. If any provision of this License is held to be
unenforceable, such provision shall be reformed only to the extent
necessary to make it enforceable. Any law or regulation which provides
that the language of a contract shall be construed against the drafter
shall not be used to construe this License against a Contributor.
10. Versions of the License
---------------------------
10.1. New Versions
Mozilla Foundation is the license steward. Except as provided in Section
10.3, no one other than the license steward has the right to modify or
publish new versions of this License. Each version will be given a
distinguishing version number.
10.2. Effect of New Versions
You may distribute the Covered Software under the terms of the version
of the License under which You originally received the Covered Software,
or under the terms of any subsequent version published by the license
steward.
10.3. Modified Versions
If you create software not governed by this License, and you want to
create a new license for such software, you may create and use a
modified version of this License if you rename the license and remove
any references to the name of the license steward (except to note that
such modified license differs from this License).
10.4. Distributing Source Code Form that is Incompatible With Secondary
Licenses
If You choose to distribute Source Code Form that is Incompatible With
Secondary Licenses under the terms of this version of the License, the
notice described in Exhibit B of this License must be attached.
Exhibit A - Source Code Form License Notice
-------------------------------------------
This Source Code Form is subject to the terms of the Mozilla Public
License, v. 2.0. If a copy of the MPL was not distributed with this
file, You can obtain one at http://mozilla.org/MPL/2.0/.
If it is not possible or desirable to put the notice in a particular
file, then You may include the notice in a location (such as a LICENSE
file in a relevant directory) where a recipient would be likely to look
for such a notice.
You may add additional accurate notices of copyright ownership.
Exhibit B - "Incompatible With Secondary Licenses" Notice
---------------------------------------------------------
This Source Code Form is "Incompatible With Secondary Licenses", as
defined by the Mozilla Public License, v. 2.0.
================================================
FILE: Makefile
================================================
################################################################################
######################### User configurable parameters #########################
# filename extensions
CEXTS:=c
ASMEXTS:=s S
CXXEXTS:=cpp c++ cc
# probably shouldn't modify these, but you may need them below
ROOT=.
FWDIR:=$(ROOT)/firmware
BINDIR=$(ROOT)/bin
SRCDIR=$(ROOT)/src
INCDIR=$(ROOT)/include
EXTRA_INCDIR=$(FWDIR)/libv5rts/sdk/vexv5/patched_include
# Directories to be excluded from all builds
EXCLUDE_SRCDIRS+=$(SRCDIR)/tests
C_STANDARD=gnu2x
CXX_STANDARD=gnu++23
WARNFLAGS+=-Wall -Wpedantic
EXTRA_CFLAGS+=
EXTRA_CXXFLAGS=-D_PROS_KERNEL_SUPPRESS_LLEMU_WARNING
.DEFAULT_GOAL=quick
USE_PACKAGE:=0
# Set this to 1 to add additional rules to compile your project as a PROS library template
IS_LIBRARY:=1
LIBNAME:=libpros
VERSION=$(shell cat $(ROOT)/version)
# EXCLUDE_SRC_FROM_LIB= $(SRCDIR)/unpublishedfile.c
EXCLUDE_SRC_FROM_LIB+=$(EXCLUDE_SRCDIRS)
# this line excludes opcontrol.c and similar files
EXCLUDE_SRC_FROM_LIB+=$(foreach file, $(SRCDIR)/main,$(foreach cext,$(CEXTS),$(file).$(cext)) $(foreach cxxext,$(CXXEXTS),$(file).$(cxxext)))
# files that get distributed to every user (beyond your source archive) - add
# whatever files you want here. This line is configured to add all header files
# that are in the the include directory get exported
TEMPLATE_FILES=$(ROOT)/common.mk $(FWDIR)/v5.ld $(FWDIR)/v5-common.ld $(FWDIR)/v5-hot.ld
TEMPLATE_FILES+=$(FWDIR)/libc.a $(FWDIR)/libm.a
TEMPLATE_FILES+= $(INCDIR)/api.h $(INCDIR)/main.h $(INCDIR)/pros/*.*
TEMPLATE_FILES+= $(SRCDIR)/main.cpp
TEMPLATE_FILES+= $(ROOT)/template-gitignore
PATCHED_SDK=$(FWDIR)/libv5rts/sdk/vexv5/libv5rts.patched.a
EXTRA_LIB_DEPS=$(INCDIR)/api.h $(PATCHED_SDK)
################################################################################
################################################################################
########## Nothing below this line should be edited by typical users ###########
-include ./common.mk
.PHONY: $(INCDIR)/pros/version.h patch_sdk_headers clean
$(INCDIR)/pros/version.h: version.py
$(VV)python version.py
patch_sdk_headers: patch_headers.py
@echo "Patching SDK headers"
$(VV)python patch_headers.py
# Override clean, necessary to remove patched sdk on clean
clean::
@echo "Cleaning patched SDK"
@rm -f $(PATCHED_SDK)
@rm -rf $(EXTRA_INCDIR)
$(PATCHED_SDK): $(FWDIR)/libv5rts/sdk/vexv5/libv5rts.a
$(call test_output_2,Stripping unwanted symbols from libv5rts.a ,$(STRIP) $^ @libv5rts-strip-options.txt -o $@, $(DONE_STRING))
CREATE_TEMPLATE_ARGS=--system "./**/*"
CREATE_TEMPLATE_ARGS+=--user "src/main.{cpp,c,cc}" --user "include/main.{hpp,h,hh}" --user "Makefile" --user ".gitignore"
CREATE_TEMPLATE_ARGS+=--target v5
CREATE_TEMPLATE_ARGS+=--output bin/monolith.bin --cold_output bin/cold.package.bin --hot_output bin/hot.package.bin --cold_addr 58720256 --hot_addr 125829120
template:: patch_sdk_headers clean-template library
$(VV)mkdir -p $(TEMPLATE_DIR)
@echo "Moving template files to $(TEMPLATE_DIR)"
$Dif [ $(shell uname -s) == "Darwin" ]; then \
rsync -R $(TEMPLATE_FILES) $(TEMPLATE_DIR); \
else \
cp --parents -r $(TEMPLATE_FILES) $(TEMPLATE_DIR); \
fi
$(VV)mkdir -p $(TEMPLATE_DIR)/firmware
$Dcp $(LIBAR) $(TEMPLATE_DIR)/firmware
$Dcp $(ROOT)/template-Makefile $(TEMPLATE_DIR)/Makefile
$Dmv $(TEMPLATE_DIR)/template-gitignore $(TEMPLATE_DIR)/.gitignore
@echo "Creating template"
$Dpros c create-template $(TEMPLATE_DIR) kernel $(shell cat $(ROOT)/version) $(CREATE_TEMPLATE_ARGS)
LIBV5RTS_EXTRACTION_DIR=$(BINDIR)/libv5rts
$(LIBAR): patch_sdk_headers $(call GETALLOBJ,$(EXCLUDE_SRC_FROM_LIB)) $(EXTRA_LIB_DEPS)
$(VV)mkdir -p $(LIBV5RTS_EXTRACTION_DIR)
$(call test_output_2,Extracting libv5rts ,cd $(LIBV5RTS_EXTRACTION_DIR) && $(AR) x ../../$(PATCHED_SDK),$(DONE_STRING))
$(eval LIBV5RTS_OBJECTS := $(shell $(AR) t $(PATCHED_SDK)))
-$Drm -f $@
$(call test_output_2,Creating $@ ,$(AR) rcs $@ $(addprefix $(LIBV5RTS_EXTRACTION_DIR)/, $(LIBV5RTS_OBJECTS)) $(call GETALLOBJ,$(EXCLUDE_SRC_FROM_LIB)),$(DONE_STRING))
# @echo -n "Stripping non-public symbols "
# $(call test_output,$D$(OBJCOPY) -S -D -g --strip-unneeded --keep-symbols public_symbols.txt $@,$(DONE_STRING))
================================================
FILE: README.md
================================================
# PROS Kernel for the VEX V5 Brain
[](https://dev.azure.com/purdue-acm-sigbots/Kernel/_build/latest?definitionId=5&branchName=develop)
### What is PROS?
PROS is a lightweight and fast alternative open source operating system for the VEX V5 Brain. PROS is built with developers in mind and with a focus on providing an environment for industry-applicable experience.
Primary maintenance of PROS is done by students at Purdue University through [Purdue ACM SIGBots](http://purduesigbots.com). Inspiration for this project came from several computer science and engineering students itching to write code for the extended autonomous period. We created PROS to leverage this opportunity.
All PROS development is open sourced and available for the community to inspect. We believe that sharing source improves PROS through community contributions and allows students to learn by example.
PROS is built using the GCC toolchain and standard C/C++ practices (C23 & C++23 w/GNU extensions) to make the learning curve small. Structures, pointers, dynamic memory allocation, and function pointers are all available. Additionally, code is run on bare metal, allowing you to take full advantage of the microcontroller's power.
You can develop code on Windows, OS X, or Linux. Code is compiled using GCC and the PROS CLI is available on most operating systems. The PROS development team makes distributions for Windows, OS X, and Debian-based Linux distributions.
The PROS team develops a plugin for Atom to making developing projects in PROS the best possible experience. The highly customizable editor designed for the 21st century enables students to learn how to code in a modern environment.
### What's the difference between PROS 4 and 3?
PROS 4 is a Kernel upgrade from PROS 4 to both decrease the size of the base Kernel, and provide utilities such as the base device class and liblvgl that makes it easier for both users and library writers to customize their PROS projects. This version also moves all documentation to a doxygen site rather than a Sphinx documentation page.
### What's the difference between PROS 2 and PROS 3?
PROS 2 refers to the kernel that runs on the [VEX Arm Cortex-based Microcontroller](https://www.vexrobotics.com/276-2194.html). The source for this kernel is still available on the `cortex-master` branch. The future development for this version of the PROS kernel will be focused on maintenance and critical bugfixes.
PROS 3 refers to the kernel that runs on the [VEX V5](https://www.vexrobotics.com/vexedr/v5) microcontroller platform. The majority of our development focus will be on this version of the PROS kernel.
### Does PROS support C++?
- PROS 3.x and 4.x (V5) officially supports C++. We're still working on enabling all of the features of C++ (particularly in the I/O area).
- PROS 2.x (Cortex) does not officially support C++. Some users have found ways around this, but be warned: we will not be able to help if you run into issues doing this.
### Cool, how do I get it?
Pay a visit to our website, [pros.cs.purdue.edu](https://pros.cs.purdue.edu), to download our latest installer or view installation instructions for your preferred platform.
### How do I use it?
We have a number of resources available on our website, including
- [A basic tutorial to get you acquainted with the PROS ecosystem](https://pros.cs.purdue.edu/v5/getting-started/new-users.html)
- [A series of tutorials on how to use some of the more advanced features of PROS](https://pros.cs.purdue.edu/v5/tutorials/index.html)
- [Extensive documentation on the kernel's API](https://pros.cs.purdue.edu/v5/api/index.html)
### I still have questions!
Drop us a line
- at pros_development@cs.purdue.edu
- on the [VEX Forum](https://www.vexforum.com/)
- on [VEX Teams of the World Discord](https://discord.gg/xddjWGj)
### I think I found a bug!
We maintain GitHub repositories for the three major components of the PROS ecosystem:
- The Command Line Interface (cli) at [purduesigbots/pros-cli](https://github.com/purduesigbots/pros-cli)
- The VS Code plugin at [purduesigbots/pros-vsc](https://github.com/purduesigbots/pros-vsc)
- The kernel [here](https://github.com/purduesigbots/pros)
If you find a problem with our documentation or tutorials, we have a repository for that, too, at [purduesigbots/pros-docs](https://github.com/purduesigbots/pros-docs).
### Hey! Why can't I build the PROS kernel?
The PROS kernel depends on VEX's proprietary Software Development Kit (SDK), which is not publicly available.
================================================
FILE: STYLEGUIDE.md
================================================
# PROS Kernel Styleguide
Maintaining a consistent coding style throughout the PROS kernel is important for future developers and students to learn about the PROS kernel. An inconsistent style can lead to confusion for everyone.
The PROS style is based on the Google C++ coding style (with some modifications noted a bit farther down), which allows `clang-format` to be used on every file and get correctly formatted code.
Some additional notes follow:
## File extensions
- C source files will have the extension `.c`
- C++ source files will have the extension `.cpp`
- C header files will have the extension `.h`
- C++ header files will have the extension `.hpp`
## Naming Conventions
The PROS kernel follows these naming conventions:
- Structures: `structname_s`:
- Structure members: these do not have any special convention, as you will never see a structure member without seeing that it is in a structure.
- Enumerated types: `enumname_e`
- Enumerated type members: `E_ENUMNAME_MEMBERNAME`
For example, in `task_state_e`, you might have members such as `E_TASK_STATE_RUNNING`. Note that "ENUMNAME" can be multiple words, separated by underscores.
- Function pointers: `funcname_fn`
- Type definitions: append `_t` to the end of the structure/enum/function pointer name
- C++ classes: these should be named in UpperCamelCase (also known as PascalCase)
- Class members: use lower_snake_case as normal, and use good sense when naming
This section provides only a brief overview of the naming conventions used in the PROS kernel. For more about the motivations behind these, see section 4 (Naming) below.
## Documentation
Use Doxygen-style comments as shown in the sections below.
### File-Level Comments
These should be placed at the very start of a file.
```c
/**
* \file filename.h
*
* Short description of the file
*
* Extended description goes here. This should explain what the functions (etc)
* in the file contains and a general description of what they do (no specifics,
* but they should all have something in common anyway).
*
* This file should not be modified by users, since it gets replaced whenever
* a kernel upgrade occurs.
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
```
### Enum-Level Comments
These should be placed immediately before the declaration of the enum.
```c
/*
* Short description of the enum
*
* Extended description of the enum goes here. This should explain general usage
* patterns for the enum.
*/
enum my_enum {
E_MEMBER_0, // short description of member 0 goes here.
E_MEMBER_1, // these can be omitted if it's painfully obvious
E_MEMBER_2, // what each is for, or if there are just so many of
E_MEMBER_3, // them it doesn't make practical sense to
E_MEMBER_4 // document them all.
}
```
_Note: in the above example, the comments describing each member of the `enum` run together and form complete sentences for effect. Please do not do this in your code!_
### Function-Level Comments
These should be placed immediately before the function prototype they are describing in a header file.
```c
/**
* Brief description of the function.
*
* An extended description of the function (if applicable).
*
* This function uses the following values of errno when an error state is
* reached:
* ERRNO_VALUE - Description of what causes this error
*
* \param parameter_name
* The parameter description
* \param other_parameter_name
* The parameter description
*
* \return The description of the return value, if this is longer than one line
* then it will wrap around under the return statement
*/
```
### Inline Implementation Comments
Sometimes it is necessary to explain a particularly complex statement or series of statements. In this case, you should use inline comments, placed either immediately before or trailing the line or lines in question. In general, prefer placing such comments before offending lines, unless the comment is quite short. These comments should start with a `//` followed by a space. If they are placed trailing a line, they should be separated from the end of the line by one space.
```c
float Q_rsqrt(float number) {
long i;
float x2, y;
const float threehalfs = 1.5F;
x2 = number * 0.5F;
y = number;
// perform some absolute magic on these numbers to get the inverse square root
i = *(long*)&y; // evil floating point bit level hacking
i = 0x5f3759df - (i >> 1); // what the [heck]?
y = *(float*)&i;
y = y * (threehalfs - (x2 * y * y)); // 1st iteration
//y = y * (threehalfs - (x2 * y * y)); // 2nd iteration, this can be removed
return y;
}
```
_Note: in the above example, there is a line of code that has been commented out. This is fine to do while testing, but any commented out lines of code should be removed before any merge into the master branch takes place, unless a compelling reason can be presented for them to remain._
All that being said, try to avoid code that is so complex that it requires inline comments for its purpose to be clear.
#### Notes to Other Developers (Or Yourself)
When writing code, it can sometimes be useful to leave notes to other developers or to yourself in the future. Examples of these include:
- `// TODO: something that should be done`
- `// NOTE: a note about something in the code`
- `// NB: this is the same as NOTE, but it's in Latin, so it's fancier`
- `// HACK: used to describe a particularly nasty way of solving a problem-- could be improved, but it works for now`
- `// FIXME: this code is broken and should be fixed`
- `// XXX: this is like FIXME, but it's worse (note that this has also been used in the same way as HACK, so you should use that or FIXME to clarify what is meant)`
- `// BUG: this is used to mark a line of code that is known to cause a bug. kind of like FIXME, though it may include some more specific information than FIXME would`
While it is not strictly necessary to use these keywords in comments, they can be helpful-- modern editors (like Atom or VSCode) either highlight some of these keywords by default or have extensions that do. This can make certain comments stand out even more when developers are "grepping" the codebase (visually or otherwise).
### Word Choice and Tense
Content for the docs should follow the
[Google Developer Documentation Style Guide](https://developers.google.com/style/),
and the [API Reference Comments Section](https://developers.google.com/style/api-reference-comments)
in particular.
While the Google Style Guide should determine the vast majority of the docs' word choices,
additionally follow these content-specific guides:
- All ports, Smart, ADI, or otherwise, should be referred to as a port, not a channel
or pin.
- C++ functions should be written as their full function name, without removing the
`pros::` namespace (e.g. `pros::Motor::move`).
- All enumerated values referenced in the code comments should be written as their
full name per the PROS Style Guide, not the `PROS_USE_SIMPLE_NAMES` version.
(e.g. `E_MOTOR_GEARSET_18`, not `E_MOTOR_GEARSET_18`).
### C/C++ Format Guide
The PROS Coding style is based on the [Google C++ Coding Style](https://google.github.io/styleguide/cppguide.html) with the following modifications:
```
TabWidth: 2
UseTab: ForIndentation
ColumnLimit: 120
DerivePointerAlignment: false
PointerAlignment: Left
FixNamespaceComments: true
ReflowComments: true
SortIncludes: true
AccessModifierOffset: 0
AllowShortBlocksOnASingleLine: false
AllowShortCaseLabelsOnASingleLine: false
AllowShortFunctionsOnASingleLine: Empty
```
================================================
FILE: VSCode.md
================================================
Use the following include paths for intellisense completion:
"${env:PROS_TOOLCHAIN}/arm-none-eabi/include",
"${env:PROS_TOOLCHAIN}/lib/gcc/arm-none-eabi/6.3.1/include",
"${workspaceRoot}",
"${workspaceRoot}/include"
Add "_INTELLISENSE" to your defines to fix certain intellisense errors that will actually compile without issue
================================================
FILE: azure-build-libc.yaml
================================================
###############################################################################
#
# This pipeline builds newlib with the same flags as the official toolchain,
# but adds -funwind-tables so we can have proper unwind info inside libc
#
###############################################################################
variables:
source_url: 'https://developer.arm.com/-/media/Files/downloads/gnu-rm/8-2018q4/gcc-arm-none-eabi-8-2018-q4-major-src.tar.bz2'
source_directory: 'gcc-arm-none-eabi-8-2018-q4-major'
jobs:
- job: BuildLibc
pool:
vmImage: 'ubuntu-16.04'
timeoutInMinutes: 0
steps:
- bash: |
sudo apt-get install software-properties-common
sudo dpkg --add-architecture i386
sudo add-apt-repository ppa:team-gcc-arm-embedded/ppa
sudo apt-get update
sudo apt-get install build-essential autoconf autogen bison dejagnu flex flip gawk git gperf gzip \
nsis openssh-client p7zip-full perl python-dev libisl-dev scons tcl tofrodos \
wget libncurses5-dev pv
sudo apt-get install gcc-arm-embedded
displayName: Install apt packages
- bash: |
curl -L $(source_url) -o $(source_directory).tar.bz2
pv -f $(source_directory).tar.bz2 | tar -xjf -
displayName: Download/extract arm-none-eabi-gcc source
- bash: |
sed -i '95s/TERM|\\/TERM|agent.jobstatus|\\/' ./build-common.sh
sed -i '302s/http:\/\/www.mr511.de\/software\//https:\/\/github.com\/gnu-mcu-eclipse\/files\/raw\/master\/libs\//' ./build-common.sh
displayName: Edit ./build-common.sh
workingDirectory: $(source_directory)
- bash: |
sed -i "294s/.*/saveenvvar CFLAGS_FOR_TARGET '-g -O2 -ffunction-sections -fdata-sections -funwind-tables'/" ./build-toolchain.sh
head -n 316 ./build-toolchain.sh > ./build-toolchain.sh
displayName: Edit ./build-toolchain.sh
workingDirectory: $(source_directory)
- bash: |
./install-sources.sh --skip_steps=mingw32
displayName: Install sources
workingDirectory: $(source_directory)
- bash: |
./build-prerequisites.sh --skip_steps=mingw32
displayName: Build prerequisites
workingDirectory: $(source_directory)
- bash: |
export CFLAGS_FOR_TARGET='-g -O2 -ffunction-sections -fdata-sections -funwind-tables'
export ROOT=`pwd`
mkdir -p $ROOT/build-native/newlib
pushd $ROOT/build-native/newlib
$ROOT/src/newlib/configure \
--build="`uname -m | sed 'y/XI/xi/'`"-linux-gnu --host="`uname -m | sed 'y/XI/xi/'`"-linux-gnu \
--target=arm-none-eabi \
--prefix=$ROOT/newlib \
--enable-newlib-io-long-long \
--enable-newlib-io-c99-formats \
--enable-newlib-register-fini \
--enable-newlib-retargetable-locking \
--disable-newlib-supplied-syscalls \
--disable-nls \
make -j`grep ^processor /proc/cpuinfo|wc -l`
make install
ls -R $ROOT/newlib
ls -R $ROOT/build-native/newlib
cp $ROOT/newlib/arm-none-eabi/lib/thumb/v7-ar/libc.a $(Build.ArtifactStagingDirectory)
cp $ROOT/newlib/arm-none-eabi/lib/thumb/v7-ar/libm.a $(Build.ArtifactStagingDirectory)
ls $(Build.ArtifactStagingDirectory)
TARGET_LIBRARIES=`find $(Build.ArtifactStagingDirectory) -name \*.a`
for target_lib in $TARGET_LIBRARIES ; do
echo Stripping $target_lib
arm-none-eabi-objcopy -R .comment -R .note -R .debug_info -R .debug_aranges -R .debug_pubnames -R .debug_pubtypes -R .debug_abbrev -R .debug_line -R .debug_str -R .debug_ranges -R .debug_loc $target_lib || true
done
displayName: Build toolchain
workingDirectory: $(source_directory)
- task: PublishPipelineArtifact@0
inputs:
artifactName: 'newlib'
targetPath: $(Build.ArtifactStagingDirectory)
================================================
FILE: azure-pipelines.yml
================================================
jobs:
- job: BuildTemplate
variables:
toolchain_update: 13.3.rel1
toolchain: https://developer.arm.com/-/media/Files/downloads/gnu/$(toolchain_update)/binrel/arm-gnu-toolchain-$(toolchain_update)-x86_64-arm-none-eabi.tar.xz
pool:
vmImage: 'ubuntu-latest'
steps:
- task: InstallSSHKey@0
inputs:
sshKeySecureFile: id_sigbot_github_azure_devops
hostName: $(gh.knownhosts)
sshPublicKey: $(gh.publickey)
- checkout: self
- bash: |
curl -LSso toolchain.tar.xz $(toolchain)
tar -xJvf toolchain.tar.xz
echo "##vso[task.prependpath]$(pwd)/arm-gnu-toolchain-$(toolchain_update)-x86_64-arm-none-eabi/bin"
displayName: Install gcc-arm-embedded
- task: UsePythonVersion@0
inputs:
addToPath: true
versionSpec: '3.11.0'
- task: PipAuthenticate@1
inputs:
artifactFeeds: 'pros-cli'
# use official PyPi registry first and fall back to internal feed as needed
onlyAddExtraIndex: true
- bash: pip install pros-cli
displayName: Install CLI
- bash: |
make template
mkdir -p artifacts
cp template/*.zip artifacts
displayName: Build template
- bash: |
echo "##vso[build.UpdateBuildNumber]`cat version`"
echo "##vso[task.setvariable variable=KernelVersion]`cat version`"
displayName: Update Build Number
- bash: |
make
displayName: Build binaries
- task: PublishPipelineArtifact@0
inputs:
targetPath: artifacts
artifactName: template
condition: succeeded()
# - task: UniversalPackages@0
# inputs:
# command: publish
# publishDirectory: artifacts
# vstsFeedPublish: 'pros-depot-nightly'
# vstsFeedPackagePublish: 'kernel'
# versionOption: custom
# versionPublish: $(KernelVersion)
# packagePublishDescription: 'CI Build of Kernel'
# condition: and(succeeded(), or(eq(variables['Build.SourceBranch'], 'refs/heads/master'), eq(variables['Build.SourceBranch'], 'refs/heads/develop')))
================================================
FILE: common.mk
================================================
ARCHTUPLE=arm-none-eabi-
DEVICE=VEX EDR V5
MFLAGS=-mcpu=cortex-a9 -mfpu=neon-fp16 -mfloat-abi=hard -Os -g -mthumb
CPPFLAGS=-D_POSIX_THREADS -D_UNIX98_THREAD_MUTEX_ATTRIBUTES -D_POSIX_TIMERS -D_POSIX_MONOTONIC_CLOCK
GCCFLAGS=-ffunction-sections -fdata-sections -fdiagnostics-color -funwind-tables
# Check if the llemu files in libvgl exist. If they do, define macros that the
# llemu headers in the kernel repo can use to conditionally include the libvgl
# versions
ifneq (,$(wildcard ./include/liblvgl/llemu.h))
CPPFLAGS += -D_PROS_INCLUDE_LIBLVGL_LLEMU_H
endif
ifneq (,$(wildcard ./include/liblvgl/llemu.hpp))
CPPFLAGS += -D_PROS_INCLUDE_LIBLVGL_LLEMU_HPP
endif
WARNFLAGS+=-Wno-psabi
SPACE := $() $()
COMMA := ,
C_STANDARD?=gnu23
CXX_STANDARD?=gnu++26
DEPDIR := .d
$(shell mkdir -p $(DEPDIR))
DEPFLAGS = -MT $$@ -MMD -MP -MF $(DEPDIR)/$$*.Td
MAKEDEPFOLDER = -$(VV)mkdir -p $(DEPDIR)/$$(dir $$(patsubst $(BINDIR)/%, %, $(ROOT)/$$@))
RENAMEDEPENDENCYFILE = -$(VV)mv -f $(DEPDIR)/$$*.Td $$(patsubst $(SRCDIR)/%, $(DEPDIR)/%.d, $(ROOT)/$$<) && touch $$@
LIBRARIES+=$(wildcard $(FWDIR)/*.a)
# Cannot include newlib and libc because not all of the req'd stubs are implemented
EXCLUDE_COLD_LIBRARIES+=$(FWDIR)/libc.a $(FWDIR)/libm.a
COLD_LIBRARIES=$(filter-out $(EXCLUDE_COLD_LIBRARIES), $(LIBRARIES))
wlprefix=-Wl,$(subst $(SPACE),$(COMMA),$1)
LNK_FLAGS=--gc-sections --start-group $(strip $(LIBRARIES)) -lgcc -lstdc++ --end-group -T$(FWDIR)/v5-common.ld --no-warn-rwx-segments --sort-section=alignment --sort-common
ASMFLAGS=$(MFLAGS) $(WARNFLAGS)
CFLAGS=$(MFLAGS) $(CPPFLAGS) $(WARNFLAGS) $(GCCFLAGS) --std=$(C_STANDARD)
CXXFLAGS=$(MFLAGS) $(CPPFLAGS) $(WARNFLAGS) $(GCCFLAGS) --std=$(CXX_STANDARD)
LDFLAGS=$(MFLAGS) $(WARNFLAGS) -nostdlib $(GCCFLAGS)
SIZEFLAGS=-d --common
NUMFMTFLAGS=--to=iec --format %.2f --suffix=B
AR:=$(ARCHTUPLE)ar
# using arm-none-eabi-as generates a listing by default. This produces a super verbose output.
# Using gcc accomplishes the same thing without the extra output
AS:=$(ARCHTUPLE)gcc
CC:=$(ARCHTUPLE)gcc
CXX:=$(ARCHTUPLE)g++
LD:=$(ARCHTUPLE)g++
OBJCOPY:=$(ARCHTUPLE)objcopy
SIZETOOL:=$(ARCHTUPLE)size
READELF:=$(ARCHTUPLE)readelf
STRIP:=$(ARCHTUPLE)strip
ifneq (, $(shell command -v gnumfmt 2> /dev/null))
SIZES_NUMFMT:=| gnumfmt --field=-4 --header $(NUMFMTFLAGS)
else
ifneq (, $(shell command -v numfmt 2> /dev/null))
SIZES_NUMFMT:=| numfmt --field=-4 --header $(NUMFMTFLAGS)
else
SIZES_NUMFMT:=
endif
endif
ifneq (, $(shell command -v sed 2> /dev/null))
SIZES_SED:=| sed -e 's/ dec/total/'
else
SIZES_SED:=
endif
rwildcard=$(foreach d,$(filter-out $3,$(wildcard $1*)),$(call rwildcard,$d/,$2,$3)$(filter $(subst *,%,$2),$d))
# Colors
NO_COLOR=$(shell printf "%b" "\033[0m")
OK_COLOR=$(shell printf "%b" "\033[32;01m")
ERROR_COLOR=$(shell printf "%b" "\033[31;01m")
WARN_COLOR=$(shell printf "%b" "\033[33;01m")
STEP_COLOR=$(shell printf "%b" "\033[37;01m")
OK_STRING=$(OK_COLOR)[OK]$(NO_COLOR)
DONE_STRING=$(OK_COLOR)[DONE]$(NO_COLOR)
ERROR_STRING=$(ERROR_COLOR)[ERRORS]$(NO_COLOR)
WARN_STRING=$(WARN_COLOR)[WARNINGS]$(NO_COLOR)
ECHO=/bin/printf "%s\n"
echo=@$(ECHO) "$2$1$(NO_COLOR)"
echon=@/bin/printf "%s" "$2$1$(NO_COLOR)"
define test_output_2
@if test $(BUILD_VERBOSE) -eq $(or $4,1); then printf "%s\n" "$2"; fi;
@output="$$($2 2>&1)"; exit=$$?; \
if test 0 -ne $$exit; then \
printf "%s%s\n" "$1" "$(ERROR_STRING)"; \
printf "%s\n" "$$output"; \
exit $$exit; \
elif test -n "$$output"; then \
printf "%s%s\n" "$1" "$(WARN_STRING)"; \
printf "%s\n" "$$output"; \
else \
printf "%s%s\n" "$1" "$3"; \
fi;
endef
define test_output
@output=$$($1 2>&1); exit=$$?; \
if test 0 -ne $$exit; then \
printf "%s\n" "$(ERROR_STRING)" $$?; \
printf "%s\n" $$output; \
exit $$exit; \
elif test -n "$$output"; then \
printf "%s\n" "$(WARN_STRING)"; \
printf "%s" $$output; \
else \
printf "%s\n" "$2"; \
fi;
endef
# Makefile Verbosity
ifeq ("$(origin VERBOSE)", "command line")
BUILD_VERBOSE = $(VERBOSE)
endif
ifeq ("$(origin V)", "command line")
BUILD_VERBOSE = $(V)
endif
ifndef BUILD_VERBOSE
BUILD_VERBOSE = 0
endif
# R is reduced (default messages) - build verbose = 0
# V is verbose messages - verbosity = 1
# VV is super verbose - verbosity = 2
ifeq ($(BUILD_VERBOSE), 0)
R = @echo
D = @
VV = @
endif
ifeq ($(BUILD_VERBOSE), 1)
R = @echo
D =
VV = @
endif
ifeq ($(BUILD_VERBOSE), 2)
R =
D =
VV =
endif
INCLUDE=$(foreach dir,$(INCDIR) $(EXTRA_INCDIR),-iquote"$(dir)")
ASMSRC=$(foreach asmext,$(ASMEXTS),$(call rwildcard, $(SRCDIR),*.$(asmext), $1))
ASMOBJ=$(addprefix $(BINDIR)/,$(patsubst $(SRCDIR)/%,%.o,$(call ASMSRC,$1)))
CSRC=$(foreach cext,$(CEXTS),$(call rwildcard, $(SRCDIR),*.$(cext), $1))
COBJ=$(addprefix $(BINDIR)/,$(patsubst $(SRCDIR)/%,%.o,$(call CSRC, $1)))
CXXSRC=$(foreach cxxext,$(CXXEXTS),$(call rwildcard, $(SRCDIR),*.$(cxxext), $1))
CXXOBJ=$(addprefix $(BINDIR)/,$(patsubst $(SRCDIR)/%,%.o,$(call CXXSRC,$1)))
GETALLOBJ=$(sort $(call ASMOBJ,$1) $(call COBJ,$1) $(call CXXOBJ,$1))
ARCHIVE_TEXT_LIST=$(subst $(SPACE),$(COMMA),$(notdir $(basename $(LIBRARIES))))
LDTIMEOBJ:=$(BINDIR)/_pros_ld_timestamp.o
MONOLITH_BIN:=$(BINDIR)/monolith.bin
MONOLITH_ELF:=$(basename $(MONOLITH_BIN)).elf
HOT_BIN:=$(BINDIR)/hot.package.bin
HOT_ELF:=$(basename $(HOT_BIN)).elf
COLD_BIN:=$(BINDIR)/cold.package.bin
COLD_ELF:=$(basename $(COLD_BIN)).elf
# Check if USE_PACKAGE is defined to check for migration steps from purduesigbots/pros#87
ifndef USE_PACKAGE
$(error Your Makefile must be migrated! Visit https://pros.cs.purdue.edu/v5/releases/kernel3.1.6.html to learn how)
endif
DEFAULT_BIN=$(MONOLITH_BIN)
ifeq ($(USE_PACKAGE),1)
DEFAULT_BIN=$(HOT_BIN)
endif
-include $(wildcard $(FWDIR)/*.mk)
.PHONY: all clean quick
quick: $(DEFAULT_BIN)
all: clean $(DEFAULT_BIN)
clean::
@echo Cleaning project
-$Drm -rf $(BINDIR)
-$Drm -rf $(DEPDIR)
ifeq ($(IS_LIBRARY),1)
ifeq ($(LIBNAME),libbest)
$(error "You should rename your library! libbest is the default library name and should be changed")
endif
LIBAR=$(BINDIR)/$(LIBNAME).a
TEMPLATE_DIR=$(ROOT)/template
clean-template:
@echo Cleaning $(TEMPLATE_DIR)
-$Drm -rf $(TEMPLATE_DIR)
$(LIBAR): $(call GETALLOBJ,$(EXCLUDE_SRC_FROM_LIB)) $(EXTRA_LIB_DEPS)
-$Dmkdir $(BINDIR)
-$Drm -f $@
$(call test_output_2,Creating $@ ,$(AR) rcs $@ $^, $(DONE_STRING))
.PHONY: library
library: $(LIBAR)
.PHONY: template
template:: clean-template $(LIBAR)
$Dpros c create-template . $(LIBNAME) $(VERSION) $(foreach file,$(TEMPLATE_FILES) $(LIBAR),--system "$(file)") --target v5 $(CREATE_TEMPLATE_FLAGS)
endif
# if project is a library source, compile the archive and link output.elf against the archive rather than source objects
ifeq ($(IS_LIBRARY),1)
ELF_DEPS+=$(filter-out $(call GETALLOBJ,$(EXCLUDE_SRC_FROM_LIB)), $(call GETALLOBJ,$(EXCLUDE_SRCDIRS)))
LIBRARIES+=$(LIBAR)
else
ELF_DEPS+=$(call GETALLOBJ,$(EXCLUDE_SRCDIRS))
endif
$(MONOLITH_BIN): $(MONOLITH_ELF) $(BINDIR)
$(call test_output_2,Creating $@ for $(DEVICE) ,$(OBJCOPY) $< -O binary -R .hot_init $@,$(DONE_STRING))
$(MONOLITH_ELF): $(ELF_DEPS) $(LIBRARIES)
$(call _pros_ld_timestamp)
$(call test_output_2,Linking project with $(ARCHIVE_TEXT_LIST) ,$(LD) $(LDFLAGS) $(ELF_DEPS) $(LDTIMEOBJ) $(call wlprefix,-T$(FWDIR)/v5.ld $(LNK_FLAGS)) -o $@,$(OK_STRING))
@echo Section sizes:
-$(VV)$(SIZETOOL) $(SIZEFLAGS) $@ $(SIZES_SED) $(SIZES_NUMFMT)
$(COLD_BIN): $(COLD_ELF)
$(call test_output_2,Creating cold package binary for $(DEVICE) ,$(OBJCOPY) $< -O binary -R .hot_init $@,$(DONE_STRING))
$(COLD_ELF): $(COLD_LIBRARIES)
$(VV)mkdir -p $(dir $@)
$(call test_output_2,Creating cold package with $(ARCHIVE_TEXT_LIST) ,$(LD) $(LDFLAGS) $(call wlprefix,--gc-keep-exported --whole-archive $^ -lstdc++ --no-whole-archive) $(call wlprefix,-T$(FWDIR)/v5.ld $(LNK_FLAGS) -o $@),$(OK_STRING))
$(call test_output_2,Stripping cold package ,$(OBJCOPY) --strip-symbol=install_hot_table --strip-symbol=__libc_init_array --strip-symbol=_PROS_COMPILE_DIRECTORY --strip-symbol=_PROS_COMPILE_TIMESTAMP --strip-symbol=_PROS_COMPILE_TIMESTAMP_INT $@ $@, $(DONE_STRING))
@echo Section sizes:
-$(VV)$(SIZETOOL) $(SIZEFLAGS) $@ $(SIZES_SED) $(SIZES_NUMFMT)
$(HOT_BIN): $(HOT_ELF) $(COLD_BIN)
$(call test_output_2,Creating $@ for $(DEVICE) ,$(OBJCOPY) $< -O binary $@,$(DONE_STRING))
$(HOT_ELF): $(COLD_ELF) $(ELF_DEPS)
$(call _pros_ld_timestamp)
$(call test_output_2,Linking hot project with $(COLD_ELF) and $(ARCHIVE_TEXT_LIST) ,$(LD) -nostartfiles $(LDFLAGS) $(call wlprefix,-R $<) $(filter-out $<,$^) $(LDTIMEOBJ) $(LIBRARIES) $(call wlprefix,-T$(FWDIR)/v5-hot.ld $(LNK_FLAGS) -o $@),$(OK_STRING))
@printf "%s\n" "Section sizes:"
-$(VV)$(SIZETOOL) $(SIZEFLAGS) $@ $(SIZES_SED) $(SIZES_NUMFMT)
define asm_rule
$(BINDIR)/%.$1.o: $(SRCDIR)/%.$1
$(VV)mkdir -p $$(dir $$@)
$$(call test_output_2,Compiled $$< ,$(AS) -c $(ASMFLAGS) -o $$@ $$<,$(OK_STRING))
endef
$(foreach asmext,$(ASMEXTS),$(eval $(call asm_rule,$(asmext))))
define c_rule
$(BINDIR)/%.$1.o: $(SRCDIR)/%.$1
$(BINDIR)/%.$1.o: $(SRCDIR)/%.$1 $(DEPDIR)/$(basename %).d
$(VV)mkdir -p $$(dir $$@)
$(MAKEDEPFOLDER)
$$(call test_output_2,Compiled $$< ,$(CC) -c $(INCLUDE) -iquote"$(INCDIR)/$$(dir $$*)" $(CFLAGS) $(EXTRA_CFLAGS) $(DEPFLAGS) -o $$@ $$<,$(OK_STRING))
$(RENAMEDEPENDENCYFILE)
endef
$(foreach cext,$(CEXTS),$(eval $(call c_rule,$(cext))))
define cxx_rule
$(BINDIR)/%.$1.o: $(SRCDIR)/%.$1
$(BINDIR)/%.$1.o: $(SRCDIR)/%.$1 $(DEPDIR)/$(basename %).d
$(VV)mkdir -p $$(dir $$@)
$(MAKEDEPFOLDER)
$$(call test_output_2,Compiled $$< ,$(CXX) -c $(INCLUDE) -iquote"$(INCDIR)/$$(dir $$*)" $(CXXFLAGS) $(EXTRA_CXXFLAGS) $(DEPFLAGS) -o $$@ $$<,$(OK_STRING))
$(RENAMEDEPENDENCYFILE)
endef
$(foreach cxxext,$(CXXEXTS),$(eval $(call cxx_rule,$(cxxext))))
define _pros_ld_timestamp
$(VV)mkdir -p $(dir $(LDTIMEOBJ))
@# Pipe a line of code defining _PROS_COMPILE_TOOLSTAMP and _PROS_COMPILE_DIRECTORY into GCC,
@# which allows compilation from stdin. We define _PROS_COMPILE_DIRECTORY using a command line-defined macro
@# which is the pwd | tail bit, which will truncate the path to the last 23 characters
@#
@# const int _PROS_COMPILE_TIMESTAMP_INT = $(( $(date +%s) - $(date +%z) * 3600 ))
@# char const * const _PROS_COMPILE_TIEMSTAMP = __DATE__ " " __TIME__
@# char const * const _PROS_COMPILE_DIRECTORY = "$(shell pwd | tail -c23)";
@#
@# The shell command $$(($$(date +%s)+($$(date +%-z)/100*3600))) fetches the current
@# unix timestamp, and then adds the UTC timezone offset to account for time zones.
$(call test_output_2,Adding timestamp ,echo 'const int _PROS_COMPILE_TIMESTAMP_INT = $(shell echo $$(($$(date +%s)+($$(date +%-z)/100*3600)))); char const * const _PROS_COMPILE_TIMESTAMP = __DATE__ " " __TIME__; char const * const _PROS_COMPILE_DIRECTORY = "$(wildcard $(shell pwd | tail -c23))";' | $(CC) -c -x c $(CFLAGS) $(EXTRA_CFLAGS) -o $(LDTIMEOBJ) -,$(OK_STRING))
endef
# these rules are for build-compile-commands, which just print out sysroot information
cc-sysroot:
@echo | $(CC) -c -x c $(CFLAGS) $(EXTRA_CFLAGS) --verbose -o /dev/null -
cxx-sysroot:
@echo | $(CXX) -c -x c++ $(CXXFLAGS) $(EXTRA_CXXFLAGS) --verbose -o /dev/null -
$(DEPDIR)/%.d: ;
.PRECIOUS: $(DEPDIR)/%.d
include $(wildcard $(patsubst $(SRCDIR)/%,$(DEPDIR)/%.d,$(CSRC) $(CXXSRC)))
================================================
FILE: firmware/v5-common.ld
================================================
/* Define the sections, and where they are mapped in memory */
SECTIONS
{
/* This will get stripped out before uploading, but we need to place code
here so we can at least link to it (install_hot_table) */
.hot_init : {
KEEP (*(.hot_magic))
KEEP (*(.hot_init))
} > HOT_MEMORY
.text : {
KEEP (*(.vectors))
/* boot data should be exactly 32 bytes long */
*(.boot_data)
. = 0x20;
*(.boot)
. = ALIGN(64);
*(.freertos_vectors)
*(.text)
*(.text.*)
*(.gnu.linkonce.t.*)
*(.plt)
*(.gnu_warning)
*(.gcc_except_table)
*(.glue_7)
*(.glue_7t)
*(.vfp11_veneer)
*(.ARM.extab)
*(.gnu.linkonce.armextab.*)
} > RAM
.init : {
KEEP (*(.init))
} > RAM
.fini : {
KEEP (*(.fini))
} > RAM
.rodata : {
__rodata_start = .;
*(.rodata)
*(.rodata.*)
*(.gnu.linkonce.r.*)
__rodata_end = .;
} > RAM
.rodata1 : {
__rodata1_start = .;
*(.rodata1)
*(.rodata1.*)
__rodata1_end = .;
} > RAM
.sdata2 : {
__sdata2_start = .;
*(.sdata2)
*(.sdata2.*)
*(.gnu.linkonce.s2.*)
__sdata2_end = .;
} > RAM
.sbss2 : {
__sbss2_start = .;
*(.sbss2)
*(.sbss2.*)
*(.gnu.linkonce.sb2.*)
__sbss2_end = .;
} > RAM
.data : {
__data_start = .;
*(.data)
*(.data.*)
*(.gnu.linkonce.d.*)
*(.jcr)
*(.got)
*(.got.plt)
__data_end = .;
} > RAM
.data1 : {
__data1_start = .;
*(.data1)
*(.data1.*)
__data1_end = .;
} > RAM
.got : {
*(.got)
} > RAM
.ctors : {
__CTOR_LIST__ = .;
___CTORS_LIST___ = .;
KEEP (*crtbegin.o(.ctors))
KEEP (*(EXCLUDE_FILE(*crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
__CTOR_END__ = .;
___CTORS_END___ = .;
} > RAM
.dtors : {
__DTOR_LIST__ = .;
___DTORS_LIST___ = .;
KEEP (*crtbegin.o(.dtors))
KEEP (*(EXCLUDE_FILE(*crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
__DTOR_END__ = .;
___DTORS_END___ = .;
} > RAM
.fixup : {
__fixup_start = .;
*(.fixup)
__fixup_end = .;
} > RAM
.eh_frame : {
*(.eh_frame)
} > RAM
.eh_framehdr : {
__eh_framehdr_start = .;
*(.eh_framehdr)
__eh_framehdr_end = .;
} > RAM
.gcc_except_table : {
*(.gcc_except_table)
} > RAM
.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx*)
*(.gnu.linkonce.armexidix.*.*)
__exidx_end = .;
} > RAM
.preinit_array : {
__preinit_array_start = .;
KEEP (*(SORT(.preinit_array.*)))
KEEP (*(.preinit_array))
__preinit_array_end = .;
} > RAM
.init_array : {
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
} > RAM
.fini_array : {
__fini_array_start = .;
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array))
__fini_array_end = .;
} > RAM
/DISCARD/ : {
*(.ARM.attributes*)
}
.sdata : {
__sdata_start = .;
*(.sdata)
*(.sdata.*)
*(.gnu.linkonce.s.*)
__sdata_end = .;
} > RAM
.sbss (NOLOAD) : {
__sbss_start = .;
*(.sbss)
*(.sbss.*)
*(.gnu.linkonce.sb.*)
__sbss_end = .;
} > RAM
.tdata : {
__tdata_start = .;
*(.tdata)
*(.tdata.*)
*(.gnu.linkonce.td.*)
__tdata_end = .;
} > RAM
.tbss : {
__tbss_start = .;
*(.tbss)
*(.tbss.*)
*(.gnu.linkonce.tb.*)
__tbss_end = .;
} > RAM
.bss (NOLOAD) : {
__bss_start = .;
*(.bss)
*(.bss.*)
*(.gnu.linkonce.b.*)
__bss_end = .;
} > RAM
_SDA_BASE_ = __sdata_start + ((__sbss_end - __sdata_start) / 2 );
_SDA2_BASE_ = __sdata2_start + ((__sbss2_end - __sdata2_start) / 2 );
/* Stack section
provides __stack for the partner SDK initialization (vexMain).
This prevents the stack from being placed in .bss, which would
cause corruption of variables at the end of .bss (see issue #783).
FreeRTOS task stacks are dynamically allocated separately. */
.stack (NOLOAD) : ALIGN(8) {
_stack_end = .;
. += _STACK_SIZE;
__stack = .;
_stack_start = .;
} > RAM
.heap (NOLOAD) : {
. = ALIGN(16);
_heap = .;
HeapBase = .;
_heap_start = .;
. += _HEAP_SIZE;
_heap_end = .;
HeapLimit = .;
} > HEAP
_end = .;
}
================================================
FILE: firmware/v5-hot.ld
================================================
/* This stack is used during initialization, but FreeRTOS tasks have their own
stack allocated in BSS or Heap (kernel tasks in FreeRTOS .bss heap; user tasks
in standard heap) */
_STACK_SIZE = DEFINED(_STACK_SIZE) ? _STACK_SIZE : 0x2000;
_HEAP_SIZE = DEFINED(_HEAP_SIZE) ? _HEAP_SIZE : 0x02E00000; /* ~48 MB */
/* Define Memories in the system */
start_of_cold_mem = 0x03800000;
_COLD_MEM_SIZE = 0x04800000;
end_of_cold_mem = start_of_cold_mem + _COLD_MEM_SIZE;
start_of_hot_mem = 0x07800000;
_HOT_MEM_SIZE = 0x00800000;
end_of_hot_mem = start_of_hot_mem + _HOT_MEM_SIZE;
MEMORY
{
/* user code 72M */
COLD_MEMORY : ORIGIN = start_of_cold_mem, LENGTH = _COLD_MEM_SIZE /* Just under 19 MB */
HEAP : ORIGIN = 0x04A00000, LENGTH = _HEAP_SIZE
HOT_MEMORY : ORIGIN = start_of_hot_mem, LENGTH = _HOT_MEM_SIZE /* Just over 8 MB */
}
REGION_ALIAS("RAM", HOT_MEMORY);
ENTRY(install_hot_table)
================================================
FILE: firmware/v5.ld
================================================
/* This stack is used during initialization, but FreeRTOS tasks have their own
stack allocated in BSS or Heap (kernel tasks in FreeRTOS .bss heap; user tasks
in standard heap) */
_STACK_SIZE = DEFINED(_STACK_SIZE) ? _STACK_SIZE : 0x2000;
_HEAP_SIZE = DEFINED(_HEAP_SIZE) ? _HEAP_SIZE : 0x02E00000; /* ~48 MB */
/* Define Memories in the system */
start_of_cold_mem = 0x03800000;
_COLD_MEM_SIZE = 0x04800000;
end_of_cold_mem = start_of_cold_mem + _COLD_MEM_SIZE;
start_of_hot_mem = 0x07800000;
_HOT_MEM_SIZE = 0x00800000;
end_of_hot_mem = start_of_hot_mem + _HOT_MEM_SIZE;
MEMORY
{
/* user code 72M */
COLD_MEMORY : ORIGIN = start_of_cold_mem, LENGTH = _COLD_MEM_SIZE /* Just under 19 MB */
HEAP : ORIGIN = 0x04A00000, LENGTH = _HEAP_SIZE
HOT_MEMORY : ORIGIN = start_of_hot_mem, LENGTH = _HOT_MEM_SIZE /* Just over 8 MB */
}
REGION_ALIAS("RAM", COLD_MEMORY);
ENTRY(vexStartup)
================================================
FILE: include/api.h
================================================
/**
* \file api.h
*
* PROS API header provides high-level user functionality
*
* Contains declarations for use by typical VEX programmers using PROS.
*
* This file should not be modified by users, since it gets replaced whenever
* a kernel upgrade occurs.
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
* All rights reserved.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#ifndef _PROS_API_H_
#define _PROS_API_H_
#ifdef __cplusplus
#include <cerrno>
#include <cmath>
#include <cstddef>
#include <cstdint>
#include <cstdio>
#include <cstdlib>
#include <iostream>
#else /* (not) __cplusplus */
#include <errno.h>
#include <math.h>
#include <stdbool.h>
#include <stddef.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#endif /* __cplusplus */
#include "pros/adi.h"
#include "pros/ai_vision.h"
#include "pros/colors.h"
#include "pros/device.h"
#include "pros/distance.h"
#include "pros/error.h"
#include "pros/ext_adi.h"
#include "pros/gps.h"
#include "pros/imu.h"
#include "pros/link.h"
#include "pros/llemu.h"
#include "pros/misc.h"
#include "pros/motors.h"
#include "pros/optical.h"
#include "pros/rotation.h"
#include "pros/rtos.h"
#include "pros/screen.h"
#include "pros/vision.h"
#ifdef __cplusplus
#include "pros/adi.hpp"
#include "pros/ai_vision.hpp"
#include "pros/colors.hpp"
#include "pros/device.hpp"
#include "pros/distance.hpp"
#include "pros/gps.hpp"
#include "pros/imu.hpp"
#include "pros/link.hpp"
#include "pros/llemu.hpp"
#include "pros/misc.hpp"
#include "pros/motor_group.hpp"
#include "pros/motors.hpp"
#include "pros/optical.hpp"
#include "pros/rotation.hpp"
#include "pros/rtos.hpp"
#include "pros/screen.hpp"
#include "pros/vision.hpp"
#endif
#endif // _PROS_API_H_
================================================
FILE: include/common/cobs.h
================================================
/**
* \file common/cobs.h
*
* Consistent Overhead Byte Stuffing header
*
* See common/cobs.c for discussion
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
* All rights reserved.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include <stdint.h>
#define COBS_ENCODE_MEASURE_MAX(src_len) ((src_len) + (((src_len) + 253) / 254))
/**
* Encodes src in the Consistent Overhead Byte Stuffing algorithm, and writes
* the result to dest. dest must be sufficiently long. use cobs_encode_measure()
* to compute the size of the buff or use COBS_ENCODE_MEASURE_MAX(src_len) macro
* to get the max buffer size needed (e.g. for static allocation)
*
* \param[out] dest
* The location to write the stuffed data to
* \param[in] src
* The location of the incoming data
* \param src_len
* The length of the source data
* \param prefix
* The four character stream identifier
*
* \return The number of bytes written
*/
int cobs_encode(uint8_t* restrict dest, const uint8_t* restrict src, const size_t src_len, const uint32_t prefix);
/**
* Same as cobs_encode() but doesn't write to an output buffer. Used to
* determine how much space is needed for src.
*
* \param[in] src
* The location of the incoming data
* \param src_len
* The length of the source data
* \param prefix
* The four character stream identifier
*
* \return The size of src when encoded
*/
size_t cobs_encode_measure(const uint8_t* restrict src, const size_t src_len, const uint32_t prefix);
================================================
FILE: include/common/gid.h
================================================
/**
* \file common/gid.h
*
* Globally unique Identifer facility header
*
* See common/gid.c for discussion
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
* All rights reserved.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include <stdint.h>
#include "api.h"
struct gid_metadata {
uint32_t* const bitmap; // a constant pointer to a bitmap
const size_t max; // Maximum gid value
const size_t reserved; // first n GIDs may be reserved, at most 32, but at least 1
const size_t bitmap_size; // Cached number of uint32_t's used to map gid_max.
// Use gid_size_to_words to compute
// internal usage to ensure that GIDs get delegated linearly before wrapping
// around back to 0
size_t _cur_val;
mutex_t _lock;
};
#ifndef UINT32_WIDTH
#define UINT32_WIDTH 32
#endif
/**
* convert the maximum number of gids into a number of words needed to store the
* bitmap
*/
#define gid_size_to_words(size) (((size) + UINT32_WIDTH - 1) / UINT32_WIDTH)
/**
* Initializes a gid_metadata structure by "freeing" all IDs in the bitmap
*
* \param[in] metadata
* The gid_metadata structure to initialize
*/
void gid_init(struct gid_metadata* const metadata);
/**
* Allocates a gid from the gid structure and returns it.
*
* \param[in] metadata
* The gid_metadata to record to the gid structure
*
* \return The gid, or 0 if there are no more gids left.
*/
uint32_t gid_alloc(struct gid_metadata* const metadata);
/**
* Frees the gid specified from the structure.
*
* \param[in] metadata
* The gid_metadata to free from the gid structure
* \param id
* The gid value indicating the metadata's position in the gid structure
*/
void gid_free(struct gid_metadata* const metadata, uint32_t id);
/**
* Checks if the gid specified is allocated.
*
* \param[in] metadata
* The gid_metadata to check
* \param id
* The gid value indicating the metadata's position in the gid structure
*
* \return True if the given metadata/id combo is present in the gid structure,
* false otherwise.
*/
bool gid_check(struct gid_metadata* metadata, uint32_t id);
================================================
FILE: include/common/linkedlist.h
================================================
/*
* \file common/linkedlist.h
*
* Linked list implementation for internal use
*
* This file defines a linked list implementation that operates on the FreeRTOS
* heap, and is able to generically store function pointers and data
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
typedef void (*generic_fn_t)(void);
typedef struct ll_node_s {
union {
generic_fn_t func; // Note: a list should not contain both data/funcs
void* data;
} payload;
struct ll_node_s* next;
} ll_node_s_t;
typedef struct {
ll_node_s_t* head;
} linked_list_s_t;
/**
* Initialize a linked list node storing an arbitrary function pointer
*
* \param func
* Function pointer to store in the node
*
* \return A linked list node that stores a function pointer
*/
ll_node_s_t* linked_list_init_func_node(generic_fn_t func);
/**
* Initialize a linked list node storing a pointer to arbitrary data
*
* \param[in] data
* Pointer to data
*
* \return A linked list node that stores some data
*/
ll_node_s_t* linked_list_init_data_node(void* data);
/**
* Initialize a linked list
*
* \return An initialized linked list
*/
linked_list_s_t* linked_list_init();
/**
* Prepend a node containing a function pointer to a linked list
*
* If the provided linked list is NULL, it will be initialized first.
*
* \param[in, out] list
* Linked list to which the node will be prepended
* \param func
* Function pointer with which to initialize the node
*/
void linked_list_prepend_func(linked_list_s_t* list, generic_fn_t func);
/**
* Prepend a node containing some data to a linked list
*
* If the provided linked list is NULL, it will be initialized first.
*
* \param[in, out] list
* Linked list to which the node will be prepended
* \param[in] data
* Data with which to initialize the node
*/
void linked_list_prepend_data(linked_list_s_t* list, void* data);
/**
* Append a node containing a function pointer to a linked list
*
* If the provided linked list is NULL, it will be initialized first.
*
* \param[in, out] list
* Linked list to which the node will be appended
* \param func
* Function pointer with which to initialize the node
*/
void linked_list_append_func(linked_list_s_t* list, generic_fn_t func);
/**
* Removes the node containing the given function pointer from the linked list
*
* \param[in, out] list
* Linked list from which the node will be removed
* \param func
* Function pointer to be removed
*/
void linked_list_remove_func(linked_list_s_t* list, generic_fn_t func);
/**
* Append a node containing some data to a linked list
*
* If the provided linked list is NULL, it will be initialized first.
*
* \param[in, out] list
* Linked list to which the node will be appended
* \param data
* Data with which to initialize the node
*/
void linked_list_append_data(linked_list_s_t* list, void* data);
/**
* Remove the node containing the given data from the linked list
*
* \param[in, out] list
* Linked list from which the node will be removed
* \param data
* Data to be removed
*/
void linked_list_remove_data(linked_list_s_t* list, void* data);
typedef void (*linked_list_foreach_fn_t)(ll_node_s_t*, void*);
/**
* Perform a function on every node in a linked list
*
* If the provided linked list is NULL, the function will terminate.
*
* \param list
* Linked list upon which to perform the function
* \param cb
* Pointer to a callback function that will be provided the current node
* as well as some extra data
* \param extra_data
* Extra data to pass to the callback function
*/
void linked_list_foreach(linked_list_s_t* list, linked_list_foreach_fn_t, void* extra_data);
/**
* Frees a linked_list_s_t, making it no longer a valid list. This does not free any
* internal data, only the linekd_list structure.
*
* \param list
* List to free
*/
void linked_list_free(linked_list_s_t* list);
================================================
FILE: include/common/set.h
================================================
/**
* \file common/set.h
*
* Kernel-allocated thread-safe simple sets header
*
* See common/set.c for discussion
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
* All rights reserved.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include <stdbool.h>
#include <stddef.h>
#include <stdint.h>
#include "kapi.h"
struct set {
uint32_t* arr;
size_t used;
size_t size;
static_sem_s_t mtx_buf;
mutex_t mtx;
};
/**
* Initializes a a set.
*
* \param set
* A pointer to a set structure
*/
void set_initialize(struct set* const set);
/**
* Adds item to the set if it didn't already exist
*
* \param set
* A pointer to the set structure
* \param item
* Item to add to the set
*
* \return Ttrue if the item was added to the set or was already present
*/
bool set_add(struct set* const set, uint32_t item);
/**
* Removes an item from the set
*
* \param set
* A pointer to the set structure
* \param item
* The item to remove
*
* \return True if the item was removed (or was already not present)
*/
bool set_rm(struct set* const set, uint32_t item);
/**
* Checks if the set contains an item
*
* \param set
* A pointer to the set structure
* \param item
* The item to check
*
* \return True if the item is in the set
*/
bool set_contains(struct set* set, uint32_t item);
/**
* Checks if the list contains an item
*
* \param list
* A pointer to a list of words
* \param size
* The number of items in the list
* \param item
* The item to check
*
* \return True if the item is in the list
*/
bool list_contains(uint32_t const* const list, const size_t size, const uint32_t item);
================================================
FILE: include/common/string.h
================================================
/**
* \file common/string.h
*
* Extra string functions header
*
* See common/string.c for discussion
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
* All rights reserved.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
/**
* strdup but uses the kernel heap
*
* \param s
* Pointer to the string to duplicate
*
* \return The duplicate string
*/
char* kstrdup(const char* s);
/**
* strndup but uses the kernel heap
*
* \param s
* Pointer to the string to duplicate
* \param n
* The number of characters to duplicate
*
* \return The duplicate string
*/
char* kstrndup(const char* s, size_t n);
================================================
FILE: include/kapi.h
================================================
/**
* \file kapi.h
*
* Kernel API header
*
* Contains additional declarations for use internally within kernel
* development. This file includes the FreeRTOS header, which allows for
* creation of statically allocated FreeRTOS primitives like tasks, semaphores,
* and queues.
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
* All rights reserved.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#pragma once
#include "api.h"
#include "pros/apix.h"
#include "rtos/FreeRTOS.h"
#include "rtos/stream_buffer.h"
#ifdef __cplusplus
extern "C" {
#define task_t pros::task_t
#define task_fn_t pros::task_fn_t
#define mutex_t pros::mutex_t
#define sem_t pros::c::sem_t
#define queue_t pros::c::queue_t
#endif
#define KDBG_FILENO 3
#define warn_printf(fmt, ...) dprintf(STDERR_FILENO, "%s:%d -- " fmt "\n", __FILE__, __LINE__, ##__VA_ARGS__)
#define warn_wprint(str) wprintf("%s", str)
#define kprintf(fmt, ...) dprintf(KDBG_FILENO, "%s:%d -- " fmt "\n", __FILE__, __LINE__, ##__VA_ARGS__)
#define kprint(str) kprintf("%s", str)
#ifndef PROS_RELEASING
#define kassert(cond) \
do { \
if (!(cond)) { \
kprint("Assertion failed: " #cond); \
} \
} while (0)
#else
#define kassert(cond)
#endif
typedef uint32_t task_stack_t;
/**
* Suspends the scheduler without disabling interrupts. context switches will
* not occur while the scheduler is suspended. RTOS ticks that occur while the
* scheduler is suspended will be held pending until the scheduler has been
* unsuspended with rtos_resume_all()
*
* When used correctly, this function ensures that operations occur atomically
* w.r.t. multitasking. Functions like task_delay, queue_send, and other
* functions MUST NOT be called while the scheduler is disabled.
*/
void rtos_suspend_all(void);
/**
* Resumes the scheduler. It does not resume unsuspended tasks that were
* previously suspended by task_suspend.
*
* if(rtos_resume_all()) {
* task_delay(0); // force context switch
* }
* \return True if a context switch is necessary.
*/
int32_t rtos_resume_all(void);
/**
* Creates a task using statically allocated buffers. All tasks used by the PROS
* system must use statically allocated buffers.
* This function uses the following values of errno when an error state is
* reached:
* ENOMEM - The stack cannot be used as the TCB was not created.
*
* \param function
* Pointer to the task entry function
* \param parameters
* Pointer to memory that will be used as a parameter for the task being
* created. This memory should not typically come from stack, but rather
* from dynamically (i.e., malloc'd) or statically allocated memory.
* \param prio
* The priority at which the task should run.
* TASK_PRIO_DEFAULT plus/minus 1 or 2 is typically used.
* \param stack_depth
* The number of words (i.e. 4 * stack_depth) available on the task's
* stack. TASK_STACK_DEPTH_DEFAULT is typically sufficienct.
* \param name
* A descriptive name for the task. This is mainly used to facilitate
* debugging. The name may be up to 32 characters long.
*
* \return A handle by which the newly created task can be referenced. If an
* error occurred, NULL will be returned and errno can be checked for hints as
* to why task_create failed.
*/
task_t task_create_static(task_fn_t task_code, void* const param, uint32_t priority, const size_t stack_size,
const char* const name, task_stack_t* const stack_buffer, static_task_s_t* const task_buffer);
/**
* Creates a statically allocated mutex.
*
* All FreeRTOS primitives must be created statically if they are required for
* operation of the kernel.
*
* \param[out] mutex_buffer
* A buffer to store the mutex in
*
* \return A handle to a newly created mutex. If an error occurred, NULL will be
* returned and errno can be checked for hints as to why mutex_create failed.
*/
mutex_t mutex_create_static(static_sem_s_t* mutex_buffer);
/**
* Creates a statically allocated semaphore.
*
* All FreeRTOS primitives must be created statically if they are required for
* operation of the kernel.
*
* \param max_count
* The maximum count value that can be reached.
* \param init_count
* The initial count value assigned to the new semaphore.
* \param[out] semaphore_buffer
* A buffer to store the semaphore in
*
* \return A newly created semaphore. If an error occurred, NULL will be
* returned and errno can be checked for hints as to why sem_create failed.
*/
sem_t sem_create_static(uint32_t max_count, uint32_t init_count, static_sem_s_t* semaphore_buffer);
/**
* Creates a statically allocated queue.
*
* All FreeRTOS primitives must be created statically if they are required for
* operation of the kernel.
*
* \param length
* The maximum number of items that the queue can contain.
* \param item_size
* The number of bytes each item in the queue will require.
* \param[out] storage_buffer
* A memory location for data storage
* \param[out] queue_buffer
* A buffer to store the queue in
*
* \return A handle to a newly created queue, or NULL if the queue cannot be
* created.
*/
queue_t queue_create_static(uint32_t length, uint32_t item_size, uint8_t* storage_buffer,
static_queue_s_t* queue_buffer);
/**
* Display a fatal error to the built-in LCD/touch screen.
*
* This function is intended to be used when the integrity of the RTOS cannot be
* trusted. No thread-safety mechanisms are used and this function only relies
* on the use of the libv5rts.
*
* \param[in] text
* The text string to display to the screen
*/
void display_fatal_error(const char* text);
/**
* Prints hex characters to the terminal.
*
* \param[in] s
* The array of hex characters to print
* \param len
* The number of hex characters to print
*/
void kprint_hex(uint8_t* s, size_t len);
int32_t xTaskGetSchedulerState();
#define taskSCHEDULER_SUSPENDED ((int32_t)0)
#define taskSCHEDULER_NOT_STARTED ((int32_t)1)
#define taskSCHEDULER_RUNNING ((int32_t)2)
#ifdef __cplusplus
#undef task_t
#undef task_fn_t
#undef mutex_t
}
#endif
================================================
FILE: include/main.h
================================================
/**
* \file main.h
*
* Contains common definitions and header files used throughout your PROS
* project.
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
* All rights reserved.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#ifndef _PROS_MAIN_H_
#define _PROS_MAIN_H_
/**
* If defined, some commonly used enums will have preprocessor macros which give
* a shorter, more convenient naming pattern. If this isn't desired, simply
* comment the following line out.
*
* For instance, E_CONTROLLER_MASTER has a shorter name: CONTROLLER_MASTER.
* E_CONTROLLER_MASTER is pedantically correct within the PROS styleguide, but
* not convenient for most student programmers.
*/
#define PROS_USE_SIMPLE_NAMES
/**
* If defined, C++ literals will be available for use. All literals are in the
* pros::literals namespace.
*
* For instance, you can do `4_mtr = 50` to set motor 4's target velocity to 50
*/
#define PROS_USE_LITERALS
#include "api.h"
/**
* You should add more #includes here
*/
//#include "okapi/api.hpp"
/**
* If you find doing pros::Motor() to be tedious and you'd prefer just to do
* Motor, you can use the namespace with the following commented out line.
*
* IMPORTANT: Only the okapi or pros namespace may be used, not both
* concurrently! The okapi namespace will export all symbols inside the pros
* namespace.
*/
// using namespace pros;
// using namespace pros::literals;
// using namespace okapi;
/**
* Prototypes for the competition control tasks are redefined here to ensure
* that they can be called from user code (i.e. calling autonomous from a
* button press in opcontrol() for testing purposes).
*/
#ifdef __cplusplus
extern "C" {
#endif
void autonomous(void);
void initialize(void);
void disabled(void);
void competition_initialize(void);
void opcontrol(void);
#ifdef __cplusplus
}
#endif
#ifdef __cplusplus
/**
* You can add C++-only headers here
*/
//#include <iostream>
#endif
#endif // _PROS_MAIN_H_
================================================
FILE: include/pros/abstract_motor.hpp
================================================
/**
* \file abstract_motor.hpp
* \ingroup cpp-abstract-motor
*
* Contains prototypes for AbstractMotor, the abstract base class of both
* motors and motor groups. Abstract motors cannot be directly constructed, but
* you can use motors and motor groups as abstract motors.
*
* This file should not be modified by users, since it gets replaced whenever
* a kernel upgrade occurs.
*
* \copyright Copyright (c) 2017-2026, Purdue University ACM SIGBots.
* All rights reserved.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*/
#ifndef _PROS_ABSTRACT_MOTORS_HPP_
#define _PROS_ABSTRACT_MOTORS_HPP_
#include <cstdint>
#include <iostream>
#include "pros/device.hpp"
#include "pros/motors.h"
#include "rtos.hpp"
namespace pros {
inline namespace v5 {
/**
* \enum MotorBrake
* Indicates the current 'brake mode' of a motor.
*/
enum class MotorBrake {
coast = 0, ///< Motor coasts when stopped, traditional behavior
brake = 1, ///< Motor brakes when stopped
hold = 2, ///< Motor actively holds position when stopped
invalid = INT32_MAX ///< Invalid brake mode
};
/**
* \enum MotorEncoderUnits
* Indicates the units used by the motor encoders.
*/
enum class MotorEncoderUnits {
degrees = 0, ///< Position is recorded as angle in degrees as a floating point number
deg = 0, ///< Position is recorded as angle in degrees as a floating point number
rotations = 1, ///< Position is recorded as angle in rotations as a floating point number
counts = 2, ///< Position is recorded as raw encoder ticks as a whole number
invalid = INT32_MAX ///< Invalid motor encoder units
};
// Alias for MotorEncoderUnits
using MotorUnits = MotorEncoderUnits;
enum class MotorGears {
ratio_36_to_1 = 0, ///< 36:1, 100 RPM, Red gear set
red = ratio_36_to_1, ///< 36:1, 100 RPM, Red gear set
rpm_100 = ratio_36_to_1, ///< 36:1, 100 RPM, Red gear set
ratio_18_to_1 = 1, ///< 18:1, 200 RPM, Green gear set
green = ratio_18_to_1, ///< 18:1, 200 RPM, Green gear set
rpm_200 = ratio_18_to_1, ///< 18:1, 200 RPM, Green gear set
ratio_6_to_1 = 2, ///< 6:1, 600 RPM, Blue gear set
blue = ratio_6_to_1, ///< 6:1, 600 RPM, Blue gear set
rpm_600 = ratio_6_to_1, ///< 6:1, 600 RPM, Blue gear set
invalid = INT32_MAX ///< Error return code
};
/**
* \enum MotorType
* Indicates the type of a motor
*/
enum class MotorType {
v5 = 0, ///< 11w motor
exp = 1, ///< 5.5w motor
invalid = INT32_MAX ///< Error return code
};
// Provide Aliases for MotorGears
using MotorGearset = MotorGears;
using MotorCart = MotorGears;
using MotorCartridge = MotorGears;
using MotorGear = MotorGears;
/**
* \ingroup cpp-abstract-motor
*/
class AbstractMotor {
/**
* \addtogroup cpp-abstract-motor
* @{
*/
public:
/// \name Motor movement functions
/// These functions allow programmers to make motors move
///@{
/**
* Sets the voltage for the motor from -127 to 127.
*
* This is designed to map easily to the input from the controller's analog
* stick for simple opcontrol use. The actual behavior of the motor is
* analogous to use of motor_move(), or motorSet() from the PROS 2 API.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param voltage
* The new motor voltage from -127 to 127
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t move(std::int32_t voltage) const = 0;
/**
* Sets the target absolute position for the motor to move to.
*
* This movement is relative to the position of the motor when initialized or
* the position when it was most recently reset with
* pros::Motor::set_zero_position().
*
* \note This function simply sets the target for the motor, it does not block
* program execution until the movement finishes.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param position
* The absolute position to move to in the motor's encoder units
* \param velocity
* The maximum allowable velocity for the movement in RPM
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t move_absolute(const double position, const std::int32_t velocity) const = 0;
/**
* Sets the relative target position for the motor to move to.
*
* This movement is relative to the current position of the motor as given in
* pros::Motor::motor_get_position(). Providing 10.0 as the position parameter
* would result in the motor moving clockwise 10 units, no matter what the
* current position is.
*
* \note This function simply sets the target for the motor, it does not block
* program execution until the movement finishes.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param position
* The relative position to move to in the motor's encoder units
* \param velocity
* The maximum allowable velocity for the movement in RPM
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t move_relative(const double position, const std::int32_t velocity) const = 0;
/**
* Sets the velocity for the motor.
*
* This velocity corresponds to different actual speeds depending on the
* gearset used for the motor. This results in a range of +-100 for
* E_MOTOR_GEARSET_36, +-200 for E_MOTOR_GEARSET_18, and +-600 for
* E_MOTOR_GEARSET_6. The velocity is held with PID to ensure consistent
* speed, as opposed to setting the motor's voltage.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param velocity
* The new motor velocity from -+-100, +-200, or +-600 depending on the
* motor's gearset
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t move_velocity(const std::int32_t velocity) const = 0;
/**
* Sets the output voltage for the motor from -12000 to 12000 in millivolts.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param port
* The V5 port number from 1-21
* \param voltage
* The new voltage value from -12000 to 12000
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t move_voltage(const std::int32_t voltage) const = 0;
/**
* Stops the motor using the currently configured brake mode.
*
* This function sets motor velocity to zero, which will cause it to act
* according to the set brake mode. If brake mode is set to MOTOR_BRAKE_HOLD,
* this function may behave differently than calling move_absolute(0)
* or motor_move_relative(0).
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*/
virtual std::int32_t brake(void) const = 0;
/**
* Changes the output velocity for a profiled movement (motor_move_absolute or
* motor_move_relative). This will have no effect if the motor is not following
* a profiled movement.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param velocity
* The new motor velocity from +-100, +-200, or +-600 depending on the
* motor's gearset
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t modify_profiled_velocity(const std::int32_t velocity) const = 0;
/**
* Gets the target position set for the motor by the user, with a parameter
* for the motor index.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The target position in its encoder units or PROS_ERR_F if the
* operation failed, setting errno.
*/
virtual double get_target_position(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector containing the target position(s) set for the motor(s) by the user
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
*
* \return A vector containing the target position(s) in its encoder units or PROS_ERR_F if the
* operation failed, setting errno.
*/
virtual std::vector<double> get_target_position_all(void) const = 0;
/**
* Gets the velocity commanded to the motor by the user.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The commanded motor velocity from +-100, +-200, or +-600, or
* PROS_ERR if the operation failed, setting errno.
*/
virtual std::int32_t get_target_velocity(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector containing the velocity/velocities commanded to the motor(s) by the user
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \return A vector containing the commanded motor velocity/velocities from +-100,
* +-200, or +-600, or PROS_ERR if the operation failed, setting errno.
*/
virtual std::vector<std::int32_t> get_target_velocity_all(void) const = 0;
///@}
/// \name Motor telemetry functions
/// \addtogroup cpp-motor-telemetry
/// These functions allow programmers to collect telemetry from motors
///@{
/**
* Gets the actual velocity of the motor.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's actual velocity in RPM or PROS_ERR_F if the operation
* failed, setting errno.
*/
virtual double get_actual_velocity(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector containing the actual velocity/velocities of the motor(s)
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \return A vector containing the motor's/motors' actual velocity/velocities in RPM or PROS_ERR_F
* if the operation failed, setting errno.
*/
virtual std::vector<double> get_actual_velocity_all(void) const = 0;
/**
* Gets the current drawn by the motor in mA.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's current in mA or PROS_ERR if the operation failed,
* setting errno.
*/
virtual std::int32_t get_current_draw(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector containing the current(s) drawn by the motor(s) in mA.
*
* This function uses the following values of errno when an error state is
* reached:
*
* ENODEV - The port cannot be configured as a motor
*
*
* \return A vector conatining the motor's/motors' current(s) in mA or PROS_ERR if the operation failed,
* setting errno.
*/
virtual std::vector<std::int32_t> get_current_draw_all(void) const = 0;
/**
* Gets the direction of movement for the motor.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 for moving in the positive direction, -1 for moving in the
* negative direction, and PROS_ERR if the operation failed, setting errno.
*/
virtual std::int32_t get_direction(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector containing the direction(s) of movement for the motor(s).
*
*
* This function uses the following values of errno when an error state is
* reached:
*
* ENODEV - The port cannot be configured as a motor
*
*
* \return A vector containing 1 for moving in the positive direction, -1 for moving in the
* negative direction, and PROS_ERR if the operation failed, setting errno.
*/
virtual std::vector<std::int32_t> get_direction_all(void) const = 0;
/**
* Gets the efficiency of the motor in percent.
*
* An efficiency of 100% means that the motor is moving electrically while
* drawing no electrical power, and an efficiency of 0% means that the motor
* is drawing power but not moving.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's efficiency in percent or PROS_ERR_F if the operation
* failed, setting errno.
*/
virtual double get_efficiency(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector containing the efficiency/efficiencies of the motor(s) in percent.
*
* An efficiency of 100% means that the motor is moving electrically while
* drawing no electrical power, and an efficiency of 0% means that the motor
* is drawing power but not moving.
*
* This function uses the following values of errno when an error state is
* reached:
*
* ENODEV - The port cannot be configured as a motor
*
*
* \return A vector containing the motor's/motors' efficiency/efficiencies in percent or PROS_ERR_F if the operation
* failed, setting errno.
*/
virtual std::vector<double> get_efficiency_all(void) const = 0;
/**
* Gets the faults experienced by the motor.
*
* Compare this bitfield to the bitmasks in pros::motor_fault_e_t.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A bitfield containing the motor's faults.
*/
virtual std::uint32_t get_faults(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the faults experienced by the motor(s).
*
* Compare this bitfield to the bitmasks in pros::motor_fault_e_t.
*
* This function uses the following values of errno when an error state is
* reached:
*
* ENODEV - The port cannot be configured as a motor
*
* \return A bitfield containing the motor's/motors' faults.
*/
virtual std::vector<std::uint32_t> get_faults_all(void) const = 0;
/**
* Gets the flags set by the motor's operation.
*
* Compare this bitfield to the bitmasks in pros::motor_flag_e_t.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A bitfield containing the motor's flags.
*/
virtual std::uint32_t get_flags(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the flags set by the motor's/motors' operation.
*
* Compare this bitfield to the bitmasks in pros::motor_flag_e_t.
*
* This function uses the following values of errno when an error state is
* reached:
*
* ENODEV - The port cannot be configured as a motor
*
*
* \return A bitfield containing the motor's/motors' flags.
*/
virtual std::vector<std::uint32_t> get_flags_all(void) const = 0;
/**
* Gets the absolute position of the motor in its encoder units.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's absolute position in its encoder units or PROS_ERR_F
* if the operation failed, setting errno.
*/
virtual double get_position(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector containing the absolute position(s) of the motor(s) in its encoder units.
*
* This function uses the following values of errno when an error state is
* reached:
*
* ENODEV - The port cannot be configured as a motor
*
* \return A vector containing the motor's/motors' absolute position(s) in its encoder units or PROS_ERR_F
* if the operation failed, setting errno.
*/
virtual std::vector<double> get_position_all(void) const = 0;
/**
* Gets the power drawn by the motor in Watts.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's power draw in Watts or PROS_ERR_F if the operation
* failed, setting errno.
*/
virtual double get_power(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector containing the power(s) drawn by the motor(s) in Watts.
*
* This function uses the following values of errno when an error state is
* reached:
*
* ENODEV - The port cannot be configured as a motor
*
* \return A vector containing the motor's/motors' power draw in Watts or PROS_ERR_F if the operation
* failed, setting errno.
*/
virtual std::vector<double> get_power_all(void) const = 0;
/**
* Gets the raw encoder count of the motor at a given timestamp.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param[in] timestamp
* A pointer to a time in milliseconds for which the encoder count
* will be returned. If NULL, the timestamp at which the encoder
* count was read will not be supplied
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The raw encoder count at the given timestamp or PROS_ERR if the
* operation failed.
*/
virtual std::int32_t get_raw_position(std::uint32_t* const timestamp, const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the raw encoder count(s) of the motor(s) at a given timestamp.
*
*
* This function uses the following values of errno when an error state is
* reached:
*
* ENODEV - The port cannot be configured as a motor
*
* \param timestamp
* A pointer to a time in milliseconds for which the encoder count
* will be returned. If NULL, the timestamp at which the encoder
* count was read will not be supplied
*
* \return A vector containing the raw encoder count(s) at the given timestamp or PROS_ERR if the
* operation failed.
*/
virtual std::vector<std::int32_t> get_raw_position_all(std::uint32_t* const timestamp) const = 0;
/**
* Gets the temperature of the motor in degrees Celsius.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's temperature in degrees Celsius or PROS_ERR_F if the
* operation failed, setting errno.
*/
virtual double get_temperature(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the temperature(s) of the motor(s) in degrees Celsius.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A vector containing the motor's/motors' temperature(s) in degrees Celsius or PROS_ERR_F if the
* operation failed, setting errno.
*/
virtual std::vector<double> get_temperature_all(void) const = 0;
/**
* Gets the torque generated by the motor in Newton Meters (Nm).
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's torque in Nm or PROS_ERR_F if the operation failed,
* setting errno.
*/
virtual double get_torque(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the torque(s) generated by the motor(s) in Newton Meters (Nm).
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A vector containing the motor's/motors' torque(s) in Nm or PROS_ERR_F if the operation failed,
* setting errno.
*/
virtual std::vector<double> get_torque_all(void) const = 0;
/**
* Gets the voltage delivered to the motor in millivolts.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's voltage in mV or PROS_ERR_F if the operation failed,
* setting errno.
*/
virtual std::int32_t get_voltage(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the voltage(s) delivered to the motor(s) in millivolts.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A vector containing the motor's/motors' voltage(s) in mV or PROS_ERR_F if the operation failed,
* setting errno.
*/
virtual std::vector<std::int32_t> get_voltage_all(void) const = 0;
/**
* Checks if the motor is drawing over its current limit.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the motor's current limit is being exceeded and 0 if the
* current limit is not exceeded, or PROS_ERR if the operation failed, setting
* errno.
*/
virtual std::int32_t is_over_current(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of whether each motor is drawing over its current limit.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the motor's current limit is being exceeded and 0 if the
* current limit is not exceeded, or PROS_ERR if the operation failed, setting
* errno.
*/
virtual std::vector<std::int32_t> is_over_current_all(void) const = 0;
/**
* Gets the temperature limit flag for the motor.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the temperature limit is exceeded and 0 if the temperature is
* below the limit, or PROS_ERR if the operation failed, setting errno.
*/
virtual std::int32_t is_over_temp(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the temperature limit flag(s) for the motor(s).
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the temperature limit is exceeded and 0 if the temperature is
* below the limit, or PROS_ERR if the operation failed, setting errno.
*/
virtual std::vector<std::int32_t> is_over_temp_all(void) const = 0;
///@}
/// \name Motor configuration functions
/// \addtogroup cpp-motor-configuration
/// These functions allow programmers to configure the behavior of motors
///@{
/**
* Gets the brake mode that was set for the motor.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return One of MotorBrake, according to what was set for the
* motor, or E_MOTOR_BRAKE_INVALID if the operation failed, setting errno.
*/
virtual MotorBrake get_brake_mode(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the brake mode(s) that was set for the motor(s).
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A vector containing MotorBrake(s), according to what was set for the
* motor(s), or E_MOTOR_BRAKE_INVALID if the operation failed, setting errno.
*/
virtual std::vector<MotorBrake> get_brake_mode_all(void) const = 0;
/**
* Gets the current limit for the motor in mA.
*
* The default value is 2500 mA.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's current limit in mA or PROS_ERR if the operation failed,
* setting errno.
*/
virtual std::int32_t get_current_limit(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the current limit(s) for the motor(s) in mA.
*
* The default value is 2500 mA.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A vector containing the motor's/motors' current limit(s) in mA or PROS_ERR if the operation failed,
* setting errno.
*/
virtual std::vector<std::int32_t> get_current_limit_all(void) const = 0;
/**
* Gets the encoder units that were set for the motor.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return One of MotorUnits according to what is set for the
* motor or E_MOTOR_ENCODER_INVALID if the operation failed.
*/
virtual MotorUnits get_encoder_units(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the encoder units that were set for the motor(s).
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A vector of MotorUnits according to what is set for the
* motor(s) or E_MOTOR_ENCODER_INVALID if the operation failed.
*/
virtual std::vector<MotorUnits> get_encoder_units_all(void) const = 0;
/**
* Gets the gearset that was set for the motor.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return One of MotorGears according to what is set for the motor,
* or pros::MotorGears::invalid if the operation failed.
*/
virtual MotorGears get_gearing(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the gearset(s) that was/were set for the motor(s).
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A vector of MotorGears according to what is set for the motor(s),
* or pros::MotorGears::invalid if the operation failed.
*/
virtual std::vector<MotorGears> get_gearing_all(void) const = 0;
/**
* @brief Gets returns a vector with all the port numbers in the motor group.
*
* @return std::vector<std::int8_t>
*/
virtual std::vector<std::int8_t> get_port_all(void) const = 0;
/**
* Gets the voltage limit set by the user.
*
* Default value is 0V, which means that there is no software limitation
* imposed on the voltage.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return The motor's voltage limit in V or PROS_ERR if the operation failed,
* setting errno.
*/
virtual std::int32_t get_voltage_limit(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the voltage limit(s) set by the user.
*
* Default value is 0V, which means that there is no software limitation
* imposed on the voltage.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return A vector containing the motor's/motors' voltage limit(s) in V or PROS_ERR if the operation failed,
* setting errno.
*/
virtual std::vector<std::int32_t> get_voltage_limit_all(void) const = 0;
/**
* Gets the operation direction of the motor as set by the user.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the motor has been reversed and 0 if the motor was not
* reversed, or PROS_ERR if the operation failed, setting errno.
*/
virtual std::int32_t is_reversed(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the operation direction(s) of the motor(s) as set by the user.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the motor has been reversed and 0 if the motor was not
* reversed, or PROS_ERR if the operation failed, setting errno.
*/
virtual std::vector<std::int32_t> is_reversed_all(void) const = 0;
/**
* Gets the type of the motor
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return One of MotorType according to the type of the motor,
* or pros::MotorType::invalid if the operation failed
*/
virtual MotorType get_type(const std::uint8_t index = 0) const = 0;
/**
* Gets a vector of the type(s) of the motor(s).
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \return A vector of MotorType according to the type(s) of the motor(s),
* or pros::MotorType::invalid if the operation failed.
*/
virtual std::vector<MotorType> get_type_all(void) const = 0;
/**
* Sets one of MotorBrake to the motor. Works with the C enum
* and the C++ enum class.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param mode
* The MotorBrake to set for the motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t set_brake_mode(const MotorBrake mode, const std::uint8_t index = 0) const = 0;
virtual std::int32_t set_brake_mode(const pros::motor_brake_mode_e_t mode, const std::uint8_t index = 0) const = 0;
virtual std::int32_t set_brake_mode_all(const MotorBrake mode) const = 0;
virtual std::int32_t set_brake_mode_all(const pros::motor_brake_mode_e_t mode) const = 0;
/**
* Sets the current limit for the motor in mA.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param limit
* The new current limit in mA
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t set_current_limit(const std::int32_t limit, const std::uint8_t index = 0) const = 0;
virtual std::int32_t set_current_limit_all(const std::int32_t limit) const = 0;
/**
* Sets one of MotorUnits for the motor encoder. Works with the C
* enum and the C++ enum class.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param units
* The new motor encoder units
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t set_encoder_units(const MotorUnits units, const std::uint8_t index = 0) const = 0;
virtual std::int32_t set_encoder_units(const pros::motor_encoder_units_e_t units, const std::uint8_t index = 0) const = 0;
virtual std::int32_t set_encoder_units_all(const MotorUnits units) const = 0;
virtual std::int32_t set_encoder_units_all(const pros::motor_encoder_units_e_t units) const = 0;
/**
* Sets one of the gear cartridge (red, green, blue) for the motor. Usable with
* the C++ enum class and the C enum.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param gearset
* The new motor gearset
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t set_gearing(const MotorGears gearset, const std::uint8_t index = 0) const = 0;
virtual std::int32_t set_gearing(const pros::motor_gearset_e_t gearset, const std::uint8_t index = 0) const = 0;
virtual std::int32_t set_gearing_all(const MotorGears gearset) const = 0;
virtual std::int32_t set_gearing_all(const pros::motor_gearset_e_t gearset) const = 0;
/**
* Sets the reverse flag for the motor.
*
* This will invert its movements and the values returned for its position.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param reverse
* True reverses the motor, false is default
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t set_reversed(const bool reverse, const std::uint8_t index = 0) = 0;
virtual std::int32_t set_reversed_all(const bool reverse) = 0;
/**
* Sets the voltage limit for the motor in Volts.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param limit
* The new voltage limit in Volts
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t set_voltage_limit(const std::int32_t limit, const std::uint8_t index = 0) const = 0;
virtual std::int32_t set_voltage_limit_all(const std::int32_t limit) const = 0;
/**
* Sets the position for the motor in its encoder units.
*
* This will be the future reference point for the motor's "absolute"
* position.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param position
* The new reference position in its encoder units
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t set_zero_position(const double position, const std::uint8_t index = 0) const = 0;
virtual std::int32_t set_zero_position_all(const double position) const = 0;
/**
* Sets the "absolute" zero position of the motor to its current position.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port cannot be configured as a motor
*
* \param index Optional parameter.
* The index of the motor to get the target position of.
* By default index is 0, and will return an error for an out of bounds index
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*/
virtual std::int32_t tare_position(const std::uint8_t index = 0) const = 0;
virtual std::int32_t tare_position_all(void) const = 0;
virtual std::int8_t get_port(const std::uint8_t index = 0) const = 0;
/**
* @brief Returns the number of objects
*
* @return std::int8_t
*/
virtual std::int8_t size(void) const = 0;
///@}
private:
};
} // namespace v5
} // namespace pros
///@}
#endif
================================================
FILE: include/pros/adi.h
================================================
/**
* \file pros/adi.h
* \ingroup c-adi
*
* Contains prototypes for interfacing with the ADI.
*
* This file should not be modified by users, since it gets replaced whenever
* a kernel upgrade occurs.
*
* \Copyright (c) 2017-2026, Purdue University ACM SIGBots.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*
* \defgroup c-adi ADI (TriPort) C API
* \note The external ADI API can be found [here.](@ref ext-adi)
* \note Additional example code for this module can be found in its [Tutorial.](@ref adi)
*/
#ifndef _PROS_ADI_H_
#define _PROS_ADI_H_
#include <stdbool.h>
#include <stdint.h>
#ifndef PROS_ERR
#define PROS_ERR (INT32_MAX)
#endif
#ifdef __cplusplus
extern "C" {
namespace pros {
#endif
/**
* \ingroup c-adi
*/
/**
* \addtogroup c-adi
* @{
*/
/**
* \enum adi_port_config_e
* Represents the port type for an ADI port.
*/
typedef enum adi_port_config_e {
E_ADI_ANALOG_IN = 0,
E_ADI_ANALOG_OUT = 1,
E_ADI_DIGITAL_IN = 2,
E_ADI_DIGITAL_OUT = 3,
#ifdef _INTELLISENSE
#define _DEPRECATE_DIGITAL_IN = E_ADI_DIGITAL_IN
#define _DEPRECATE_ANALOG_IN = E_ADI_ANALOG_IN
#else
#define _DEPRECATE_DIGITAL_IN __attribute__((deprecated("use E_ADI_DIGITAL_IN instead"))) = E_ADI_DIGITAL_IN
#define _DEPRECATE_ANALOG_IN __attribute__((deprecated("use E_ADI_ANALOG_IN instead"))) = E_ADI_ANALOG_IN
#endif
E_ADI_SMART_BUTTON _DEPRECATE_DIGITAL_IN,
E_ADI_SMART_POT _DEPRECATE_ANALOG_IN,
E_ADI_LEGACY_BUTTON _DEPRECATE_DIGITAL_IN,
E_ADI_LEGACY_POT _DEPRECATE_ANALOG_IN,
E_ADI_LEGACY_LINE_SENSOR _DEPRECATE_ANALOG_IN,
E_ADI_LEGACY_LIGHT_SENSOR _DEPRECATE_ANALOG_IN,
E_ADI_LEGACY_GYRO = 10,
E_ADI_LEGACY_ACCELEROMETER _DEPRECATE_ANALOG_IN,
#undef _DEPRECATE_DIGITAL_IN
#undef _DEPRECATE_ANALOG_IN
E_ADI_LEGACY_SERVO = 12,
E_ADI_LEGACY_PWM = 13,
E_ADI_LEGACY_ENCODER = 14,
E_ADI_LEGACY_ULTRASONIC = 15,
E_ADI_TYPE_UNDEFINED = 255,
E_ADI_ERR = PROS_ERR
} adi_port_config_e_t;
/**
* \enum adi_potentiometer_type_e_t
* Represents the potentiometer version type.
*/
typedef enum adi_potentiometer_type_e {
E_ADI_POT_EDR = 0,
E_ADI_POT_V2
} adi_potentiometer_type_e_t;
#ifdef PROS_USE_SIMPLE_NAMES
#ifdef __cplusplus
#define ADI_ANALOG_IN pros::E_ADI_ANALOG_IN
#define ADI_ANALOG_OUT pros::E_ADI_ANALOG_OUT
#define ADI_DIGITAL_IN pros::E_ADI_DIGITAL_IN
#define ADI_DIGITAL_OUT pros::E_ADI_DIGITAL_OUT
#define ADI_SMART_BUTTON pros::E_ADI_SMART_BUTTON
#define ADI_SMART_POT pros::E_ADI_SMART_POT
#define ADI_LEGACY_BUTTON pros::E_ADI_LEGACY_BUTTON
#define ADI_LEGACY_POT pros::E_ADI_LEGACY_POT
#define ADI_LEGACY_LINE_SENSOR pros::E_ADI_LEGACY_LINE_SENSOR
#define ADI_LEGACY_LIGHT_SENSOR pros::E_ADI_LEGACY_LIGHT_SENSOR
#define ADI_LEGACY_GYRO pros::E_ADI_LEGACY_GYRO
#define ADI_LEGACY_ACCELEROMETER pros::E_ADI_LEGACY_ACCELEROMETER
#define ADI_LEGACY_SERVO pros::E_ADI_LEGACY_SERVO
#define ADI_LEGACY_PWM pros::E_ADI_LEGACY_PWM
#define ADI_LEGACY_ENCODER pros::E_ADI_LEGACY_ENCODER
#define ADI_LEGACY_ULTRASONIC pros::E_ADI_LEGACY_ULTRASONIC
#define ADI_TYPE_UNDEFINED pros::E_ADI_TYPE_UNDEFINED
#define ADI_ERR pros::E_ADI_ERR
#else
#define ADI_ANALOG_IN E_ADI_ANALOG_IN
#define ADI_ANALOG_OUT E_ADI_ANALOG_OUT
#define ADI_DIGITAL_IN E_ADI_DIGITAL_IN
#define ADI_DIGITAL_OUT E_ADI_DIGITAL_OUT
#define ADI_SMART_BUTTON E_ADI_SMART_BUTTON
#define ADI_SMART_POT E_ADI_SMART_POT
#define ADI_LEGACY_BUTTON E_ADI_LEGACY_BUTTON
#define ADI_LEGACY_POT E_ADI_LEGACY_POT
#define ADI_LEGACY_LINE_SENSOR E_ADI_LEGACY_LINE_SENSOR
#define ADI_LEGACY_LIGHT_SENSOR E_ADI_LEGACY_LIGHT_SENSOR
#define ADI_LEGACY_GYRO E_ADI_LEGACY_GYRO
#define ADI_LEGACY_ACCELEROMETER E_ADI_LEGACY_ACCELEROMETER
#define ADI_LEGACY_SERVO E_ADI_LEGACY_SERVO
#define ADI_LEGACY_PWM E_ADI_LEGACY_PWM
#define ADI_LEGACY_ENCODER E_ADI_LEGACY_ENCODER
#define ADI_LEGACY_ULTRASONIC E_ADI_LEGACY_ULTRASONIC
#define ADI_TYPE_UNDEFINED E_ADI_TYPE_UNDEFINED
#define ADI_ERR E_ADI_ERR
#endif
#endif
#define INTERNAL_ADI_PORT 22
#define NUM_ADI_PORTS 8
#ifdef __cplusplus
namespace c {
#endif
/** @} Add to group c-adi*/
/**
* \ingroup c-adi
*/
/**
* \addtogroup c-adi
* @{
*/
/**
* Gets the configuration for the given ADI port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports.
*
* \param port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') for which to return
* the configuration
*
* \return The ADI configuration for the given port
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void initialize() {
* adi_port_set_config(ANALOG_SENSOR_PORT, E_ADI_ANALOG_IN);
* // Displays the value of E_ADI_ANALOG_IN
* printf("Port Type: %d\n", adi_port_get_config(ANALOG_SENSOR_PORT));
* }
* \endcode
*/
adi_port_config_e_t adi_port_get_config(uint8_t port);
/**
* Gets the value for the given ADI port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports.
*
* \param port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') for which the value
* will be returned
*
* \return The value stored for the given port
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void opcontrol() {
* adi_port_set_config(ANALOG_SENSOR_PORT, E_ADI_ANALOG_IN);
* printf("Port Value: %d\n", adi_get_value(ANALOG_SENSOR_PORT));
* }
* \endcode
*/
int32_t adi_port_get_value(uint8_t port);
/**
* Configures an ADI port to act as a given sensor type.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports.
*
* \param port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
* \param type
* The configuration type for the port
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void initialize() {
* adi_port_set_config(ANALOG_SENSOR_PORT, E_ADI_ANALOG_IN);
* }
* \endcode
*/
int32_t adi_port_set_config(uint8_t port, adi_port_config_e_t type);
/**
* Sets the value for the given ADI port.
*
* This only works on ports configured as outputs, and the behavior will change
* depending on the configuration of the port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports.
*
* \param port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') for which the value
* will be set
* \param value
* The value to set the ADI port to
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1
*
* void initialize() {
* adi_port_set_config(DIGITAL_SENSOR_PORT, E_ADI_DIGITAL_OUT);
* adi_set_value(DIGITAL_SENSOR_PORT, HIGH);
* }
* \endcode
*/
int32_t adi_port_set_value(uint8_t port, int32_t value);
/**
* Calibrates the analog sensor on the specified port and returns the new
* calibration value.
*
* This method assumes that the true sensor value is not actively changing at
* this time and computes an average from approximately 500 samples, 1 ms apart,
* for a 0.5 s period of calibration. The average value thus calculated is
* returned and stored for later calls to the adi_analog_read_calibrated() and
* adi_analog_read_calibrated_HR() functions. These functions will return
* the difference between this value and the current sensor value when called.
*
* Do not use this function when the sensor value might be unstable
* (gyro rotation, accelerometer movement).
*
* \note The ADI currently returns data at 10ms intervals, in constrast to the
* calibrate function’s 1ms sample rate.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
*
* \param port
* The ADI port to calibrate (from 1-8, 'a'-'h', 'A'-'H')
*
* \return The average sensor value computed by this function
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void initialize() {
* adi_analog_calibrate(ANALOG_SENSOR_PORT);
* printf("Calibrated Reading: %d\n", adi_analog_read_calibrated(ANALOG_SENSOR_PORT));
* // All readings from then on will be calibrated
* }
* \endcode
*/
int32_t adi_analog_calibrate(uint8_t port);
/**
* Gets the 12-bit value of the specified port.
*
* The value returned is undefined if the analog pin has been switched to a
* different mode.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an analog input
*
* \param port
* The ADI port (from 1-8, 'a'-'h', 'A'-'H') for which the value will be
* returned
*
* \return The analog sensor value, where a value of 0 reflects an input voltage
* of nearly 0 V and a value of 4095 reflects an input voltage of nearly 5 V
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void opcontrol() {
* while (true) {
* printf("Sensor Reading: %d\n", adi_analog_read(ANALOG_SENSOR_PORT));
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_analog_read(uint8_t port);
/**
* Gets the 12 bit calibrated value of an analog input port.
*
* The adi_analog_calibrate() function must be run first. This function is
* inappropriate for sensor values intended for integration, as round-off error
* can accumulate causing drift over time. Use adi_analog_read_calibrated_HR()
* instead.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an analog input
*
* \param port
* The ADI port (from 1-8, 'a'-'h', 'A'-'H') for which the value will be
* returned
*
* \return The difference of the sensor value from its calibrated default from
* -4095 to 4095
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void opcontrol() {
* while (true) {
* printf("Sensor Reading: %d\n", adi_analog_read_calibrated(ANALOG_SENSOR_PORT));
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_analog_read_calibrated(uint8_t port);
/**
* Gets the 16 bit calibrated value of an analog input port.
*
* The adi_analog_calibrate() function must be run first. This is intended for
* integrated sensor values such as gyros and accelerometers to reduce drift due
* to round-off, and should not be used on a sensor such as a line tracker
* or potentiometer.
*
* The value returned actually has 16 bits of "precision", even though the ADC
* only reads 12 bits, so that error induced by the average value being between
* two values when integrated over time is trivial. Think of the value as the
* true value times 16.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an analog input
*
* \param port
* The ADI port (from 1-8, 'a'-'h', 'A'-'H') for which the value will be
* returned
*
* \return The difference of the sensor value from its calibrated default from
* -16384 to 16384
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void opcontrol() {
* while (true) {
* adi_analog_calibrate(ANALOG_SENSOR_PORT);
* printf("Sensor Reading: %d\n", adi_analog_read_calibrated_HR(ANALOG_SENSOR_PORT));
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_analog_read_calibrated_HR(uint8_t port);
/**
* Gets the digital value (1 or 0) of a port configured as a digital input.
*
* If the port is configured as some other mode, the digital value which
* reflects the current state of the port is returned, which may or may not
* differ from the currently set value. The return value is undefined for ports
* configured as any mode other than a Digital Input.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a digital input
*
* \param port
* The ADI port to read (from 1-8, 'a'-'h', 'A'-'H')
*
* \return True if the pin is HIGH, or false if it is LOW
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1
*
* void opcontrol() {
* while (true) {
* printf("Sensor Value: %d\n", adi_digital_read(DIGITAL_SENSOR_PORT));
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_digital_read(uint8_t port);
/**
* Gets a rising-edge case for a digital button press.
*
* This function is not thread-safe.
* Multiple tasks polling a single button may return different results under the
* same circumstances, so only one task should call this function for any given
* button. E.g., Task A calls this function for buttons 1 and 2. Task B may call
* this function for button 3, but should not for buttons 1 or 2. A typical
* use-case for this function is to call inside opcontrol to detect new button
* presses, and not in any other tasks.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a digital input
*
* \param port
* The ADI port to read (from 1-8, 'a'-'h', 'A'-'H')
*
* \return 1 if the button is pressed and had not been pressed
* the last time this function was called, 0 otherwise.
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1
*
* void opcontrol() {
* while (true) {
* if (adi_digital_get_new_press(DIGITAL_SENSOR_PORT)) {
* // Toggle pneumatics or other state operations
* }
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_digital_get_new_press(uint8_t port);
/**
* Sets the digital value (1 or 0) of a port configured as a digital output.
*
* If the port is configured as some other mode, behavior is undefined.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a digital output
*
* \param port
* The ADI port to read (from 1-8, 'a'-'h', 'A'-'H')
* \param value
* An expression evaluating to "true" or "false" to set the output to
* HIGH or LOW respectively, or the constants HIGH or LOW themselves
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT
*
* void opcontrol() {
* bool state = LOW;
* while (true) {
* state != state;
* adi_digital_write(DIGITAL_SENSOR_PORT, state);
* delay(5); // toggle the sensor value every 50ms
* }
* }
* \endcode
*/
int32_t adi_digital_write(uint8_t port, bool value);
/**
* Configures the port as an input or output with a variety of settings.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
*
* \param port
* The ADI port to read (from 1-8, 'a'-'h', 'A'-'H')
* \param mode
* One of INPUT, INPUT_ANALOG, INPUT_FLOATING, OUTPUT, or OUTPUT_OD
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void initialize() {
* adi_pin_mode(ANALOG_SENSOR_PORT, INPUT_ANALOG);
* }
* \endcode
*/
int32_t adi_pin_mode(uint8_t port, uint8_t mode);
/**
* Sets the speed of the motor on the given port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an motor
*
* \param port
* The ADI port to set (from 1-8, 'a'-'h', 'A'-'H')
* \param speed
* The new signed speed; -127 is full reverse and 127 is full forward,
* with 0 being off
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define MOTOR_PORT 1
*
* void opcontrol() {
* adi_motor_set(MOTOR_PORT, 127); // Go full speed forward
* delay(1000);
* adi_motor_set(MOTOR_PORT, 0); // Stop the motor
* }
* \endcode
*/
int32_t adi_motor_set(uint8_t port, int8_t speed);
/**
* Gets the last set speed of the motor on the given port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an motor
*
* \param port
* The ADI port to get (from 1-8, 'a'-'h', 'A'-'H')
*
* \return The last set speed of the motor on the given port
*
* \b Example
* \code
* #define MOTOR_PORT 1
*
* void opcontrol() {
* adi_motor_set(MOTOR_PORT, 127); // Go full speed forward
* printf("Commanded Motor Power: %d\n", adi_motor_get(MOTOR_PORT)); // Will display 127
* delay(1000);
* adi_motor_set(MOTOR_PORT, 0); // Stop the motor
* }
* \endcode
*/
int32_t adi_motor_get(uint8_t port);
/**
* Stops the motor on the given port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an motor
*
* \param port
* The ADI port to set (from 1-8, 'a'-'h', 'A'-'H')
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define MOTOR_PORT 1
*
* void opcontrol() {
* adi_motor_set(MOTOR_PORT, 127); // Go full speed forward
* delay(1000);
* // adi_motor_set(MOTOR_PORT, 0); // Stop the motor
* adi_motor_stop(MOTOR_PORT); // use this instead
* }
* \endcode
*/
int32_t adi_motor_stop(uint8_t port);
/**
* Reference type for an initialized encoder.
*
* This merely contains the port number for the encoder.
*/
typedef int32_t adi_encoder_t;
/**
* Gets the number of ticks recorded by the encoder.
*
* There are 360 ticks in one revolution.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an encoder
*
* \param enc
* The adi_encoder_t object from adi_encoder_init() to read
*
* \return The signed and cumulative number of counts since the last start or
* reset
*
* \b Example
* \code
* #define PORT_TOP 1
* #define PORT_BOTTOM 2
*
* void opcontrol() {
* adi_encoder_t enc = adi_encoder_init(PORT_TOP, PORT_BOTTOM, false);
* while (true) {
* printf("Encoder Value: %d\n", adi_encoder_get(enc));
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_encoder_get(adi_encoder_t enc);
/**
* Creates an encoder object and configures the specified ports accordingly.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an encoder
*
* \param port_top
* The "top" wire from the encoder sensor with the removable cover side
* up. This should be in port 1, 3, 5, or 7 ('A', 'C', 'E', or 'G').
* \param port_bottom
* The "bottom" wire from the encoder sensor
* \param reverse
* If "true", the sensor will count in the opposite direction
*
* \return An adi_encoder_t object to be stored and used for later calls to
* encoder functions
*
* \b Example
* \code
* #define PORT_TOP 1
* #define PORT_BOTTOM 2
*
* void opcontrol() {
* adi_encoder_t enc = adi_encoder_init(PORT_TOP, PORT_BOTTOM, false);
* while (true) {
* printf("Encoder Value: %d\n", adi_encoder_get(enc));
* delay(5);
* }
* }
* \endcode
*/
adi_encoder_t adi_encoder_init(uint8_t port_top, uint8_t port_bottom, bool reverse);
/**
* Sets the encoder value to zero.
*
* It is safe to use this method while an encoder is enabled. It is not
* necessary to call this method before stopping or starting an encoder.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an encoder
*
* \param enc
* The adi_encoder_t object from adi_encoder_init() to reset
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define PORT_TOP 1
* #define PORT_BOTTOM 2
*
* void opcontrol() {
* adi_encoder_t enc = adi_encoder_init(PORT_TOP, PORT_BOTTOM, false);
* delay(1000); // Move the encoder around in this time
* adi_encoder_reset(enc); // The encoder is now zero again
* }
* \endcode
*/
int32_t adi_encoder_reset(adi_encoder_t enc);
/**
* Disables the encoder and voids the configuration on its ports.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an encoder
*
* \param enc
* The adi_encoder_t object from adi_encoder_init() to stop
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define PORT_TOP 1
* #define PORT_BOTTOM 2
*
* void opcontrol() {
* adi_encoder_t enc = adi_encoder_init(PORT_TOP, PORT_BOTTOM, false);
* // Use the encoder
* adi_encoder_shutdown(enc);
* }
* \endcode
*/
int32_t adi_encoder_shutdown(adi_encoder_t enc);
/**
* Reference type for an initialized ultrasonic.
*
* This merely contains the port number for the ultrasonic.
*/
typedef int32_t adi_ultrasonic_t;
/**
* Gets the current ultrasonic sensor value in centimeters.
*
* If no object was found, zero is returned. If the ultrasonic sensor was never
* started, the return value is undefined. Round and fluffy objects can cause
* inaccurate values to be returned.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an ultrasonic
*
* \param ult
* The adi_ultrasonic_t object from adi_ultrasonic_init() to read
*
* \return The distance to the nearest object in m^-4 (10000 indicates 1 meter),
* measured from the sensor's mounting points.
*
* \b Example
* \code
* #define PORT_PING 1
* #define PORT_ECHO 2
*
* void opcontrol() {
* adi_ultrasonic_t ult = adi_ultrasonic_init(PORT_PING, PORT_ECHO);
* while (true) {
* // Print the distance read by the ultrasonic
* printf("Distance: %d\n", adi_ultrasonic_get(ult));
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_ultrasonic_get(adi_ultrasonic_t ult);
/**
* Creates an ultrasonic object and configures the specified ports accordingly.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an ultrasonic
*
* \param port_ping
* The port connected to the orange OUTPUT cable. This should be in port
* 1, 3, 5, or 7 ('A', 'C', 'E', 'G').
* \param port_echo
* The port connected to the yellow INPUT cable. This should be in the
* next highest port following port_ping.
*
* \return An adi_ultrasonic_t object to be stored and used for later calls to
* ultrasonic functions
*
* \b Example
* \code
* #define PORT_PING 1
* #define PORT_ECHO 2
*
* void opcontrol() {
* adi_ultrasonic_t ult = adi_ultrasonic_init(PORT_PING, PORT_ECHO);
* while (true) {
* // Print the distance read by the ultrasonic
* printf("Distance: %d\n", adi_ultrasonic_get(ult));
* delay(5);
* }
* }
* \endcode
*/
adi_ultrasonic_t adi_ultrasonic_init(uint8_t port_ping, uint8_t port_echo);
/**
* Disables the ultrasonic sensor and voids the configuration on its ports.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as an ultrasonic
*
* \param ult
* The adi_ultrasonic_t object from adi_ultrasonic_init() to stop
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define PORT_PING 1
* #define PORT_ECHO 2
*
* void opcontrol() {
* adi_ultrasonic_t ult = adi_ultrasonic_init(PORT_PING, PORT_ECHO);
* while (true) {
* // Print the distance read by the ultrasonic
* printf("Distance: %d\n", adi_ultrasonic_get(ult));
* delay(5);
* }
* adi_ultrasonic_shutdown(ult);
* }
* \endcode
*/
int32_t adi_ultrasonic_shutdown(adi_ultrasonic_t ult);
/**
* Reference type for an initialized gyroscope.
*
* This merely contains the port number for the gyroscope.
*/
typedef int32_t adi_gyro_t;
/**
* Gets the current gyro angle in tenths of a degree. Unless a multiplier is
* applied to the gyro, the return value will be a whole number representing
* the number of degrees of rotation times 10.
*
* There are 360 degrees in a circle, thus the gyro will return 3600 for one
* whole rotation.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a gyro
*
* \param gyro
* The adi_gyro_t object for which the angle will be returned
*
* \return The gyro angle in degrees.
*
* \b Example
* \code
* #define GYRO_PORT 1
* #define GYRO_MULTIPLIER 1 // Standard behavior
*
* void opcontrol() {
* adi_gyro_t gyro = adi_gyro_init(GYRO_PORT, GYRO_MULTIPLIER);
* while (true) {
* // Print the gyro's heading
* printf("Heading: %lf\n", adi_gyro_get(gyro));
* delay(5);
* }
* }
* \endcode
*/
double adi_gyro_get(adi_gyro_t gyro);
/**
* Initializes a gyroscope on the given port. If the given port has not
* previously been configured as a gyro, then this function starts a 1300 ms
* calibration period.
*
* It is highly recommended that this function be called from initialize() when
* the robot is stationary to ensure proper calibration.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a gyro
*
* \param port
* The ADI port to initialize as a gyro (from 1-8, 'a'-'h', 'A'-'H')
* \param multiplier
* A scalar value that will be multiplied by the gyro heading value
* supplied by the ADI
*
* \return An adi_gyro_t object containing the given port, or PROS_ERR if the
* initialization failed.
*
* \b Example
* \code
* #define GYRO_PORT 1
* #define GYRO_MULTIPLIER 1 // Standard behavior
*
* void opcontrol() {
* adi_gyro_t gyro = adi_gyro_init(GYRO_PORT, GYRO_MULTIPLIER);
* while (true) {
* // Print the gyro's heading
* printf("Heading: %lf\n", adi_gyro_get(gyro));
* delay(5);
* }
* }
* \endcode
*/
adi_gyro_t adi_gyro_init(uint8_t port, double multiplier);
/**
* Resets the gyroscope value to zero.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a gyro
*
* \param gyro
* The adi_gyro_t object for which the angle will be returned
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define GYRO_PORT 1
* #define GYRO_MULTIPLIER 1 // Standard behavior
*
* void opcontrol() {
* adi_gyro_t gyro = adi_gyro_init(GYRO_PORT, GYRO_MULTIPLIER);
* uint32_t now = millis();
* while (true) {
* // Print the gyro's heading
* printf("Heading: %lf\n", adi_gyro_get(gyro));
*
* if (millis() - now > 2000) {
* // Reset the gyro every 2 seconds
* adi_gyro_reset(gyro);
* now = millis();
* }
*
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_gyro_reset(adi_gyro_t gyro);
/**
* Disables the gyro and voids the configuration on its port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a gyro
*
* \param gyro
* The adi_gyro_t object to be shut down
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define GYRO_PORT 1
* #define GYRO_MULTIPLIER 1 // Standard behavior
*
* void opcontrol() {
* adi_gyro_t gyro = adi_gyro_init(GYRO_PORT, GYRO_MULTIPLIER);
* uint32_t now = millis();
* while (true) {
* // Print the gyro's heading
* printf("Heading: %lf\n", adi_gyro_get(gyro));
*
* if (millis() - now > 2000) {
* adi_gyro_shutdown(gyro);
* // Shut down the gyro after two seconds
* break;
* }
*
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_gyro_shutdown(adi_gyro_t gyro);
/**
* Reference type for an initialized potentiometer.
*
* This merely contains the port number for the potentiometer.
*/
typedef int32_t adi_potentiometer_t;
/**
* Initializes a potentiometer on the given port of the original potentiometer.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a potentiometer
*
* \param port
* The ADI port to initialize as a gyro (from 1-8, 'a'-'h', 'A'-'H')
*
* \return An adi_potentiometer_t object containing the given port, or PROS_ERR if the
* initialization failed.
*
* \b Example
* \code
* #define POTENTIOMETER_PORT 1
*
* void opcontrol() {
* adi_potentiometer_t potentiometer = adi_potentiometer_init(POTENTIOMETER_PORT);
* while (true) {
* // Print the potentiometer's angle
* printf("Angle: %lf\n", adi_potentiometer_get_angle(potentiometer));
* delay(5);
* }
* }
* \endcode
*/
adi_potentiometer_t adi_potentiometer_init(uint8_t port);
/**
* Initializes a potentiometer on the given port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a potentiometer
*
* \param port
* The ADI port to initialize as a gyro (from 1-8, 'a'-'h', 'A'-'H')
* \param potentiometer_type
* An adi_potentiometer_type_e_t enum value specifying the potentiometer version type
*
* \return An adi_potentiometer_t object containing the given port, or PROS_ERR if the
* initialization failed.
*
* \b Example
* \code
* #define POTENTIOMETER_PORT 1
* #define POTENTIOMETER_TYPE E_ADI_POT_EDR
*
* void opcontrol() {
* adi_potentiometer_t potentiometer = adi_potentiometer_type_init(POTENTIOMETER_PORT, POTENTIOMETER_TYPE);
* while (true) {
* // Print the potentiometer's angle
* printf("Angle: %lf\n", adi_potentiometer_get_angle(potentiometer));
* delay(5);
* }
* }
* \endcode
*/
adi_potentiometer_t adi_potentiometer_type_init(uint8_t port, adi_potentiometer_type_e_t potentiometer_type);
/**
* Gets the current potentiometer angle in tenths of a degree.
*
* The original potentiometer rotates 250 degrees thus returning an angle between 0-250 degrees.
* Potentiometer V2 rotates 330 degrees thus returning an angle between 0-330 degrees.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EADDRINUSE - The port is not configured as a potentiometer
*
* \param potentiometer
* The adi_potentiometer_t object for which the angle will be returned
*
* \return The potentiometer angle in degrees.
*
* \b Example
* \code
* #define POTENTIOMETER_PORT 1
*
* void opcontrol() {
* adi_potentiometer_t potentiometer = adi_potentiometer_t(POTENTIOMETER_PORT);
* while (true) {
* // Print the potnetiometer's angle
* printf("Angle: %lf\n", adi_potentiometer_get_angle(potentiometer));
* delay(5);
* }
* }
* \endcode
*/
double adi_potentiometer_get_angle(adi_potentiometer_t potentiometer);
/**
* Reference type for an initialized addressable led.
*
* This merely contains the port number for the led, unlike its use as an
* object to store led data in the C++ API.
*/
typedef int32_t adi_led_t;
/**
* Initializes a led on the given port of the original led.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EINVAL - The ADI port given is not a valid port as defined below
* EADDRINUSE - The port is not configured for ADI output
*
* \param port
* The ADI port to initialize as a led (from 1-8, 'a'-'h', 'A'-'H')
*
* \return An adi_led_t object containing the given port, or PROS_ERR if the
* initialization failed, setting errno
*
* \b Example
* \code
* #define LED_PORT 1
*
* void opcontrol() {
* adi_led_t led = adi_led_init(LED_PORT);
* uint32_t buffer[10] = {0xFF0000, 0x00FF00, 0x0000FF, 0xFFFF00, 0x00FFFF, 0xFF00FF, 0xFFFFFF, 0x000000, 0x000000, 0x000000};
* while (true) {
* // Set the led to the colors in the buffer
* adi_led_set(led, buffer, 10);
* delay(5);
* }
* }
* \endcode
*/
adi_led_t adi_led_init(uint8_t port);
/**
* @brief Clear the entire led strip of color
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EINVAL - A given value is not correct, or the buffer is null
* EADDRINUSE - The port is not configured for ADI output
*
* @param led port of type adi_led_t
* @param buffer array of colors in format 0xRRGGBB, recommended that individual RGB value not to exceed 0x80 due to current draw
* @param buffer_length length of buffer to clear
* @return PROS_SUCCESS if successful, PROS_ERR if not
*
* \b Example
* \code
* #define LED_PORT 1
*
* void opcontrol() {
* adi_led_t led = adi_led_init(LED_PORT);
* uint32_t buffer[10] = {0xFF0000, 0x00FF00, 0x0000FF, 0xFFFF00, 0x00FFFF, 0xFF00FF, 0xFFFFFF, 0x000000, 0x000000, 0x000000};
* while (true) {
* // Set the led to the colors in the buffer
* adi_led_set(led, buffer, 10);
* delay(5);
*
* // Clear the led strip
* adi_led_clear(led);
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_led_clear_all(adi_led_t led, uint32_t* buffer, uint32_t buffer_length);
/**
* @brief Set the entire led strip using the colors contained in the buffer
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EINVAL - A given value is not correct, or the buffer is null
* EADDRINUSE - The port is not configured for ADI output
*
* @param led port of type adi_led_t
* @param buffer array of colors in format 0xRRGGBB, recommended that individual RGB value not to exceed 0x80 due to current draw
* @param buffer_length length of buffer to clear
* @return PROS_SUCCESS if successful, PROS_ERR if not
*
* \b Example
* \code
* #define LED_PORT 1
*
* void opcontrol() {
* adi_led_t led = adi_led_init(LED_PORT);
* uint32_t buffer[10] = {0xFF0000, 0x00FF00, 0x0000FF, 0xFFFF00, 0x00FFFF, 0xFF00FF, 0xFFFFFF, 0x000000, 0x000000, 0x000000};
* while (true) {
* // Set the led strip to the colors in the buffer
* adi_led_set(led, buffer, 10);
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_led_set(adi_led_t led, uint32_t* buffer, uint32_t buffer_length);
/**
* @brief Set the entire led strip to one color
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EINVAL - A given value is not correct, or the buffer is null
* EADDRINUSE - The port is not configured for ADI output
*
* @param led port of type adi_led_t
* @param buffer array of colors in format 0xRRGGBB, recommended that individual RGB value not to exceed 0x80 due to current draw
* @param buffer_length length of buffer to clear
* @param color color to set all the led strip value to
* @return PROS_SUCCESS if successful, PROS_ERR if not
*
* \b Example
* \code
* #define LED_PORT 1
*
* void opcontrol() {
* adi_led_t led = adi_led_init(LED_PORT);
* uint32_t buffer[10] = {0xFF0000, 0x00FF00, 0x0000FF, 0xFFFF00, 0x00FFFF, 0xFF00FF, 0xFFFFFF, 0x000000, 0x000000, 0x000000};
* while (true) {
* // Set the led strip to red
* adi_led_set_all(led, buffer, 10, 0xFF0000);
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_led_set_all(adi_led_t led, uint32_t* buffer, uint32_t buffer_length, uint32_t color);
/**
* @brief Set one pixel on the led strip
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EINVAL - A given value is not correct, or the buffer is null
* EADDRINUSE - The port is not configured for ADI output
*
* @param led port of type adi_led_t
* @param buffer array of colors in format 0xRRGGBB, recommended that individual RGB value not to exceed 0x80 due to current draw
* @param buffer_length length of the input buffer
* @param color color to clear all the led strip to
* @param pixel_position position of the pixel to clear
* @return PROS_SUCCESS if successful, PROS_ERR if not
*
* \b Example
* \code
* #define LED_PORT 1
*
* void opcontrol() {
* adi_led_t led = adi_led_init(LED_PORT);
* uint32_t buffer[10] = {0xFF0000, 0x00FF00, 0x0000FF, 0xFFFF00, 0x00FFFF, 0xFF00FF, 0xFFFFFF, 0x000000, 0x000000, 0x000000};
* while (true) {
* // Set the first pixel to red
* adi_led_set_pixel(led, buffer, 10, 0xFF0000, 0);
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_led_set_pixel(adi_led_t led, uint32_t* buffer, uint32_t buffer_length, uint32_t color, uint32_t pixel_position);
/**
* @brief Clear one pixel on the led strip
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - The given value is not within the range of ADI Ports
* EINVAL - A given value is not correct, or the buffer is null
* EADDRINUSE - The port is not configured for ADI output
*
* @param led port of type adi_led_t
* @param buffer array of colors in format 0xRRGGBB, recommended that individual RGB value not to exceed 0x80 due to current draw
* @param buffer_length length of the input buffer
* @param pixel_position position of the pixel to clear
* @return PROS_SUCCESS if successful, PROS_ERR if not
*
* \b Example
* \code
* #define LED_PORT 1
*
* void opcontrol() {
* adi_led_t led = adi_led_init(LED_PORT);
* uint32_t buffer[10] = {0xFF0000, 0x00FF00, 0x0000FF, 0xFFFF00, 0x00FFFF, 0xFF00FF, 0xFFFFFF, 0x000000, 0x000000, 0x000000};
* while (true) {
* // Set the first pixel to red
* adi_led_set_pixel(led, buffer, 10, 0xFF0000, 0);
* delay(5);
*
* // Clear the first pixel
* adi_led_clear_pixel(led, buffer, 10, 0);
* delay(5);
* }
* }
* \endcode
*/
int32_t adi_led_clear_pixel(adi_led_t led, uint32_t* buffer, uint32_t buffer_length, uint32_t pixel_position);
/**
* \name Ease of use macro definitions
* These functions provide ease of use definitions for the ADI functions.
* @{
*/
/**
* Used for adi_digital_write() to specify a logic HIGH state to output.
*
* In reality, using any non-zero expression or "true" will work to set a pin to
* HIGH.
*/
#define HIGH 1
/**
* Used for adi_digital_write() to specify a logic LOW state to output.
*
* In reality, using a zero expression or "false" will work to set a pin to LOW.
*/
#define LOW 0
/**
* adi_pin_mode() state for a digital input.
*/
#define INPUT 0x00
/**
* adi_pin_mode() state for a digital output.
*/
#define OUTPUT 0x01
/**
* adi_pin_mode() state for an analog input.
*/
#define INPUT_ANALOG 0x02
/**
* adi_pin_mode() state for an analog output.
*/
#define OUTPUT_ANALOG 0x03
/** @} Name: Ease of use macro definitions*/
/** @} Add to group: c-adi*/
#ifdef __cplusplus
} // namespace c
} // namespace pros
}
#endif
#endif // _PROS_ADI_H_
================================================
FILE: include/pros/adi.hpp
================================================
/**
* \file pros/adi.hpp
* \ingroup cpp-adi
*
* Contains prototypes for interfacing with the ADI.
*
* This file should not be modified by users, since it gets replaced whenever
* a kernel upgrade occurs.
*
* \Copyright (c) 2017-2026, Purdue University ACM SIGBots.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at http://mozilla.org/MPL/2.0/.
*
* \defgroup cpp-adi ADI (TriPort) C++ API
* \note The external ADI API can be found [here.](@ref ext-adi)
* \note Additional example code for this module can be found in its [Tutorial.](@ref adi)
*/
#ifndef _PROS_ADI_HPP_
#define _PROS_ADI_HPP_
#include <cstdint>
#include <iostream>
#include <tuple>
#include <utility>
#include <vector>
#include "pros/adi.h"
#define LEGACY_TYPEDEF(old_name, new_name) using old_name [[deprecated("use " #new_name " instead")]] = new_name
namespace pros {
namespace adi {
/** type definition for the pair of smart port and adi port for the basic adi devices */
using ext_adi_port_pair_t = std::pair<std::uint8_t, std::uint8_t>;
/** type definition for the triplet of smart port and two adi ports for the two wire adi devices*/
using ext_adi_port_tuple_t = std::tuple<std::uint8_t, std::uint8_t, std::uint8_t>;
/**
* \ingroup cpp-adi
*/
class Port {
/**
* \addtogroup cpp-adi
* @{
*/
public:
/**
* Configures an ADI port to act as a given sensor type.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param adi_port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
* \param type
* The configuration type for the port
*
* \b Example
* \code
* #define POTENTIOMETER_PORT 1
* #define POTENTIOMETER_TYPE pros::E_ADI_POT_EDR
*
* void opcontrol() {
* pros::ADIPotentiometer potentiometer (POTENTIOMETER_PORT, POTENTIOMETER_TYPE);
* while (true) {
* // Get the potentiometer angle
* std::cout << "Angle: " << potnetiometer.get_angle();
* pros::delay(10);
* }
* }
* \endcode
*/
explicit Port(std::uint8_t adi_port, adi_port_config_e_t type = E_ADI_TYPE_UNDEFINED);
/**
* Configures an ADI port on an adi expander to act as a given sensor type.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param port_pair
* The pair of the smart port number (from 1-22) and the ADI port number
* (from 1-8, 'a'-'h', 'A'-'H') to configure
* \param type
* The configuration type for the port
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 'a'
* #define EXT_ADI_SMART_PORT 1
*
* void initialize() {
* pros::adi::Port sensor ({EXT_ADI_SMART_PORT, ANALOG_SENSOR_PORT}, E_ADI_ANALOG_IN);
* // Displays the value of E_ADI_ANALOG_IN
* std::cout << "Port Type: " << sensor.get_config();
* }
* \endcode
*/
explicit Port(ext_adi_port_pair_t port_pair, adi_port_config_e_t type = E_ADI_TYPE_UNDEFINED);
/**
* Gets the configuration for the given ADI port.
*
* \return The ADI configuration for the given port
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
* void initialize() {
* adi_port_set_config(ANALOG_SENSOR_PORT, E_ADI_ANALOG_IN);
* // Displays the value of E_ADI_ANALOG_IN
* printf("Port Type: %d\n", adi_port_get_config(ANALOG_SENSOR_PORT));
* }
* \endcode
*/
std::int32_t get_config() const;
/**
* Gets the value for the given ADI port.
*
* \return The value stored for the given port
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void opcontrol() {
* pros::adi::Port sensor (ANALOG_SENSOR_PORT, E_ADI_ANALOG_IN);
* std::cout << "Port Value: " << sensor.get_value();
* }
* \endcode
*/
std::int32_t get_value() const;
/**
* Configures an ADI port to act as a given sensor type.
*
* \param type
* The configuration type for the port
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void initialize() {
* pros::adi::Port sensor (ANALOG_SENSOR_PORT, E_ADI_DIGITAL_IN);
* // Do things as a digital sensor
* // Digital is unplugged and an analog is plugged in
* sensor.set_config(E_ADI_ANALOG_IN);
* }
* \endcode
*/
std::int32_t set_config(adi_port_config_e_t type) const;
/**
* Sets the value for the given ADI port.
*
* This only works on ports configured as outputs, and the behavior will
* change depending on the configuration of the port.
*
* \param value
* The value to set the ADI port to
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1
*
* void initialize() {
* pros::adi::Port sensor (DIGITAL_SENSOR_PORT, E_ADI_DIGITAL_OUT);
* sensor.set_value(DIGITAL_SENSOR_PORT, HIGH);
* }
* \endcode
*/
std::int32_t set_value(std::int32_t value) const;
/**
* Gets the port of the sensor.
*
* \return returns a tuple of integer ports.
*
* \note The parts of the tuple are {smart port, adi port, second adi port (when applicable)}.
*
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1 // 'A'
*
* void initialize() {
* pros::adi::AnalogIn sensor (DIGITAL_SENSOR_PORT);
*
* // Getting values from the tuple using std::get<index>
* int sensorSmartPort = std::get<0>(sensor.get_port()); // First value
* int sensorAdiPort = std::get<1>(sensor.get_port()); // Second value
*
* // Prints the first and second value from the port tuple (The Adi Port. The first value is the Smart Port)
* printf("Sensor Smart Port: %d\n", sensorSmartPort);
* printf("Sensor Adi Port: %d\n", sensorAdiPort);
* }
* \endcode
*/
virtual ext_adi_port_tuple_t get_port() const;
protected:
std::uint8_t _smart_port;
std::uint8_t _adi_port;
};
///@}
class AnalogIn : protected Port {
/**
* \addtogroup cpp-adi
* @{
*/
public:
/**
* Configures an ADI port to act as an Analog Input.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param adi_port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void opcontrol() {
* pros::ADIAnalogIn sensor (ANALOG_SENSOR_PORT);
* while (true) {
* // Use the sensor
* }
* }
* \endcode
*/
explicit AnalogIn(std::uint8_t adi_port);
/**
* Configures an ADI port to act as an Analog Input.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param adi_port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define EXT_ADI_SENSOR_PORT 1
* #define ADI_PORT 'a'
*
* void opcontrol() {
* pros::ADIAnalogIn sensor ({EXT_ADI_SMART_PORT, ADI_PORT});
* while (true) {
* // Use the sensor
* }
* }
* \endcode
*/
explicit AnalogIn(ext_adi_port_pair_t port_pair);
/**
* Calibrates the analog sensor on the specified port and returns the new
* calibration value.
*
* This method assumes that the true sensor value is not actively changing at
* this time and computes an average from approximately 500 samples, 1 ms
* apart, for a 0.5 s period of calibration. The average value thus calculated
* is returned and stored for later calls to the
* pros::AnalogIn::get_value_calibrated() and
* pros::AnalogIn::get_value_calibrated_HR() functions. These functions
* will return the difference between this value and the current sensor value
* when called.
*
* Do not use this function when the sensor value might be unstable (gyro
* rotation, accelerometer movement).
*
* \note The ADI currently returns data at 10ms intervals, in contrast to the
* calibrate function’s 1ms sample rate.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port is not configured as an analog input
*
* \return The average sensor value computed by this function
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void initialize() {
* pros::adi::AnalogIn sensor (ANALOG_SENSOR_PORT);
* sensor.calibrate(ANALOG_SENSOR_PORT);
* std::cout << "Calibrated Reading:" << sensor.get_value_calibrated();
* // All readings from then on will be calibrated
* }
* \endcode
*/
std::int32_t calibrate() const;
/**
* Gets the 12 bit calibrated value of an analog input port.
*
* The pros::adi::AnalogIn::calibrate() function must be run first. This
* function is inappropriate for sensor values intended for integration, as
* round-off error can accumulate causing drift over time. Use
* pros::adi::AnalogIn::get_value_calibrated_HR() instead.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port is not configured as an analog input
*
* \return The difference of the sensor value from its calibrated default from
* -4095 to 4095
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void initialize() {
* pros::adi::AnalogIn sensor (ANALOG_SENSOR_PORT);
* sensor.calibrate(ANALOG_SENSOR_PORT);
* std::cout << "Calibrated Reading:" << sensor.get_value_calibrated();
* // All readings from then on will be calibrated
* }
* \endcode
*/
std::int32_t get_value_calibrated() const;
/**
* Gets the 16 bit calibrated value of an analog input port.
*
* The pros::adi::AnalogIn::calibrate() function must be run first. This is
* intended for integrated sensor values such as gyros and accelerometers to
* reduce drift due to round-off, and should not be used on a sensor such as a
* line tracker or potentiometer.
*
* The value returned actually has 16 bits of "precision", even though the ADC
* only reads 12 bits, so that error induced by the average value being
* between two values when integrated over time is trivial. Think of the value
* as the true value times 16.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port is not configured as an analog input
*
* \return The difference of the sensor value from its calibrated default from
* -16384 to 16384
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void initialize() {
* pros::adi::AnalogIn sensor (ANALOG_SENSOR_PORT);
* sensor.calibrate(ANALOG_SENSOR_PORT);
* std::cout << "Calibrated Reading:" << sensor.get_value_calibrated();
* // All readings from then on will be calibrated
* }
* \endcode
*/
std::int32_t get_value_calibrated_HR() const;
/**
* Reads an analog input channel and returns the 12-bit value.
*
* The value returned is undefined if the analog pin has been switched to a different mode. The meaning of the
* returned value varies depending on the sensor attached.
*
* Inherited from ADIPort::get_value.
*
* This function uses the following values of errno when an error state is reached:
* EADDRINUSE - The port is not configured as an analog input (e.g. the port has been reconfigured)
*
* \return The analog sensor value, where a value of 0 reflects an input
* voltage of nearly 0 V and a value of 4095 reflects an input voltage of
* nearly 5 V
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void initialize() {
* pros::adi::AnalogIn sensor (ANALOG_SENSOR_PORT);
* std::cout << "Sensor Reading:" << sensor.get_value();
* }
* \endcode
*/
using Port::get_value;
/**
* This is the overload for the << operator for printing to streams
*
* Prints in format(this below is all in one line with no new line):
* AnalogIn [smart_port: analog_in._smart_port, adi_port: analog_in._adi_port,
* value calibrated: (12 bit calibrated value),
* value calibrated HR: (16 bit calibrated value), value: (12 bit value)]
*/
friend std::ostream& operator<<(std::ostream& os, pros::adi::AnalogIn& analog_in);
using Port::get_port;
};
///@}
// using ADIPotentiometer = ADIAnalogIn;
using LineSensor = AnalogIn;
using LightSensor = AnalogIn;
using Accelerometer = AnalogIn;
class AnalogOut : private Port {
/**
* \addtogroup cpp-adi
* @{
*/
public:
/**
* Configures an ADI port to act as an Analog Output.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param adi_port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void opcontrol() {
* pros::AnalogOut sensor (ANALOG_SENSOR_PORT);
* // Use the sensor
* }
* @endcode
*/
explicit AnalogOut(std::uint8_t adi_port);
/**
* Configures an ADI port on an adi_expander to act as an Analog Output.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param port_pair
* The pair of the smart port number (from 1-22) and the
* ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
*
* \b Example
* \code
* #define EXT_ADI_SMART_PORT 1
* #define ADI_PORT 'a'
*
* void opcontrol() {
* pros::AnalogOut sensor ({EXT_ADI_SMART_PORT, ADI_PORT});
* // Use the sensor
* }
* \endcode
*/
explicit AnalogOut(ext_adi_port_pair_t port_pair);
/**
* Sets the output for the Analog Output from 0 (0V) to 4095 (5V).
*
* Inherited from ADIPort::set_value.
*
* This function uses the following values of errno when an error state is reached:
* EACCES - Another resource is currently trying to access the ADI.
*
* \param value
* The value to set the ADI port to
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define ANALOG_SENSOR_PORT 1
*
* void opcontrol() {
* pros::AnalogOut sensor (ANALOG_SENSOR_PORT);
* sensor.set_value(4095); // Set the port to 5V
* }
* \endcode
*/
using Port::set_value;
using Port::get_port;
/**
* This is the overload for the << operator for printing to streams
*
* Prints in format(this below is all in one line with no new line):
* AnalogOut [smart_port: analog_out._smart_port, adi_port: analog_out._adi_port,
* value: (value)]
*/
friend std::ostream& operator<<(std::ostream& os, pros::adi::AnalogOut& analog_out);
};
///@}
class DigitalOut : private Port {
/**
* \addtogroup cpp-adi
* @{
*/
public:
/**
* Configures an ADI port to act as a Digital Output.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param adi_port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
* \param init_state
* The initial state for the port
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1
*
* void opcontrol() {
* bool state = LOW;
* pros::adi::DigitalOut sensor (DIGITAL_SENSOR_PORT, state);
* while (true) {
* state != state;
* sensor.set_value(state);
* pros::delay(10); // toggle the sensor value every 50ms
* }
* }
* \endcode
*/
explicit DigitalOut(std::uint8_t adi_port, bool init_state = LOW);
/**
* Configures an ADI port on an adi_expander to act as a Digital Output.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param port_pair
* The pair of the smart port number (from 1-22) and the
* ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
* \param init_state
* The initial state for the port
*
* \b Example
* \code
* #define EXT_ADI_SMART_PORT 1
* #define ADI_PORT 'a'
*
* void opcontrol() {
* bool state = LOW;
* pros::adi::DigitalOut sensor ({EXT_ADI_SMART_PORT , ADI_PORT});
* while (true) {
* state != state;
* sensor.set_value(state);
* pros::delay(10); // toggle the sensor value every 50ms
* }
* }
* \endcode
*/
explicit DigitalOut(ext_adi_port_pair_t port_pair, bool init_state = LOW);
/**
* Sets the digital value (1 or 0) of a pin.
*
* Inherited from ADIPort::set_value.
*
* This function uses the following values of errno when an error state is
* reached:
* EADDRINUSE - The port is not configured as a digital output (e.g. the port has been reconfigured)
*
* \param value
* The value to set the ADI port to
*
* \return if the operation was successful or PROS_ERR if the operation failed, setting errno.
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1
*
* void opcontrol() {
* bool state = LOW;
* pros::adi::DigitalOut sensor (DIGITAL_SENSOR_PORT);
* while (true) {
* state != state;
* sensor.set_value(state);
* pros::delay(10); // toggle the sensor value every 50ms
* }
* }
* \endcode
*/
using Port::set_value;
using Port::get_port;
/**
* This is the overload for the << operator for printing to streams
*
* Prints in format(this below is all in one line with no new line):
* DigitalOut [smart_port: digital_out._smart_port, adi_port: digital_out._adi_port,
* value: (value)]
*/
friend std::ostream& operator<<(std::ostream& os, pros::adi::DigitalOut& digital_out);
};
///@}
class DigitalIn : private Port {
/**
* \addtogroup cpp-adi
* @{
*/
public:
/**
* Configures an ADI port to act as a Digital Input.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param adi_port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1
*
* void opcontrol() {
* pros::adi::DigitalIn sensor (ANALOG_SENSOR_PORT);
* // Use the sensor
* }
* \endcode
*/
explicit DigitalIn(std::uint8_t adi_port);
/**
* Configures an ADI port on an adi_expander to act as a Digital Input.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param port_pair
* The pair of the smart port number (from 1-22) and the
* ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
*
* \b Example
* \code
* #define EXT_ADI_SMART_PORT 1
* #define ADI_PORT 'a'
*
* void opcontrol() {
* pros::adi::DigitalIn sensor ({EXT_ADI_SMART_PORT, ADI_PORT});
* // Use the sensor
* }
* \endcode
*/
explicit DigitalIn(ext_adi_port_pair_t port_pair);
/**
* Gets a rising-edge case for a digital button press.
*
* This function is not thread-safe.
* Multiple tasks polling a single button may return different results under
* the same circumstances, so only one task should call this function for any
* given button. E.g., Task A calls this function for buttons 1 and 2. Task B
* may call this function for button 3, but should not for buttons 1 or 2. A
* typical use-case for this function is to call inside opcontrol to detect
* new button presses, and not in any other tasks.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port is not configured as a digital input
*
* \return 1 if the button is pressed and had not been pressed the last time
* this function was called, 0 otherwise.
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1
*
* void opcontrol() {
* pros::adi::DigitalIn sensor (DIGITAL_SENSOR_PORT);
* while (true) {
* if (sensor.get_new_press()) {
* // Toggle pneumatics or other state operations
* }
* pros::delay(10);
* }
* }
* \endcode
*/
std::int32_t get_new_press() const;
/**
* Gets the digital value (1 or 0) of a pin.
*
* Inherited from ADIPort::get_value.
*
* This function uses the following values of errno when an error state is reached:
*
* EADDRINUSE - The port is not configured as a digital input (e.g. the port has been reconfigured)
*
* Analogous to adi_digital_read.
*
* \return The value stored for the given port
*
* \b Example
* \code
* #define DIGITAL_SENSOR_PORT 1
*
* void opcontrol() {
* pros::adi::DigitalIn sensor (DIGITAL_SENSOR_PORT);
* while (true) {
* std::cout << "Sensor Value:" << sensor.get_value();
* pros::delay(10);
* }
* }
* \endcode
*/
using Port::get_value;
/**
* This is the overload for the << operator for printing to streams
*
* Prints in format(this below is all in one line with no new line):
* DigitalIn [smart_port: digital_in._smart_port, adi_port: digital_in._adi_port,
* value: (value)]
*/
friend std::ostream& operator<<(std::ostream& os, pros::adi::DigitalIn& digital_in);
using Port::get_port;
};
///@}
// Derived Class(es) from DigitalIn
using Button = DigitalIn;
class Motor : private Port {
/**
* \addtogroup cpp-adi
* @{
*/
public:
/**
* Configures an ADI port to act as a Motor.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param adi_port
* The ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
*
* \b Example
* \code
* #define MOTOR_PORT 1
*
* void opcontrol() {
* pros::adi::Motor motor (MOTOR_PORT);
* motor.set_value(127); // Go full speed forward
* std::cout << "Commanded Motor Power: " << motor.get_value(); // Will display 127
* delay(1000);
* motor.set_value(0); // Stop the motor
* }
* \endcode
*/
explicit Motor(std::uint8_t adi_port);
/**
* Configures an ADI port on an adi_expander to act as a Motor.
*
* This function uses the following values of errno when an error state is
* reached:
* ENXIO - Either the ADI port value or the smart port value is not within its
* valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21).
*
* \param port_pair
* The pair of the smart port number (from 1-22) and the
* ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure
*
* \b Example
* \code
* #define EXT_ADI_SMART_PORT 1
* #define ADI_MOTOR_PORT 'a'
*
* void opcontrol() {
* pros::adi::Motor motor ({EXT_ADI_SMART_PORT, ADI_MOTOR_PORT});
* motor.set_value(127); // Go full speed forward
* std::cout << "Commanded Motor Power: " << motor.get_value(); // Will display 127
* delay(1000);
* motor.set_value(0); // Stop the motor
* }
* \endcode
*/
explicit Motor(ext_adi_port_pair_t port_pair);
/**
* Stops the motor on the given port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port is not configured as a motor
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define MOTOR_PORT 1
*
* void opcontrol() {
* pros::adi::Motor motor (MOTOR_PORT);
* motor.set_value(127); // Go full speed forward
* std::cout << "Commanded Motor Power: " << motor.get_value(); // Will display 127
* delay(1000);
* motor.stop(); // Stop the motor
* }
* \endcode
*/
std::int32_t stop() const;
/**
* Sets the speed of the motor on the given port.
*
* This function uses the following values of errno when an error state is
* reached:
* ENODEV - The port is not configured as a motor
*
* \param value
* The new signed speed; -127 is full reverse and 127 is full forward,
* with 0 being off
*
* \return 1 if the operation was successful or PROS_ERR if the operation
* failed, setting errno.
*
* \b Example
* \code
* #define MOTOR_PORT 1
*
* void opcontrol() {
* pros::adi::Motor motor (MOTOR_PORT);
* motor.set_value(127); // Go full speed forward
* std::cout <<
gitextract_74vec5n_/ ├── .arcconfig ├── .arclint ├── .clang-format ├── .github/ │ ├── CONTRIBUTING.md │ ├── ISSUE_TEMPLATE.md │ └── PULL_REQUEST_TEMPLATE.md ├── .gitignore ├── .gitmodules ├── .vs/ │ └── pros/ │ └── v16/ │ └── .suo ├── LICENSE ├── Makefile ├── README.md ├── STYLEGUIDE.md ├── VSCode.md ├── azure-build-libc.yaml ├── azure-pipelines.yml ├── common.mk ├── firmware/ │ ├── libc.a │ ├── libm.a │ ├── v5-common.ld │ ├── v5-hot.ld │ └── v5.ld ├── include/ │ ├── api.h │ ├── common/ │ │ ├── cobs.h │ │ ├── gid.h │ │ ├── linkedlist.h │ │ ├── set.h │ │ └── string.h │ ├── kapi.h │ ├── main.h │ ├── pros/ │ │ ├── abstract_motor.hpp │ │ ├── adi.h │ │ ├── adi.hpp │ │ ├── ai_vision.h │ │ ├── ai_vision.hpp │ │ ├── apix.h │ │ ├── colors.h │ │ ├── colors.hpp │ │ ├── device.h │ │ ├── device.hpp │ │ ├── distance.h │ │ ├── distance.hpp │ │ ├── error.h │ │ ├── ext_adi.h │ │ ├── gps.h │ │ ├── gps.hpp │ │ ├── imu.h │ │ ├── imu.hpp │ │ ├── link.h │ │ ├── link.hpp │ │ ├── llemu.h │ │ ├── llemu.hpp │ │ ├── misc.h │ │ ├── misc.hpp │ │ ├── motor_group.hpp │ │ ├── motors.h │ │ ├── motors.hpp │ │ ├── optical.h │ │ ├── optical.hpp │ │ ├── rotation.h │ │ ├── rotation.hpp │ │ ├── rtos.h │ │ ├── rtos.hpp │ │ ├── screen.h │ │ ├── screen.hpp │ │ ├── serial.h │ │ ├── serial.hpp │ │ ├── version.h │ │ ├── vision.h │ │ └── vision.hpp │ ├── rtos/ │ │ ├── FreeRTOS.h │ │ ├── FreeRTOSConfig.h │ │ ├── StackMacros.h │ │ ├── list.h │ │ ├── message_buffer.h │ │ ├── portable.h │ │ ├── portmacro.h │ │ ├── projdefs.h │ │ ├── queue.h │ │ ├── semphr.h │ │ ├── stack_macros.h │ │ ├── stream_buffer.h │ │ ├── task.h │ │ ├── tcb.h │ │ └── timers.h │ ├── system/ │ │ ├── dev/ │ │ │ ├── banners.h │ │ │ ├── dev.h │ │ │ ├── ser.h │ │ │ ├── usd.h │ │ │ └── vfs.h │ │ ├── hot.h │ │ ├── optimizers.h │ │ ├── user_functions/ │ │ │ ├── c_list.h │ │ │ ├── cpp_list.h │ │ │ └── list.h │ │ └── user_functions.h │ └── vdml/ │ ├── port.h │ ├── registry.h │ └── vdml.h ├── libv5rts-strip-options.txt ├── patch_headers.py ├── project.pros ├── public_symbols.txt ├── src/ │ ├── common/ │ │ ├── README.md │ │ ├── cobs.c │ │ ├── gid.c │ │ ├── linkedlist.c │ │ ├── set.c │ │ └── string.c │ ├── devices/ │ │ ├── README.md │ │ ├── battery.c │ │ ├── battery.cpp │ │ ├── controller.c │ │ ├── controller.cpp │ │ ├── registry.c │ │ ├── screen.c │ │ ├── screen.cpp │ │ ├── vdml.c │ │ ├── vdml_adi.c │ │ ├── vdml_adi.cpp │ │ ├── vdml_ai_vision.c │ │ ├── vdml_ai_vision.cpp │ │ ├── vdml_device.c │ │ ├── vdml_device.cpp │ │ ├── vdml_distance.c │ │ ├── vdml_distance.cpp │ │ ├── vdml_ext_adi.c │ │ ├── vdml_gps.c │ │ ├── vdml_gps.cpp │ │ ├── vdml_imu.c │ │ ├── vdml_imu.cpp │ │ ├── vdml_link.c │ │ ├── vdml_link.cpp │ │ ├── vdml_motorgroup.cpp │ │ ├── vdml_motors.c │ │ ├── vdml_motors.cpp │ │ ├── vdml_optical.c │ │ ├── vdml_optical.cpp │ │ ├── vdml_rotation.c │ │ ├── vdml_rotation.cpp │ │ ├── vdml_serial.c │ │ ├── vdml_serial.cpp │ │ ├── vdml_usd.c │ │ ├── vdml_usd.cpp │ │ ├── vdml_vision.c │ │ └── vdml_vision.cpp │ ├── main.cpp │ ├── rtos/ │ │ ├── LICENSE │ │ ├── README.md │ │ ├── heap_4.c │ │ ├── list.c │ │ ├── port.c │ │ ├── portASM.S │ │ ├── portmacro.h │ │ ├── queue.c │ │ ├── refactor.sh │ │ ├── refactor.tsv │ │ ├── rtos.cpp │ │ ├── semphr.c │ │ ├── stream_buffer.c │ │ ├── task_notify_when_deleting.c │ │ ├── tasks.c │ │ └── timers.c │ ├── system/ │ │ ├── cpp_support.cpp │ │ ├── dev/ │ │ │ ├── dev_driver.c │ │ │ ├── file_system_stubs.c │ │ │ ├── ser_daemon.c │ │ │ ├── ser_driver.c │ │ │ ├── usd_driver.c │ │ │ └── vfs.c │ │ ├── envlock.c │ │ ├── hot.c │ │ ├── mlock.c │ │ ├── newlib_stubs.c │ │ ├── newlib_stubs_support.cpp │ │ ├── rtos_hooks.c │ │ ├── startup.c │ │ ├── system_daemon.c │ │ ├── unwind.c │ │ ├── user_functions.c │ │ └── xilinx_vectors.s │ └── tests/ │ ├── adi.cpp │ ├── basic_test.c │ ├── basic_test.cpp │ ├── errno_reentrancy.c │ ├── exceptions.cpp │ ├── ext_adi.cpp │ ├── generic_serial.cpp │ ├── generic_serial_file.cpp │ ├── gyro.c │ ├── gyro.cpp │ ├── mutexes.c │ ├── pnuematics.cpp │ ├── rtos_function_linking.c │ ├── segfault.cpp │ ├── simple_names.c │ ├── simple_names.cpp │ ├── static_tast_states.c │ ├── task_notify_when_deleting.c │ └── vision_test.cpp ├── template-Makefile ├── template-gitignore ├── verify-symbols.sh └── version.py
SYMBOL INDEX (1171 symbols across 145 files)
FILE: include/common/gid.h
type gid_metadata (line 21) | struct gid_metadata {
type gid_metadata (line 50) | struct gid_metadata
type gid_metadata (line 60) | struct gid_metadata
type gid_metadata (line 70) | struct gid_metadata
type gid_metadata (line 83) | struct gid_metadata
FILE: include/common/linkedlist.h
type ll_node_s_t (line 20) | typedef struct ll_node_s {
type linked_list_s_t (line 28) | typedef struct {
FILE: include/common/set.h
type set (line 23) | struct set {
type set (line 37) | struct set
type set (line 49) | struct set
type set (line 61) | struct set
type set (line 73) | struct set
FILE: include/kapi.h
type task_stack_t (line 54) | typedef uint32_t task_stack_t;
FILE: include/pros/abstract_motor.hpp
type pros (line 30) | namespace pros {
type v5 (line 31) | inline namespace v5 {
type MotorBrake (line 37) | enum class MotorBrake {
type MotorEncoderUnits (line 48) | enum class MotorEncoderUnits {
type MotorGears (line 59) | enum class MotorGears {
type MotorType (line 76) | enum class MotorType {
class AbstractMotor (line 92) | class AbstractMotor {
FILE: include/pros/adi.h
type adi_port_config_e_t (line 48) | typedef enum adi_port_config_e {
type adi_potentiometer_type_e_t (line 89) | typedef enum adi_potentiometer_type_e {
function namespace (line 140) | namespace c {
FILE: include/pros/adi.hpp
type pros (line 34) | namespace pros {
type adi (line 35) | namespace adi {
class Port (line 46) | class Port {
class AnalogIn (line 225) | class AnalogIn : protected Port {
class AnalogOut (line 437) | class AnalogOut : private Port {
class DigitalOut (line 530) | class DigitalOut : private Port {
class DigitalIn (line 642) | class DigitalIn : private Port {
class Motor (line 776) | class Motor : private Port {
class Encoder (line 919) | class Encoder : private Port {
class Ultrasonic (line 1052) | class Ultrasonic : private Port {
class Gyro (line 1158) | class Gyro : private Port {
class Potentiometer (line 1311) | class Potentiometer : public AnalogIn {
class Led (line 1473) | class Led : protected Port {
class Pneumatics (line 1770) | class Pneumatics : public DigitalOut {
FILE: include/pros/ai_vision.h
type aivision_detected_type_e_t (line 57) | typedef enum aivision_detected_type {
type aivision_mode_type_e_t (line 70) | typedef enum aivision_mode_type {
type aivision_color_s_t (line 85) | typedef struct aivision_color_s {
type aivision_code_s_t (line 102) | typedef struct aivision_code_s {
type aivision_tag_family_e_t (line 117) | typedef enum aivision_tag_family_e {
type aivision_object_color_s_t (line 128) | typedef struct __attribute__((packed)) aivision_object_color_s {
type aivision_object_tag_s_t (line 140) | typedef struct __attribute__((packed)) aivision_object_tag_s {
type aivision_object_element_s_t (line 151) | typedef struct __attribute__((packed)) aivision_object_element_s {
type aivision_object_s_t (line 167) | typedef struct __attribute__((packed)) aivision_object_s {
function namespace (line 179) | namespace c {
FILE: include/pros/ai_vision.hpp
type pros (line 31) | namespace pros {
type v5 (line 32) | inline namespace v5 {
type AivisionDetectType (line 39) | enum class AivisionDetectType : uint8_t {
type AivisionModeType (line 51) | enum class AivisionModeType : uint8_t {
type AivisionTagFamily (line 64) | enum class AivisionTagFamily { tag_21H7 = 0, tag_16H5 = 1, tag_25H9 ...
class AIVision (line 69) | class AIVision : public Device {
method AIVision (line 100) | AIVision(const Device& device) : AIVision(device.get_port()){}
method enable_detection_types (line 250) | int32_t enable_detection_types(Flags... flags) {
method disable_detection_types (line 311) | int32_t disable_detection_types(Flags... flags) {
FILE: include/pros/apix.h
function namespace (line 37) | namespace pros::c {
FILE: include/pros/colors.h
function namespace (line 37) | namespace pros {
FILE: include/pros/colors.hpp
type pros (line 21) | namespace pros{
type Color (line 38) | enum class Color {
FILE: include/pros/device.h
function namespace (line 26) | namespace pros::c {
FILE: include/pros/device.hpp
type pros (line 24) | namespace pros {
type v5 (line 25) | inline namespace v5 {
type DeviceType (line 43) | enum class DeviceType {
class Device (line 59) | class Device {
method Device (line 193) | Device(const std::uint8_t port, const enum DeviceType deviceType) :
type DeviceType (line 199) | enum DeviceType
FILE: include/pros/distance.h
function namespace (line 27) | namespace pros {
FILE: include/pros/distance.hpp
type pros (line 28) | namespace pros {
type v5 (line 29) | inline namespace v5 {
class Distance (line 33) | class Distance : public Device {
method Distance (line 61) | Distance(const Device& device) : Distance(device.get_port()){}
type literals (line 228) | namespace literals {
FILE: include/pros/ext_adi.h
function namespace (line 38) | namespace c {
FILE: include/pros/gps.h
type gps_position_s_t (line 43) | typedef struct __attribute__((__packed__)) gps_position_s {
type gps_status_s_t (line 53) | typedef struct __attribute__((__packed__)) gps_status_s {
type gps_orientation_s_t (line 69) | typedef struct __attribute__((__packed__)) gps_orientation_s {
type gps_raw_s (line 82) | struct gps_raw_s {
type gps_accel_s_t (line 95) | typedef struct gps_raw_s gps_accel_s_t;
type gps_gyro_s_t (line 101) | typedef struct gps_raw_s gps_gyro_s_t;
FILE: include/pros/gps.hpp
type pros (line 31) | namespace pros {
type v5 (line 32) | inline namespace v5 {
class Gps (line 37) | class Gps : public Device {
method Gps (line 61) | Gps(const std::uint8_t port) : Device(port, DeviceType::gps){}
method Gps (line 63) | Gps(const Device& device) : Gps(device.get_port()){}
method Gps (line 89) | explicit Gps(const std::uint8_t port, double xInitial, double yIni...
method Gps (line 116) | explicit Gps(const std::uint8_t port, double xOffset, double yOffs...
method Gps (line 148) | explicit Gps(const std::uint8_t port, double xInitial, double yIni...
type literals (line 909) | namespace literals {
FILE: include/pros/imu.h
type imu_status_e_t (line 43) | typedef enum imu_status_e {
type imu_orientation_e_t (line 52) | typedef enum imu_orientation_e {
type quaternion_s_t (line 66) | typedef struct __attribute__((__packed__)) quaternion_s {
type imu_raw_s (line 77) | struct imu_raw_s {
type imu_gyro_s_t (line 87) | typedef struct imu_raw_s imu_gyro_s_t;
type imu_accel_s_t (line 93) | typedef struct imu_raw_s imu_accel_s_t;
type euler_s_t (line 99) | typedef struct __attribute__((__packed__)) euler_s {
FILE: include/pros/imu.hpp
type pros (line 27) | namespace pros {
type ImuStatus (line 42) | enum class ImuStatus {
type v5 (line 51) | inline namespace v5 {
class Imu (line 55) | class Imu : public Device {
method Imu (line 87) | Imu(const std::uint8_t port) : Device(port, DeviceType::imu){}
method Imu (line 89) | Imu(const Device& device) : Imu(device.get_port()){}
type literals (line 1056) | namespace literals {
FILE: include/pros/link.h
type link_type_e_t (line 43) | typedef enum link_type_e {
FILE: include/pros/link.hpp
type pros (line 27) | namespace pros {
class Link (line 31) | class Link : public Device {
FILE: include/pros/llemu.h
function namespace (line 23) | namespace pros {
FILE: include/pros/llemu.hpp
type lcd (line 51) | namespace lcd {
type lcd (line 53) | namespace [[deprecated("Without liblvgl, LLEMU functions will not disp...
function T (line 59) | T convert_args(T arg) {
function print (line 128) | bool print(std::int16_t line, const char* fmt, Params... args) {
FILE: include/pros/misc.h
type competition_status (line 45) | typedef enum {
function namespace (line 54) | namespace pros {
type controller_id_e_t (line 178) | typedef enum {
type controller_analog_e_t (line 188) | typedef enum {
type controller_digital_e_t (line 202) | typedef enum {
function namespace (line 298) | namespace c {
FILE: include/pros/misc.hpp
type pros (line 30) | namespace pros {
type v5 (line 31) | inline namespace v5 {
class Controller (line 35) | class Controller {
method T (line 256) | T convert_args(T arg) {
method print (line 304) | std::int32_t print(std::uint8_t line, std::uint8_t col, const char...
type battery (line 447) | namespace battery {
type competition (line 526) | namespace competition {
type usd (line 555) | namespace usd {
FILE: include/pros/motor_group.hpp
type pros (line 36) | namespace pros {
type v5 (line 37) | inline namespace v5 {
class MotorGroup (line 38) | class MotorGroup : public virtual AbstractMotor {
FILE: include/pros/motors.h
type motor_fault_e_t (line 548) | typedef enum motor_fault_e {
type motor_flag_e_t (line 617) | typedef enum motor_flag_e {
type motor_brake_mode_e_t (line 860) | typedef enum motor_brake_mode_e {
type motor_encoder_units_e_t (line 875) | typedef enum motor_encoder_units_e {
type motor_gearset_e_t (line 890) | typedef enum motor_gearset_e {
type motor_type_e_t (line 907) | typedef enum motor_type_e {
type motor_pid_full_s_t (line 971) | typedef struct motor_pid_full_s {
type motor_pid_s_t (line 998) | typedef struct motor_pid_s {
function namespace (line 1010) | namespace c {
FILE: include/pros/motors.hpp
type pros (line 31) | namespace pros {
type v5 (line 32) | inline namespace v5 {
class Motor (line 34) | class Motor : public AbstractMotor, public Device {
method Motor (line 77) | Motor(const Device& device) : Motor(device.get_port()){}
type literals (line 2445) | namespace literals {
FILE: include/pros/optical.h
function namespace (line 32) | namespace pros {
FILE: include/pros/optical.hpp
type pros (line 30) | namespace pros {
type v5 (line 31) | inline namespace v5 {
class Optical (line 35) | class Optical : public Device {
method Optical (line 59) | Optical(const Device& device) : Optical(device.get_port()){}
type literals (line 449) | namespace literals {
FILE: include/pros/rotation.h
function namespace (line 27) | namespace pros {
FILE: include/pros/rotation.hpp
type pros (line 27) | namespace pros {
type v5 (line 28) | inline namespace v5 {
class Rotation (line 32) | class Rotation : public Device {
method Rotation (line 58) | Rotation(const Device& device) : Rotation(device.get_port()){}
type literals (line 375) | namespace literals {
FILE: include/pros/rtos.h
type task_state_e_t (line 119) | typedef enum {
type notify_action_e_t (line 131) | typedef enum {
function namespace (line 200) | namespace c {
FILE: include/pros/rtos.hpp
type pros (line 36) | namespace pros {
type rtos (line 37) | inline namespace rtos {
class Task (line 41) | class Task {
method task_t (line 150) | static task_t create(F&& function, std::uint32_t prio = TASK_PRIOR...
method task_t (line 187) | static task_t create(F&& function, const char* name) {
method Task (line 224) | explicit Task(F&& function, std::uint32_t prio = TASK_PRIORITY_DEF...
method Task (line 266) | Task(F&& function, const char* name)
type Clock (line 790) | struct Clock {
class Mutex (line 824) | class Mutex {
method Mutex (line 828) | constexpr Mutex() {
method Mutex (line 836) | Mutex(const Mutex&) = delete;
method Mutex (line 837) | Mutex(Mutex&&) = delete;
method Mutex (line 839) | Mutex& operator=(const Mutex&) = delete;
method Mutex (line 840) | Mutex& operator=(Mutex&&) = delete;
method try_lock_for (line 1316) | [[nodiscard]] bool try_lock_for(const std::chrono::duration<Rep, P...
method try_lock_until (line 1351) | bool try_lock_until(const std::chrono::time_point<Clock, Duration>...
class RecursiveMutex (line 1358) | class RecursiveMutex {
method RecursiveMutex (line 1362) | constexpr RecursiveMutex() {
method RecursiveMutex (line 1370) | RecursiveMutex(const RecursiveMutex&) = delete;
method RecursiveMutex (line 1371) | RecursiveMutex(RecursiveMutex&&) = delete;
method RecursiveMutex (line 1373) | RecursiveMutex& operator=(const RecursiveMutex&) = delete;
method RecursiveMutex (line 1374) | RecursiveMutex& operator=(RecursiveMutex&&) = delete;
method try_lock_for (line 1850) | [[nodiscard]] bool try_lock_for(const std::chrono::duration<Rep, P...
method try_lock_until (line 1885) | bool try_lock_until(const std::chrono::time_point<Clock, Duration>...
class MutexVar (line 1894) | class MutexVar
method MutexVar (line 1989) | MutexVar(Args&&... args) : mutex(), var(std::forward<Args>(args).....
method try_lock (line 2021) | std::optional<MutexVarLock<Var>> try_lock(std::uint32_t timeout) {
method try_lock (line 2061) | std::optional<MutexVarLock<Var>> try_lock(const std::chrono::durat...
method lock (line 2086) | MutexVarLock<Var> lock() {
class MutexVarLock (line 1897) | class MutexVarLock {
method MutexVarLock (line 1903) | constexpr MutexVarLock(Mutex& mutex, Var& var) : mutex(mutex), var...
method Var (line 1909) | constexpr Var& operator*() const {
method Var (line 1916) | constexpr Var* operator->() const {
class MutexVar (line 1926) | class MutexVar {
method MutexVar (line 1989) | MutexVar(Args&&... args) : mutex(), var(std::forward<Args>(args).....
method try_lock (line 2021) | std::optional<MutexVarLock<Var>> try_lock(std::uint32_t timeout) {
method try_lock (line 2061) | std::optional<MutexVarLock<Var>> try_lock(const std::chrono::durat...
method lock (line 2086) | MutexVarLock<Var> lock() {
FILE: include/pros/screen.h
type text_format_e_t (line 49) | typedef enum {
type last_touch_e_t (line 66) | typedef enum {
type screen_touch_status_s_t (line 81) | typedef struct screen_touch_status_s {
function namespace (line 114) | namespace c {
FILE: include/pros/screen.hpp
type pros (line 26) | namespace pros {
type screen (line 27) | namespace screen {
function T (line 34) | T convert_args(T arg) {
function print (line 634) | void print(pros::text_format_e_t txt_fmt, const std::int16_t line, c...
function print (line 639) | void print(pros::text_format_e_t txt_fmt, const std::int16_t x, cons...
function lvgl_init (line 715) | extern __attribute__((weak)) void lvgl_init() {}
FILE: include/pros/serial.h
function namespace (line 27) | namespace pros {
FILE: include/pros/serial.hpp
type pros (line 27) | namespace pros {
class Serial (line 32) | class Serial : public Device {
type literals (line 327) | namespace literals {
FILE: include/pros/vision.h
type vision_object_type_e_t (line 62) | typedef enum vision_object_type {
type vision_signature_s_t (line 72) | typedef struct __attribute__((__packed__)) vision_signature {
type vision_color_code_t (line 90) | typedef uint16_t vision_color_code_t;
type vision_object_s_t (line 96) | typedef struct __attribute__((__packed__)) vision_object {
type vision_zero_e_t (line 121) | typedef enum vision_zero {
function namespace (line 145) | namespace c {
FILE: include/pros/vision.hpp
type pros (line 29) | namespace pros {
type v5 (line 30) | inline namespace v5 {
class Vision (line 34) | class Vision : public Device {
method Vision (line 62) | Vision(const Device& device) : Vision(device.get_port()){}
type literals (line 770) | namespace literals {
FILE: include/rtos/FreeRTOS.h
type xSTATIC_LIST_ITEM (line 951) | struct xSTATIC_LIST_ITEM
type StaticListItem_t (line 956) | typedef struct xSTATIC_LIST_ITEM StaticListItem_t;
type xSTATIC_MINI_LIST_ITEM (line 959) | struct xSTATIC_MINI_LIST_ITEM
type StaticMiniListItem_t (line 964) | typedef struct xSTATIC_MINI_LIST_ITEM StaticMiniListItem_t;
type StaticList_t (line 967) | typedef struct xSTATIC_LIST
type static_task_s_t (line 987) | typedef struct xSTATIC_TCB
type static_queue_s_t (line 1049) | typedef struct xSTATIC_QUEUE
type static_queue_s_t (line 1077) | typedef static_queue_s_t static_sem_s_t;
type StaticEventGroup_t (line 1093) | typedef struct xSTATIC_EVENT_GROUP
type StaticTimer_t (line 1122) | typedef struct xSTATIC_TIMER
type static_stream_buf_s_t (line 1153) | typedef struct xSTATIC_STREAM_BUFFER
type static_stream_buf_s_t (line 1164) | typedef static_stream_buf_s_t static_msg_buf_s_t;
FILE: include/rtos/list.h
type xLIST_ITEM (line 139) | struct xLIST_ITEM
type list_item_t (line 149) | typedef struct xLIST_ITEM list_item_t;
type xMINI_LIST_ITEM (line 151) | struct xMINI_LIST_ITEM
type MiniListItem_t (line 158) | typedef struct xMINI_LIST_ITEM MiniListItem_t;
FILE: include/rtos/portable.h
type HeapRegion_t (line 88) | typedef struct HeapRegion
FILE: include/rtos/portmacro.h
type portSTACK_TYPE (line 96) | typedef portSTACK_TYPE task_stack_t;
FILE: include/rtos/semphr.h
type queue_t (line 38) | typedef queue_t sem_t;
type queue_t (line 39) | typedef queue_t mutex_t;
FILE: include/rtos/task.h
type task_state_e_t (line 71) | typedef enum
type notify_action_e_t (line 82) | typedef enum
type TimeOut_t (line 94) | typedef struct xTIME_OUT
type TaskParameters_t (line 104) | typedef struct xTASK_PARAMETERS
type TaskStatus_t (line 116) | typedef struct xTASK_STATUS
type eSleepModeStatus (line 130) | typedef enum
FILE: include/rtos/tcb.h
type tskTCB (line 11) | typedef struct tskTaskControlBlock
type tskTCB (line 82) | typedef tskTCB TCB_t;
FILE: include/system/dev/dev.h
type fs_driver (line 18) | struct fs_driver
type _reent (line 19) | struct _reent
FILE: include/system/dev/ser.h
type fs_driver (line 20) | struct fs_driver
type _reent (line 21) | struct _reent
FILE: include/system/dev/usd.h
type fs_driver (line 20) | struct fs_driver
type _reent (line 21) | struct _reent
FILE: include/system/dev/vfs.h
type fs_driver (line 23) | struct fs_driver {
type file_entry (line 33) | struct file_entry {
type _reent (line 39) | struct _reent
type fs_driver (line 39) | struct fs_driver
type fs_driver (line 44) | struct fs_driver
FILE: include/system/hot.h
type hot_table (line 3) | struct hot_table {
type hot_table (line 17) | struct hot_table
FILE: include/vdml/port.h
function merge_adi_ports (line 29) | static inline uint32_t merge_adi_ports(uint8_t smart_port, uint8_t adi_p...
FILE: include/vdml/registry.h
type v5_smart_device_s_t (line 25) | typedef struct {
FILE: patch_headers.py
function print_and_exit (line 9) | def print_and_exit(message):
FILE: src/common/cobs.c
function cobs_encode_measure (line 21) | size_t cobs_encode_measure(const uint8_t* restrict src, const size_t src...
function cobs_encode (line 58) | int cobs_encode(uint8_t* restrict dest, const uint8_t* restrict src, con...
FILE: src/common/gid.c
function gid_init (line 25) | void gid_init(struct gid_metadata* const metadata) {
function gid_alloc (line 39) | uint32_t gid_alloc(struct gid_metadata* const metadata) {
function gid_free (line 79) | void gid_free(struct gid_metadata* const metadata, uint32_t id) {
function gid_check (line 88) | bool gid_check(struct gid_metadata* metadata, uint32_t id) {
FILE: src/common/linkedlist.c
function ll_node_s_t (line 24) | ll_node_s_t* linked_list_init_func_node(generic_fn_t func) {
function ll_node_s_t (line 32) | ll_node_s_t* linked_list_init_data_node(void* data) {
function linked_list_s_t (line 40) | linked_list_s_t* linked_list_init() {
function linked_list_prepend_func (line 47) | void linked_list_prepend_func(linked_list_s_t* list, generic_fn_t func) {
function linked_list_prepend_data (line 56) | void linked_list_prepend_data(linked_list_s_t* list, void* data) {
function linked_list_append_func (line 65) | void linked_list_append_func(linked_list_s_t* list, generic_fn_t func) {
function linked_list_remove_func (line 81) | void linked_list_remove_func(linked_list_s_t* list, generic_fn_t func) {
function linked_list_append_data (line 101) | void linked_list_append_data(linked_list_s_t* list, void* data) {
function linked_list_remove_data (line 117) | void linked_list_remove_data(linked_list_s_t* list, void* data) {
function linked_list_foreach (line 137) | void linked_list_foreach(linked_list_s_t* list, linked_list_foreach_fn_t...
function linked_list_free (line 147) | void linked_list_free(linked_list_s_t* list) {
FILE: src/common/set.c
function set_initialize (line 22) | void set_initialize(struct set* const set) {
function set_add (line 29) | bool set_add(struct set* const set, uint32_t item) {
function set_rm (line 57) | bool set_rm(struct set* set, uint32_t item) {
function set_contains (line 78) | bool set_contains(struct set* set, uint32_t item) {
function list_contains (line 87) | bool list_contains(uint32_t const* list, const size_t size, const uint32...
FILE: src/common/string.c
function kprint_hex (line 34) | void kprint_hex(uint8_t* s, size_t len) {
FILE: src/devices/battery.c
function battery_get_voltage (line 18) | int32_t battery_get_voltage(void) {
function battery_get_current (line 28) | int32_t battery_get_current(void) {
function battery_get_temperature (line 38) | double battery_get_temperature(void) {
function battery_get_capacity (line 48) | double battery_get_capacity(void) {
FILE: src/devices/battery.cpp
type pros (line 16) | namespace pros {
type battery (line 17) | namespace battery {
function get_capacity (line 20) | double get_capacity(void) {
function get_current (line 24) | std::int32_t get_current(void) {
function get_temperature (line 28) | double get_temperature(void) {
function get_voltage (line 32) | std::int32_t get_voltage(void) {
FILE: src/devices/controller.c
type controller_data_s_t (line 28) | typedef struct __attribute__((__may_alias__)) controller_data {
function get_button_pressed (line 44) | static bool get_button_pressed(int port, int button) {
function set_button_pressed (line 48) | static void set_button_pressed(int port, int button, bool state) {
function get_button_released (line 52) | static bool get_button_released(int port, int button) {
function set_button_released (line 56) | static void set_button_released(int port, int button, bool state) {
function controller_is_connected (line 60) | int32_t controller_is_connected(controller_id_e_t id) {
function controller_get_analog (line 68) | int32_t controller_get_analog(controller_id_e_t id, controller_analog_e_...
function controller_get_battery_capacity (line 76) | int32_t controller_get_battery_capacity(controller_id_e_t id) {
function controller_get_battery_level (line 84) | int32_t controller_get_battery_level(controller_id_e_t id) {
function controller_get_digital (line 92) | int32_t controller_get_digital(controller_id_e_t id, controller_digital_...
function controller_get_digital_new_press (line 101) | int32_t controller_get_digital_new_press(controller_id_e_t id, controlle...
function controller_get_digital_new_release (line 122) | int32_t controller_get_digital_new_release(controller_id_e_t id, control...
function controller_set_text (line 143) | int32_t controller_set_text(controller_id_e_t id, uint8_t line, uint8_t ...
function controller_print (line 165) | int32_t controller_print(controller_id_e_t id, uint8_t line, uint8_t col...
function controller_clear_line (line 192) | int32_t controller_clear_line(controller_id_e_t id, uint8_t line) {
function controller_clear (line 208) | int32_t controller_clear(controller_id_e_t id) {
function controller_rumble (line 221) | int32_t controller_rumble(controller_id_e_t id, const char* rumble_patte...
function competition_get_status (line 225) | uint8_t competition_get_status(void) {
function competition_is_disabled (line 229) | uint8_t competition_is_disabled(void) {
function competition_is_connected (line 233) | uint8_t competition_is_connected(void) {
function competition_is_autonomous (line 237) | uint8_t competition_is_autonomous(void) {
function competition_is_field (line 241) | uint8_t competition_is_field(void) {
function competition_is_switch (line 245) | uint8_t competition_is_switch(void) {
FILE: src/devices/controller.cpp
type pros (line 17) | namespace pros {
type v5 (line 18) | inline namespace v5 {
type competition (line 73) | namespace competition {
function get_status (line 75) | std::uint8_t get_status(void) {
function is_autonomous (line 79) | std::uint8_t is_autonomous(void) {
function is_connected (line 83) | std::uint8_t is_connected(void) {
function is_disabled (line 87) | std::uint8_t is_disabled(void) {
function is_field_control (line 91) | std::uint8_t is_field_control(void) {
function is_competition_switch (line 95) | std::uint8_t is_competition_switch(void) {
FILE: src/devices/registry.c
function registry_init (line 28) | void registry_init() {
function registry_update_types (line 42) | void registry_update_types() {
function registry_bind_port (line 46) | int registry_bind_port(uint8_t port, v5_device_e_t device_type) {
function registry_unbind_port (line 70) | int registry_unbind_port(uint8_t port) {
function v5_smart_device_s_t (line 80) | v5_smart_device_s_t* registry_get_device(uint8_t port) {
function v5_smart_device_s_t (line 88) | v5_smart_device_s_t* registry_get_device_internal(uint8_t port) {
function v5_device_e_t (line 96) | v5_device_e_t registry_get_bound_type(uint8_t port) {
function v5_device_e_t (line 104) | v5_device_e_t registry_get_plugged_type(uint8_t port) {
function registry_validate_binding (line 112) | int32_t registry_validate_binding(uint8_t port, v5_device_e_t expected_t) {
FILE: src/devices/screen.c
type touch_event_position_data_s_t (line 34) | typedef struct touch_event_position_data_s {
function screen_set_pen (line 39) | uint32_t screen_set_pen(uint32_t color){
function screen_set_eraser (line 52) | uint32_t screen_set_eraser(uint32_t color){
function screen_get_pen (line 65) | uint32_t screen_get_pen(void){
function screen_get_eraser (line 77) | uint32_t screen_get_eraser(void){
function screen_erase (line 89) | uint32_t screen_erase(void){
function screen_scroll (line 102) | uint32_t screen_scroll(int16_t start_line, int16_t lines){
function screen_scroll_area (line 115) | uint32_t screen_scroll_area(int16_t x0, int16_t y0, int16_t x1, int16_t ...
function screen_copy_area (line 128) | uint32_t screen_copy_area(int16_t x0, int16_t y0, int16_t x1, int16_t y1...
function screen_draw_pixel (line 141) | uint32_t screen_draw_pixel(int16_t x, int16_t y){
function screen_erase_pixel (line 154) | uint32_t screen_erase_pixel(int16_t x, int16_t y){
function screen_draw_line (line 167) | uint32_t screen_draw_line(int16_t x0, int16_t y0, int16_t x1, int16_t y1){
function screen_erase_line (line 180) | uint32_t screen_erase_line(int16_t x0, int16_t y0, int16_t x1, int16_t y1){
function screen_draw_rect (line 193) | uint32_t screen_draw_rect(int16_t x0, int16_t y0, int16_t x1, int16_t y1){
function screen_erase_rect (line 206) | uint32_t screen_erase_rect(int16_t x0, int16_t y0, int16_t x1, int16_t y1){
function screen_fill_rect (line 219) | uint32_t screen_fill_rect(int16_t x0, int16_t y0, int16_t x1, int16_t y1){
function screen_draw_circle (line 232) | uint32_t screen_draw_circle(int16_t x, int16_t y, int16_t radius){
function screen_erase_circle (line 245) | uint32_t screen_erase_circle(int16_t x, int16_t y, int16_t radius){
function screen_fill_circle (line 258) | uint32_t screen_fill_circle(int16_t x, int16_t y, int16_t radius){
function screen_print (line 277) | uint32_t screen_print(text_format_e_t txt_fmt, const int16_t line, const...
function screen_print_at (line 287) | uint32_t screen_print_at(text_format_e_t txt_fmt, int16_t x, int16_t y, ...
function screen_vprintf (line 297) | uint32_t screen_vprintf(text_format_e_t txt_fmt, const int16_t line, con...
function screen_vprintf_at (line 340) | uint32_t screen_vprintf_at(text_format_e_t txt_fmt, const int16_t x, con...
function screen_touch_status_s_t (line 387) | screen_touch_status_s_t screen_touch_status(void){
function _set_up_touch_callback_storage (line 411) | static void _set_up_touch_callback_storage() {
function screen_touch_callback (line 417) | uint32_t screen_touch_callback(touch_event_cb_fn_t cb, last_touch_e_t ev...
function _handle_cb (line 448) | static volatile void _handle_cb(ll_node_s_t* current, void* extra_data) {
function _touch_status_equivalent (line 452) | static inline bool _touch_status_equivalent(V5_TouchStatus x, V5_TouchSt...
function _touch_handle_task (line 456) | void _touch_handle_task(void* ignore) {
function display_fatal_error (line 482) | void display_fatal_error(const char* text) {
function graphical_context_daemon_initialize (line 498) | void graphical_context_daemon_initialize(void) {
FILE: src/devices/screen.cpp
type pros (line 18) | namespace pros {
type screen (line 19) | namespace screen {
function set_pen (line 21) | std::uint32_t set_pen(pros::Color color){
function set_eraser (line 25) | std::uint32_t set_eraser(pros::Color color){
function set_pen (line 29) | std::uint32_t set_pen(std::uint32_t color){
function set_eraser (line 33) | std::uint32_t set_eraser(std::uint32_t color) {
function get_pen (line 37) | std::uint32_t get_pen(){
function get_eraser (line 41) | std::uint32_t get_eraser(){
function erase (line 45) | std::uint32_t erase(){
function scroll (line 49) | std::uint32_t scroll(const std::int16_t start_line, const std::int16...
function scroll_area (line 53) | std::uint32_t scroll_area(const std::int16_t x0, const std::int16_t ...
function copy_area (line 57) | std::uint32_t copy_area(const std::int16_t x0, const std::int16_t y0...
function draw_pixel (line 61) | std::uint32_t draw_pixel(const std::int16_t x, const std::int16_t y){
function erase_pixel (line 65) | std::uint32_t erase_pixel(const std::int16_t x, const std::int16_t y){
function draw_line (line 69) | std::uint32_t draw_line(const std::int16_t x0, const std::int16_t y0...
function erase_line (line 73) | std::uint32_t erase_line(const std::int16_t x0, const std::int16_t y...
function draw_rect (line 77) | std::uint32_t draw_rect(const std::int16_t x0, const std::int16_t y0...
function erase_rect (line 81) | std::uint32_t erase_rect(const std::int16_t x0, const std::int16_t y...
function fill_rect (line 85) | std::uint32_t fill_rect(const std::int16_t x0, const std::int16_t y0...
function draw_circle (line 89) | std::uint32_t draw_circle(const std::int16_t x, const std::int16_t y...
function erase_circle (line 93) | std::uint32_t erase_circle(const std::int16_t x, const std::int16_t ...
function fill_circle (line 97) | std::uint32_t fill_circle(const std::int16_t x, const std::int16_t y...
function screen_touch_status_s_t (line 101) | screen_touch_status_s_t touch_status() {
function touch_callback (line 105) | std::uint32_t touch_callback(touch_event_cb_fn_t cb, last_touch_e_t ...
type lcd (line 114) | namespace lcd {
function is_initialized (line 119) | extern __attribute__((weak)) bool is_initialized(void) {return fal...
function initialize (line 120) | extern __attribute__((weak)) bool initialize(void) {return false;}
function shutdown (line 121) | extern __attribute__((weak)) bool shutdown(void) {return false;}
function set_text (line 122) | extern __attribute__((weak)) bool set_text(std::int16_t line, std:...
function clear (line 123) | extern __attribute__((weak)) bool clear(void) {return false;}
function clear_line (line 124) | extern __attribute__((weak)) bool clear_line(std::int16_t line) {r...
function register_btn0_cb (line 127) | extern __attribute__((weak)) void register_btn0_cb(lcd_btn_cb_fn_t...
function register_btn1_cb (line 128) | extern __attribute__((weak)) void register_btn1_cb(lcd_btn_cb_fn_t...
function register_btn2_cb (line 129) | extern __attribute__((weak)) void register_btn2_cb(lcd_btn_cb_fn_t...
function read_buttons (line 130) | extern __attribute__((weak)) std::uint8_t read_buttons(void) {retu...
function print (line 133) | extern __attribute__((weak)) bool print(std::int16_t line, const c...
FILE: src/devices/vdml.c
function claim_port_try (line 32) | int32_t claim_port_try(uint8_t port, v5_device_e_t type) {
function vdml_initialize (line 58) | void vdml_initialize() {
function port_mutex_init (line 71) | void port_mutex_init() {
function port_mutex_take (line 77) | int port_mutex_take(uint8_t port) {
function internal_port_mutex_take (line 85) | int internal_port_mutex_take(uint8_t port) {
function port_mutex_give (line 99) | int port_mutex_give(uint8_t port) {
function internal_port_mutex_give (line 107) | int internal_port_mutex_give(uint8_t port) {
function port_mutex_take_all (line 115) | void port_mutex_take_all() {
function port_mutex_give_all (line 121) | void port_mutex_give_all() {
function vdml_set_port_error (line 127) | void vdml_set_port_error(uint8_t port) {
function vdml_unset_port_error (line 133) | void vdml_unset_port_error(uint8_t port) {
function vdml_get_port_error (line 139) | bool vdml_get_port_error(uint8_t port) {
function vdml_reset_port_error (line 148) | void vdml_reset_port_error() {
function vdml_background_processing (line 165) | void vdml_background_processing() {
FILE: src/devices/vdml_adi.c
function adi_port_config_e_t (line 16) | adi_port_config_e_t adi_port_get_config(uint8_t port) {
function adi_port_get_value (line 20) | int32_t adi_port_get_value(uint8_t port) {
function adi_port_set_config (line 24) | int32_t adi_port_set_config(uint8_t port, adi_port_config_e_t type) {
function adi_port_set_value (line 28) | int32_t adi_port_set_value(uint8_t port, int32_t value) {
function adi_analog_calibrate (line 32) | int32_t adi_analog_calibrate(uint8_t port) {
function adi_analog_read (line 36) | int32_t adi_analog_read(uint8_t port) {
function adi_analog_read_calibrated (line 40) | int32_t adi_analog_read_calibrated(uint8_t port) {
function adi_analog_read_calibrated_HR (line 44) | int32_t adi_analog_read_calibrated_HR(uint8_t port) {
function adi_digital_read (line 48) | int32_t adi_digital_read(uint8_t port) {
function adi_digital_get_new_press (line 52) | int32_t adi_digital_get_new_press(uint8_t port) {
function adi_digital_write (line 56) | int32_t adi_digital_write(uint8_t port, bool value) {
function adi_pin_mode (line 60) | int32_t adi_pin_mode(uint8_t port, uint8_t mode) {
function adi_motor_set (line 64) | int32_t adi_motor_set(uint8_t port, int8_t speed) {
function adi_motor_get (line 68) | int32_t adi_motor_get(uint8_t port) {
function adi_motor_stop (line 72) | int32_t adi_motor_stop(uint8_t port) {
function adi_encoder_t (line 76) | adi_encoder_t adi_encoder_init(uint8_t port_top, uint8_t port_bottom, bo...
function adi_encoder_get (line 80) | int32_t adi_encoder_get(adi_encoder_t enc) {
function adi_encoder_reset (line 84) | int32_t adi_encoder_reset(adi_encoder_t enc) {
function adi_encoder_shutdown (line 88) | int32_t adi_encoder_shutdown(adi_encoder_t enc) {
function adi_ultrasonic_t (line 92) | adi_ultrasonic_t adi_ultrasonic_init(uint8_t port_ping, uint8_t port_ech...
function adi_ultrasonic_get (line 96) | int32_t adi_ultrasonic_get(adi_ultrasonic_t ult) {
function adi_ultrasonic_shutdown (line 100) | int32_t adi_ultrasonic_shutdown(adi_ultrasonic_t ult) {
function adi_gyro_t (line 104) | adi_gyro_t adi_gyro_init(uint8_t adi_port, double multiplier) {
function adi_gyro_get (line 108) | double adi_gyro_get(adi_gyro_t gyro) {
function adi_gyro_reset (line 112) | int32_t adi_gyro_reset(adi_gyro_t gyro) {
function adi_gyro_shutdown (line 116) | int32_t adi_gyro_shutdown(adi_gyro_t gyro) {
function adi_potentiometer_t (line 120) | adi_potentiometer_t adi_potentiometer_init(uint8_t port) {
function adi_potentiometer_t (line 124) | adi_potentiometer_t adi_potentiometer_type_init(uint8_t port, adi_potent...
function adi_potentiometer_get_angle (line 128) | double adi_potentiometer_get_angle(adi_potentiometer_t potentiometer) {
function adi_led_t (line 132) | adi_led_t adi_led_init(uint8_t port) {
function adi_led_set (line 136) | int32_t adi_led_set(adi_led_t led, uint32_t* buffer, uint32_t buffer_len...
function adi_led_set_pixel (line 140) | int32_t adi_led_set_pixel(adi_led_t led, uint32_t* buffer, uint32_t buff...
function adi_led_set_all (line 144) | int32_t adi_led_set_all(adi_led_t led, uint32_t* buffer, uint32_t buffer...
function adi_led_clear_all (line 148) | int32_t adi_led_clear_all(adi_led_t led, uint32_t* buffer, uint32_t buff...
function adi_led_clear_pixel (line 152) | int32_t adi_led_clear_pixel(adi_led_t led, uint32_t* buffer, uint32_t bu...
FILE: src/devices/vdml_adi.cpp
type pros (line 19) | namespace pros {
type adi (line 20) | namespace adi {
function ext_adi_port_tuple_t (line 49) | ext_adi_port_tuple_t Port::get_port() const {
function ext_adi_port_tuple_t (line 159) | ext_adi_port_tuple_t ADIEncoder::get_port() const {
FILE: src/devices/vdml_ai_vision.c
function aivision_reset (line 30) | int32_t aivision_reset(uint8_t port) {
function aivision_set_enabled_detection_types (line 36) | int32_t aivision_set_enabled_detection_types(uint8_t port, uint8_t bits,...
function aivision_get_enabled_detection_types (line 42) | int32_t aivision_get_enabled_detection_types(uint8_t port) {
function aivision_enable_detection_types (line 48) | int32_t aivision_enable_detection_types(uint8_t port, uint8_t types_mask) {
function aivision_disable_detection_types (line 54) | int32_t aivision_disable_detection_types(uint8_t port, uint8_t types_mas...
function aivision_get_class_name (line 60) | int32_t aivision_get_class_name(uint8_t port, int32_t id, uint8_t* class...
function aivision_set_color (line 66) | int32_t aivision_set_color(uint8_t port, const aivision_color_s_t* color) {
function aivision_color_s_t (line 79) | aivision_color_s_t aivision_get_color(uint8_t port, uint32_t id) {
function aivision_get_object_count (line 96) | int32_t aivision_get_object_count(uint8_t port) {
function aivision_get_temperature (line 102) | double aivision_get_temperature(uint8_t port) {
function aivision_set_tag_family (line 108) | int32_t aivision_set_tag_family(uint8_t port, aivision_tag_family_e_t fa...
function aivision_set_tag_family_override (line 117) | int32_t aivision_set_tag_family_override(uint8_t port, aivision_tag_fami...
function aivision_set_usb_bounding_box_overlay (line 124) | int32_t aivision_set_usb_bounding_box_overlay(uint8_t port, bool enabled) {
function aivision_start_awb (line 138) | int32_t aivision_start_awb(uint8_t port) {
function aivision_object_s_t (line 145) | aivision_object_s_t aivision_get_object(uint8_t port, uint32_t object_in...
function aivision_code_s_t (line 156) | aivision_code_s_t aivision_get_code(uint8_t port, uint32_t id) {
function aivision_set_code (line 174) | int32_t aivision_set_code(uint8_t port, const aivision_code_s_t* code) {
FILE: src/devices/vdml_ai_vision.cpp
type pros (line 17) | namespace pros {
type v5 (line 18) | inline namespace v5 {
function AivisionModeType (line 21) | AivisionModeType operator|(AivisionModeType lhs, AivisionModeType rh...
FILE: src/devices/vdml_device.c
function v5_device_e_t (line 21) | v5_device_e_t get_plugged_type(uint8_t port) {
FILE: src/devices/vdml_device.cpp
type pros (line 21) | namespace pros {
type v5 (line 22) | inline namespace v5 {
FILE: src/devices/vdml_distance.c
function distance_get (line 27) | int32_t distance_get(uint8_t port) {
function distance_get_confidence (line 34) | int32_t distance_get_confidence(uint8_t port) {
function distance_get_object_size (line 41) | int32_t distance_get_object_size(uint8_t port) {
function distance_get_object_velocity (line 48) | double distance_get_object_velocity(uint8_t port) {
FILE: src/devices/vdml_distance.cpp
type pros (line 16) | namespace pros {
type v5 (line 17) | inline namespace v5 {
type literals (line 62) | namespace literals {
FILE: src/devices/vdml_ext_adi.c
type adi_data_s_t (line 34) | typedef union adi_data {
function adi_port_config_e_t (line 126) | adi_port_config_e_t ext_adi_port_get_config(uint8_t smart_port, uint8_t ...
function ext_adi_port_get_value (line 133) | int32_t ext_adi_port_get_value(uint8_t smart_port, uint8_t adi_port) {
function ext_adi_port_set_config (line 140) | int32_t ext_adi_port_set_config(uint8_t smart_port, uint8_t adi_port, ad...
function ext_adi_port_set_value (line 147) | int32_t ext_adi_port_set_value(uint8_t smart_port, uint8_t adi_port, int...
function ext_adi_analog_calibrate (line 154) | int32_t ext_adi_analog_calibrate(uint8_t smart_port, uint8_t adi_port) {
function ext_adi_analog_read (line 169) | int32_t ext_adi_analog_read(uint8_t smart_port, uint8_t adi_port) {
function ext_adi_analog_read_calibrated (line 177) | int32_t ext_adi_analog_read_calibrated(uint8_t smart_port, uint8_t adi_p...
function ext_adi_analog_read_calibrated_HR (line 186) | int32_t ext_adi_analog_read_calibrated_HR(uint8_t smart_port, uint8_t ad...
function ext_adi_digital_read (line 195) | int32_t ext_adi_digital_read(uint8_t smart_port, uint8_t adi_port) {
function ext_adi_digital_get_new_press (line 203) | int32_t ext_adi_digital_get_new_press(uint8_t smart_port, uint8_t adi_po...
function ext_adi_digital_write (line 223) | int32_t ext_adi_digital_write(uint8_t smart_port, uint8_t adi_port, bool...
function ext_adi_pin_mode (line 231) | int32_t ext_adi_pin_mode(uint8_t smart_port, uint8_t adi_port, uint8_t m...
function ext_adi_motor_set (line 252) | int32_t ext_adi_motor_set(uint8_t smart_port, uint8_t adi_port, int8_t s...
function ext_adi_motor_get (line 264) | int32_t ext_adi_motor_get(uint8_t smart_port, uint8_t adi_port) {
function ext_adi_motor_stop (line 272) | int32_t ext_adi_motor_stop(uint8_t smart_port, uint8_t adi_port) {
function ext_adi_encoder_t (line 276) | ext_adi_encoder_t ext_adi_encoder_init(uint8_t smart_port, uint8_t adi_p...
function ext_adi_encoder_get (line 289) | int32_t ext_adi_encoder_get(ext_adi_encoder_t enc) {
function ext_adi_encoder_reset (line 305) | int32_t ext_adi_encoder_reset(ext_adi_encoder_t enc) {
function ext_adi_encoder_shutdown (line 316) | int32_t ext_adi_encoder_shutdown(ext_adi_encoder_t enc) {
function ext_adi_ultrasonic_t (line 327) | ext_adi_ultrasonic_t ext_adi_ultrasonic_init(uint8_t smart_port, uint8_t...
function ext_adi_ultrasonic_get (line 340) | int32_t ext_adi_ultrasonic_get(ext_adi_ultrasonic_t ult) {
function ext_adi_ultrasonic_shutdown (line 351) | int32_t ext_adi_ultrasonic_shutdown(ext_adi_ultrasonic_t ult) {
function ext_adi_gyro_t (line 362) | ext_adi_gyro_t ext_adi_gyro_init(uint8_t smart_port, uint8_t adi_port, d...
function ext_adi_gyro_get (line 387) | double ext_adi_gyro_get(ext_adi_gyro_t gyro) {
function ext_adi_gyro_reset (line 401) | int32_t ext_adi_gyro_reset(ext_adi_gyro_t gyro) {
function ext_adi_gyro_shutdown (line 413) | int32_t ext_adi_gyro_shutdown(ext_adi_gyro_t gyro) {
function ext_adi_potentiometer_t (line 424) | ext_adi_potentiometer_t ext_adi_potentiometer_init(uint8_t smart_port, u...
function ext_adi_potentiometer_get_angle (line 434) | double ext_adi_potentiometer_get_angle(ext_adi_potentiometer_t potentiom...
function ext_adi_led_t (line 458) | ext_adi_led_t ext_adi_led_init(uint8_t smart_port, uint8_t adi_port) {
function ext_adi_led_set (line 465) | int32_t ext_adi_led_set(ext_adi_led_t led, uint32_t* buffer, uint32_t bu...
function ext_adi_led_set_pixel (line 481) | int32_t ext_adi_led_set_pixel(ext_adi_led_t led, uint32_t* buffer, uint3...
function ext_adi_led_set_all (line 498) | int32_t ext_adi_led_set_all(ext_adi_led_t led, uint32_t* buffer, uint32_...
function ext_adi_led_clear_all (line 505) | int32_t ext_adi_led_clear_all(ext_adi_led_t led, uint32_t* buffer, uint3...
function ext_adi_led_clear_pixel (line 509) | int32_t ext_adi_led_clear_pixel(ext_adi_led_t led, uint32_t* buffer, uin...
FILE: src/devices/vdml_gps.c
function gps_initialize_full (line 28) | int32_t gps_initialize_full(uint8_t port, double xInitial, double yIniti...
function gps_set_offset (line 36) | int32_t gps_set_offset(uint8_t port, double xOffset, double yOffset) {
function gps_position_s_t (line 42) | gps_position_s_t gps_get_offset(uint8_t port) {
function gps_set_position (line 58) | int32_t gps_set_position(uint8_t port, double xInitial, double yInitial,...
function gps_set_data_rate (line 64) | int32_t gps_set_data_rate(uint8_t port, uint32_t rate) {
function gps_get_error (line 78) | double gps_get_error(uint8_t port) {
function gps_status_s_t (line 84) | gps_status_s_t gps_get_position_and_orientation(uint8_t port) {
function gps_position_s_t (line 100) | gps_position_s_t gps_get_position(uint8_t port) {
function gps_get_position_x (line 113) | double gps_get_position_x(uint8_t port) {
function gps_get_position_y (line 121) | double gps_get_position_y(uint8_t port) {
function gps_orientation_s_t (line 129) | gps_orientation_s_t gps_get_orientation(uint8_t port) {
function gps_get_pitch (line 143) | double gps_get_pitch(uint8_t port) {
function gps_get_roll (line 151) | double gps_get_roll(uint8_t port) {
function gps_get_yaw (line 159) | double gps_get_yaw(uint8_t port) {
function gps_get_heading (line 167) | double gps_get_heading(uint8_t port) {
function gps_get_heading_raw (line 173) | double gps_get_heading_raw(uint8_t port) {
function gps_gyro_s_t (line 179) | gps_gyro_s_t gps_get_gyro_rate(uint8_t port) {
function gps_get_gyro_rate_x (line 193) | double gps_get_gyro_rate_x(uint8_t port) {
function gps_get_gyro_rate_y (line 201) | double gps_get_gyro_rate_y(uint8_t port) {
function gps_get_gyro_rate_z (line 209) | double gps_get_gyro_rate_z(uint8_t port) {
function gps_accel_s_t (line 217) | gps_accel_s_t gps_get_accel(uint8_t port) {
function gps_get_accel_x (line 231) | double gps_get_accel_x(uint8_t port) {
function gps_get_accel_y (line 239) | double gps_get_accel_y(uint8_t port) {
function gps_get_accel_z (line 247) | double gps_get_accel_z(uint8_t port) {
FILE: src/devices/vdml_gps.cpp
type pros (line 17) | namespace pros {
type v5 (line 18) | inline namespace v5 {
type literals (line 153) | namespace literals {
FILE: src/devices/vdml_imu.c
type imu_data_s_t (line 34) | typedef struct __attribute__((packed, __may_alias__)) imu_reset_data {
function imu_reset (line 42) | int32_t imu_reset(uint8_t port) {
function imu_reset_blocking (line 66) | int32_t imu_reset_blocking(uint8_t port) {
function imu_set_data_rate (line 104) | int32_t imu_set_data_rate(uint8_t port, uint32_t rate) {
function imu_get_rotation (line 119) | double imu_get_rotation(uint8_t port) {
function imu_get_heading (line 127) | double imu_get_heading(uint8_t port) {
function quaternion_s_t (line 139) | quaternion_s_t imu_get_quaternion(uint8_t port) {
function euler_s_t (line 173) | euler_s_t imu_get_euler(uint8_t port) {
function imu_get_pitch (line 191) | double imu_get_pitch(uint8_t port) {
function imu_get_roll (line 204) | double imu_get_roll(uint8_t port) {
function imu_get_yaw (line 217) | double imu_get_yaw(uint8_t port) {
function imu_gyro_s_t (line 232) | imu_gyro_s_t imu_get_gyro_rate(uint8_t port) {
function imu_accel_s_t (line 250) | imu_accel_s_t imu_get_accel(uint8_t port) {
function imu_status_e_t (line 266) | imu_status_e_t imu_get_status(uint8_t port) {
function imu_tare (line 277) | int32_t imu_tare(uint8_t port) {
function imu_tare_euler (line 293) | int32_t imu_tare_euler(uint8_t port) {
function imu_tare_heading (line 297) | int32_t imu_tare_heading(uint8_t port) {
function imu_tare_rotation (line 301) | int32_t imu_tare_rotation(uint8_t port) {
function imu_tare_pitch (line 305) | int32_t imu_tare_pitch(uint8_t port) {
function imu_tare_roll (line 309) | int32_t imu_tare_roll(uint8_t port) {
function imu_tare_yaw (line 313) | int32_t imu_tare_yaw(uint8_t port) {
function imu_set_rotation (line 318) | int32_t imu_set_rotation(uint8_t port, double target) {
function imu_set_heading (line 331) | int32_t imu_set_heading(uint8_t port, double target) {
function imu_set_pitch (line 346) | int32_t imu_set_pitch(uint8_t port, double target) {
function imu_set_roll (line 361) | int32_t imu_set_roll(uint8_t port, double target) {
function imu_set_yaw (line 376) | int32_t imu_set_yaw(uint8_t port, double target) {
function imu_set_euler (line 391) | int32_t imu_set_euler(uint8_t port, euler_s_t target) {
function imu_orientation_e_t (line 411) | imu_orientation_e_t imu_get_physical_orientation(uint8_t port) {
FILE: src/devices/vdml_imu.cpp
type pros (line 18) | namespace pros {
type v5 (line 19) | inline namespace v5 {
function imu_orientation_e_t (line 141) | imu_orientation_e_t Imu::get_physical_orientation() const {
function Imu (line 145) | Imu Imu::get_imu() {
type literals (line 179) | namespace literals {
FILE: src/devices/vdml_link.c
function _clear_rx_buf (line 27) | static uint32_t _clear_rx_buf(v5_smart_device_s_t* device) {
function _link_init (line 35) | static uint32_t _link_init(uint8_t port, const char* link_id, link_type_...
function link_init (line 57) | uint32_t link_init(uint8_t port, const char* link_id, link_type_e_t type) {
function link_init_override (line 61) | uint32_t link_init_override(uint8_t port, const char* link_id, link_type...
function link_connected (line 65) | bool link_connected(uint8_t port) {
function link_raw_receivable_size (line 71) | uint32_t link_raw_receivable_size(uint8_t port) {
function link_raw_transmittable_size (line 77) | uint32_t link_raw_transmittable_size(uint8_t port) {
function link_transmit_raw (line 83) | uint32_t link_transmit_raw(uint8_t port, void* data, uint16_t data_size) {
function link_receive_raw (line 101) | uint32_t link_receive_raw(uint8_t port, void* dest, uint16_t data_size) {
function link_transmit (line 119) | uint32_t link_transmit(uint8_t port, void* data, uint16_t data_size) {
function link_receive (line 153) | uint32_t link_receive(uint8_t port, void* dest, uint16_t data_size) {
function link_clear_receive_buf (line 210) | uint32_t link_clear_receive_buf(uint8_t port) {
FILE: src/devices/vdml_link.cpp
type pros (line 19) | namespace pros {
FILE: src/devices/vdml_motorgroup.cpp
type pros (line 19) | namespace pros {
type v5 (line 20) | inline namespace v5 {
FILE: src/devices/vdml_motors.c
function motor_move (line 30) | int32_t motor_move(int8_t port, int32_t voltage) {
function motor_brake (line 49) | int32_t motor_brake(int8_t port) {
function motor_move_absolute (line 53) | int32_t motor_move_absolute(int8_t port, double position, int32_t veloci...
function motor_move_relative (line 61) | int32_t motor_move_relative(int8_t port, double position, int32_t veloci...
function motor_move_velocity (line 69) | int32_t motor_move_velocity(int8_t port, int32_t velocity) {
function motor_move_voltage (line 77) | int32_t motor_move_voltage(int8_t port, int32_t voltage) {
function motor_modify_profiled_velocity (line 85) | int32_t motor_modify_profiled_velocity(int8_t port, int32_t velocity) {
function motor_get_target_position (line 93) | double motor_get_target_position(int8_t port) {
function motor_get_target_velocity (line 101) | int32_t motor_get_target_velocity(int8_t port) {
function motor_get_actual_velocity (line 111) | double motor_get_actual_velocity(int8_t port) {
function motor_get_current_draw (line 119) | int32_t motor_get_current_draw(int8_t port) {
function motor_get_direction (line 126) | int32_t motor_get_direction(int8_t port) {
function motor_get_efficiency (line 134) | double motor_get_efficiency(int8_t port) {
function motor_is_over_current (line 141) | int32_t motor_is_over_current(int8_t port) {
function motor_is_over_temp (line 148) | int32_t motor_is_over_temp(int8_t port) {
function motor_get_faults (line 155) | uint32_t motor_get_faults(int8_t port) {
function motor_get_flags (line 162) | uint32_t motor_get_flags(int8_t port) {
function motor_get_raw_position (line 169) | int32_t motor_get_raw_position(int8_t port, uint32_t* const timestamp) {
function motor_get_position (line 177) | double motor_get_position(int8_t port) {
function motor_get_power (line 185) | double motor_get_power(int8_t port) {
function motor_get_temperature (line 192) | double motor_get_temperature(int8_t port) {
function motor_get_torque (line 199) | double motor_get_torque(int8_t port) {
function motor_get_voltage (line 206) | int32_t motor_get_voltage(int8_t port) {
function motor_set_zero_position (line 216) | int32_t motor_set_zero_position(int8_t port, const double position) {
function motor_tare_position (line 223) | int32_t motor_tare_position(int8_t port) {
function motor_set_brake_mode (line 230) | int32_t motor_set_brake_mode(int8_t port, const motor_brake_mode_e_t mod...
function motor_set_current_limit (line 237) | int32_t motor_set_current_limit(int8_t port, const int32_t limit) {
function motor_set_encoder_units (line 244) | int32_t motor_set_encoder_units(int8_t port, const motor_encoder_units_e...
function motor_set_gearing (line 251) | int32_t motor_set_gearing(int8_t port, const motor_gearset_e_t gearset) {
function motor_set_reversed (line 258) | int32_t motor_set_reversed(int8_t port, const bool reverse) {
function motor_set_voltage_limit (line 265) | int32_t motor_set_voltage_limit(int8_t port, const int32_t limit) {
function motor_brake_mode_e_t (line 272) | motor_brake_mode_e_t motor_get_brake_mode(int8_t port) {
function motor_get_current_limit (line 279) | int32_t motor_get_current_limit(int8_t port) {
function motor_encoder_units_e_t (line 286) | motor_encoder_units_e_t motor_get_encoder_units(int8_t port) {
function motor_gearset_e_t (line 293) | motor_gearset_e_t motor_get_gearing(int8_t port) {
function motor_is_reversed (line 300) | int32_t motor_is_reversed(int8_t port) {
function motor_get_voltage_limit (line 307) | int32_t motor_get_voltage_limit(int8_t port) {
function motor_type_e_t (line 314) | motor_type_e_t motor_get_type(int8_t port) {
FILE: src/devices/vdml_motors.cpp
type pros (line 18) | namespace pros {
type v5 (line 19) | inline namespace v5 {
type literals (line 568) | namespace literals {
FILE: src/devices/vdml_optical.c
function optical_get_hue (line 25) | double optical_get_hue(uint8_t port) {
function optical_get_saturation (line 31) | double optical_get_saturation(uint8_t port) {
function optical_get_brightness (line 37) | double optical_get_brightness(uint8_t port) {
function optical_get_proximity (line 43) | int32_t optical_get_proximity(uint8_t port) {
function optical_set_led_pwm (line 49) | int32_t optical_set_led_pwm(uint8_t port, uint8_t value) {
function optical_get_led_pwm (line 55) | int32_t optical_get_led_pwm(uint8_t port) {
function optical_rgb_s_t (line 64) | optical_rgb_s_t optical_get_rgb(uint8_t port) {
function optical_raw_s_t (line 83) | optical_raw_s_t optical_get_raw(uint8_t port) {
function optical_direction_e_t (line 99) | optical_direction_e_t optical_get_gesture(uint8_t port) {
function optical_gesture_s_t (line 111) | optical_gesture_s_t optical_get_gesture_raw(uint8_t port) {
function optical_enable_gesture (line 131) | int32_t optical_enable_gesture(uint8_t port) {
function optical_disable_gesture (line 137) | int32_t optical_disable_gesture(uint8_t port) {
function optical_get_integration_time (line 143) | double optical_get_integration_time(uint8_t port) {
function optical_set_integration_time (line 149) | int32_t optical_set_integration_time(uint8_t port, double time) {
FILE: src/devices/vdml_optical.cpp
type pros (line 17) | namespace pros {
type v5 (line 18) | inline namespace v5 {
function optical_rgb_s_t (line 56) | optical_rgb_s_t Optical::get_rgb(){
function optical_raw_s_t (line 60) | optical_raw_s_t Optical::get_raw(){
function optical_direction_e_t (line 64) | optical_direction_e_t Optical::get_gesture(){
function optical_gesture_s_t (line 68) | optical_gesture_s_t Optical::get_gesture_raw(){
type literals (line 101) | namespace literals {
FILE: src/devices/vdml_rotation.c
function rotation_reset (line 22) | int32_t rotation_reset(uint8_t port) {
function rotation_set_data_rate (line 28) | int32_t rotation_set_data_rate(uint8_t port, uint32_t rate) {
function rotation_reset_position (line 42) | int32_t rotation_reset_position(uint8_t port) {
function rotation_set_position (line 48) | int32_t rotation_set_position(uint8_t port, int32_t position) {
function rotation_get_position (line 54) | int32_t rotation_get_position(uint8_t port) {
function rotation_get_velocity (line 60) | int32_t rotation_get_velocity(uint8_t port) {
function rotation_get_angle (line 66) | int32_t rotation_get_angle(uint8_t port) {
function rotation_set_reversed (line 72) | int32_t rotation_set_reversed(uint8_t port, bool value) {
function rotation_init_reverse (line 78) | int32_t rotation_init_reverse(uint8_t port, bool reverse_flag) {
function rotation_reverse (line 98) | int32_t rotation_reverse(uint8_t port){
function rotation_get_reversed (line 104) | int32_t rotation_get_reversed(uint8_t port) {
FILE: src/devices/vdml_rotation.cpp
type pros (line 16) | namespace pros {
type v5 (line 17) | inline namespace v5 {
type literals (line 87) | namespace literals {
FILE: src/devices/vdml_serial.c
function serial_enable (line 25) | int32_t serial_enable(uint8_t port) {
function serial_set_baudrate (line 45) | int32_t serial_set_baudrate(uint8_t port, int32_t baudrate) {
function serial_flush (line 51) | int32_t serial_flush(uint8_t port) {
function serial_get_read_avail (line 59) | int32_t serial_get_read_avail(uint8_t port) {
function serial_get_write_free (line 65) | int32_t serial_get_write_free(uint8_t port) {
function serial_peek_byte (line 73) | int32_t serial_peek_byte(uint8_t port) {
function serial_read_byte (line 79) | int32_t serial_read_byte(uint8_t port) {
function serial_read (line 85) | int32_t serial_read(uint8_t port, uint8_t* buffer, int32_t length) {
function serial_write_byte (line 93) | int32_t serial_write_byte(uint8_t port, uint8_t buffer) {
function serial_write (line 103) | int32_t serial_write(uint8_t port, uint8_t* buffer, int32_t length) {
FILE: src/devices/vdml_serial.cpp
type pros (line 17) | namespace pros {
type literals (line 65) | namespace literals {
FILE: src/devices/vdml_usd.c
function usd_is_installed (line 17) | int32_t usd_is_installed(void) {
function usd_list_files (line 24) | int32_t usd_list_files(const char* path, char* buffer, int32_t len) {
FILE: src/devices/vdml_usd.cpp
type pros (line 16) | namespace pros {
type usd (line 17) | namespace usd {
function is_installed (line 20) | std::int32_t is_installed(void) {
function list_files (line 24) | int32_t list_files(const char* path, char* buffer, int32_t len) {
FILE: src/devices/vdml_vision.c
type vision_data_s_t (line 19) | typedef struct vision_data {
function vision_zero_e_t (line 23) | static vision_zero_e_t get_zero_point(uint8_t port) {
function set_zero_point (line 27) | static void set_zero_point(uint8_t port, vision_zero_e_t zero_point) {
function _vision_transform_coords (line 32) | static void _vision_transform_coords(uint8_t port, vision_object_s_t* ob...
function vision_get_object_count (line 45) | int32_t vision_get_object_count(uint8_t port) {
function vision_object_s_t (line 51) | vision_object_s_t vision_get_by_size(uint8_t port, const uint32_t size_i...
function vision_object_s_t (line 76) | vision_object_s_t _vision_get_by_sig(uint8_t port, const uint32_t size_i...
function vision_object_s_t (line 120) | vision_object_s_t vision_get_by_sig(uint8_t port, const uint32_t size_id...
function vision_object_s_t (line 130) | vision_object_s_t vision_get_by_code(uint8_t port, const uint32_t size_i...
function vision_read_by_size (line 134) | int32_t vision_read_by_size(uint8_t port, const uint32_t size_id, const ...
function _vision_read_by_sig (line 160) | int32_t _vision_read_by_sig(uint8_t port, const uint32_t size_id, const ...
function vision_read_by_sig (line 201) | int32_t vision_read_by_sig(uint8_t port, const uint32_t size_id, const u...
function vision_read_by_code (line 213) | int32_t vision_read_by_code(uint8_t port, const uint32_t size_id, const ...
function vision_signature_s_t (line 218) | vision_signature_s_t vision_get_signature(uint8_t port, const uint8_t si...
function vision_set_signature (line 239) | int32_t vision_set_signature(uint8_t port, const uint8_t signature_id, v...
function vision_signature_s_t (line 251) | vision_signature_s_t vision_signature_from_utility(const int32_t id, con...
function vision_color_code_t (line 267) | vision_color_code_t vision_create_color_code(uint8_t port, const uint32_...
function vision_set_led (line 293) | int32_t vision_set_led(uint8_t port, const int32_t rgb) {
function vision_clear_led (line 301) | int32_t vision_clear_led(uint8_t port) {
function vision_set_exposure (line 307) | int32_t vision_set_exposure(uint8_t port, const uint8_t percent) {
function vision_get_exposure (line 314) | int32_t vision_get_exposure(uint8_t port) {
function vision_set_auto_white_balance (line 321) | int32_t vision_set_auto_white_balance(uint8_t port, const uint8_t enable) {
function vision_set_white_balance (line 331) | int32_t vision_set_white_balance(uint8_t port, const int32_t rgb) {
function vision_get_white_balance (line 339) | int32_t vision_get_white_balance(uint8_t port) {
function vision_set_zero_point (line 345) | int32_t vision_set_zero_point(uint8_t port, vision_zero_e_t zero_point) {
function vision_set_wifi_mode (line 362) | int32_t vision_set_wifi_mode(uint8_t port, const uint8_t enable) {
function vision_print_signature (line 368) | int32_t vision_print_signature(const vision_signature_s_t sig) {
FILE: src/devices/vdml_vision.cpp
type pros (line 16) | namespace pros {
type v5 (line 17) | inline namespace v5 {
function vision_signature_s_t (line 28) | vision_signature_s_t Vision::signature_from_utility(const std::int32...
function vision_color_code_t (line 36) | vision_color_code_t Vision::create_color_code(const std::uint32_t si...
function vision_object_s_t (line 53) | vision_object_s_t Vision::get_by_size(const std::uint32_t size_id) c...
function vision_object_s_t (line 57) | vision_object_s_t Vision::get_by_sig(const std::uint32_t size_id, co...
function vision_object_s_t (line 61) | vision_object_s_t Vision::get_by_code(const std::uint32_t size_id, c...
function vision_signature_s_t (line 92) | vision_signature_s_t Vision::get_signature(const std::uint8_t signat...
function Vision (line 127) | Vision Vision::get_vision() {
type literals (line 143) | namespace literals {
FILE: src/main.cpp
function on_center_button (line 9) | void on_center_button() {
function initialize (line 25) | void initialize() {
function disabled (line 37) | void disabled() {}
function competition_initialize (line 48) | void competition_initialize() {}
function autonomous (line 61) | void autonomous() {}
function opcontrol (line 76) | void opcontrol() {
FILE: src/rtos/heap_4.c
type BlockLink_t (line 62) | typedef struct A_BLOCK_LINK
function kfree (line 256) | void kfree( void *pv )
function xPortGetFreeHeapSize (line 304) | size_t xPortGetFreeHeapSize( void )
function xPortGetMinimumEverFreeHeapSize (line 310) | size_t xPortGetMinimumEverFreeHeapSize( void )
function vPortInitialiseBlocks (line 316) | void vPortInitialiseBlocks( void )
function prvHeapInit (line 322) | static void prvHeapInit( void )
function prvInsertBlockIntoFreeList (line 370) | static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert )
FILE: src/rtos/list.c
function vListInitialise (line 37) | void vListInitialise( List_t * const pxList )
function vListInitialiseItem (line 62) | void vListInitialiseItem( list_item_t * const pxItem )
function vListInsertEnd (line 74) | void vListInsertEnd( List_t * const pxList, list_item_t * const pxNewLis...
function vListInsert (line 103) | void vListInsert( List_t * const pxList, list_item_t * const pxNewListIt...
function uxListRemove (line 170) | uint32_t uxListRemove( list_item_t * const pxItemToRemove )
FILE: src/rtos/port.c
function task_clean_up (line 216) | void task_clean_up() {
function task_stack_t (line 225) | task_stack_t *pxPortInitialiseStack( task_stack_t *pxTopOfStack, task_fn...
function prvTaskExitError (line 317) | static void prvTaskExitError( void )
function xPortStartScheduler (line 331) | int32_t xPortStartScheduler( void )
function vPortEndScheduler (line 409) | void vPortEndScheduler( void )
function vPortEnterCritical (line 417) | void vPortEnterCritical( void )
function vPortExitCritical (line 439) | void vPortExitCritical( void )
function FreeRTOS_Tick_Handler (line 459) | void FreeRTOS_Tick_Handler( void )
function vPortTaskUsesFPU (line 486) | void vPortTaskUsesFPU( void )
function vPortClearInterruptMask (line 501) | void vPortClearInterruptMask( uint32_t ulNewMaskValue )
function ulPortSetInterruptMask (line 510) | uint32_t ulPortSetInterruptMask( void )
function vPortValidateInterruptPriority (line 537) | void vPortValidateInterruptPriority( void )
function vApplicationFPUSafeIRQHandler (line 571) | void vApplicationFPUSafeIRQHandler( uint32_t ulICCIAR )
FILE: src/rtos/portmacro.h
type portSTACK_TYPE (line 54) | typedef portSTACK_TYPE task_stack_t;
FILE: src/rtos/queue.c
type xQUEUE (line 73) | typedef struct QueueDefinition
type xQUEUE (line 112) | typedef xQUEUE Queue_t;
type xQueueRegistryItem (line 125) | typedef struct QUEUE_REGISTRY_ITEM
type xQueueRegistryItem (line 134) | typedef xQueueRegistryItem QueueRegistryItem_t;
function xQueueGenericReset (line 232) | int32_t xQueueGenericReset( queue_t xQueue, int32_t xNewQueue )
function queue_reset (line 285) | void queue_reset(queue_t queue) {
function queue_t (line 291) | queue_t xQueueGenericCreateStatic( const uint32_t uxQueueLength, const u...
function queue_t (line 342) | queue_t queue_create_static(uint32_t uxQueueLength, uint32_t uxItemSize,...
function queue_t (line 353) | queue_t xQueueGenericCreate( const uint32_t uxQueueLength, const uint32_...
function queue_t (line 401) | queue_t queue_create(uint32_t length, uint32_t item_size) {
function prvInitialiseNewQueue (line 408) | static void prvInitialiseNewQueue( const uint32_t uxQueueLength, const u...
function prvInitialiseMutex (line 452) | static void prvInitialiseMutex( Queue_t *pxNewQueue )
function queue_t (line 482) | queue_t xQueueCreateMutex( const uint8_t ucQueueType )
function queue_t (line 498) | queue_t xQueueCreateMutexStatic( const uint8_t ucQueueType, static_queue...
function xQueueGiveMutexRecursive (line 574) | int32_t xQueueGiveMutexRecursive( queue_t xMutex )
function xQueueTakeMutexRecursive (line 629) | int32_t xQueueTakeMutexRecursive( queue_t xMutex, uint32_t timeout )
function queue_t (line 671) | queue_t xQueueCreateCountingSemaphoreStatic( const uint32_t uxMaxCount, ...
function queue_t (line 699) | queue_t xQueueCreateCountingSemaphore( const uint32_t uxMaxCount, const ...
function xQueueGenericSend (line 725) | int32_t xQueueGenericSend( queue_t xQueue, const void * const pvItemToQu...
function queue_prepend (line 924) | bool queue_prepend(queue_t queue, const void* item, uint32_t timeout) {
function queue_append (line 927) | bool queue_append(queue_t queue, const void* item, uint32_t timeout) {
function xQueueGenericSendFromISR (line 931) | int32_t xQueueGenericSendFromISR( queue_t xQueue, const void * const pvI...
function xQueueGiveFromISR (line 1082) | int32_t xQueueGiveFromISR( queue_t xQueue, int32_t * const pxHigherPrior...
function queue_recv (line 1247) | int32_t queue_recv(queue_t queue, void* const buffer, uint32_t timeout)
function xQueueSemaphoreTake (line 1389) | int32_t xQueueSemaphoreTake( queue_t xQueue, uint32_t timeout )
function queue_peek (line 1608) | int32_t queue_peek(queue_t queue, void* const buffer, uint32_t timeout)
function xQueueReceiveFromISR (line 1758) | int32_t xQueueReceiveFromISR( queue_t xQueue, void * const buffer, int32...
function xQueuePeekFromISR (line 1849) | int32_t xQueuePeekFromISR( queue_t xQueue, void * const buffer )
function queue_get_waiting (line 1903) | uint32_t queue_get_waiting(const queue_t queue)
function queue_get_available (line 1919) | uint32_t queue_get_available(const queue_t queue)
function uxQueueMessagesWaitingFromISR (line 1937) | uint32_t uxQueueMessagesWaitingFromISR( const queue_t xQueue )
function queue_delete (line 1949) | void queue_delete(queue_t queue)
function uxQueueGetQueueNumber (line 1993) | uint32_t uxQueueGetQueueNumber( queue_t xQueue )
function vQueueSetQueueNumber (line 2003) | void vQueueSetQueueNumber( queue_t xQueue, uint32_t uxQueueNumber )
function ucQueueGetQueueType (line 2013) | uint8_t ucQueueGetQueueType( queue_t xQueue )
function prvGetDisinheritPriorityAfterTimeout (line 2023) | static uint32_t prvGetDisinheritPriorityAfterTimeout( const Queue_t * co...
function prvCopyDataToQueue (line 2048) | static int32_t prvCopyDataToQueue( Queue_t * const pxQueue, const void *...
function prvCopyDataFromQueue (line 2127) | static void prvCopyDataFromQueue( Queue_t * const pxQueue, void * const ...
function prvUnlockQueue (line 2145) | static void prvUnlockQueue( Queue_t * const pxQueue )
function prvIsQueueEmpty (line 2265) | static int32_t prvIsQueueEmpty( const Queue_t *pxQueue )
function xQueueIsQueueEmptyFromISR (line 2286) | int32_t xQueueIsQueueEmptyFromISR( const queue_t xQueue )
function prvIsQueueFull (line 2304) | static int32_t prvIsQueueFull( const Queue_t *pxQueue )
function xQueueIsQueueFullFromISR (line 2325) | int32_t xQueueIsQueueFullFromISR( const queue_t xQueue )
function xQueueCRSend (line 2345) | int32_t xQueueCRSend( queue_t xQueue, const void *pvItemToQueue, uint32_...
function xQueueCRReceive (line 2422) | int32_t xQueueCRReceive( queue_t xQueue, void *buffer, uint32_t timeout )
function xQueueCRSendFromISR (line 2512) | int32_t xQueueCRSendFromISR( queue_t xQueue, const void *pvItemToQueue, ...
function xQueueCRReceiveFromISR (line 2560) | int32_t xQueueCRReceiveFromISR( queue_t xQueue, void *buffer, int32_t *p...
function vQueueAddToRegistry (line 2620) | void vQueueAddToRegistry( queue_t xQueue, const char *pcQueueName ) /*li...
function vQueueUnregisterQueue (line 2677) | void vQueueUnregisterQueue( queue_t xQueue )
function vQueueWaitForMessageRestricted (line 2709) | void vQueueWaitForMessageRestricted( queue_t xQueue, uint32_t timeout, c...
function QueueSetHandle_t (line 2745) | QueueSetHandle_t xQueueCreateSet( const uint32_t uxEventQueueLength )
function xQueueAddToSet (line 2759) | int32_t xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueS...
function xQueueRemoveFromSet (line 2792) | int32_t xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, Q...
function QueueSetMemberHandle_t (line 2828) | QueueSetMemberHandle_t xQueueSelectFromSet( QueueSetHandle_t xQueueSet, ...
function QueueSetMemberHandle_t (line 2841) | QueueSetMemberHandle_t xQueueSelectFromSetFromISR( QueueSetHandle_t xQue...
function prvNotifyQueueSetContainer (line 2854) | static int32_t prvNotifyQueueSetContainer( const Queue_t * const pxQueue...
FILE: src/rtos/rtos.cpp
type pros (line 28) | namespace pros {
function Task (line 39) | Task& Task::operator=(const task_t in) {
function Task (line 44) | Task Task::current() {
function mutex_t (line 112) | mutex_t Mutex::lazy_init() {
function mutex_t (line 155) | mutex_t RecursiveMutex::lazy_init() {
FILE: src/rtos/semphr.c
function sem_wait (line 69) | uint8_t sem_wait(sem_t sem, uint32_t timeout) {
function sem_post (line 134) | uint8_t sem_post(sem_t sem) {
function mutex_t (line 193) | mutex_t mutex_create(void) {
function mutex_give (line 197) | uint8_t mutex_give(mutex_t mutex) {
function mutex_take (line 201) | uint8_t mutex_take(mutex_t mutex, uint32_t timeout) {
function mutex_delete (line 205) | void mutex_delete(mutex_t mutex){
function sem_t (line 266) | sem_t sem_binary_create(void) {
function mutex_t (line 333) | mutex_t mutex_recursive_create(void) {
function mutex_recursive_give (line 419) | uint8_t mutex_recursive_give(mutex_t mutex) {
function mutex_recursive_take (line 514) | uint8_t mutex_recursive_take(mutex_t mutex, uint32_t timeout) {
function sem_t (line 518) | sem_t sem_create(uint32_t max_count, uint32_t init_count) {
function sem_delete (line 522) | void sem_delete(sem_t sem) {
function task_t (line 526) | task_t mutex_get_owner(mutex_t mutex) {
function sem_get_count (line 530) | uint32_t sem_get_count(sem_t sem) {
function mutex_t (line 534) | mutex_t mutex_create_static(static_sem_s_t* pxMutexBuffer) {
function sem_t (line 538) | sem_t sem_create_static(uint32_t max_count, uint32_t init_count, static_...
FILE: src/rtos/stream_buffer.c
type StreamBuffer_t (line 141) | typedef struct xSTREAM_BUFFER /*lint !e9058 Style convention uses tag. */
function stream_buf_t (line 219) | stream_buf_t xStreamBufferGenericCreate( size_t xBufferSizeBytes, size_t...
function stream_buf_t (line 271) | stream_buf_t xStreamBufferGenericCreateStatic( size_t xBufferSizeBytes,
function vStreamBufferDelete (line 335) | void vStreamBufferDelete( stream_buf_t xStreamBuffer )
function stream_buf_reset (line 368) | int32_t stream_buf_reset( stream_buf_t xStreamBuffer )
function stream_buf_set_trigger (line 422) | int32_t stream_buf_set_trigger( stream_buf_t xStreamBuffer, size_t xTrig...
function stream_buf_get_unused (line 451) | size_t stream_buf_get_unused( stream_buf_t xStreamBuffer )
function stream_buf_get_used (line 475) | size_t stream_buf_get_used( stream_buf_t xStreamBuffer )
function stream_buf_send (line 487) | size_t stream_buf_send( stream_buf_t xStreamBuffer,
function xStreamBufferSendFromISR (line 590) | size_t xStreamBufferSendFromISR( stream_buf_t xStreamBuffer,
function prvWriteMessageToBuffer (line 641) | static size_t prvWriteMessageToBuffer( StreamBuffer_t * const pxStreamBu...
function stream_buf_recv (line 697) | size_t stream_buf_recv( stream_buf_t xStreamBuffer,
function xStreamBufferReceiveFromISR (line 801) | size_t xStreamBufferReceiveFromISR( stream_buf_t xStreamBuffer,
function prvReadMessageFromBuffer (line 858) | static size_t prvReadMessageFromBuffer( StreamBuffer_t *pxStreamBuffer,
function stream_buf_is_empty (line 912) | int32_t stream_buf_is_empty( stream_buf_t xStreamBuffer )
function stream_buf_is_full (line 935) | int32_t stream_buf_is_full( stream_buf_t xStreamBuffer )
function xStreamBufferSendCompletedFromISR (line 970) | int32_t xStreamBufferSendCompletedFromISR( stream_buf_t xStreamBuffer, i...
function xStreamBufferReceiveCompletedFromISR (line 1000) | int32_t xStreamBufferReceiveCompletedFromISR( stream_buf_t xStreamBuffer...
function prvWriteBytesToBuffer (line 1030) | static size_t prvWriteBytesToBuffer( StreamBuffer_t * const pxStreamBuff...
function prvReadBytesFromBuffer (line 1076) | static size_t prvReadBytesFromBuffer( StreamBuffer_t *pxStreamBuffer, ui...
function prvBytesInBuffer (line 1131) | static size_t prvBytesInBuffer( const StreamBuffer_t * const pxStreamBuf...
function prvInitialiseNewStreamBuffer (line 1151) | static void prvInitialiseNewStreamBuffer( StreamBuffer_t * const pxStrea...
function uxStreamBufferGetStreamBufferNumber (line 1183) | uint32_t uxStreamBufferGetStreamBufferNumber( stream_buf_t xStreamBuffer )
function vStreamBufferSetStreamBufferNumber (line 1193) | void vStreamBufferSetStreamBufferNumber( stream_buf_t xStreamBuffer, uin...
function ucStreamBufferGetStreamBufferType (line 1203) | uint8_t ucStreamBufferGetStreamBufferType( stream_buf_t xStreamBuffer )
FILE: src/rtos/task_notify_when_deleting.c
type notify_delete_action (line 19) | struct notify_delete_action {
type _find_task_args (line 25) | struct _find_task_args {
function _find_task_cb (line 30) | static void _find_task_cb(ll_node_s_t* node, void* extra) {
type notify_delete_action (line 39) | struct notify_delete_action
type _find_task_args (line 40) | struct _find_task_args
function task_notify_when_deleting_init (line 49) | void task_notify_when_deleting_init() {
function task_notify_when_deleting (line 53) | void task_notify_when_deleting(task_t target_task, task_t task_to_notify,
function unsubscribe_hook_cb (line 143) | static void unsubscribe_hook_cb(ll_node_s_t* node, void* task_to_remove) {
function delete_hook_cb (line 152) | static void delete_hook_cb(ll_node_s_t* node, void* ignore) {
function task_notify_when_deleting_hook (line 161) | void task_notify_when_deleting_hook(task_t task) {
FILE: src/rtos/tasks.c
function task_t (line 504) | task_t task_create_static( task_fn_t task_code, void* const param,
function task_t (line 566) | task_t task_create(task_fn_t function,
function prvInitialiseNewTask (line 657) | static void prvInitialiseNewTask( task_fn_t pxTaskCode,
function prvAddNewTaskToReadyList (line 828) | static void prvAddNewTaskToReadyList( TCB_t *pxNewTCB )
function task_delete (line 913) | void task_delete(task_t task)
function task_finish_termination (line 1004) | void task_finish_termination(TCB_t* pxTCB)
function task_delay_until (line 1035) | void task_delay_until(uint32_t* const prev_time, const uint32_t delta)
function task_delay (line 1121) | void task_delay(const uint32_t milliseconds)
function delay (line 1161) | void delay(const uint32_t milliseconds)
function task_state_e_t (line 1171) | task_state_e_t task_get_state(task_t task)
function task_get_priority (line 1242) | uint32_t task_get_priority(task_t task)
function uxTaskPriorityGetFromISR (line 1264) | uint32_t uxTaskPriorityGetFromISR( task_t task )
function task_set_priority (line 1304) | void task_set_priority(task_t task, uint32_t prio)
function task_suspend (line 1468) | void task_suspend(task_t task)
function prvTaskIsTaskSuspended (line 1569) | static int32_t prvTaskIsTaskSuspended( const task_t task )
function task_resume (line 1615) | void task_resume(task_t task)
function xTaskResumeFromISR (line 1669) | int32_t xTaskResumeFromISR( task_t task )
function rtos_sched_start (line 1739) | void rtos_sched_start( void )
function rtos_sched_stop (line 1858) | void rtos_sched_stop( void )
function rtos_suspend_all (line 1869) | void rtos_suspend_all( void )
function prvGetExpectedIdleTime (line 1881) | static uint32_t prvGetExpectedIdleTime( void )
function rtos_resume_all (line 1942) | int32_t rtos_resume_all( void )
function millis (line 2052) | uint32_t millis(void)
function micros (line 2066) | uint64_t micros(void)
function xTaskGetTickCountFromISR (line 2072) | uint32_t xTaskGetTickCountFromISR( void )
function task_get_count (line 2103) | uint32_t task_get_count(void)
function TCB_t (line 2125) | static TCB_t *prvSearchForNameWithinSingleList( List_t *pxList, const ch...
function task_t (line 2186) | task_t task_get_by_name(const char* name) /*lint !e971 Unqualified char ...
function uxTaskGetSystemState (line 2251) | uint32_t uxTaskGetSystemState( TaskStatus_t * const pxTaskStatusArray, c...
function task_t (line 2325) | task_t xTaskGetIdleTaskHandle( void )
function vTaskStepTick (line 2342) | void vTaskStepTick( const uint32_t xTicksToJump )
function task_abort_delay (line 2357) | int32_t task_abort_delay(task_t task)
function xTaskIncrementTick (line 2431) | int32_t xTaskIncrementTick( void )
function vTaskSetApplicationTaskTag (line 2605) | void vTaskSetApplicationTaskTag( task_t task, TaskHookFunction_t pxHookF...
function TaskHookFunction_t (line 2632) | TaskHookFunction_t xTaskGetApplicationTaskTag( task_t task )
function xTaskCallApplicationTaskHook (line 2663) | int32_t xTaskCallApplicationTaskHook( task_t task, void *pvParameter )
function vTaskSwitchContext (line 2693) | void vTaskSwitchContext( void )
function vTaskPlaceOnEventList (line 2752) | void vTaskPlaceOnEventList( List_t * const pxEventList, const uint32_t t...
function vTaskPlaceOnUnorderedEventList (line 2769) | void vTaskPlaceOnUnorderedEventList( List_t * pxEventList, const uint32_...
function vTaskPlaceOnEventListRestricted (line 2795) | void vTaskPlaceOnEventListRestricted( List_t * const pxEventList, uint32...
function xTaskRemoveFromEventList (line 2826) | int32_t xTaskRemoveFromEventList( const List_t * const pxEventList )
function vTaskRemoveFromUnorderedEventList (line 2894) | void vTaskRemoveFromUnorderedEventList( list_item_t * pxEventListItem, c...
function vTaskSetTimeOutState (line 2928) | void vTaskSetTimeOutState( TimeOut_t * const pxTimeOut )
function vTaskInternalSetTimeOutState (line 2940) | void vTaskInternalSetTimeOutState( TimeOut_t * const pxTimeOut )
function xTaskCheckForTimeOut (line 2948) | int32_t xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, uint32_t * co...
function vTaskMissedYield (line 3011) | void vTaskMissedYield( void )
function uxTaskGetTaskNumber (line 3019) | uint32_t uxTaskGetTaskNumber( task_t task )
function vTaskSetTaskNumber (line 3042) | void vTaskSetTaskNumber( task_t task, const uint32_t uxHandle )
function eSleepModeStatus (line 3185) | eSleepModeStatus eTaskConfirmSleepModeStatus( void )
function vTaskSetThreadLocalStoragePointer (line 3225) | void vTaskSetThreadLocalStoragePointer( task_t xTaskToSet, int32_t xInde...
function prvInitialiseTaskLists (line 3262) | static void prvInitialiseTaskLists( void )
function prvCheckTasksWaitingTermination (line 3294) | static void prvCheckTasksWaitingTermination( void )
function vTaskGetInfo (line 3325) | void vTaskGetInfo( task_t task, TaskStatus_t *pxTaskStatus, int32_t xGet...
function prvListTasksWithinSingleList (line 3421) | static uint32_t prvListTasksWithinSingleList( TaskStatus_t *pxTaskStatus...
function prvTaskCheckFreeStackSpace (line 3454) | static uint16_t prvTaskCheckFreeStackSpace( const uint8_t * pucStackByte )
function uxTaskGetStackHighWaterMark (line 3474) | uint32_t uxTaskGetStackHighWaterMark( task_t task )
function prvDeleteTCB (line 3502) | static void prvDeleteTCB( TCB_t *pxTCB )
function prvResetNextTaskUnblockTime (line 3556) | static void prvResetNextTaskUnblockTime( void )
function task_t (line 3582) | task_t task_get_current( void )
function xTaskGetSchedulerState (line 3599) | int32_t xTaskGetSchedulerState( void )
function xTaskPriorityInherit (line 3627) | int32_t xTaskPriorityInherit( task_t const pxMutexHolder )
function xTaskPriorityDisinherit (line 3714) | int32_t xTaskPriorityDisinherit( task_t const pxMutexHolder )
function vTaskPriorityDisinheritAfterTimeout (line 3794) | void vTaskPriorityDisinheritAfterTimeout( task_t const pxMutexHolder, ui...
function vTaskEnterCritical (line 3896) | void vTaskEnterCritical( void )
function vTaskExitCritical (line 3926) | void vTaskExitCritical( void )
function vTaskList (line 3985) | void vTaskList( char * pcWriteBuffer )
function vTaskGetRunTimeStats (line 4083) | void vTaskGetRunTimeStats( char *pcWriteBuffer )
function uxTaskResetEventItemValue (line 4208) | uint32_t uxTaskResetEventItemValue( void )
function task_notify_take (line 4241) | uint32_t task_notify_take(bool clear_on_exit, uint32_t timeout)
function task_notify_wait (line 4309) | int32_t task_notify_wait( uint32_t ulBitsToClearOnEntry, uint32_t ulBits...
function task_notify_ext (line 4389) | int32_t task_notify_ext(task_t task, uint32_t value, notify_action_e_t a...
function xTaskGenericNotifyFromISR (line 4495) | int32_t xTaskGenericNotifyFromISR( task_t task, uint32_t value, notify_a...
function vTaskNotifyGiveFromISR (line 4619) | void vTaskNotifyGiveFromISR( task_t task, int32_t *pxHigherPriorityTaskW...
function task_notify_clear (line 4708) | int32_t task_notify_clear(task_t task)
function task_notify (line 4741) | int32_t task_notify(task_t task) {
function task_join (line 4752) | void task_join(task_t task) {
function prvAddCurrentTaskToDelayedList (line 4768) | static void prvAddCurrentTaskToDelayedList( uint32_t timeout, const int3...
function freertos_tasks_c_additions_init (line 4892) | static void freertos_tasks_c_additions_init( void )
FILE: src/rtos/timers.c
type xTIMER (line 68) | typedef struct tmrTimerControl
type xTIMER (line 87) | typedef xTIMER Timer_t;
type TimerParameter_t (line 94) | typedef struct tmrTimerParameters
type CallbackParameters_t (line 101) | typedef struct tmrCallbackParameters
type DaemonTaskMessage_t (line 110) | typedef struct tmrTimerQueueMessage
function xTimerCreateTimerTask (line 223) | int32_t xTimerCreateTimerTask( void )
function TimerHandle_t (line 278) | TimerHandle_t xTimerCreate( const char * const pcTimerName, /*lint !e9...
function TimerHandle_t (line 310) | TimerHandle_t xTimerCreateStatic( const char * const pcTimerName, /*lin...
function prvInitialiseNewTimer (line 352) | static void prvInitialiseNewTimer( const char * const pcTimerName, /*l...
function xTimerGenericCommand (line 381) | int32_t xTimerGenericCommand( TimerHandle_t xTimer, const int32_t xComma...
function task_t (line 424) | task_t xTimerGetTimerDaemonTaskHandle( void )
function xTimerGetPeriod (line 433) | uint32_t xTimerGetPeriod( TimerHandle_t xTimer )
function xTimerGetExpiryTime (line 442) | uint32_t xTimerGetExpiryTime( TimerHandle_t xTimer )
function prvProcessExpiredTimer (line 462) | static void prvProcessExpiredTimer( const uint32_t xNextExpireTime, cons...
function prvTimerTask (line 502) | static void prvTimerTask( void *pvParameters )
function prvProcessTimerOrBlockTask (line 538) | static void prvProcessTimerOrBlockTask( const uint32_t xNextExpireTime, ...
function prvGetNextExpireTime (line 598) | static uint32_t prvGetNextExpireTime( int32_t * const pxListWasEmpty )
function prvSampleTimeNow (line 624) | static uint32_t prvSampleTimeNow( int32_t * const pxTimerListsWereSwitch...
function prvInsertTimerInActiveList (line 647) | static int32_t prvInsertTimerInActiveList( Timer_t * const pxTimer, cons...
function prvProcessReceivedCommands (line 688) | static void prvProcessReceivedCommands( void )
function prvSwitchTimerLists (line 835) | static void prvSwitchTimerLists( void )
function prvCheckForValidListAndQueue (line 894) | static void prvCheckForValidListAndQueue( void )
function xTimerIsTimerActive (line 945) | int32_t xTimerIsTimerActive( TimerHandle_t xTimer )
function vTimerSetTimerID (line 983) | void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID )
function xTimerPendFunctionCallFromISR (line 999) | int32_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend,...
function xTimerPendFunctionCall (line 1023) | int32_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *...
function uxTimerGetTimerNumber (line 1052) | uint32_t uxTimerGetTimerNumber( TimerHandle_t xTimer )
function vTimerSetTimerNumber (line 1062) | void vTimerSetTimerNumber( TimerHandle_t xTimer, uint32_t uxTimerNumber )
FILE: src/system/cpp_support.cpp
function task_fn_wrapper (line 22) | void task_fn_wrapper(task_fn_t fn, void* args) {
function autonomous (line 48) | __attribute__((weak)) void autonomous() {}
function initialize (line 49) | __attribute__((weak)) void initialize() {}
function opcontrol (line 50) | __attribute__((weak)) void opcontrol() {}
function disabled (line 51) | __attribute__((weak)) void disabled() {}
function competition_initialize (line 52) | __attribute__((weak)) void competition_initialize() {}
function cpp_autonomous (line 54) | void cpp_autonomous() {
function cpp_initialize (line 57) | void cpp_initialize() {
function cpp_opcontrol (line 60) | void cpp_opcontrol() {
function cpp_disabled (line 63) | void cpp_disabled() {
function cpp_competition_initialize (line 66) | void cpp_competition_initialize() {
FILE: src/system/dev/dev_driver.c
type dev_file_arg_t (line 34) | typedef struct dev_file_arg {
function dev_read_r (line 42) | int dev_read_r(struct _reent* r, void* const arg, uint8_t* buffer, const...
function dev_write_r (line 63) | int dev_write_r(struct _reent* r, void* const arg, const uint8_t* buf, c...
function dev_close_r (line 85) | int dev_close_r(struct _reent* r, void* const arg) {
function dev_fstat_r (line 89) | int dev_fstat_r(struct _reent* r, void* const arg, struct stat* st) {
function dev_isatty_r (line 95) | int dev_isatty_r(struct _reent* r, void* const arg) {
function off_t (line 100) | off_t dev_lseek_r(struct _reent* r, void* const arg, off_t ptr, int dir) {
function dev_ctl (line 106) | int dev_ctl(void* const arg, const uint32_t cmd, void* const extra_arg) {
type fs_driver (line 125) | struct fs_driver
type fs_driver (line 133) | struct fs_driver
function dev_open_r (line 135) | int dev_open_r(struct _reent* r, const char* path, int flags, int mode) {
FILE: src/system/dev/file_system_stubs.c
function chdir (line 20) | int chdir(const char* path) {
function mkdir (line 25) | int mkdir(const char* pathname, mode_t mode) {
function chmod (line 30) | int chmod(const char* pathname, mode_t mode) {
function fchmod (line 35) | int fchmod(int fd, mode_t mode) {
function fchmodat (line 40) | int fchmodat(int dirfd, const char* pathname, mode_t mode, int flags) {
function pathconf (line 45) | long pathconf(const char* path, int name) {
function _unlink (line 55) | int _unlink(const char* name) {
function _link (line 60) | int _link(const char* old, const char* new) {
function _stat (line 65) | int _stat(const char* file, struct stat* st) {
function symlink (line 70) | int symlink(const char* file, const char* linkpath) {
function readlink (line 75) | ssize_t readlink(const char* pathname, char* buf, size_t bufsiz) {
function truncate (line 80) | int truncate(const char* path, off_t length) {
FILE: src/system/dev/ser_daemon.c
function enable_banner (line 35) | void enable_banner(bool enabled) {
function print_small_banner (line 39) | void print_small_banner(void) {
function print_large_banner (line 48) | void print_large_banner(void) {
function inp_buffer_initialize (line 72) | static inline void inp_buffer_initialize() {
function inp_buffer_post (line 78) | bool inp_buffer_post(uint8_t b) {
function inp_buffer_read (line 82) | int32_t inp_buffer_read(uint32_t timeout) {
function inp_buffer_available (line 96) | int32_t inp_buffer_available() {
function vex_read_char (line 106) | static inline uint8_t vex_read_char() {
function ser_daemon_task (line 117) | static void ser_daemon_task(void* ign) {
function ser_initialize (line 195) | void ser_initialize(void) {
FILE: src/system/dev/ser_driver.c
type ser_file_s_t (line 33) | typedef struct ser_file_arg {
type set (line 74) | struct set
function ser_output_flush (line 102) | void ser_output_flush(void) {
function ser_output_write (line 110) | bool ser_output_write(const uint8_t* buffer, size_t size, bool noblock) {
function ser_read_r (line 117) | int ser_read_r(struct _reent* r, void* const arg, uint8_t* buffer, const...
function ser_write_r (line 149) | int ser_write_r(struct _reent* r, void* const arg, const uint8_t* buf, c...
function ser_close_r (line 198) | int ser_close_r(struct _reent* r, void* const arg) {
function ser_fstat_r (line 203) | int ser_fstat_r(struct _reent* r, void* const arg, struct stat* st) {
function ser_isatty_r (line 209) | int ser_isatty_r(struct _reent* r, void* const arg) {
function off_t (line 214) | off_t ser_lseek_r(struct _reent* r, void* const arg, off_t ptr, int dir) {
function ser_ctl (line 220) | int ser_ctl(void* const arg, const uint32_t cmd, void* const extra_arg) {
type fs_driver (line 248) | struct fs_driver
type fs_driver (line 256) | struct fs_driver
function ser_open_r (line 258) | int ser_open_r(struct _reent* r, const char* path, int flags, int mode) {
function serctl (line 295) | int32_t serctl(const uint32_t action, void* const extra_arg) {
function ser_driver_initialize (line 327) | void ser_driver_initialize(void) {
FILE: src/system/dev/usd_driver.c
type usd_file_arg_t (line 28) | typedef struct usd_file_arg {
type fa_flags (line 35) | enum fa_flags {
function usd_read_r (line 46) | int usd_read_r(struct _reent* r, void* const arg, uint8_t* buffer, const...
function usd_write_r (line 53) | int usd_write_r(struct _reent* r, void* const arg, const uint8_t* buf, c...
function usd_close_r (line 62) | int usd_close_r(struct _reent* r, void* const arg) {
function usd_fstat_r (line 68) | int usd_fstat_r(struct _reent* r, void* const arg, struct stat* st) {
function usd_isatty_r (line 74) | int usd_isatty_r(struct _reent* r, void* const arg) {
function off_t (line 78) | off_t usd_lseek_r(struct _reent* r, void* const arg, off_t ptr, int dir) {
function usd_ctl (line 89) | int usd_ctl(void* const arg, const uint32_t cmd, void* const extra_arg) {
type fs_driver (line 97) | struct fs_driver
type fs_driver (line 104) | struct fs_driver
function usd_open_r (line 106) | int usd_open_r(struct _reent* r, const char* path, int flags, int mode) {
FILE: src/system/dev/vfs.c
type gid_metadata (line 45) | struct gid_metadata
type file_entry (line 51) | struct file_entry
function vfs_initialize (line 53) | void vfs_initialize(void) {
function vfs_add_entry_r (line 64) | int vfs_add_entry_r(struct _reent* r, struct fs_driver const* const driv...
function vfs_update_entry (line 78) | int vfs_update_entry(int file, struct fs_driver const* const driver, voi...
function _open (line 92) | int _open(const char* file, int flags, int mode) {
function _write (line 117) | ssize_t _write(int file, const void* buf, size_t len) {
function _read (line 127) | ssize_t _read(int file, void* buf, size_t len) {
function _close (line 137) | int _close(int file) {
function _fstat (line 157) | int _fstat(int file, struct stat* st) {
function off_t (line 167) | off_t _lseek(int file, off_t ptr, int dir) {
function _isatty (line 177) | int _isatty(int file) {
function fdctl (line 187) | int32_t fdctl(int file, const uint32_t action, void* const extra_arg) {
FILE: src/system/envlock.c
function __env_lock (line 18) | void __env_lock(void) {
function __env_unlock (line 22) | void __env_unlock(void) {
FILE: src/system/hot.c
type hot_table (line 6) | struct hot_table
type hot_table (line 7) | struct hot_table
function install_hot_table (line 35) | __attribute__((section(".hot_init"))) void install_hot_table(struct hot_...
function invoke_install_hot_table (line 79) | void invoke_install_hot_table() {
function get_timestamp_int (line 94) | static const int get_timestamp_int(void) {
FILE: src/system/mlock.c
function __malloc_lock (line 18) | void __malloc_lock(void) {
function __malloc_unlock (line 22) | void __malloc_unlock(void) {
FILE: src/system/newlib_stubs.c
function _exit (line 33) | void _exit(int status) {
function usleep (line 49) | int usleep( useconds_t period ) {
function sleep (line 61) | unsigned sleep( unsigned period ) {
function getentropy (line 66) | int getentropy(void *_buffer, size_t _length) {
function __sync_synchronize (line 75) | void __sync_synchronize(void) {
type timespec (line 86) | struct timespec
function clock_settime (line 89) | int clock_settime(clockid_t clock_id, const struct timespec *tp) {
function clock_gettime (line 110) | int clock_gettime(clockid_t clock_id, struct timespec* tp) {
function set_get_timestamp_int_func (line 159) | void set_get_timestamp_int_func(const int (*func)(void))
function _gettimeofday (line 164) | int _gettimeofday(struct timeval* tp, void* tzvp) {
FILE: src/system/newlib_stubs_support.cpp
function flush_output_streams (line 5) | void flush_output_streams() {
FILE: src/system/rtos_hooks.c
function FIQInterrupt (line 26) | void FIQInterrupt() {
function DataAbortInterrupt (line 30) | void DataAbortInterrupt() {
function PrefetchAbortInterrupt (line 46) | void PrefetchAbortInterrupt() {
function _boot (line 62) | void _boot() {
function rtos_initialize (line 67) | void rtos_initialize() {
function rtos_tick_interrupt_config (line 79) | void rtos_tick_interrupt_config() {
function rtos_tick_interrupt_clear (line 84) | void rtos_tick_interrupt_clear() {
function vApplicationFPUSafeIRQHandler (line 88) | void vApplicationFPUSafeIRQHandler(uint32_t ulICCIAR) {
function vInitialiseTimerForRunTimeStats (line 92) | void vInitialiseTimerForRunTimeStats(void) {
function vApplicationMallocFailedHook (line 96) | void vApplicationMallocFailedHook(void) {
function vApplicationStackOverflowHook (line 108) | void vApplicationStackOverflowHook(task_t pxTask, char* pcTaskName) {
function vApplicationIdleHook (line 124) | void vApplicationIdleHook(void) {
function vAssertCalled (line 140) | void vAssertCalled(const char* pcFile, unsigned long ulLine) {
function vApplicationGetIdleTaskMemory (line 163) | void vApplicationGetIdleTaskMemory(static_task_s_t** ppxIdleTaskTCBBuffe...
function vApplicationGetTimerTaskMemory (line 188) | void vApplicationGetTimerTaskMemory(static_task_s_t** ppxTimerTaskTCBBuf...
function memcmp (line 266) | int memcmp(const void *pvMem1, const void *pvMem2, size_t ulBytes) {
FILE: src/system/startup.c
function display_initialize (line 25) | extern __attribute__((weak)) void display_initialize(void) {}
function pros_init (line 37) | __attribute__((constructor(102))) static void pros_init(void) {
function main (line 57) | int main() {
FILE: src/system/system_daemon.c
type state_task (line 40) | enum state_task { E_OPCONTROL_TASK = 0, E_AUTON_TASK, E_DISABLED_TASK, E...
function do_background_operations (line 49) | static inline void do_background_operations() {
function _system_daemon_task (line 59) | static void _system_daemon_task(void* ign) {
function system_daemon_initialize (line 125) | void system_daemon_initialize() {
FILE: src/system/unwind.c
type core_regs (line 47) | struct core_regs {
type phase2_vrs (line 51) | struct phase2_vrs {
type phase2_vrs (line 57) | struct phase2_vrs
function print_phase2_vrs (line 65) | static inline void print_phase2_vrs(struct phase2_vrs* vrs) {
type __EIT_entry (line 79) | struct __EIT_entry {
type __EIT_entry (line 84) | struct __EIT_entry
type __EIT_entry (line 85) | struct __EIT_entry
function _Unwind_Ptr (line 88) | _Unwind_Ptr __gnu_Unwind_Find_exidx(_Unwind_Ptr pc, int* nrec) {
type trace_t (line 99) | struct trace_t {
function _Unwind_Reason_Code (line 105) | _Unwind_Reason_Code trace_fn(_Unwind_Context* unwind_ctx, void* d) {
function p2vrs_from_data_abort (line 134) | __attribute__((target("arm")))
function report_fatal_error (line 155) | void report_fatal_error(uint32_t _sp, const char* error_name) {
function p2vrs_from_task (line 218) | static inline struct phase2_vrs p2vrs_from_task(task_t task) {
function backtrace_task (line 260) | void backtrace_task(task_t task) {
FILE: src/tests/adi.cpp
function opcontrol (line 17) | void opcontrol() {
FILE: src/tests/basic_test.c
function my_task (line 3) | void my_task(void* ign) {
function my_task2 (line 10) | void my_task2(void* ign) {
function opcontrol (line 20) | void opcontrol() {
FILE: src/tests/basic_test.cpp
function my_task (line 4) | void my_task(void* str) {
function opcontrol (line 13) | void opcontrol() {
FILE: src/tests/errno_reentrancy.c
function task_a_fn (line 5) | void task_a_fn(void* ign) {
function task_b_fn (line 15) | void task_b_fn(void* ign) {
function test_errno_reentrancy (line 22) | void test_errno_reentrancy() {
FILE: src/tests/exceptions.cpp
function throw_it (line 9) | void throw_it() {
function test_exceptions (line 13) | void test_exceptions() {
FILE: src/tests/ext_adi.cpp
function opcontrol (line 14) | void opcontrol() {
FILE: src/tests/generic_serial.cpp
function verbose_printf (line 27) | void verbose_printf(const char *format, ...) {
function test_send_recv_byte (line 36) | bool test_send_recv_byte(const uint32_t interval, const uint32_t bytes) {
function test_send_recv_block (line 88) | bool test_send_recv_block() {
function set_baudrate (line 145) | void set_baudrate(const int32_t baudrate) {
function flush (line 151) | void flush() {
function init_ports (line 157) | void init_ports(uint8_t write_port, uint8_t recv_port) {
function run_tests (line 166) | bool run_tests() {
function opcontrol (line 183) | void opcontrol() {
FILE: src/tests/generic_serial_file.cpp
function verbose_printf (line 29) | void verbose_printf(const char *format, ...) {
function test_send_recv_byte (line 38) | bool test_send_recv_byte(const uint32_t interval, const uint32_t bytes) {
function test_send_recv_block (line 91) | bool test_send_recv_block() {
function set_baudrate (line 150) | void set_baudrate(const int32_t baudrate) {
function flush (line 156) | void flush() {
function init_ports (line 162) | void init_ports(uint8_t write_port, uint8_t recv_port) {
function run_tests (line 175) | bool run_tests() {
function opcontrol (line 192) | void opcontrol() {
FILE: src/tests/gyro.c
function opcontrol (line 17) | void opcontrol() {
FILE: src/tests/gyro.cpp
function opcontrol (line 17) | void opcontrol() {
FILE: src/tests/mutexes.c
function test_mutex (line 1) | void test_mutex() {
FILE: src/tests/pnuematics.cpp
function on_center_button (line 10) | void on_center_button() {
function initialize (line 26) | void initialize() {
function disabled (line 39) | void disabled() {}
function competition_initialize (line 50) | void competition_initialize() {}
function autonomous (line 63) | void autonomous() {}
function opcontrol (line 78) | void opcontrol() {
FILE: src/tests/rtos_function_linking.c
function x (line 18) | void x(void* ign) {}
function test_all (line 19) | void test_all() {
FILE: src/tests/segfault.cpp
function thing_1 (line 3) | [[gnu::noinline]] static void thing_1(uint8_t i) {
function initialize (line 21) | void initialize() {
function disabled (line 26) | void disabled() {}
function competition_initialize (line 28) | void competition_initialize() {}
function autonomous (line 30) | void autonomous() {}
function opcontrol (line 32) | void opcontrol() {}
FILE: src/tests/simple_names.c
function opcontrol (line 18) | void opcontrol() {
FILE: src/tests/simple_names.cpp
function opcontrol (line 18) | void opcontrol() {
FILE: src/tests/static_tast_states.c
function myTask (line 16) | void myTask(void* ign) {
function myStaticTask (line 28) | void myStaticTask(void* ign) {
function opcontrol (line 40) | void opcontrol() {
FILE: src/tests/task_notify_when_deleting.c
function target_task (line 4) | void target_task(void* ignore) {
function notify_task (line 10) | void notify_task(void* ignore) {
function opcontrol (line 16) | void opcontrol() {
FILE: src/tests/vision_test.cpp
function opcontrol (line 3) | void opcontrol() {
Condensed preview — 204 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (2,381K chars).
[
{
"path": ".arcconfig",
"chars": 254,
"preview": "{\n\t\"phabricator.uri\": \"https://phabricator.purduesigbots.com/\",\n\t\"repoistory.callsign\": \"rRESTRICTEDPROS\",\n\t\"lint.engine"
},
{
"path": ".arclint",
"chars": 511,
"preview": "{\n\t\"linters\": {\n\t\t\"clang-format\": {\n\t\t\t\"type\": \"clang-format\",\n\t\t\t\"include\": \"(.*\\\\.(c|cpp|h|hpp)$)\",\n\t\t\t\"exclude\": \"(^("
},
{
"path": ".clang-format",
"chars": 365,
"preview": "BasedOnStyle: Google\nTabWidth: 2\nLanguage: Cpp\nUseTab: ForIndentation\nColumnLimit: 120\nStandard: Cpp11\nDerivePointerAlig"
},
{
"path": ".github/CONTRIBUTING.md",
"chars": 2774,
"preview": "# Contributing to PROS\n\n:tada: :+1: :steam_locomotive: Thanks for taking the time to contribute! :steam_locomotive: :+1:"
},
{
"path": ".github/ISSUE_TEMPLATE.md",
"chars": 544,
"preview": "#### Expected Behavior:\n<!-- Describe what you expected to happen -->\n\n#### Actual Behavior:\n<!-- Describe what actually"
},
{
"path": ".github/PULL_REQUEST_TEMPLATE.md",
"chars": 414,
"preview": "#### Summary:\n<!-- Provide a concise description of your changes -->\n\n#### Motivation:\n<!-- Provide a brief description "
},
{
"path": ".gitignore",
"chars": 154,
"preview": ".vscode/\n.idea/\nbin/\n.*.sw*\ntemplate/\nversion\ncquery_log.txt\ncompile_commands.json\n.ccls-cache/\n.ccls\ntemp.log\ntemp.erro"
},
{
"path": ".gitmodules",
"chars": 123,
"preview": "[submodule \"firmware/libv5rts\"]\n\tpath = firmware/libv5rts\n\turl = git@github.com:purduesigbots/libv5rts.git\n\tignore = dir"
},
{
"path": "LICENSE",
"chars": 16955,
"preview": "PROS 4.0 contains modified or linked source code from the following packages:\n - FreeRTOS (src/rtos/LICENSE)\n\nUnless "
},
{
"path": "Makefile",
"chars": 4231,
"preview": "################################################################################\n######################### User configur"
},
{
"path": "README.md",
"chars": 4652,
"preview": "# PROS Kernel for the VEX V5 Brain\n\n[\n *\n * This file should not be modi"
},
{
"path": "include/pros/colors.hpp",
"chars": 4738,
"preview": "/**\n * \\file pros/colors.hpp\n *\n * Contains enum class definitions of colors\n *\n * This file should not be modified by u"
},
{
"path": "include/pros/device.h",
"chars": 2495,
"preview": "/**\n * \\file pros/device.h\n *\n * Contains functions for interacting with VEX devices.\n *\n *\n *\n * This file should not b"
},
{
"path": "include/pros/device.hpp",
"chars": 5056,
"preview": "/**\n * \\file pros/device.hpp\n *\n * Base class for all smart devices.\n *\n * This file should not be modified by users, si"
},
{
"path": "include/pros/distance.h",
"chars": 4025,
"preview": "/**\n * \\file pros/distance.h\n * \\ingroup c-distance\n *\n * Contains prototypes for functions related to the VEX Distance "
},
{
"path": "include/pros/distance.hpp",
"chars": 6628,
"preview": "/**\n * \\file pros/distance.hpp\n * \\ingroup cpp-distance\n *\n * Contains prototypes for the V5 Distance Sensor-related fun"
},
{
"path": "include/pros/error.h",
"chars": 1010,
"preview": "/**\n * \\file pros/error.h\n *\n * Contains macro definitions for return types, mostly errors\n *\n * This file should not be"
},
{
"path": "include/pros/ext_adi.h",
"chars": 42913,
"preview": "/**\n * \\file pros/ext_adi.h\n * \\ingroup ext-adi\n *\n * Contains prototypes for interfacing with the 3-Wire Expander.\n *\n "
},
{
"path": "include/pros/gps.h",
"chars": 22931,
"preview": "/**\n * \\file pros/gps.h\n * \\ingroup c-gps\n *\n * Contains prototypes for functions related to the VEX GPS.\n *\n * This fil"
},
{
"path": "include/pros/gps.hpp",
"chars": 26731,
"preview": "/**\n * \\file pros/gps.hpp\n * \\ingroup cpp-gps\n *\n * Contains prototypes for functions related to the VEX GPS.\n *\n * This"
},
{
"path": "include/pros/imu.h",
"chars": 27464,
"preview": "/**\n * \\file pros/imu.h\n * \\ingroup c-imu\n *\n * Contains prototypes for functions related to the VEX Inertial sensor.\n *"
},
{
"path": "include/pros/imu.hpp",
"chars": 29816,
"preview": "/**\n * \\file pros/imu.hpp\n * \\ingroup cpp-imu\n *\n * Contains prototypes for functions related to the VEX Inertial sensor"
},
{
"path": "include/pros/link.h",
"chars": 12811,
"preview": "/**\n * \\file pros/link.h\n * \\ingroup c-link\n *\n * Contains prototypes for functions related to the robot to robot commun"
},
{
"path": "include/pros/link.hpp",
"chars": 9201,
"preview": "/**\n * \\file pros/link.hpp\n * \\ingroup cpp-link\n *\n * Contains prototypes for functions related to robot to robot commun"
},
{
"path": "include/pros/llemu.h",
"chars": 1835,
"preview": "#ifndef _PROS_LLEMU_H_\n#define _PROS_LLEMU_H_\n\n// TODO:? Should there be weak symbols for the C api in here as well?\n\n#i"
},
{
"path": "include/pros/llemu.hpp",
"chars": 5255,
"preview": "/**\n * \\file pros/llemu.hpp\n * \\ingroup cpp-llemu\n * \n * Legacy LCD Emulator\n *\n * \\details This file defines a high-lev"
},
{
"path": "include/pros/misc.h",
"chars": 26370,
"preview": "/**\n * \\file pros/misc.h\n * \\ingroup c-misc\n *\n * Contains prototypes for miscellaneous functions pertaining to the cont"
},
{
"path": "include/pros/misc.hpp",
"chars": 17355,
"preview": "/**\n * \\file pros/misc.hpp\n * \\ingroup cpp-pros\n *\n * Contains prototypes for miscellaneous functions pertaining to the "
},
{
"path": "include/pros/motor_group.hpp",
"chars": 78802,
"preview": "/**\n * \\file pros/motor_group.hpp\n * \\ingroup cpp-motor-group\n *\n * Contains prototypes for the V5 Motor-related functio"
},
{
"path": "include/pros/motors.h",
"chars": 43019,
"preview": "/**\n * \\file pros/motors.h\n * \\ingroup c-motors\n *\n * Contains prototypes for the V5 Motor-related functions.\n *\n * This"
},
{
"path": "include/pros/motors.hpp",
"chars": 78128,
"preview": "/**\n * \\file pros/motors.hpp\n * \\ingroup cpp-motors\n *\n * Contains prototypes for the V5 Motor-related functions.\n *\n * "
},
{
"path": "include/pros/optical.h",
"chars": 13500,
"preview": "/**\n * \\file pros/optical.h\n * \\ingroup c-optical\n *\n * Contains prototypes for functions related to the VEX Optical sen"
},
{
"path": "include/pros/optical.hpp",
"chars": 13981,
"preview": "/**\n * \\file pros/optical.hpp\n * \\ingroup cpp-optical\n *\n * Contains prototypes for functions related to the VEX Optical"
},
{
"path": "include/pros/rotation.h",
"chars": 10247,
"preview": "/**\n * \\file pros/rotation.h\n * \\ingroup c-rotation\n *\n * Contains prototypes for functions related to the VEX Rotation "
},
{
"path": "include/pros/rotation.hpp",
"chars": 11086,
"preview": "/**\n * \\file pros/rotation.hpp\n * \\ingroup cpp-rotation\n *\n * Contains prototypes for functions related to the VEX Rotat"
},
{
"path": "include/pros/rtos.h",
"chars": 33321,
"preview": "/**\n * \\file pros/rtos.h\n * \\ingroup c-rtos\n *\n * Contains declarations for the PROS RTOS kernel for use by typical VEX\n"
},
{
"path": "include/pros/rtos.hpp",
"chars": 64120,
"preview": "/**\n * \\file pros/rtos.hpp\n * \\ingroup cpp-rtos\n *\n * Contains declarations for the PROS RTOS kernel for use by typical "
},
{
"path": "include/pros/screen.h",
"chars": 24036,
"preview": "/**\n * \\file screen.h\n * \\ingroup c-screen\n *\n * Brain screen display and touch functions.\n *\n * Contains user calls to "
},
{
"path": "include/pros/screen.hpp",
"chars": 24868,
"preview": "/**\n * \\file screen.hpp\n * \\ingroup cpp-screen\n *\n * Brain screen display and touch functions.\n *\n * Contains user calls"
},
{
"path": "include/pros/serial.h",
"chars": 10842,
"preview": "/**\n * \\file pros/serial.h\n * \\ingroup c-serial\n *\n * Contains prototypes for the V5 Generic Serial related functions.\n "
},
{
"path": "include/pros/serial.hpp",
"chars": 10125,
"preview": "/**\n * \\file pros/serial.hpp\n * \\ingroup cpp-serial\n *\n * Contains prototypes for the V5 Generic Serial related function"
},
{
"path": "include/pros/version.h",
"chars": 535,
"preview": "/**\n* \\file version.h\n*\n* PROS Version Information\n*\n* Contains PROS kernel version information\n*\n*\n* \\copyright Copyrig"
},
{
"path": "include/pros/vision.h",
"chars": 25802,
"preview": "/**\n * \\file pros/vision.h\n * \\ingroup c-vision\n *\n * Contains prototypes for the VEX Vision Sensor-related functions.\n "
},
{
"path": "include/pros/vision.hpp",
"chars": 25073,
"preview": "/**\n * \\file pros/vision.hpp\n * \\ingroup cpp-vision\n *\n * Contains prototypes for the VEX Vision Sensor-related function"
},
{
"path": "include/rtos/FreeRTOS.h",
"chars": 37060,
"preview": "/*\r\n * FreeRTOS Kernel V10.0.1\r\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\r\n *\r\n * "
},
{
"path": "include/rtos/FreeRTOSConfig.h",
"chars": 11651,
"preview": "/*\n FreeRTOS V9.0.0 - Copyright (C) 2016 Real Time Engineers Ltd.\n All rights reserved\n\n VISIT http://www.FreeR"
},
{
"path": "include/rtos/StackMacros.h",
"chars": 6059,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/list.h",
"chars": 18041,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/message_buffer.h",
"chars": 35634,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/portable.h",
"chars": 4318,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/portmacro.h",
"chars": 11203,
"preview": "/*\n FreeRTOS V9.0.0 - Copyright (C) 2016 Real Time Engineers Ltd.\n All rights reserved\n\n VISIT http://www.FreeR"
},
{
"path": "include/rtos/projdefs.h",
"chars": 5602,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/queue.h",
"chars": 58058,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/semphr.h",
"chars": 44731,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/stack_macros.h",
"chars": 5803,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/stream_buffer.h",
"chars": 36404,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/task.h",
"chars": 84382,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/rtos/tcb.h",
"chars": 3874,
"preview": "#pragma once\n\n#include \"rtos/FreeRTOS.h\"\n#include \"rtos/list.h\"\n\n/*\n * Task control block. A task control block (TCB) i"
},
{
"path": "include/rtos/timers.h",
"chars": 58081,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "include/system/dev/banners.h",
"chars": 2642,
"preview": "/**\n * \\file system/dev/banners.h\n *\n * PROS banners printed over serial line\n *\n * This file should only be included ON"
},
{
"path": "include/system/dev/dev.h",
"chars": 560,
"preview": "/**\n * \\file system/dev/dev.h\n *\n * Generic Serial Device driver header\n *\n * \\copyright Copyright (c) 2017-2026, Purdue"
},
{
"path": "include/system/dev/ser.h",
"chars": 622,
"preview": "/**\n * \\file system/dev/ser.h\n *\n * Serial driver header\n *\n * See system/dev/ser_driver.c and system/dev/ser_daemon.c f"
},
{
"path": "include/system/dev/usd.h",
"chars": 600,
"preview": "/**\n * \\file system/dev/usd.h\n *\n * microSD card driver header\n *\n * See system/dev/usd_driver.c for discussion\n *\n * \\c"
},
{
"path": "include/system/dev/vfs.h",
"chars": 1399,
"preview": "/**\n * \\file system/dev/vfs.h\n *\n * Virtual File System header\n *\n * See system/dev/vfs.c for discussion\n *\n * \\copyrigh"
},
{
"path": "include/system/hot.h",
"chars": 292,
"preview": "#pragma once\n\nstruct hot_table {\n\tchar const* compile_timestamp;\n\tchar const* compile_directory;\n\n\tvoid* __exidx_start;\n"
},
{
"path": "include/system/optimizers.h",
"chars": 602,
"preview": "/**\n * \\file system/optimizers.h\n *\n * Optimizers for the kernel\n *\n * Probably shouldn't use anything from this header\n"
},
{
"path": "include/system/user_functions/c_list.h",
"chars": 145,
"preview": "#ifndef FUNC\n#error \"FUNC must be defined\"\n#endif\n\nFUNC(autonomous)\nFUNC(initialize)\nFUNC(opcontrol)\nFUNC(disabled)\nFUNC"
},
{
"path": "include/system/user_functions/cpp_list.h",
"chars": 165,
"preview": "#ifndef FUNC\n#error \"FUNC must be defined\"\n#endif\n\nFUNC(cpp_autonomous)\nFUNC(cpp_initialize)\nFUNC(cpp_opcontrol)\nFUNC(cp"
},
{
"path": "include/system/user_functions/list.h",
"chars": 137,
"preview": "#ifndef FUNC\n#error \"FUNC must be defined\"\n#endif\n\n#include \"system/user_functions/c_list.h\"\n#include \"system/user_funct"
},
{
"path": "include/system/user_functions.h",
"chars": 100,
"preview": "#pragma once\n\n#define FUNC(F) void user_ ##F();\n#include \"system/user_functions/list.h\"\n#undef FUNC\n"
},
{
"path": "include/vdml/port.h",
"chars": 1044,
"preview": "/**\n * \\file devices/port.h\n *\n * This file contains the standard header info for port macros and bit masks, \n * used mo"
},
{
"path": "include/vdml/registry.h",
"chars": 3055,
"preview": "/**\n * \\file vdml/registry.h\n *\n * This file contains the standard header info for the VDML (Vex Data Management\n * Laye"
},
{
"path": "include/vdml/vdml.h",
"chars": 7559,
"preview": "/**\n * \\file vdml/vdml.h\n *\n * This file contains all types and functions used throughout multiple VDML\n * (Vex Data Man"
},
{
"path": "libv5rts-strip-options.txt",
"chars": 82,
"preview": "-N open\n-N _fstat\n-N fcntl\n-N lseek\n-N read\n-N write\n-N isatty\n-R .ARM.attributes\n"
},
{
"path": "patch_headers.py",
"chars": 3195,
"preview": "'''\nAdds __attribute__((pcs(\"aapcs\")) to all sdk function declarations to allow properly linking\nwith the sdk (which use"
},
{
"path": "project.pros",
"chars": 563,
"preview": "{\"py/object\": \"pros.conductor.project.Project\", \"py/state\": {\"project_name\": \"kernel-dev\", \"target\": \"v5\", \"templates\": "
},
{
"path": "public_symbols.txt",
"chars": 563,
"preview": "millis\ntask_create\ntask_delete\ntask_delay\ntask_delay_until\ntask_get_priority\ntask_set_priority\ntask_get_state\ntask_suspe"
},
{
"path": "src/common/README.md",
"chars": 117,
"preview": "# Common Facilities\n\nThis folder contains common facilities used throughout the PROS 3 kernel, such\nas JSON parsing.\n"
},
{
"path": "src/common/cobs.c",
"chars": 2179,
"preview": "/**\n * \\file common/cobs.c\n *\n * Consistent Overhead Byte Stuffing\n *\n * Contains an implementation of Consistent Overhe"
},
{
"path": "src/common/gid.c",
"chars": 2635,
"preview": "/**\n * \\file gid.c\n *\n * Globally Unique Identifiers Map\n *\n * Contains an implementation to efficiently assign globally"
},
{
"path": "src/common/linkedlist.c",
"chars": 3530,
"preview": "/*\n * \\file common/linkedlist.c\n *\n * Linked list implementation for internal use\n *\n * This file defines a linked list "
},
{
"path": "src/common/set.c",
"chars": 2375,
"preview": "/**\n * \\file common/set.c\n *\n * Contains an implementation of a thread-safe basic set in the kernel heap.\n * It's used t"
},
{
"path": "src/common/string.c",
"chars": 990,
"preview": "/**\n * \\file common/string.c\n *\n * Contains extra string functions useful for PROS and kstrdup/kstrndup which\n * use the"
},
{
"path": "src/devices/README.md",
"chars": 131,
"preview": "# Devices\n\nThese source files implement VDML - the VEX Data Mesh Layer, which controls the\nV5 Smart Devices and other pe"
},
{
"path": "src/devices/battery.c",
"chars": 1373,
"preview": "/**\n * \\file devices/battery.c\n *\n * Contains functions for interacting with the V5 Battery.\n *\n * \\copyright Copyright "
},
{
"path": "src/devices/battery.cpp",
"chars": 794,
"preview": "/**\n * \\file devices/battery.cpp\n *\n * Contains functions for interacting with the V5 Battery.\n *\n * \\copyright Copyrigh"
},
{
"path": "src/devices/controller.c",
"chars": 7009,
"preview": "/**\n * \\file devices/controller.c\n *\n * Contains functions for interacting with the V5 Controller.\n *\n * \\copyright Copy"
},
{
"path": "src/devices/controller.cpp",
"chars": 2579,
"preview": "/**\n * \\file devices/controller.cpp\n *\n * Contains functions for interacting with the V5 Controller, as well as the\n * c"
},
{
"path": "src/devices/registry.c",
"chars": 4227,
"preview": "/**\n * \\file devices/registry.c\n *\n * This file is the VDML (Vex Data Management Layer) Registry. It keeps track of\n * w"
},
{
"path": "src/devices/screen.c",
"chars": 13172,
"preview": "/**\n * \\file screen.c\n *\n * \\brief Brain screen display and touch functions.\n *\n * Contains user calls to the v5 screen "
},
{
"path": "src/devices/screen.cpp",
"chars": 5665,
"preview": "/**\n * \\file screen.cpp\n *\n * \\brief Brain screen display and touch functions.\n *\n * Contains user calls to the v5 scree"
},
{
"path": "src/devices/vdml.c",
"chars": 6727,
"preview": "/**\n * \\file devices/vdml.c\n *\n * VDML - VEX Data Management Layer\n *\n * VDML ensures thread saftey for operations on sm"
},
{
"path": "src/devices/vdml_adi.c",
"chars": 4993,
"preview": "/**\n * \\file devices/vdml_adi.c\n *\n * Contains functions for interacting with the V5 ADI.\n *\n * \\copyright Copyright (c)"
},
{
"path": "src/devices/vdml_adi.cpp",
"chars": 11038,
"preview": "/**\n * \\file devices/vdml_adi.cpp\n *\n * Contains functions for interacting with the V5 ADI.\n *\n * \\copyright Copyright ("
},
{
"path": "src/devices/vdml_ai_vision.c",
"chars": 6725,
"preview": "/**\n * \\file devices/vdml_aivision.c\n *\n * Contains functions for interacting with the V5 Vision Sensor.\n *\n * \\copyrigh"
},
{
"path": "src/devices/vdml_ai_vision.cpp",
"chars": 3700,
"preview": "/**\n * \\file devices/vdml_vision.cpp\n *\n * Contains functions for interacting with the V5 Vision Sensor.\n *\n * \\copyrigh"
},
{
"path": "src/devices/vdml_device.c",
"chars": 863,
"preview": "/**\n * \\file devices/vdml_device.c\n *\n * Contains functions for interacting with VEX devices.\n *\n *\n *\n * This file shou"
},
{
"path": "src/devices/vdml_device.cpp",
"chars": 2015,
"preview": "/**\n * \\file devices/vdml_device.cpp\n *\n * Base class for all smart devices.\n *\n *\n *\n * This file should not be modifie"
},
{
"path": "src/devices/vdml_distance.c",
"chars": 1795,
"preview": "/**\n * \\file devices/vdml_distance.c\n *\n * Contains functions for interacting with the VEX Distance sensor.\n *\n * \\copyr"
},
{
"path": "src/devices/vdml_distance.cpp",
"chars": 1832,
"preview": "/**\n * \\file devices/vdml_distance.cpp\n *\n * Contains functions for interacting with the VEX Distance sensor.\n *\n * \\cop"
},
{
"path": "src/devices/vdml_ext_adi.c",
"chars": 20006,
"preview": "/**\n * \\file devices/vdml_ext_adi.c\n *\n * Contains functions for interacting with the V5 3-Wire Expander.\n *\n * \\copyrig"
},
{
"path": "src/devices/vdml_gps.c",
"chars": 7466,
"preview": "/**\n * \\file devices/vdml_gps.c\n *\n * Contains functions for interacting with the VEX GPS.\n *\n * \\copyright Copyright (c"
},
{
"path": "src/devices/vdml_gps.cpp",
"chars": 4027,
"preview": "/**\n * \\file devices/vdml_gps.cpp\n *\n * Contains functions for interacting with the VEX GPS.\n *\n * \\copyright Copyright "
},
{
"path": "src/devices/vdml_imu.c",
"chars": 14769,
"preview": "/**\n * \\file devices/vdml_imu.c\n *\n * Contains functions for interacting with the VEX Inertial sensor.\n *\n * \\copyright "
},
{
"path": "src/devices/vdml_imu.cpp",
"chars": 4527,
"preview": "/**\n * \\file devices/vdml_imu.cpp\n *\n * Contains functions for interacting with the VEX Inertial sensor.\n *\n * \\copyrigh"
},
{
"path": "src/devices/vdml_link.c",
"chars": 7866,
"preview": "/**\n * \\file vdml_link.c\n *\n * \\brief Contains source code for functions related to the robot to robot communications.\n "
},
{
"path": "src/devices/vdml_link.cpp",
"chars": 1730,
"preview": "/**\n * \\file vdml_link.cpp\n *\n * \\brief Contains source code for functions related to the robot to robot communications."
},
{
"path": "src/devices/vdml_motorgroup.cpp",
"chars": 23820,
"preview": "/**\n * \\file devices/vdml_motors.cpp\n *\n * Contains functions for interacting with the V5 Motors.\n *\n * \\copyright Copyr"
},
{
"path": "src/devices/vdml_motors.c",
"chars": 9701,
"preview": "/**\n * \\file devices/vdml_motors.c\n *\n * Contains functions for interacting with the V5 Motors.\n *\n * \\copyright Copyrig"
},
{
"path": "src/devices/vdml_motors.cpp",
"chars": 16203,
"preview": "/**\n * \\file devices/vdml_motors.cpp\n *\n * Contains functions for interacting with the V5 Motors.\n *\n * \\copyright Copyr"
},
{
"path": "src/devices/vdml_optical.c",
"chars": 5167,
"preview": "/**\n * \\file devices/vdml_optical.c\n *\n * Contains functions for interacting with the VEX Optical sensor.\n *\n * \\copyrig"
},
{
"path": "src/devices/vdml_optical.cpp",
"chars": 2715,
"preview": "/**\n * \\file devices/vdml_optical.cpp\n *\n * Contains functions for interacting with the VEX Optical sensor.\n *\n * \\copyr"
},
{
"path": "src/devices/vdml_rotation.c",
"chars": 3430,
"preview": "/**\n * \\file devices/vdml_rotation.c\n *\n * Contains functions for interacting with the VEX Rotation sensor.\n *\n * \\copyr"
},
{
"path": "src/devices/vdml_rotation.cpp",
"chars": 2551,
"preview": "/**\n * \\file devices/vdml_rotation.cpp\n *\n * Contains functions for interacting with the VEX Rotation sensor.\n *\n * \\cop"
},
{
"path": "src/devices/vdml_serial.c",
"chars": 3207,
"preview": "/**\n * \\file devices/vdml_serial.c\n *\n * Contains functions for interacting with V5 Generic Serial devices.\n *\n * \\copyr"
},
{
"path": "src/devices/vdml_serial.cpp",
"chars": 1774,
"preview": "/**\n * \\file devices/vdml_serial.cpp\n *\n * Contains functions for interacting with V5 Generic Serial devices.\n *\n * \\cop"
},
{
"path": "src/devices/vdml_usd.c",
"chars": 1010,
"preview": "/**\n * \\file devices/usd.c\n *\n * Contains functions for interacting with the SD card.\n *\n * \\copyright Copyright (c) 201"
},
{
"path": "src/devices/vdml_usd.cpp",
"chars": 691,
"preview": "/**\n * \\file devices/usd.cpp\n *\n * Contains functions for interacting with the SD card.\n *\n * \\copyright Copyright (c) 2"
},
{
"path": "src/devices/vdml_vision.c",
"chars": 12712,
"preview": "/**\n * \\file devices/vdml_vision.c\n *\n * Contains functions for interacting with the V5 Vision Sensor.\n *\n * \\copyright "
},
{
"path": "src/devices/vdml_vision.cpp",
"chars": 5230,
"preview": "/**\n * \\file devices/vdml_vision.cpp\n *\n * Contains functions for interacting with the V5 Vision Sensor.\n *\n * \\copyrigh"
},
{
"path": "src/main.cpp",
"chars": 3526,
"preview": "#include \"main.h\"\n\n/**\n * A callback function for LLEMU's center button.\n *\n * When this callback is fired, it will togg"
},
{
"path": "src/rtos/LICENSE",
"chars": 2024,
"preview": "The FreeRTOS kernel is released under the MIT open source license, the text of\nwhich is provided below.\n\nThis license co"
},
{
"path": "src/rtos/README.md",
"chars": 1889,
"preview": "## The FreeRTOS Kernel Library\n\n__Note: modifiying these files may break PROS or make PROS unstable__\n\n_This file serves"
},
{
"path": "src/rtos/heap_4.c",
"chars": 13612,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "src/rtos/list.c",
"chars": 8200,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "src/rtos/port.c",
"chars": 21942,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "src/rtos/portASM.S",
"chars": 8861,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "src/rtos/portmacro.h",
"chars": 8664,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "src/rtos/queue.c",
"chars": 89895,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "src/rtos/refactor.sh",
"chars": 338,
"preview": "# Change the current order of the awk print is to convert FreeRTOS style to PROS \n# style. Change from `$1, $2` to `$2, "
},
{
"path": "src/rtos/refactor.tsv",
"chars": 3784,
"preview": "Original\t\t\tRefactored\nTaskHandle_t\t\ttask_t\nTaskFunction_t\t\ttask_fn_t\neTaskState\t\t\ttask_state_e_t\neRunning\t\t\tE_TASK_STATE"
},
{
"path": "src/rtos/rtos.cpp",
"chars": 4427,
"preview": "/**\n * \\file rtos/rtos.cpp\n *\n * Contains functions for the PROS RTOS kernel for use by typical\n * VEX programmers.\n *\n "
},
{
"path": "src/rtos/semphr.c",
"chars": 19581,
"preview": "#include \"FreeRTOS.h\"\n#include \"semphr.h\"\n\n/**\n * semphr. h\n * <pre>sem_wait(\n * sem_t sem,\n * "
},
{
"path": "src/rtos/stream_buffer.c",
"chars": 41540,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "src/rtos/task_notify_when_deleting.c",
"chars": 6629,
"preview": "#include \"kapi.h\"\r\n#include \"common/linkedlist.h\"\r\n\r\n// NOTE: can't just include task.h because of redefinition that goe"
},
{
"path": "src/rtos/tasks.c",
"chars": 152468,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "src/rtos/timers.c",
"chars": 38156,
"preview": "/*\n * FreeRTOS Kernel V10.0.1\n * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.\n *\n * Perm"
},
{
"path": "src/system/cpp_support.cpp",
"chars": 2001,
"preview": "/**\n * \\file system/cpp_support.cpp\n *\n * C++ support hooks\n *\n * \\Copyright (c) 2017-2026, Purdue University ACM SIGBot"
},
{
"path": "src/system/dev/dev_driver.c",
"chars": 4514,
"preview": "/**\n * \\file system/dev/dev_driver.c\n *\n * Generic Serial Device driver\n *\n * Contains the driver for writing to any sma"
},
{
"path": "src/system/dev/file_system_stubs.c",
"chars": 1672,
"preview": "/**\r\n * \\file system/dev/dev_driver.c\r\n *\r\n * Generic Serial Device driver\r\n *\r\n * Contains temporary stubs for the file"
},
{
"path": "src/system/dev/ser_daemon.c",
"chars": 6951,
"preview": "/**\n * \\file system/dev/ser_daemon.c\n *\n * Serial Input Daemon\n *\n * The serial input daemon is responsible for polling "
},
{
"path": "src/system/dev/ser_driver.c",
"chars": 11328,
"preview": "/**\n * \\file system/dev/ser_driver.c\n *\n * Serial Driver\n *\n * Contains the driver for communicating over the serial lin"
},
{
"path": "src/system/dev/usd_driver.c",
"chars": 4367,
"preview": "/**\n * \\file system/dev/usd_driver.c\n *\n * Contains the driver for writing files to the microSD card.\n *\n * \\copyright C"
},
{
"path": "src/system/dev/vfs.c",
"chars": 5699,
"preview": "/**\n * \\file system/dev/vfs.c\n *\n * Virtual File System\n *\n * VFS is responsible for maintaining the global file table a"
},
{
"path": "src/system/envlock.c",
"chars": 569,
"preview": "/**\n * \\file system/envlock.c\n *\n * environment lock newlib stubs\n *\n * Contains implementations of environment-locking "
},
{
"path": "src/system/hot.c",
"chars": 3723,
"preview": "#include \"system/hot.h\"\n#include \"kapi.h\"\n#include \"v5_api.h\"\n\n// stored only in cold\nstruct hot_table __HOT_TABLE = {0}"
},
{
"path": "src/system/mlock.c",
"chars": 569,
"preview": "/**\n * \\file system/mlock.c\n *\n * memory lock newlib stubs\n *\n * Contains implementations of memory-locking functions fo"
},
{
"path": "src/system/newlib_stubs.c",
"chars": 5385,
"preview": "/**\n * \\file system/newlib_stubs.c\n *\n * Port of newlib to PROS for the V5\n *\n * Contains the various methods needed to "
},
{
"path": "src/system/newlib_stubs_support.cpp",
"chars": 161,
"preview": "#include <cstdio>\n#include <iostream>\n\n// called by _exit in newlib_stubs.c\nextern \"C\" void flush_output_streams() {\n "
},
{
"path": "src/system/rtos_hooks.c",
"chars": 9049,
"preview": "/**\n * \\file system/rtos_hooks.c\n *\n * FreeRTOS hooks for initialization and interrupts\n *\n * FreeRTOS requires some por"
},
{
"path": "src/system/startup.c",
"chars": 1992,
"preview": "/**\n * \\file system/startup.c\n *\n * Contains the main startup code for PROS 3.0. main is called from vexStartup\n * code."
},
{
"path": "src/system/system_daemon.c",
"chars": 5241,
"preview": "/**\n * \\file system/system_daemon.c\n *\n * Competition control daemon responsible for invoking the user tasks.\n *\n * \\Cop"
},
{
"path": "src/system/unwind.c",
"chars": 10025,
"preview": "/**\n * unwind.c - Unwind functions specialized for PROS\n *\n * Unwinding is necessary in PROS because tasks containing C+"
},
{
"path": "src/system/user_functions.c",
"chars": 1750,
"preview": "#include \"system/user_functions.h\"\n#include \"kapi.h\"\n#include \"system/hot.h\"\n\n// how this all works...\n// system daemon "
},
{
"path": "src/system/xilinx_vectors.s",
"chars": 4888,
"preview": "/******************************************************************************\n*\n* (c) Copyright 2009-13 Xilinx, Inc. A"
},
{
"path": "src/tests/adi.cpp",
"chars": 981,
"preview": "/**\n * \\file tests/adi.cpp\n *\n * Test code for various ADI things\n *\n * NOTE: There should also be a call to the constru"
},
{
"path": "src/tests/basic_test.c",
"chars": 895,
"preview": "#include \"main.h\"\n\nvoid my_task(void* ign) {\n\twhile (true) {\n\t\tprintf(\"There are %d objects\\n\", vision_get_object_count("
},
{
"path": "src/tests/basic_test.cpp",
"chars": 618,
"preview": "#include <iostream>\n#include \"main.h\"\n\nvoid my_task(void* str) {\n\tpros::Vision vision(20);\n\twhile (true) {\n\t\tstd::cout <"
},
{
"path": "src/tests/errno_reentrancy.c",
"chars": 601,
"preview": "#include <errno.h>\n#include \"api.h\"\n#include \"v5_api.h\"\n\nvoid task_a_fn(void* ign) {\n\tvexDisplayString(2, \"Errno from A "
},
{
"path": "src/tests/exceptions.cpp",
"chars": 343,
"preview": "#include <stdexcept>\n#include <string>\n\n#include \"v5_api.h\"\n\n#include \"rtos/FreeRTOS.h\"\n#include \"rtos/task.h\"\n\nextern \""
},
{
"path": "src/tests/ext_adi.cpp",
"chars": 756,
"preview": "/**\n * \\file tests/ext_adi.cpp\n *\n * Test code for various External ADI things\n *\n * \\copyright Copyright (c) 2017-2026,"
},
{
"path": "src/tests/generic_serial.cpp",
"chars": 4587,
"preview": "/**\n * \\file tests/generic_serial.cpp\n *\n * Test code for the generic serial driver\n *\n * NOTE: There should be a cable "
},
{
"path": "src/tests/generic_serial_file.cpp",
"chars": 5167,
"preview": "/**\n * \\file tests/generic_serial_file.cpp\n *\n * Test code for the generic serial filesystem driver\n *\n * NOTE: There sh"
},
{
"path": "src/tests/gyro.c",
"chars": 1063,
"preview": "/**\n * \\file tests/gyro.c\n *\n * Test code for the gyroscope driver\n *\n * NOTE: There should also be a call to the constr"
},
{
"path": "src/tests/gyro.cpp",
"chars": 1134,
"preview": "/**\n * \\file tests/gyro.cpp\n *\n * Test code for the gyroscope driver\n *\n * NOTE: There should also be a call to the cons"
},
{
"path": "src/tests/mutexes.c",
"chars": 104,
"preview": "void test_mutex() {\n\tmutex_t mut = mutex_create();\n\n\tmutex_take(mut, TIMEOUT_MAX);\n\n\tmutex_give(mut);\n}\n"
},
{
"path": "src/tests/pnuematics.cpp",
"chars": 3369,
"preview": "#include \"main.h\"\n\n/**\n * A callback function for LLEMU's center button.\n *\n * When this callback is fired, it will togg"
},
{
"path": "src/tests/rtos_function_linking.c",
"chars": 1177,
"preview": "/**\n * \\file tests/rtos_function_linking.c\n *\n * Test that all the FreeRTOS functions link correctly.\n *\n * Do not actua"
},
{
"path": "src/tests/segfault.cpp",
"chars": 652,
"preview": "#include \"main.h\"\n\n[[gnu::noinline]] static void thing_1(uint8_t i) {\n printf(\"thing_1(%i)\\n\", i);\n if (i == 0) {\n"
},
{
"path": "src/tests/simple_names.c",
"chars": 4420,
"preview": "/**\n * \\file tests/simple_names.c\n *\n * Test that all the PROS_USE_SIMPLE_NAMES definitions compile correctly\n *\n * Do n"
},
{
"path": "src/tests/simple_names.cpp",
"chars": 4052,
"preview": "/**\n * \\file tests/simple_names.cpp\n *\n * Test that all the PROS_USE_SIMPLE_NAMES definitions compile correctly\n *\n * Do"
},
{
"path": "src/tests/static_tast_states.c",
"chars": 1249,
"preview": "// This test is mostly verifying that the idle task isn't being starved\n\n#include <stdio.h>\n\n#include \"rtos/FreeRTOS.h\"\n"
},
{
"path": "src/tests/task_notify_when_deleting.c",
"chars": 976,
"preview": "#include \"main.h\"\n#include \"pros/apix.h\"\n\nvoid target_task(void* ignore) {\n\tlcd_print(0, \"%s says hello\", task_get_name("
},
{
"path": "src/tests/vision_test.cpp",
"chars": 441,
"preview": "#include \"main.h\"\n\nvoid opcontrol() {\n\tpros::Vision vis(10);\n\tpros::delay(2000);\n\tpros::vision_color_code_t code;\n\tcode "
},
{
"path": "template-Makefile",
"chars": 1720,
"preview": "################################################################################\n######################### User configur"
},
{
"path": "template-gitignore",
"chars": 143,
"preview": "# Compiled Object files\n*.o\n*.obj\n\n# Executables\n*.bin\n*.elf\n\n# PROS\nbin/\n.vscode/\n.cache/\ncompile_commands.json\ntemp.lo"
},
{
"path": "verify-symbols.sh",
"chars": 855,
"preview": "#!/usr/bin/env bash\n\n# when running this script, there should be nothing red or dark blue on the right panel (what's the"
}
]
// ... and 4 more files (download for full content)
About this extraction
This page contains the full source code of the purduesigbots/pros GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 204 files (2.1 MB), approximately 567.5k tokens, and a symbol index with 1171 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.