diff --git a/.gitignore b/.gitignore index 2bbff1fb..e303e2c0 100644 --- a/.gitignore +++ b/.gitignore @@ -7,9 +7,9 @@ *.elf # PROS -.cache/ bin/ .vscode/ +.cache/ compile_commands.json temp.log temp.errors diff --git a/EZ-Template@2.1.1.zip b/EZ-Template@2.1.1.zip deleted file mode 100644 index 07f4c350..00000000 Binary files a/EZ-Template@2.1.1.zip and /dev/null differ diff --git a/EZ-Template@2.1.2.zip b/EZ-Template@2.1.2.zip new file mode 100644 index 00000000..074e3f3d Binary files /dev/null and b/EZ-Template@2.1.2.zip differ diff --git a/Makefile b/Makefile index 6e81f814..40f62961 100644 --- a/Makefile +++ b/Makefile @@ -27,7 +27,7 @@ EXCLUDE_COLD_LIBRARIES:= IS_LIBRARY:=1 # TODO: CHANGE THIS! LIBNAME:=EZ-Template -VERSION:=2.1.1 +VERSION:=2.1.2 # EXCLUDE_SRC_FROM_LIB= $(SRCDIR)/unpublishedfile.c # this line excludes opcontrol.c and similar files EXCLUDE_SRC_FROM_LIB+=$(foreach file, $(SRCDIR)/autons $(SRCDIR)/main,$(foreach cext,$(CEXTS),$(file).$(cext)) $(foreach cxxext,$(CXXEXTS),$(file).$(cxxext))) diff --git a/common.mk b/common.mk index 6341070a..84f7e219 100644 --- a/common.mk +++ b/common.mk @@ -2,7 +2,7 @@ ARCHTUPLE=arm-none-eabi- DEVICE=VEX EDR V5 MFLAGS=-mcpu=cortex-a9 -mfpu=neon-fp16 -mfloat-abi=softfp -Os -g -CPPFLAGS=-D_POSIX_THREADS -D_UNIX98_THREAD_MUTEX_ATTRIBUTES +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 WARNFLAGS+=-Wno-psabi @@ -227,7 +227,7 @@ $(COLD_BIN): $(COLD_ELF) $(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 $@ $@, $(DONE_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) @@ -272,7 +272,15 @@ $(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 -$(call test_output_2,Adding timestamp ,echo 'char const * const _PROS_COMPILE_TIMESTAMP = __DATE__ " " __TIME__; char const * const _PROS_COMPILE_DIRECTORY = "$(shell pwd | tail -c 23)";' | $(CC) -c -x c $(CFLAGS) $(EXTRA_CFLAGS) -o $(LDTIMEOBJ) -,$(OK_STRING)) +@# +@# 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 -c 23)"; +@# +@# 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 = "$(shell pwd | tail -c 23)";' | $(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 diff --git a/firmware/libpros.a b/firmware/libpros.a index 672ff7a4..db5ad452 100644 Binary files a/firmware/libpros.a and b/firmware/libpros.a differ diff --git a/firmware/v5-common.ld b/firmware/v5-common.ld index f1b64f01..762a9055 100644 --- a/firmware/v5-common.ld +++ b/firmware/v5-common.ld @@ -21,21 +21,21 @@ SECTIONS *(.gnu.linkonce.t.*) *(.plt) *(.gnu_warning) - *(.gcc_execpt_table) + *(.gcc_except_table) *(.glue_7) *(.glue_7t) *(.vfp11_veneer) *(.ARM.extab) *(.gnu.linkonce.armextab.*) -} > MEMORY +} > RAM .init : { KEEP (*(.init)) -} > MEMORY +} > RAM .fini : { KEEP (*(.fini)) -} > MEMORY +} > RAM .rodata : { __rodata_start = .; @@ -43,14 +43,14 @@ SECTIONS *(.rodata.*) *(.gnu.linkonce.r.*) __rodata_end = .; -} > MEMORY +} > RAM .rodata1 : { __rodata1_start = .; *(.rodata1) *(.rodata1.*) __rodata1_end = .; -} > MEMORY +} > RAM .sdata2 : { __sdata2_start = .; @@ -58,7 +58,7 @@ SECTIONS *(.sdata2.*) *(.gnu.linkonce.s2.*) __sdata2_end = .; -} > MEMORY +} > RAM .sbss2 : { __sbss2_start = .; @@ -66,7 +66,7 @@ SECTIONS *(.sbss2.*) *(.gnu.linkonce.sb2.*) __sbss2_end = .; -} > MEMORY +} > RAM .data : { __data_start = .; @@ -77,18 +77,18 @@ SECTIONS *(.got) *(.got.plt) __data_end = .; -} > MEMORY +} > RAM .data1 : { __data1_start = .; *(.data1) *(.data1.*) __data1_end = .; -} > MEMORY +} > RAM .got : { *(.got) -} > MEMORY +} > RAM .ctors : { __CTOR_LIST__ = .; @@ -99,7 +99,7 @@ SECTIONS KEEP (*(.ctors)) __CTOR_END__ = .; ___CTORS_END___ = .; -} > MEMORY +} > RAM .dtors : { __DTOR_LIST__ = .; @@ -110,67 +110,67 @@ SECTIONS KEEP (*(.dtors)) __DTOR_END__ = .; ___DTORS_END___ = .; -} > MEMORY +} > RAM .fixup : { __fixup_start = .; *(.fixup) __fixup_end = .; -} > MEMORY +} > RAM .eh_frame : { *(.eh_frame) -} > MEMORY +} > RAM .eh_framehdr : { __eh_framehdr_start = .; *(.eh_framehdr) __eh_framehdr_end = .; -} > MEMORY +} > RAM .gcc_except_table : { *(.gcc_except_table) -} > MEMORY +} > RAM .mmu_tbl (ALIGN(16384)) : { __mmu_tbl_start = .; *(.mmu_tbl) __mmu_tbl_end = .; -} > MEMORY +} > RAM .ARM.exidx : { __exidx_start = .; *(.ARM.exidx*) *(.gnu.linkonce.armexidix.*.*) __exidx_end = .; -} > MEMORY +} > RAM .preinit_array : { __preinit_array_start = .; KEEP (*(SORT(.preinit_array.*))) KEEP (*(.preinit_array)) __preinit_array_end = .; -} > MEMORY +} > RAM .init_array : { __init_array_start = .; KEEP (*(SORT(.init_array.*))) KEEP (*(.init_array)) __init_array_end = .; -} > MEMORY +} > RAM .fini_array : { __fini_array_start = .; KEEP (*(SORT(.fini_array.*))) KEEP (*(.fini_array)) __fini_array_end = .; -} > MEMORY +} > RAM .ARM.attributes : { __ARM.attributes_start = .; *(.ARM.attributes) __ARM.attributes_end = .; -} > MEMORY +} > RAM .sdata : { __sdata_start = .; @@ -178,7 +178,7 @@ SECTIONS *(.sdata.*) *(.gnu.linkonce.s.*) __sdata_end = .; -} > MEMORY +} > RAM .sbss (NOLOAD) : { __sbss_start = .; @@ -186,7 +186,7 @@ SECTIONS *(.sbss.*) *(.gnu.linkonce.sb.*) __sbss_end = .; -} > MEMORY +} > RAM .tdata : { __tdata_start = .; @@ -194,7 +194,7 @@ SECTIONS *(.tdata.*) *(.gnu.linkonce.td.*) __tdata_end = .; -} > MEMORY +} > RAM .tbss : { __tbss_start = .; @@ -202,7 +202,7 @@ SECTIONS *(.tbss.*) *(.gnu.linkonce.tb.*) __tbss_end = .; -} > MEMORY +} > RAM .bss (NOLOAD) : { __bss_start = .; @@ -211,7 +211,7 @@ SECTIONS *(.gnu.linkonce.b.*) *(COMMON) __bss_end = .; -} > MEMORY +} > RAM _SDA_BASE_ = __sdata_start + ((__sbss_end - __sdata_start) / 2 ); diff --git a/firmware/v5-hot.ld b/firmware/v5-hot.ld index 259bab9b..017cb356 100644 --- a/firmware/v5-hot.ld +++ b/firmware/v5-hot.ld @@ -28,6 +28,6 @@ MEMORY HOT_MEMORY : ORIGIN = start_of_hot_mem, LENGTH = _HOT_MEM_SIZE /* Just over 8 MB */ } -REGION_ALIAS("MEMORY", HOT_MEMORY); +REGION_ALIAS("RAM", HOT_MEMORY); ENTRY(install_hot_table) diff --git a/firmware/v5.ld b/firmware/v5.ld index d6933d9d..7cbd06f3 100644 --- a/firmware/v5.ld +++ b/firmware/v5.ld @@ -28,6 +28,6 @@ MEMORY HOT_MEMORY : ORIGIN = start_of_hot_mem, LENGTH = _HOT_MEM_SIZE /* Just over 8 MB */ } -REGION_ALIAS("MEMORY", COLD_MEMORY); +REGION_ALIAS("RAM", COLD_MEMORY); ENTRY(vexStartup) diff --git a/include/api.h b/include/api.h index 241b7cb7..718030d1 100644 --- a/include/api.h +++ b/include/api.h @@ -8,7 +8,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, Purdue University ACM SIGBots. * All rights reserved. * * This Source Code Form is subject to the terms of the Mozilla Public @@ -40,19 +40,18 @@ #endif /* __cplusplus */ #define PROS_VERSION_MAJOR 3 -#define PROS_VERSION_MINOR 5 -#define PROS_VERSION_PATCH 4 -#define PROS_VERSION_STRING "3.5.4" - -#define PROS_ERR (INT32_MAX) -#define PROS_ERR_F (INFINITY) +#define PROS_VERSION_MINOR 7 +#define PROS_VERSION_PATCH 3 +#define PROS_VERSION_STRING "3.7.3" #include "pros/adi.h" #include "pros/colors.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" @@ -75,6 +74,7 @@ #include "pros/rtos.hpp" #include "pros/screen.hpp" #include "pros/vision.hpp" +#include "pros/link.hpp" #endif #endif // _PROS_API_H_ diff --git a/include/display/README.md b/include/display/README.md new file mode 100644 index 00000000..afdfdeb5 --- /dev/null +++ b/include/display/README.md @@ -0,0 +1,71 @@ +# Littlev Graphics Libraray + +![LittlevGL cover](http://www.gl.littlev.hu/home/main_cover_small.png) + +LittlevGL provides everything you need to create a Graphical User Interface (GUI) on embedded systems with easy-to-use graphical elements, beautiful visual effects and low memory footprint. + +Homepage: https://littlevgl.com + +### Table Of Content +* [Key features](#key-features) +* [Porting](#porting) +* [Project set-up](#project-set-up) +* [PC simulator](#pc-simulator) +* [Screenshots](#screenshots) +* [Contributing](#contributing) +* [Donate](#donate) + +## Key features +* Powerful building blocks buttons, charts, lists, sliders, images etc +* Advanced graphics with animations, anti-aliasing, opacity, smooth scrolling +* Various input devices touch pad, mouse, keyboard, encoder, buttons etc +* Multi language support with UTF-8 decoding +* Fully customizable graphical elements +* Hardware independent to use with any microcontroller or display +* Scalable to operate with few memory (50 kB Flash, 10 kB RAM) +* OS, External memory and GPU supported but not required +* Single frame buffer operation even with advances graphical effects +* Written in C for maximal compatibility +* Simulator to develop on PC without embedded hardware +* Tutorials, examples, themes for rapid development +* Documentation and API references online + +## Porting +In the most sime case you need 4 things: +1. Call `lv_tick_inc(1)` in every millisecods in a Timer or Task +2. Register a function which can **copy a pixel array** to an area of the screen +3. Register a function which can **read an input device**. (E.g. touch pad) +4. Call `lv_task_handler()` periodically in every few milliseconds +For more information visit https://littlevgl.com/porting + +## Project set-up +1. **Clone** or [Download](https://littlevgl.com/download) the lvgl repository: `git clone https://github.com/littlevgl/lvgl.git` +2. **Create project** with your preferred IDE and add the *lvgl* folder +3. Copy **lvgl/lv_conf_templ.h** as **lv_conf.h** next to the *lvgl* folder +4. In the lv_conf.h delete the first `#if 0` and its `#endif`. Let the default configurations at first. +5. In your *main.c*: #include "lvgl/lvgl.h" +6. In your *main function*: + * lvgl_init(); + * tick, display and input device initialization (see above) +7. To **test** create a label: `lv_obj_t * label = lv_label_create(lv_scr_act(), NULL);` +8. In the main *while(1)* call `lv_task_handler();` and make a few milliseconds delay (e.g. `my_delay_ms(5);`) +9. Compile the code and load it to your embedded hardware + +## PC Simulator +If you don't have got an embedded hardware you can test the graphics library in a PC simulator. The simulator uses [SDL2](https://www.libsdl.org/) to emulate a display on your monitor and a touch pad with your mouse. + +There is a pre-configured PC project for **Eclipse CDT** in this repository: https://github.com/littlevgl/pc_simulator + +## Screenshots +![TFT material](http://www.gl.littlev.hu/github_res/tft_material.png) +![TFT zen](http://www.gl.littlev.hu/github_res/tft_zen.png) +![TFT alien](http://www.gl.littlev.hu/github_res/tft_alien.png) +![TFT night](http://www.gl.littlev.hu/github_res/tft_night.png) + +## Contributing +See [CONTRIBUTING.md](https://github.com/littlevgl/lvgl/blob/master/docs/CONTRIBUTING.md) + +## Donate +If you are pleased with the graphics library, found it useful or be happy with the support you got, please help its further development: + +[![Donate](https://littlevgl.com/donate_dir/donate_btn.png)](https://littlevgl.com/donate) diff --git a/include/display/lv_misc/lv_color.h b/include/display/lv_misc/lv_color.h index 4a3e3351..e2da8133 100644 --- a/include/display/lv_misc/lv_color.h +++ b/include/display/lv_misc/lv_color.h @@ -378,7 +378,11 @@ static inline uint8_t lv_color_brightness(lv_color_t color) # define LV_COLOR_MAKE(r8, g8, b8) ((lv_color_t){{g8 >> 5, r8 >> 3, b8 >> 3, (g8 >> 2) & 0x7}}) # endif #elif LV_COLOR_DEPTH == 32 -#define LV_COLOR_MAKE(r8, g8, b8) ((lv_color_t){{b8, g8, r8, 0xff}}) /*Fix 0xff alpha*/ +#ifdef __cplusplus +# define LV_COLOR_MAKE(r8, g8, b8) lv_color_t{b8, g8, r8, 0xff} +#else +# define LV_COLOR_MAKE(r8, g8, b8) ((lv_color_t){{b8, g8, r8, 0xff}}) /*Fix 0xff alpha*/ +#endif #endif #else #if LV_COLOR_DEPTH == 1 diff --git a/include/pros/adi.h b/include/pros/adi.h index e0d2ae7d..c06176ad 100644 --- a/include/pros/adi.h +++ b/include/pros/adi.h @@ -8,7 +8,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -69,6 +69,14 @@ typedef enum adi_port_config_e { E_ADI_ERR = PROS_ERR } adi_port_config_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 @@ -689,6 +697,175 @@ int32_t adi_gyro_reset(adi_gyro_t gyro); */ int32_t adi_gyro_shutdown(adi_gyro_t gyro); +/** + * Reference type for an initialized potentiometer. + * + * This merely contains the port number for the potentiometer, unlike its use as an + * object to store potentiometer data in PROS 2. + */ +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. + */ +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. + */ +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. + */ +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 PROS 2. + */ +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 + */ +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 + */ +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 + */ +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 + */ +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 + */ +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 + */ +int32_t adi_led_clear_pixel(adi_led_t led, uint32_t* buffer, uint32_t buffer_length, uint32_t pixel_position); + #ifdef __cplusplus } // namespace c } // namespace pros diff --git a/include/pros/adi.hpp b/include/pros/adi.hpp index 60e350bf..6dc99ef5 100644 --- a/include/pros/adi.hpp +++ b/include/pros/adi.hpp @@ -8,7 +8,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -21,6 +21,7 @@ #include #include #include +#include #include "pros/adi.h" @@ -40,7 +41,7 @@ class ADIPort { * 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). + * 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 @@ -55,7 +56,7 @@ class ADIPort { * 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). + * 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 @@ -109,7 +110,7 @@ class ADIPort { std::uint8_t _adi_port; }; -class ADIAnalogIn : private ADIPort { +class ADIAnalogIn : protected ADIPort { public: /** * Configures an ADI port to act as an Analog Input. @@ -117,7 +118,7 @@ class ADIAnalogIn : private ADIPort { * 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). + * 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 @@ -133,7 +134,7 @@ class ADIAnalogIn : private ADIPort { * 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). + * 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 @@ -224,7 +225,7 @@ class ADIAnalogIn : private ADIPort { using ADIPort::get_value; }; -using ADIPotentiometer = ADIAnalogIn; +// using ADIPotentiometer = ADIAnalogIn; using ADILineSensor = ADIAnalogIn; using ADILightSensor = ADIAnalogIn; using ADIAccelerometer = ADIAnalogIn; @@ -237,7 +238,7 @@ class ADIAnalogOut : private ADIPort { * 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). + * 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 @@ -250,7 +251,7 @@ class ADIAnalogOut : private ADIPort { * 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). + * 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 @@ -286,7 +287,7 @@ class ADIDigitalOut : private ADIPort { * 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). + * 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 @@ -301,7 +302,7 @@ class ADIDigitalOut : private ADIPort { * 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). + * 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 @@ -337,7 +338,7 @@ class ADIDigitalIn : private ADIPort { * 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). + * 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 @@ -350,7 +351,7 @@ class ADIDigitalIn : private ADIPort { * 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). + * 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 @@ -400,7 +401,7 @@ class ADIMotor : private ADIPort { * 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). + * 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 @@ -413,7 +414,7 @@ class ADIMotor : private ADIPort { * 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). + * 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 @@ -469,7 +470,7 @@ class ADIEncoder : private ADIPort { * 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). + * valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21). * * \param adi_port_top * The "top" wire from the encoder sensor with the removable cover side up @@ -486,7 +487,7 @@ class ADIEncoder : private ADIPort { * 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). + * valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21). * * \param port_tuple * The tuple of the smart port number, the "top" wire from the encoder @@ -535,7 +536,7 @@ class ADIUltrasonic : private ADIPort { * 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). + * valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21). * * \param port_ping * The port connected to the orange OUTPUT cable. This should be in port @@ -552,12 +553,12 @@ class ADIUltrasonic : private ADIPort { * 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). + * valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21). * * \param port_tuple * The tuple of the smart port number, the port connected to the orange - * OUTPUT cable (1, 3, 5, 7 or 'A', 'C', 'E', 'G'), and the port - * connected to the yellow INPUT cable (the next) highest port + * OUTPUT cable (1, 3, 5, 7 or 'A', 'C', 'E', 'G'), and the port + * connected to the yellow INPUT cable (the next) highest port * following port_ping). */ ADIUltrasonic(ext_adi_port_tuple_t port_tuple); @@ -595,7 +596,7 @@ class ADIGyro : private ADIPort { * 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). + * valid range (ADI port: 1-8, 'a'-'h', or 'A'-'H'; smart port: 1-21). * * \param adi_port * The ADI port to initialize as a gyro (from 1-8, 'a'-'h', 'A'-'H') @@ -619,7 +620,7 @@ class ADIGyro : private ADIPort { * 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). + * 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 @@ -658,6 +659,236 @@ class ADIGyro : private ADIPort { */ std::int32_t reset() const; }; + +class ADIPotentiometer : public ADIAnalogIn { + public: + /** + * Configures an ADI port to act as a Potentiometer. + * + * 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 potentiometer_type + * An adi_potentiometer_type_e_t enum value specifying the potentiometer version type + */ + ADIPotentiometer(std::uint8_t adi_port, adi_potentiometer_type_e_t potentiometer_type = E_ADI_POT_EDR); + + /** + * Configures an ADI port on an adi_expander to act as a Potentiometer. + * + * 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 pair of the smart port number (from 1-22) and the + * ADI port number (from 1-8, 'a'-'h', 'A'-'H') to configure + * \param potentiometer_type + * An adi_potentiometer_type_e_t enum value specifying the potentiometer version type + */ + ADIPotentiometer(ext_adi_port_pair_t port_pair, adi_potentiometer_type_e_t potentiometer_type = E_ADI_POT_EDR); + + /** + * 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 + + * \return The potentiometer angle in degrees. + */ + double get_angle() const; + + /** + * 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: + * ENODEV - The port is not configured as a potentiometer + * + * \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 + */ + using ADIAnalogIn::get_value; + + /** + * Calibrates the potentiometer on the specified port and returns the new + * calibration value. + * + * This method assumes that the potentiometer 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::ADIPotentiometer::get_value_calibrated() function. This function + * will return the difference between this value and the current sensor value + * when called. + * + * Do not use this function when the potentiometer value might be unstable (rotating the potentiometer) + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port is not configured as a potentiometer + * + * \return The average potentiometer value computed by this function + */ + using ADIAnalogIn::calibrate; + + /** + * Gets the 12 bit calibrated value of a potentiometer port. + * + * The pros::ADIPotentiometer::calibrate() function must be run first. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port is not configured as a potentiometer + * + * \return The difference of the potentiometer value from its calibrated default from + * -4095 to 4095 + */ + using ADIAnalogIn::get_value_calibrated; +}; + +class ADILed : protected ADIPort { + public: + /** + * @brief Configures an ADI port to act as a LED. + * + * 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 length + * The number of LEDs in the chain + */ + ADILed(std::uint8_t adi_port, std::uint32_t length); + + /** + * @brief Configures an ADI port on a adi_expander to act as a LED. + * + * 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 length + * The number of LEDs in the chain + */ + ADILed(ext_adi_port_pair_t port_pair, std::uint32_t length); + + /** + * @brief Operator overload to access the buffer in the ADILed class, it is + * recommended that you call .update(); after doing any operations with this. + * + * @param i 0 indexed pixel of the lED + * @return uint32_t& the address of the buffer at i to modify + */ + std::uint32_t& operator[] (size_t i); + + /** + * @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 parameter is out of bounds/incorrect + * EADDRINUSE - The port is not configured for ADI output + * + * @return PROS_SUCCESS if successful, PROS_ERR if not + */ + std::int32_t clear_all(); + std::int32_t clear(); + + /** + * @brief Force the LED strip to update with the current buffered values, this + * should be called after any changes to the buffer using the [] operator. + * + * This function uses the following values of errno when an error state is + * reached: + * EINVAL - A parameter is out of bounds/incorrect + * EADDRINUSE - The port is not configured for ADI output + * + * @return PROS_SUCCESS if successful, PROS_ERR if not + */ + std::int32_t update() const; + + /** + * @brief Set the entire led strip to one color + * + * This function uses the following values of errno when an error state is + * reached: + * EINVAL - A parameter is out of bounds/incorrect + * EADDRINUSE - The port is not configured for ADI output + * + * @param color color to set all the led strip value to + * @return PROS_SUCCESS if successful, PROS_ERR if not + */ + std::int32_t set_all(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: + * EINVAL - A parameter is out of bounds/incorrect + * EADDRINUSE - The port is not configured for ADI output + * + * @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 + */ + std::int32_t set_pixel(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: + * EINVAL - A parameter is out of bounds/incorrect + * EADDRINUSE - The port is not configured for ADI output + * + * @param pixel_position position of the pixel to clear + * @return PROS_SUCCESS if successful, PROS_ERR if not + */ + std::int32_t clear_pixel(uint32_t pixel_position); + + /** + * @brief Get the length of the led strip + * + * This function uses the following values of errno when an error state is + * reached: + * EINVAL - A parameter is out of bounds/incorrect + * EADDRINUSE - The port is not configured for ADI output + * + * @return The length (in pixels) of the LED strip + */ + std::int32_t length(); + + protected: + std::vector _buffer; +}; + +// Alias for ADILed +using ADILED = ADILed; + } // namespace pros #endif // _PROS_ADI_HPP_ diff --git a/include/pros/api_legacy.h b/include/pros/api_legacy.h index 748072c7..068f7e8a 100644 --- a/include/pros/api_legacy.h +++ b/include/pros/api_legacy.h @@ -10,7 +10,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, Purdue University ACM SIGBots. * All rights reserved. * * This Source Code Form is subject to the terms of the Mozilla Public diff --git a/include/pros/apix.h b/include/pros/apix.h index 14c8a313..8e7d3068 100644 --- a/include/pros/apix.h +++ b/include/pros/apix.h @@ -12,7 +12,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, Purdue University ACM SIGBots. * All rights reserved. * * This Source Code Form is subject to the terms of the Mozilla Public @@ -377,7 +377,8 @@ typedef enum v5_device_e { E_DEVICE_ADI = 12, E_DEVICE_OPTICAL = 16, E_DEVICE_GPS = 20, - E_DEVICE_GENERIC = 129, + E_DEVICE_SERIAL = 129, + E_DEVICE_GENERIC __attribute__((deprecated("use E_DEVICE_SERIAL instead"))) = E_DEVICE_SERIAL, E_DEVICE_UNDEFINED = 255 } v5_device_e_t; diff --git a/include/pros/colors.h b/include/pros/colors.h index 0f5e3b93..0aa4cb35 100644 --- a/include/pros/colors.h +++ b/include/pros/colors.h @@ -18,7 +18,7 @@ #define RGB2COLOR(R, G, B) ((R & 0xff) << 16 | (G & 0xff) << 8 | (B & 0xff)) #define COLOR2R(COLOR) ((COLOR >> 16) & 0xff) -#define COLOR2G(COLOR) ((COLOR >> 8) && 0xff) +#define COLOR2G(COLOR) ((COLOR >> 8) & 0xff) #define COLOR2B(COLOR) (COLOR & 0xff) #define COLOR_ALICE_BLUE 0x00F0F8FF diff --git a/include/pros/colors.hpp b/include/pros/colors.hpp new file mode 100644 index 00000000..e3d0ba13 --- /dev/null +++ b/include/pros/colors.hpp @@ -0,0 +1,170 @@ +/** + * \file pros/colors.hpp + * + * Contains enum class definitions of colors + * + * This file should not be modified by users, since it gets replaced whenever + * a kernel upgrade occurs. + * + * Copyright (c) 2017-2022 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/. + */ +#ifndef _PROS_COLORS_HPP_ +#define _PROS_COLORS_HPP_ + + +namespace pros{ +enum class Color { + alice_blue = 0x00F0F8FF, + antique_white = 0x00FAEBD7, + aqua = 0x0000FFFF, + aquamarine = 0x007FFFD4, + azure = 0x00F0FFFF, + beige = 0x00F5F5DC, + bisque = 0x00FFE4C4, + black = 0x00000000, + blanched_almond = 0x00FFEBCD, + blue = 0x000000FF, + blue_violet = 0x008A2BE2, + brown = 0x00A52A2A, + burly_wood = 0x00DEB887, + cadet_blue = 0x005F9EA0, + chartreuse = 0x007FFF00, + chocolate = 0x00D2691E, + coral = 0x00FF7F50, + cornflower_blue = 0x006495ED, + cornsilk = 0x00FFF8DC, + crimson = 0x00DC143C, + cyan = 0x0000FFFF, + dark_blue = 0x0000008B, + dark_cyan = 0x00008B8B, + dark_goldenrod = 0x00B8860B, + dark_gray = 0x00A9A9A9, + dark_grey = dark_gray, + dark_green = 0x00006400, + dark_khaki = 0x00BDB76B, + dark_magenta = 0x008B008B, + dark_olive_green = 0x00556B2F, + dark_orange = 0x00FF8C00, + dark_orchid = 0x009932CC, + dark_red = 0x008B0000, + dark_salmon = 0x00E9967A, + dark_sea_green = 0x008FBC8F, + dark_slate_gray = 0x002F4F4F, + dark_slate_grey = dark_slate_gray, + dark_turquoise = 0x0000CED1, + dark_violet = 0x009400D3, + deep_pink = 0x00FF1493, + deep_sky_blue = 0x0000BFFF, + dim_gray = 0x00696969, + dim_grey = dim_gray, + dodger_blue = 0x001E90FF, + fire_brick = 0x00B22222, + floral_white = 0x00FFFAF0, + forest_green = 0x00228B22, + fuchsia = 0x00FF00FF, + gainsboro = 0x00DCDCDC, + ghost_white = 0x00F8F8FF, + gold = 0x00FFD700, + goldenrod = 0x00DAA520, + gray = 0x00808080, + grey = gray, + green = 0x00008000, + green_yellow = 0x00ADFF2F, + honeydew = 0x00F0FFF0, + hot_pink = 0x00FF69B4, + indian_red = 0x00CD5C5C, + indigo = 0x004B0082, + ivory = 0x00FFFFF0, + khaki = 0x00F0E68C, + lavender = 0x00E6E6FA, + lavender_blush = 0x00FFF0F5, + lawn_green = 0x007CFC00, + lemon_chiffon = 0x00FFFACD, + light_blue = 0x00ADD8E6, + light_coral = 0x00F08080, + light_cyan = 0x00E0FFFF, + light_goldenrod_yellow = 0x00FAFAD2, + light_green = 0x0090EE90, + light_gray = 0x00D3D3D3, + light_grey = light_gray, + light_pink = 0x00FFB6C1, + light_salmon = 0x00FFA07A, + light_sea_green = 0x0020B2AA, + light_sky_blue = 0x0087CEFA, + light_slate_gray = 0x00778899, + light_slate_grey = light_slate_gray, + light_steel_blue = 0x00B0C4DE, + light_yellow = 0x00FFFFE0, + lime = 0x0000FF00, + lime_green = 0x0032CD32, + linen = 0x00FAF0E6, + magenta = 0x00FF00FF, + maroon = 0x00800000, + medium_aquamarine = 0x0066CDAA, + medium_blue = 0x000000CD, + medium_orchid = 0x00BA55D3, + medium_purple = 0x009370DB, + medium_sea_green = 0x003CB371, + medium_slate_blue = 0x007B68EE, + medium_spring_green = 0x0000FA9A, + medium_turquoise = 0x0048D1CC, + medium_violet_red = 0x00C71585, + midnight_blue = 0x00191970, + mint_cream = 0x00F5FFFA, + misty_rose = 0x00FFE4E1, + moccasin = 0x00FFE4B5, + navajo_white = 0x00FFDEAD, + navy = 0x00000080, + old_lace = 0x00FDF5E6, + olive = 0x00808000, + olive_drab = 0x006B8E23, + orange = 0x00FFA500, + orange_red = 0x00FF4500, + orchid = 0x00DA70D6, + pale_goldenrod = 0x00EEE8AA, + pale_green = 0x0098FB98, + pale_turquoise = 0x00AFEEEE, + pale_violet_red = 0x00DB7093, + papay_whip = 0x00FFEFD5, + peach_puff = 0x00FFDAB9, + peru = 0x00CD853F, + pink = 0x00FFC0CB, + plum = 0x00DDA0DD, + powder_blue = 0x00B0E0E6, + purple = 0x00800080, + red = 0x00FF0000, + rosy_brown = 0x00BC8F8F, + royal_blue = 0x004169E1, + saddle_brown = 0x008B4513, + salmon = 0x00FA8072, + sandy_brown = 0x00F4A460, + sea_green = 0x002E8B57, + seashell = 0x00FFF5EE, + sienna = 0x00A0522D, + silver = 0x00C0C0C0, + sky_blue = 0x0087CEEB, + slate_blue = 0x006A5ACD, + slate_gray = 0x00708090, + slate_grey = slate_gray, + snow = 0x00FFFAFA, + spring_green = 0x0000FF7F, + steel_blue = 0x004682B4, + tan = 0x00D2B48C, + teal = 0x00008080, + thistle = 0x00D8BFD8, + tomato = 0x00FF6347, + turquoise = 0x0040E0D0, + violet = 0x00EE82EE, + wheat = 0x00F5DEB3, + white = 0x00FFFFFF, + white_smoke = 0x00F5F5F5, + yellow = 0x00FFFF00, + yellow_green = 0x009ACD32, +}; +} // namespace pros + +#endif //_PROS_COLORS_HPP_ diff --git a/include/pros/distance.h b/include/pros/distance.h index fae64a84..b7feda19 100644 --- a/include/pros/distance.h +++ b/include/pros/distance.h @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 diff --git a/include/pros/error.h b/include/pros/error.h new file mode 100644 index 00000000..8485978a --- /dev/null +++ b/include/pros/error.h @@ -0,0 +1,29 @@ +/** + * \file pros/error.h + * + * Contains macro definitions for return types, mostly errors + * + * This file should not be modified by users, since it gets replaced whenever + * a kernel upgrade occurs. + * + * Copyright (c) 2017-2022, 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/. + */ +#ifndef _PROS_ERROR_H_ +#define _PROS_ERROR_H_ + +#include "limits.h" + +// Different Byte Size Errors +#define PROS_ERR_BYTE (INT8_MAX) +#define PROS_ERR_2_BYTE (INT16_MAX) +#define PROS_ERR (INT32_MAX) +#define PROS_ERR_F (INFINITY) + +// Return This on Success +#define PROS_SUCCESS (1) + +#endif diff --git a/include/pros/ext_adi.h b/include/pros/ext_adi.h index 11351fd0..48e79096 100644 --- a/include/pros/ext_adi.h +++ b/include/pros/ext_adi.h @@ -8,7 +8,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -630,6 +630,160 @@ int32_t ext_adi_gyro_reset(ext_adi_gyro_t gyro); */ int32_t ext_adi_gyro_shutdown(ext_adi_gyro_t gyro); +/** + * Reference type for an initialized potentiometer. + * + * This merely contains the port number for the potentiometer, unlike its use as an + * object to store gyro data in PROS 2. + */ +typedef int32_t ext_adi_potentiometer_t; + +/** + * 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 smart_port + * The smart port with the adi expander (1-21) + * \param adi_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. + */ +ext_adi_potentiometer_t ext_adi_potentiometer_init(uint8_t smart_port, uint8_t adi_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 333 degrees thus returning an angle between 0-333 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. + */ +double ext_adi_potentiometer_get_angle(ext_adi_potentiometer_t potentiometer); + +/** + * Reference type for an initialized addressable led, which stores its smart and adi port. + */ +typedef int32_t ext_adi_led_t; + +/** + * Initializes a led 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 + * EINVAL - A given value is not correct, or the buffer is null + * EADDRINUSE - The port is not configured for ADI output + * + * \param smart_port + * The smart port with the adi expander (1-21) + * \param adi_port + * The ADI port to initialize as a led (from 1-8, 'a'-'h', 'A'-'H') + * + * \return An ext_adi_led_t object containing the given port, or PROS_ERR if the + * initialization failed. + */ +ext_adi_led_t ext_adi_led_init(uint8_t smart_port, uint8_t adi_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 + */ +int32_t ext_adi_led_clear_all(ext_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 + */ +int32_t ext_adi_led_set(ext_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 + */ +int32_t ext_adi_led_set_all(ext_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 (0 indexed) + * @return PROS_SUCCESS if successful, PROS_ERR if not + */ +int32_t ext_adi_led_set_pixel(ext_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 (0 indexed) + * @return PROS_SUCCESS if successful, PROS_ERR if not + */ +int32_t ext_adi_led_clear_pixel(ext_adi_led_t led, uint32_t* buffer, uint32_t buffer_length, uint32_t pixel_position); + #ifdef __cplusplus } // namespace c } // namespace pros diff --git a/include/pros/gps.h b/include/pros/gps.h index 0a83edea..1af417bc 100644 --- a/include/pros/gps.h +++ b/include/pros/gps.h @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 diff --git a/include/pros/gps.hpp b/include/pros/gps.hpp index 5c4656c4..0d8b731c 100644 --- a/include/pros/gps.hpp +++ b/include/pros/gps.hpp @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 diff --git a/include/pros/imu.h b/include/pros/imu.h index a772769e..59116eee 100644 --- a/include/pros/imu.h +++ b/include/pros/imu.h @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -56,6 +56,16 @@ typedef struct __attribute__((__packed__)) euler_s { double yaw; } euler_s_t; +#ifdef PROS_USE_SIMPLE_NAMES +#ifdef __cplusplus +#define IMU_STATUS_CALIBRATING pros::E_IMU_STATUS_CALIBRATING +#define IMU_STATUS_ERROR pros::E_IMU_STATUS_ERROR +#else +#define IMU_STATUS_CALIBRATING E_IMU_STATUS_CALIBRATING +#define IMU_STATUS_ERROR E_IMU_STATUS_ERROR +#endif +#endif + #define IMU_MINIMUM_DATA_RATE 5 /** @@ -78,6 +88,27 @@ typedef struct __attribute__((__packed__)) euler_s { */ int32_t imu_reset(uint8_t port); +/** + * Calibrate IMU and Blocks while Calibrating + * + * Calibration takes approximately 2 seconds and blocks during this period, + * with a timeout for this operation being set a 3 seconds as a safety margin. + * Like the other reset function, this function also blocks until the IMU + * status flag is set properly to E_IMU_STATUS_CALIBRATING, with a minimum + * blocking time of 5ms and a timeout of 1 second if it's never set. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as an Inertial Sensor + * EAGAIN - The sensor is already calibrating, or time out setting the status flag. + * + * \param port + * The V5 Inertial Sensor port number from 1-21 + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed (timing out or port claim failure), setting errno. + */ +int32_t imu_reset_blocking(uint8_t port); /** * Set the Inertial Sensor's refresh interval in milliseconds. diff --git a/include/pros/imu.hpp b/include/pros/imu.hpp index 7bee256f..84272b0a 100644 --- a/include/pros/imu.hpp +++ b/include/pros/imu.hpp @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -31,9 +31,11 @@ class Imu { /** * Calibrate IMU * - * Calibration takes approximately 2 seconds, but this function only blocks - * until the IMU status flag is set properly to E_IMU_STATUS_CALIBRATING, - * with a minimum blocking time of 5ms. + * Calibration takes approximately 2 seconds and blocks during this period if + * the blocking param is true, with a timeout for this operation being set a 3 + * seconds as a safety margin. This function also blocks until the IMU + * status flag is set properly to E_IMU_STATUS_CALIBRATING, with a minimum + * blocking time of 5ms and a timeout of 1 second if it's never set. * * This function uses the following values of errno when an error state is * reached: @@ -41,10 +43,12 @@ class Imu { * ENODEV - The port cannot be configured as an Inertial Sensor * EAGAIN - The sensor is already calibrating, or time out setting the status flag. * + * \param blocking + * Whether this function blocks during calibration. * \return 1 if the operation was successful or PROS_ERR if the operation * failed, setting errno. */ - virtual std::int32_t reset() const; + virtual std::int32_t reset(bool blocking = false) const; /** * Set the Inertial Sensor's refresh interval in milliseconds. * @@ -63,7 +67,8 @@ class Imu { * ENODEV - The port cannot be configured as an Inertial Sensor * EAGAIN - The sensor is still calibrating * - * \param rate The data refresh interval in milliseconds + * \param rate + * The data refresh interval in milliseconds * \return 1 if the operation was successful or PROS_ERR if the operation * failed, setting errno. */ diff --git a/include/pros/link.h b/include/pros/link.h new file mode 100644 index 00000000..f370b7e3 --- /dev/null +++ b/include/pros/link.h @@ -0,0 +1,275 @@ +/** + * \file pros/link.h + * + * Contains prototypes for functions related to the robot to robot communications. + * + * Visit https://pros.cs.purdue.edu/v5/api/c/link.html to learn + * more. + * + * This file should not be modified by users, since it gets replaced whenever + * a kernel upgrade occurs. + * + * Copyright (c) 2017-2022, 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/. + */ + +#ifndef _PROS_LINK_H_ +#define _PROS_LINK_H_ + +#include +#include + +#ifdef __cplusplus +extern "C" { +namespace pros { +#endif + +typedef enum link_type_e { + E_LINK_RECIEVER = 0, + E_LINK_TRANSMITTER, + E_LINK_RX = E_LINK_RECIEVER, + E_LINK_TX = E_LINK_TRANSMITTER +} link_type_e_t; + +#ifdef PROS_USE_SIMPLE_NAMES +#ifdef __cplusplus +#define LINK_RECIEVER pros::E_LINK_RECIEVER +#define LINK_TRANSMITTER pros::E_LINK_TRANSMITTER +#define LINK_RX pros::E_LINK_RX +#define LINK_TX pros::E_LINK_TX +#else +#define LINK_RECIEVER E_LINK_RECIEVER +#define LINK_TRANSMITTER E_LINK_TRANSMITTER +#define LINK_RX E_LINK_RX +#define LINK_TX E_LINK_TX +#endif +#endif + +#define LINK_BUFFER_SIZE 512 + +#ifdef __cplusplus +namespace c { +#endif + +/** + * Initializes a link on a radio port, with an indicated type. There might be a + * 1 to 2 second delay from when this function is called to when the link is initializes. + * PROS currently only supports the use of one radio per brain. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \param port + * The port of the radio for the intended link. + * \param link_id + * Unique link ID in the form of a string, needs to be different from other links in + * the area. + * \param type + * Indicates whether the radio link on the brain is a transmitter or reciever, + * with the transmitter having double the transmitting bandwidth as the recieving + * end (1040 bytes/s vs 520 bytes/s). + * + * \return PROS_ERR if initialization fails, 1 if the initialization succeeds. + */ +uint32_t link_init(uint8_t port, const char* link_id, link_type_e_t type); + +/** + * Initializes a link on a radio port, with an indicated type and the ability for + * vexlink to override the controller radio. There might be a 1 to 2 second delay + * from when this function is called to when the link is initializes. + * PROS currently only supports the use of one radio per brain. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \param port + * The port of the radio for the intended link. + * \param link_id + * Unique link ID in the form of a string, needs to be different from other links in + * the area. + * \param type + * Indicates whether the radio link on the brain is a transmitter or reciever, + * with the transmitter having double the transmitting bandwidth as the recieving + * end (1040 bytes/s vs 520 bytes/s). + * + * \return PROS_ERR if initialization fails, 1 if the initialization succeeds. + */ +uint32_t link_init_override(uint8_t port, const char* link_id, link_type_e_t type); + +/** + * Checks if a radio link on a port is active or not. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \param port + * The port of the radio for the intended link. + * + * \return If a radio is connected to a port and it's connected to a link. + */ +bool link_connected(uint8_t port); + +/** + * Returns the bytes of data available to be read + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \param port + * The port of the radio for the intended link. + * + * \return PROS_ERR if port is not a link/radio, else the bytes available to be + * read by the user. + */ +uint32_t link_raw_receivable_size(uint8_t port); + +/** + * Returns the bytes of data available in transmission 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 V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \param port + * The port of the radio for the intended link. + * + * \return PROS_ERR if port is not a link/radio, + */ +uint32_t link_raw_transmittable_size(uint8_t port); + +/** + * Send raw serial data through vexlink. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * EBUSY - The transmitter buffer is still busy with a previous transmission, and there is no + * room in the FIFO buffer (queue) to transmit the data. + * EINVAL - The data given is NULL + * + * \param port + * The port of the radio for the intended link. + * \param data + * Buffer with data to send + * \param data_size + * Bytes of data to be read to the destination buffer + * + * \return PROS_ERR if port is not a link, and the successfully transmitted + * data size if it succeeded. + */ +uint32_t link_transmit_raw(uint8_t port, void* data, uint16_t data_size); + +/** + * Receive raw serial data through vexlink. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * EINVAL - The destination given is NULL, or the size given is larger than the FIFO buffer + * or destination buffer. + * + * \param port + * The port of the radio for the intended link. + * \param dest + * Destination buffer to read data to + * \param data_size + * Bytes of data to be read to the destination buffer + * + * \return PROS_ERR if port is not a link, and the successfully received + * data size if it succeeded. + */ +uint32_t link_receive_raw(uint8_t port, void* dest, uint16_t data_size); + +/** + * Send packeted message through vexlink, with a checksum and start byte. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * EBUSY - The transmitter buffer is still busy with a previous transmission, and there is no + * room in the FIFO buffer (queue) to transmit the data. + * EINVAL - The data given is NULL + * + * \param port + * The port of the radio for the intended link. + * \param data + * Buffer with data to send + * \param data_size + * Bytes of data to be read to the destination buffer + * + * \return PROS_ERR if port is not a link, and the successfully transmitted + * data size if it succeeded. + */ +uint32_t link_transmit(uint8_t port, void* data, uint16_t data_size); + +/** + * Receive packeted message through vexlink, with a checksum and start byte. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * EINVAL - The destination given is NULL, or the size given is larger than the FIFO buffer + * or destination buffer. + * EBADMSG - Protocol error related to start byte, data size, or checksum. + * + * \param port + * The port of the radio for the intended link. + * \param dest + * Destination buffer to read data to + * \param data_size + * Bytes of data to be read to the destination buffer + * + * \return PROS_ERR if port is not a link or protocol error, and the successfully + * transmitted data size if it succeeded. + */ +uint32_t link_receive(uint8_t port, void* dest, uint16_t data_size); + +/** + * Clear the receive buffer of the link, and discarding the data. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \param port + * The port of the radio for the intended link. + * + * \return PROS_ERR if port is not a link, and the successfully received + * data size if it succeeded. + */ +uint32_t link_clear_receive_buf(uint8_t port); + +#ifdef __cplusplus +} +} +} +#endif + +#endif diff --git a/include/pros/link.hpp b/include/pros/link.hpp new file mode 100644 index 00000000..d44c6bd5 --- /dev/null +++ b/include/pros/link.hpp @@ -0,0 +1,200 @@ +/** + * \file pros/link.hpp + * + * Contains prototypes for functions related to robot to robot communications. + * + * Visit https://pros.cs.purdue.edu/v5/tutorials/topical/link.html to learn + * more. + * + * This file should not be modified by users, since it gets replaced whenever + * a kernel upgrade occurs. + * + * Copyright (c) 2017-2021, 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/. + */ +#ifndef _PROS_LINK_HPP_ +#define _PROS_LINK_HPP_ + +#include +#include + +#include "pros/link.h" + +namespace pros { +class Link { + private: + std::uint8_t _port; + + public: + /** + * Initializes a link on a radio port, with an indicated type. There might be a + * 1 to 2 second delay from when this function is called to when the link is initializes. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \param port + * The port of the radio for the intended link. + * \param link_id + * Unique link ID in the form of a string, needs to be different from other links in + * the area. + * \param type + * Indicates whether the radio link on the brain is a transmitter or reciever, + * with the transmitter having double the transmitting bandwidth as the recieving + * end (1040 bytes/s vs 520 bytes/s). + * \param ov + * Indicates if the radio on the given port needs vexlink to override the controller radio + * + * \return PROS_ERR if initialization fails, 1 if the initialization succeeds. + */ + Link(const std::uint8_t port, const std::string link_id, link_type_e_t type, bool ov = false); + + /** + * Checks if a radio link on a port is active or not. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \return If a radio is connected to a port and it's connected to a link. + */ + bool connected(); + + /** + * Returns the bytes of data number of without protocol available to be read + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \return PROS_ERR if port is not a link/radio, else the bytes available to be + * read by the user. + */ + std::uint32_t raw_receivable_size(); + + /** + * Returns the bytes of data available in transmission 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 V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * + * \return PROS_ERR if port is not a link/radio, + */ + std::uint32_t raw_transmittable_size(); + + /** + * Send raw serial data through vexlink. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * EBUSY - The transmitter buffer is still busy with a previous transmission, and there is no + * room in the FIFO buffer (queue) to transmit the data. + * EINVAL - The data given is NULL + * + * \param data + * Buffer with data to send + * \param data_size + * Buffer with data to send + * + * \return PROS_ERR if port is not a link, and the successfully transmitted + * data size if it succeeded. + */ + std::uint32_t transmit_raw(void* data, std::uint16_t data_size); + + /** + * Receive raw serial data through vexlink. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * EINVAL - The destination given is NULL, or the size given is larger than the FIFO buffer + * or destination buffer. + * + * \param dest + * Destination buffer to read data to + * \param data_size + * Bytes of data to be read to the destination buffer + * + * \return PROS_ERR if port is not a link, and the successfully received + * data size if it succeeded. + */ + std::uint32_t receive_raw(void* dest, std::uint16_t data_size); + + /** + * Send packeted message through vexlink, with a checksum and start byte. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * EBUSY - The transmitter buffer is still busy with a previous transmission, and there is no + * room in the FIFO buffer (queue) to transmit the data. + * EINVAL - The data given is NULL + * + * \param data + * Buffer with data to send + * \param data_size + * Bytes of data to be read to the destination buffer + * + * \return PROS_ERR if port is not a link, and the successfully transmitted + * data size if it succeeded. + */ + std::uint32_t transmit(void* data, std::uint16_t data_size); + + /** + * Receive packeted message through vexlink, with a checksum and start byte. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + * EINVAL - The destination given is NULL, or the size given is larger than the FIFO buffer + * or destination buffer. + * EBADMSG - Protocol error related to start byte, data size, or checksum. + + * \param dest + * Destination buffer to read data to + * \param data_size + * Bytes of data to be read to the destination buffer + * + * \return PROS_ERR if port is not a link, and the successfully received + * data size if it succeeded. + */ + std::uint32_t receive(void* dest, std::uint16_t data_size); + + /** + * Clear the receive buffer of the link, and discarding the data. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a radio. + * ENXIO - The sensor is still calibrating, or no link is connected via the radio. + + * \return PROS_ERR if port is not a link, 1 if the operation succeeded. + */ + std::uint32_t clear_receive_buf(); +}; +} // namespace pros + +#endif diff --git a/include/pros/llemu.h b/include/pros/llemu.h index 7b4d64d3..4cb792b3 100644 --- a/include/pros/llemu.h +++ b/include/pros/llemu.h @@ -13,7 +13,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -225,6 +225,28 @@ bool lcd_register_btn2_cb(lcd_btn_cb_fn_t cb); */ uint8_t lcd_read_buttons(void); +/** + * Changes the color of the LCD background to a provided color expressed in + * type lv_color_t. + * + * \param color + * A color of type lv_color_t + * + * \return void + */ +void lcd_set_background_color(lv_color_t color); + +/** + * Changes the text color of the LCD to a provided color expressed in + * type lv_color_t. + * + * \param color + * A color of type lv_color_t + * + * \return void + */ +void lcd_set_text_color(lv_color_t color); + #ifdef __cplusplus } // namespace c } // namespace pros diff --git a/include/pros/llemu.hpp b/include/pros/llemu.hpp index aa96e9d6..8818eddb 100644 --- a/include/pros/llemu.hpp +++ b/include/pros/llemu.hpp @@ -13,7 +13,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -152,7 +152,7 @@ using lcd_btn_cb_fn_t = void (*)(void); * user-provided callback function will be invoked. * * \param cb - * A callback function of type lcd_btn_cb_fn_t(void (*cb)(void)) + * A callback function of type lcd_btn_cb_fn_t(void (*cb)(void)) */ void register_btn0_cb(lcd_btn_cb_fn_t cb); @@ -163,7 +163,7 @@ void register_btn0_cb(lcd_btn_cb_fn_t cb); * user-provided callback function will be invoked. * * \param cb - * A callback function of type lcd_btn_cb_fn_t(void (*cb)(void)) + * A callback function of type lcd_btn_cb_fn_t(void (*cb)(void)) */ void register_btn1_cb(lcd_btn_cb_fn_t cb); @@ -174,7 +174,7 @@ void register_btn1_cb(lcd_btn_cb_fn_t cb); * user-provided callback function will be invoked. * * \param cb - * A callback function of type lcd_btn_cb_fn_t(void (*cb)(void)) + * A callback function of type lcd_btn_cb_fn_t(void (*cb)(void)) */ void register_btn2_cb(lcd_btn_cb_fn_t cb); @@ -193,6 +193,69 @@ void register_btn2_cb(lcd_btn_cb_fn_t cb); * \return The buttons pressed as a bit mask */ std::uint8_t read_buttons(void); + +/** + * Changes the color of the LCD background to a provided color expressed in + * type lv_color_t. + * + * \param color + * A color of type lv_color_t + * + * \return void + */ +void set_background_color(lv_color_t color); + +/** + * Changes the color of the LCD background to a provided color expressed in RGB + * form, with three values of type uint8_t. + * + * \param r + * A value of type uint8_t, with a range of 0 to 255, representing the + * red value of a color + * + * \param g + * A value of type uint8_t, with a range of 0 to 255, representing the + * green value of a color + * + * \param b + * A value of type uint8_t, with a range of 0 to 255, representing the + * blue value of a color + * + * \return void + */ +void set_background_color(std::uint8_t r, std::uint8_t g, std::uint8_t b); + +/** + * Changes the text color of the LCD to a provided color expressed in + * type lv_color_t. + * + * \param color + * A color of type lv_color_t + * + * \return void + */ +void set_text_color(lv_color_t color); + +/** + * Changes the text color of the LCD to a provided color expressed in RGB + * form, with three values of type uint8_t. + * + * \param r + * A value of type uint8_t, with a range of 0 to 255, representing the + * red value of a color + * + * \param g + * A value of type uint8_t, with a range of 0 to 255, representing the + * green value of a color + * + * \param b + * A value of type uint8_t, with a range of 0 to 255, representing the + * blue value of a color + * + * \return void + */ +void set_text_color(std::uint8_t r, std::uint8_t g, std::uint8_t b); + } // namespace lcd } // namespace pros diff --git a/include/pros/misc.h b/include/pros/misc.h index b629ec04..0b6c923f 100644 --- a/include/pros/misc.h +++ b/include/pros/misc.h @@ -10,7 +10,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, Purdue University ACM SIGBots. * All rights reservered. * * This Source Code Form is subject to the terms of the Mozilla Public @@ -150,6 +150,25 @@ failed to connect or an invalid id is given. errno = EACCES; \ return PROS_ERR; \ } \ +/******************************************************************************/ +/** Date and Time **/ +/******************************************************************************/ + +extern const char* baked_date; +extern const char* baked_time; + +typedef struct { + uint16_t year; // Year - 1980 + uint8_t day; + uint8_t month; // 1 = January +} date_s_t; + +typedef struct { + uint8_t hour; + uint8_t min; + uint8_t sec; + uint8_t sec_hund; // hundredths of a second +} time_s_t; #ifdef __cplusplus namespace c { diff --git a/include/pros/misc.hpp b/include/pros/misc.hpp index efc3ed57..2415c2f1 100644 --- a/include/pros/misc.hpp +++ b/include/pros/misc.hpp @@ -10,7 +10,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, Purdue University ACM SIGBots. * All rights reservered. * * This Source Code Form is subject to the terms of the Mozilla Public diff --git a/include/pros/motors.h b/include/pros/motors.h index 62a79662..51ee02f4 100644 --- a/include/pros/motors.h +++ b/include/pros/motors.h @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -56,6 +56,27 @@ namespace c { */ int32_t motor_move(uint8_t port, int32_t voltage); +/** + * 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 motor_move_absolute(port, 0) + * or motor_move_relative(port, 0). + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as a motor + * + * \param port + * The V5 port number from 1-21 + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ +int32_t motor_brake(uint8_t port); + /** * Sets the target absolute position for the motor to move to. * @@ -576,8 +597,14 @@ typedef enum motor_encoder_units_e { */ typedef enum motor_gearset_e { E_MOTOR_GEARSET_36 = 0, // 36:1, 100 RPM, Red gear set + E_MOTOR_GEAR_RED = E_MOTOR_GEARSET_36, + E_MOTOR_GEAR_100 = E_MOTOR_GEARSET_36, E_MOTOR_GEARSET_18 = 1, // 18:1, 200 RPM, Green gear set + E_MOTOR_GEAR_GREEN = E_MOTOR_GEARSET_18, + E_MOTOR_GEAR_200 = E_MOTOR_GEARSET_18, E_MOTOR_GEARSET_06 = 2, // 6:1, 600 RPM, Blue gear set + E_MOTOR_GEAR_BLUE = E_MOTOR_GEARSET_06, + E_MOTOR_GEAR_600 = E_MOTOR_GEARSET_06, E_MOTOR_GEARSET_INVALID = INT32_MAX } motor_gearset_e_t; @@ -592,9 +619,15 @@ typedef enum motor_gearset_e { #define MOTOR_ENCODER_COUNTS pros::E_MOTOR_ENCODER_COUNTS #define MOTOR_ENCODER_INVALID pros::E_MOTOR_ENCODER_INVALID #define MOTOR_GEARSET_36 pros::E_MOTOR_GEARSET_36 +#define MOTOR_GEAR_RED pros::E_MOTOR_GEAR_RED +#define MOTOR_GEAR_100 pros::E_MOTOR_GEAR_100 #define MOTOR_GEARSET_18 pros::E_MOTOR_GEARSET_18 +#define MOTOR_GEAR_GREEN pros::E_MOTOR_GEAR_GREEN +#define MOTOR_GEAR_200 pros::E_MOTOR_GEAR_200 #define MOTOR_GEARSET_06 pros::E_MOTOR_GEARSET_06 #define MOTOR_GEARSET_6 pros::E_MOTOR_GEARSET_06 +#define MOTOR_GEAR_BLUE pros::E_MOTOR_GEAR_BLUE +#define MOTOR_GEAR_600 pros::E_MOTOR_GEAR_600 #define MOTOR_GEARSET_INVALID pros::E_MOTOR_GEARSET_INVALID #else #define MOTOR_BRAKE_COAST E_MOTOR_BRAKE_COAST @@ -606,9 +639,15 @@ typedef enum motor_gearset_e { #define MOTOR_ENCODER_COUNTS E_MOTOR_ENCODER_COUNTS #define MOTOR_ENCODER_INVALID E_MOTOR_ENCODER_INVALID #define MOTOR_GEARSET_36 E_MOTOR_GEARSET_36 +#define MOTOR_GEAR_RED E_MOTOR_GEAR_RED +#define MOTOR_GEAR_100 E_MOTOR_GEAR_100 #define MOTOR_GEARSET_18 E_MOTOR_GEARSET_18 +#define MOTOR_GEAR_GREEN E_MOTOR_GEAR_GREEN +#define MOTOR_GEAR_200 E_MOTOR_GEAR_200 #define MOTOR_GEARSET_06 E_MOTOR_GEARSET_06 #define MOTOR_GEARSET_6 E_MOTOR_GEARSET_06 +#define MOTOR_GEAR_BLUE E_MOTOR_GEAR_BLUE +#define MOTOR_GEAR_600 E_MOTOR_GEAR_600 #define MOTOR_GEARSET_INVALID E_MOTOR_GEARSET_INVALID #endif #endif diff --git a/include/pros/motors.hpp b/include/pros/motors.hpp index 6d743cfe..da330a9c 100644 --- a/include/pros/motors.hpp +++ b/include/pros/motors.hpp @@ -20,8 +20,11 @@ #define _PROS_MOTORS_HPP_ #include +#include +#include #include "pros/motors.h" +#include "pros/rtos.hpp" namespace pros { class Motor { @@ -43,16 +46,16 @@ class Motor { * \param encoder_units * The motor's encoder units */ - explicit Motor(const std::uint8_t port, const motor_gearset_e_t gearset, const bool reverse, + explicit Motor(const std::int8_t port, const motor_gearset_e_t gearset, const bool reverse, const motor_encoder_units_e_t encoder_units); - explicit Motor(const std::uint8_t port, const motor_gearset_e_t gearset, const bool reverse); + explicit Motor(const std::int8_t port, const motor_gearset_e_t gearset, const bool reverse); - explicit Motor(const std::uint8_t port, const motor_gearset_e_t gearset); + explicit Motor(const std::int8_t port, const motor_gearset_e_t gearset); - explicit Motor(const std::uint8_t port, const bool reverse); + explicit Motor(const std::int8_t port, const bool reverse); - explicit Motor(const std::uint8_t port); + explicit Motor(const std::int8_t port); /****************************************************************************/ /** Motor movement functions **/ @@ -175,8 +178,6 @@ class Motor { * 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 * @@ -185,6 +186,23 @@ class Motor { */ virtual std::int32_t move_voltage(const std::int32_t voltage) const; + /** + * 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 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 + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ + virtual std::int32_t brake(void) const; + /** * 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 @@ -340,9 +358,6 @@ class Motor { * reached: * ENODEV - The port cannot be configured as a motor * - * \param port - * The V5 port number from 1-21 - * * \return A bitfield containing the motor's faults. */ virtual std::uint32_t get_faults(void) const; @@ -356,9 +371,6 @@ class Motor { * reached: * ENODEV - The port cannot be configured as a motor * - * \param port - * The V5 port number from 1-21 - * * \return A bitfield containing the motor's flags. */ virtual std::uint32_t get_flags(void) const; @@ -566,8 +578,9 @@ class Motor { * * \return A motor_pid_s_t struct formatted properly in 4.4. */ - [[deprecated("Changing these values is not supported by VEX and may lead to permanent motor damage.")]] - static motor_pid_s_t convert_pid(double kf, double kp, double ki, double kd); + [[deprecated( + "Changing these values is not supported by VEX and may lead to permanent motor damage.")]] static motor_pid_s_t + convert_pid(double kf, double kp, double ki, double kd); /** * Takes in floating point values and returns a properly formatted pid struct. @@ -596,8 +609,10 @@ class Motor { * * \return A motor_pid_s_t struct formatted properly in 4.4. */ - [[deprecated("Changing these values is not supported by VEX and may lead to permanent motor damage.")]] - static motor_pid_full_s_t convert_pid_full(double kf, double kp, double ki, double kd, double filter, double limit, double threshold, + [[deprecated( + "Changing these values is not supported by VEX and may lead to permanent motor " + "damage.")]] static motor_pid_full_s_t + convert_pid_full(double kf, double kp, double ki, double kd, double filter, double limit, double threshold, double loopspeed); /** @@ -617,8 +632,9 @@ class Motor { * \return 1 if the operation was successful or PROS_ERR if the operation * failed, setting errno. */ - [[deprecated("Changing these values is not supported by VEX and may lead to permanent motor damage.")]] - virtual std::int32_t set_pos_pid(const motor_pid_s_t pid) const; + [[deprecated( + "Changing these values is not supported by VEX and may lead to permanent motor damage.")]] virtual std::int32_t + set_pos_pid(const motor_pid_s_t pid) const; /** * Sets one of motor_pid_full_s_t for the motor. @@ -636,8 +652,9 @@ class Motor { * \return 1 if the operation was successful or PROS_ERR if the operation * failed, setting errno. */ - [[deprecated("Changing these values is not supported by VEX and may lead to permanent motor damage.")]] - virtual std::int32_t set_pos_pid_full(const motor_pid_full_s_t pid) const; + [[deprecated( + "Changing these values is not supported by VEX and may lead to permanent motor damage.")]] virtual std::int32_t + set_pos_pid_full(const motor_pid_full_s_t pid) const; /** * Sets one of motor_pid_s_t for the motor. This intended to just modify the @@ -656,8 +673,9 @@ class Motor { * \return 1 if the operation was successful or PROS_ERR if the operation * failed, setting errno. */ - [[deprecated("Changing these values is not supported by VEX and may lead to permanent motor damage.")]] - virtual std::int32_t set_vel_pid(const motor_pid_s_t pid) const; + [[deprecated( + "Changing these values is not supported by VEX and may lead to permanent motor damage.")]] virtual std::int32_t + set_vel_pid(const motor_pid_s_t pid) const; /** * Sets one of motor_pid_full_s_t for the motor. @@ -675,8 +693,9 @@ class Motor { * \return 1 if the operation was successful or PROS_ERR if the operation * failed, setting errno. */ - [[deprecated("Changing these values is not supported by VEX and may lead to permanent motor damage.")]] - virtual std::int32_t set_vel_pid_full(const motor_pid_full_s_t pid) const; + [[deprecated( + "Changing these values is not supported by VEX and may lead to permanent motor damage.")]] virtual std::int32_t + set_vel_pid_full(const motor_pid_full_s_t pid) const; /** * Sets the reverse flag for the motor. @@ -775,8 +794,10 @@ class Motor { * \return A motor_pid_full_s_t containing the position PID constants last set * to the given motor */ - [[deprecated("Changing these values is not supported by VEX and may lead to permanent motor damage.")]] - virtual motor_pid_full_s_t get_pos_pid(void) const; + [[deprecated( + "Changing these values is not supported by VEX and may lead to permanent motor " + "damage.")]] virtual motor_pid_full_s_t + get_pos_pid(void) const; /** * Gets the velocity PID that was set for the motor. This function will return @@ -793,8 +814,10 @@ class Motor { * \return A motor_pid_full_s_t containing the velocity PID constants last set * to the given motor */ - [[deprecated("Changing these values is not supported by VEX and may lead to permanent motor damage.")]] - virtual motor_pid_full_s_t get_vel_pid(void) const; + [[deprecated( + "Changing these values is not supported by VEX and may lead to permanent motor " + "damage.")]] virtual motor_pid_full_s_t + get_vel_pid(void) const; /** * Gets the operation direction of the motor as set by the user. @@ -834,6 +857,499 @@ class Motor { const std::uint8_t _port; }; +class Motor_Group { + public: + explicit Motor_Group(const std::initializer_list motors); + explicit Motor_Group(const std::vector motor_ports); + /****************************************************************************/ + /** Motor Group movement functions **/ + /** **/ + /** These functions allow programmers to make motor groups move **/ + /****************************************************************************/ + /** + * Sets the voltage for all the motors in the motor group from -128 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 pros::Motor::move() on each motor individually + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - One of the ports cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \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. + */ + std::int32_t operator=(std::int32_t); + + /** + * Sets the voltage for the motors in the motor group 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 on each motor. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \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. + */ + std::int32_t move(std::int32_t voltage); + + /** + * Sets the target absolute position for the motors to move to. + * + * This movement is relative to the position of the motors 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 motors, 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \param position + * The absolute position to move to in the motors' 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. + */ + std::int32_t move_absolute(const double position, const std::int32_t velocity); + + /** + * 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \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. + */ + std::int32_t move_relative(const double position, const std::int32_t velocity); + + /** + * Sets the velocity for the motors. + * + * 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \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. + */ + std::int32_t move_velocity(const std::int32_t velocity); + + /** + * Sets the output voltage for the motors 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \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. + */ + std::int32_t move_voltage(const std::int32_t voltage); + + /** + * 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 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ + std::int32_t brake(void); + /****************************************************************************/ + /** Motor configuration functions **/ + /** **/ + /** These functions let programmers configure the behavior of motor groups **/ + /****************************************************************************/ + + /** + * Indexes Motor in the Motor_Group in the same way as an array. + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - Out of bounds on indexing the motor groups. + * + * \param i + * The index value in the motor group. + * + * \return the appropriate Motor reference or the erno if the operation + * failed + */ + pros::Motor& operator[](int i); + + + /** + * Indexes Motor in the Motor_Group in the same way as an array. + * + * \return the size of the vector containing motors + */ + std::int32_t size(); + + /** + * Sets the position for the motor in its encoder units. + * + * This will be the future reference point for the motors' "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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \param position + * The new reference position in its encoder units + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ + std::int32_t set_zero_position(const double position); + /** + * Sets one of motor_brake_mode_e_t to the motor group. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \param mode + * The motor_brake_mode_e_t to set for the motor + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ + std::int32_t set_brake_modes(motor_brake_mode_e_t mode); + + /** + * Sets the reverse flag for all the motors in the motor group. + * + * 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \param reverse + * True reverses the motor, false is default + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ + std::int32_t set_reversed(const bool reversed); + + /** + * Sets the voltage limit for all the motors 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \param limit + * The new voltage limit in Volts + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ + std::int32_t set_voltage_limit(const std::int32_t limit); + /** + * Sets one of motor_gearset_e_t for all the motors in the motor group. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \param gearset + * The new motor gearset + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ + std::int32_t set_gearing(const motor_gearset_e_t gearset); + + /** + * Sets one of motor_encoder_units_e_t for the all the motor encoders + * in the motor group. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \param units + * The new motor encoder units + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ + std::int32_t set_encoder_units(const motor_encoder_units_e_t units); + + /** + * Sets the "absolute" zero position of the motor group 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ + std::int32_t tare_position(void); + + /****************************************************************************/ + /** Motor telemetry functions **/ + /** **/ + /** These functions let programmers to collect telemetry from motor groups **/ + /****************************************************************************/ + /** + * Gets the actual velocity of each motor. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \return A vector with the each motor's actual velocity in RPM in the order + * or a vector filled with PROS_ERR_F if the operation failed, setting errno. + */ + std::vector get_actual_velocities(void); + + /** + * 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 + * + * \return A vector filled with The commanded motor velocities from + * +-100, +-200, or +-600, or a vector filled with PROS_ERR if the operation + * failed, setting errno. + */ + std::vector get_target_velocities(void); + + /** + * Gets the target position set for 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \return A vector filled with the target position in its encoder units + * or a vector filled with PROS_ERR_F if the operation failed, setting errno. + */ + std::vector get_target_positions(void); + + /** + * 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 + * + * \return The motor's absolute position in its encoder units or PROS_ERR_F + * if the operation failed, setting errno. + */ + std::vector get_positions(void); + /** + * Gets the efficiency of the motors 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \return A vector filled with the motor's efficiency in percent + * or a vector filled with PROS_ERR_F if the operation failed, setting errno. + */ + std::vector get_efficiencies(void); + + /** + * Checks if the motors are 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \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. + */ + std::vector are_over_current(void); + + /** + * Gets the temperature limit flag for the motors. + * + * 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 with for each motor a 1 if the temperature limit is + * exceeded and 0 if the temperature is below the limit, + * or a vector filled with PROS_ERR if the operation failed, setting errno. + */ + std::vector are_over_temp(void); + + /** + * Gets the brake mode that was set for the motors. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \return A Vector with for each motor one of motor_brake_mode_e_t, + * according to what was set for the motor, or a vector filled with + * E_MOTOR_BRAKE_INVALID if the operation failed, setting errno. + */ + std::vector get_brake_modes(void); + + /** + * 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \return One of motor_gearset_e_t according to what is set for the motor, + * or E_GEARSET_INVALID if the operation failed. + */ + std::vector get_gearing(void); + + /** + * Gets the current drawn by each 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \return A vector containing each motor's current in mA + * or a vector filled with PROS_ERR if the operation failed, setting errno. + */ + std::vector get_current_draws(void); + + /** + * Gets the current limit for each 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 + * EACCESS - The Motor group mutex can't be taken or given + * + * \return A vector with each motor's current limit in mA or a vector filled + * with PROS_ERR if the operation failed, setting errno. + */ + std::vector get_current_limits(void); + + /** + * Gets the port number of each motor. + * + * \return a vector with each motor's port number. + */ + std::vector get_ports(void); + /** + * Gets the direction of movement for the motors. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * + * \return 1 for moving in the positive direction, -1 for moving in the + * negative direction, and PROS_ERR if the operation failed, setting errno. + */ + std::vector get_directions(void); + + /** + * Gets the encoder units that were set for each motor. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \return A vector filled with one of motor_encoder_units_e_t for each motor + * according to what is set for the motor or a vector filled with + * E_MOTOR_ENCODER_INVALID if the operation failed. + */ + std::vector get_encoder_units(void); + + private: + std::vector _motors; + pros::Mutex _motor_group_mutex; + std::uint8_t _motor_count; +}; + +using MotorGroup = Motor_Group; //alias + namespace literals { const pros::Motor operator"" _mtr(const unsigned long long int m); const pros::Motor operator"" _rmtr(const unsigned long long int m); diff --git a/include/pros/optical.h b/include/pros/optical.h index b2867aa3..c3cace98 100644 --- a/include/pros/optical.h +++ b/include/pros/optical.h @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -21,7 +21,7 @@ #include #include -#include "api.h" +#include "error.h" #define OPT_GESTURE_ERR (INT8_MAX) #define OPT_COUNT_ERR (INT16_MAX) @@ -34,7 +34,14 @@ namespace c { #endif -typedef enum optical_direction_e { NO_GESTURE = 0, UP = 1, DOWN = 2, RIGHT = 3, LEFT = 4, ERROR = PROS_ERR } optical_direction_e_t; +typedef enum optical_direction_e { + NO_GESTURE = 0, + UP = 1, + DOWN = 2, + RIGHT = 3, + LEFT = 4, + ERROR = PROS_ERR +} optical_direction_e_t; typedef struct optical_rgb_s { double red; diff --git a/include/pros/optical.hpp b/include/pros/optical.hpp index 381c52d2..783520d4 100644 --- a/include/pros/optical.hpp +++ b/include/pros/optical.hpp @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 diff --git a/include/pros/rotation.h b/include/pros/rotation.h index 021a8417..197936ac 100644 --- a/include/pros/rotation.h +++ b/include/pros/rotation.h @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -180,6 +180,24 @@ int32_t rotation_set_reversed(uint8_t port, bool value); */ int32_t rotation_reverse(uint8_t port); +/** + * Initialize the Rotation Sensor with a reverse flag + * + * This function uses the following values of errno when an error state is + * reached: + * ENXIO - The given value is not within the range of V5 ports (1-21). + * ENODEV - The port cannot be configured as an Rotation Sensor + * + * \param port + * The V5 Rotation Sensor port number from 1-21 + * \param reverse_flag + * Determines if the Rotation Sensor is reversed or not. + * + * \return 1 if the operation was successful or PROS_ERR if the operation + * failed, setting errno. + */ +int32_t rotation_init_reverse(uint8_t port, bool reverse_flag); + /** * Get the Rotation Sensor's reversed flag * diff --git a/include/pros/rotation.hpp b/include/pros/rotation.hpp index fa9de552..c53ab7b1 100644 --- a/include/pros/rotation.hpp +++ b/include/pros/rotation.hpp @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 @@ -29,6 +29,8 @@ class Rotation { public: Rotation(const std::uint8_t port) : _port(port){}; + Rotation(const std::uint8_t port, const bool reverse_flag); + /** * Reset the Rotation Sensor * diff --git a/include/pros/rtos.h b/include/pros/rtos.h index 7b29526f..3afdb24a 100644 --- a/include/pros/rtos.h +++ b/include/pros/rtos.h @@ -10,7 +10,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, Purdue University ACM SIGBots. * All rights reserved. * * This Source Code Form is subject to the terms of the Mozilla Public @@ -307,6 +307,21 @@ task_t task_get_current(); */ uint32_t task_notify(task_t task); +/** + * + * Utilizes task notifications to wait until specified task is complete and deleted, + * then continues to execute the program. Analogous to std::thread::join in C++. + * + * See https://pros.cs.purdue.edu/v5/tutorials/topical/notifications.html for + * details. + * + * \param task + * The task to wait on. + * + * \return void + */ +void task_join(task_t task); + /** * Sends a notification to a task, optionally performing some action. Will also * retrieve the value of the notification in the target task before modifying diff --git a/include/pros/rtos.hpp b/include/pros/rtos.hpp index 37000fa4..0cd0d6c6 100644 --- a/include/pros/rtos.hpp +++ b/include/pros/rtos.hpp @@ -10,7 +10,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, Purdue University ACM SIGBots. * All rights reserved. * * This Source Code Form is subject to the terms of the Mozilla Public @@ -23,10 +23,12 @@ #include "pros/rtos.h" #undef delay +#include #include #include #include #include +#include #include namespace pros { @@ -57,7 +59,7 @@ class Task { * debugging. The name may be up to 32 characters long. * */ - Task(task_fn_t function, void* parameters = NULL, std::uint32_t prio = TASK_PRIORITY_DEFAULT, + Task(task_fn_t function, void* parameters = nullptr, std::uint32_t prio = TASK_PRIORITY_DEFAULT, std::uint16_t stack_depth = TASK_STACK_DEPTH_DEFAULT, const char* name = ""); /** @@ -103,14 +105,14 @@ class Task { */ template static task_t create(F&& function, std::uint32_t prio = TASK_PRIORITY_DEFAULT, - std::uint16_t stack_depth = TASK_STACK_DEPTH_DEFAULT, const char* name = "") { + std::uint16_t stack_depth = TASK_STACK_DEPTH_DEFAULT, const char* name = "") { static_assert(std::is_invocable_r_v); return pros::c::task_create( - [](void* parameters) { - std::unique_ptr> ptr{static_cast*>(parameters)}; - (*ptr)(); - }, - new std::function(std::forward(function)), prio, stack_depth, name); + [](void* parameters) { + std::unique_ptr> ptr{static_cast*>(parameters)}; + (*ptr)(); + }, + new std::function(std::forward(function)), prio, stack_depth, name); } /** @@ -131,7 +133,7 @@ class Task { static task_t create(F&& function, const char* name) { return Task::create(std::forward(function), TASK_PRIORITY_DEFAULT, TASK_STACK_DEPTH_DEFAULT, name); } - + /** * Creates a new task and add it to the list of tasks that are ready to run. * @@ -146,15 +148,21 @@ class Task { * 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. + * stack. TASK_STACK_DEPTH_DEFAULT is typically sufficient. * \param name * A descriptive name for the task. This is mainly used to facilitate * debugging. The name may be up to 32 characters long. * */ template - Task(F&& function, std::uint32_t prio = TASK_PRIORITY_DEFAULT, std::uint16_t stack_depth = TASK_STACK_DEPTH_DEFAULT, - const char* name = "") : Task(Task::create(std::forward(function), prio, stack_depth, name)) { + explicit Task(F&& function, std::uint32_t prio = TASK_PRIORITY_DEFAULT, + std::uint16_t stack_depth = TASK_STACK_DEPTH_DEFAULT, const char* name = "") + : Task( + [](void* parameters) { + std::unique_ptr> ptr{static_cast*>(parameters)}; + (*ptr)(); + }, + new std::function(std::forward(function)), prio, stack_depth, name) { static_assert(std::is_invocable_r_v); } @@ -183,7 +191,7 @@ class Task { * A task handle from task_create() for which to create a pros::Task * object. */ - Task(task_t task); + explicit Task(task_t task); /** * Get the currently running Task @@ -213,7 +221,7 @@ class Task { * * \return The priority of the task */ - std::uint32_t get_priority(void); + std::uint32_t get_priority(); /** * Sets the priority of the specified task. @@ -232,12 +240,12 @@ class Task { * * \return The state of the task */ - std::uint32_t get_state(void); + std::uint32_t get_state(); /** * Suspends the specified task, making it ineligible to be scheduled. */ - void suspend(void); + void suspend(); /** * Resumes the specified task, making it eligible to be scheduled. @@ -245,19 +253,19 @@ class Task { * \param task * The task to resume */ - void resume(void); + void resume(); /** * Gets the name of the specified task. * * \return A pointer to the name of the task */ - const char* get_name(void); + const char* get_name(); /** * Convert this object to a C task_t handle */ - operator task_t() { + explicit operator task_t() { return task; } @@ -270,7 +278,18 @@ class Task { * * \return Always returns true. */ - std::uint32_t notify(void); + std::uint32_t notify(); + + /** + * Utilizes task notifications to wait until specified task is complete and deleted, + * then continues to execute the program. Analogous to std::thread::join in C++. + * + * See https://pros.cs.purdue.edu/v5/tutorials/topical/notifications.html for + * details. + * + * \return void + */ + void join(); /** * Sends a notification to a task, optionally performing some action. Will @@ -322,7 +341,7 @@ class Task { * * \return False if there was not a notification waiting, true if there was */ - bool notify_clear(void); + bool notify_clear(); /** * Delays a task for a given number of milliseconds. @@ -359,15 +378,43 @@ class Task { * * \return The number of tasks that are currently being managed by the kernel. */ - static std::uint32_t get_count(void); + static std::uint32_t get_count(); private: - task_t task; + task_t task{}; +}; + +// STL Clock compliant clock +struct Clock { + using rep = std::uint32_t; + using period = std::milli; + using duration = std::chrono::duration; + using time_point = std::chrono::time_point; + const bool is_steady = true; + + /** + * Gets the current time. + * + * Effectively a wrapper around pros::millis() + * + * \return The current time + */ + static time_point now(); }; class Mutex { + std::shared_ptr> mutex; + public: - Mutex(void); + Mutex(); + + // disable copy and move construction and assignment per Mutex requirements + // (see https://en.cppreference.com/w/cpp/named_req/Mutex) + Mutex(const Mutex&) = delete; + Mutex(Mutex&&) = delete; + + Mutex& operator=(const Mutex&) = delete; + Mutex& operator=(Mutex&&) = delete; /** * Takes and locks a mutex indefinetly. @@ -380,7 +427,7 @@ class Mutex { * is returned, then errno is set with a hint about why the the mutex * couldn't be taken. */ - bool take(void); + bool take(); /** * Takes and locks a mutex, waiting for up to a certain number of milliseconds @@ -412,10 +459,173 @@ class Mutex { * false is returned, then errno is set with a hint about why the mutex * couldn't be returned. */ - bool give(void); + bool give(); - private: - std::shared_ptr> mutex; + /** + * Takes and locks a mutex, waiting for up to TIMEOUT_MAX milliseconds. + * + * Effectively equivalent to calling pros::Mutex::take with TIMEOUT_MAX as + * the parameter. + * + * Conforms to named requirment BasicLockable + * \see https://en.cppreference.com/w/cpp/named_req/BasicLockable + * + * \note Consider using a std::unique_lock, std::lock_guard, or + * std::scoped_lock instead of interacting with the Mutex directly. + * + * \exception std::system_error Mutex could not be locked within TIMEOUT_MAX + * milliseconds. see errno for details. + */ + void lock(); + + /** + * Unlocks a mutex. + * + * Equivalent to calling pros::Mutex::give. + * + * Conforms to named requirement BasicLockable + * \see https://en.cppreference.com/w/cpp/named_req/BasicLockable + * + * \note Consider using a std::unique_lock, std::lock_guard, or + * std::scoped_lock instead of interacting with the Mutex direcly. + */ + void unlock(); + + /** + * Try to lock a mutex. + * + * Returns immediately if unsucessful. + * + * Conforms to named requirement Lockable + * \see https://en.cppreference.com/w/cpp/named_req/Lockable + * + * \return True when lock was acquired succesfully, or false otherwise. + */ + bool try_lock(); + + /** + * Takes and locks a mutex, waiting for a specified duration. + * + * Equivalent to calling pros::Mutex::take with a duration specified in + * milliseconds. + * + * Conforms to named requirement TimedLockable + * \see https://en.cppreference.com/w/cpp/named_req/TimedLockable + * + * \param rel_time Time to wait before the mutex becomes available. + * \return True if the lock was acquired succesfully, otherwise false. + */ + template + bool try_lock_for(const std::chrono::duration& rel_time) { + return take(std::chrono::duration_cast(rel_time).count()); + } + + /** + * Takes and locks a mutex, waiting until a specified time. + * + * Conforms to named requirement TimedLockable + * \see https://en.cppreference.com/w/cpp/named_req/TimedLockable + * + * \param abs_time Time point until which to wait for the mutex. + * \return True if the lock was acquired succesfully, otherwise false. + */ + template + bool try_lock_until(const std::chrono::time_point& abs_time) { + return take(std::max(static_cast(0), (abs_time - Clock::now()).count())); + } +}; + +template +class MutexVar; + +template +class MutexVarLock { + Mutex& mutex; + Var& var; + + friend class MutexVar; + + constexpr MutexVarLock(Mutex& mutex, Var& var) : mutex(mutex), var(var) {} + + public: + /** + * Accesses the value of the mutex-protected variable. + */ + constexpr Var& operator*() const { + return var; + } + + /** + * Accesses the value of the mutex-protected variable. + */ + constexpr Var* operator->() const { + return &var; + } + + ~MutexVarLock() { + mutex.unlock(); + } +}; + +template +class MutexVar { + Mutex mutex; + Var var; + + public: + /** + * Creates a mutex-protected variable which is initialized with the given + * constructor arguments. + * + * \param args + The arguments to provide to the Var constructor. + */ + template + MutexVar(Args&&... args) : mutex(), var(std::forward(args)...) {} + + /** + * Try to lock the mutex-protected variable. + * + * \param timeout + * Time to wait before the mutex becomes available, in milliseconds. A + * timeout of 0 can be used to poll the mutex. + * + * \return A std::optional which contains a MutexVarLock providing access to + * the protected variable if locking is successful. + */ + std::optional> try_lock(std::uint32_t timeout) { + if (mutex.take(timeout)) { + return {{mutex, var}}; + } else { + return {}; + } + } + + /** + * Try to lock the mutex-protected variable. + * + * \param timeout + * Time to wait before the mutex becomes available. A timeout of 0 can + * be used to poll the mutex. + * + * \return A std::optional which contains a MutexVarLock providing access to + * the protected variable if locking is successful. + */ + template + std::optional> try_lock(const std::chrono::duration& rel_time) { + try_lock(std::chrono::duration_cast(rel_time).count()); + } + + /** + * Lock the mutex-protected variable, waiting indefinitely. + * + * \return A MutexVarLock providing access to the protected variable. + */ + MutexVarLock lock() { + while (!mutex.take(TIMEOUT_MAX)) + ; + return {mutex, var}; + } }; /** @@ -427,7 +637,7 @@ using pros::c::millis; /** * Gets the number of microseconds since PROS initialized. - * + * * \return The number of microseconds since PROS initialized */ using pros::c::micros; @@ -440,9 +650,9 @@ using pros::c::micros; * To delay cyclically, use task_delay_until(). * * \param milliseconds - * The number of milliseconds to wait (1000 milliseconds per second) + * The number of milliseconds to wait (1000 milliseconds per second) */ using pros::c::delay; } // namespace pros -#endif // _PROS_RTOS_HPP_s +#endif // _PROS_RTOS_HPP_ diff --git a/include/pros/screen.h b/include/pros/screen.h index 9d0f2251..4cffe76c 100644 --- a/include/pros/screen.h +++ b/include/pros/screen.h @@ -46,7 +46,8 @@ typedef enum { typedef enum { E_TOUCH_RELEASED = 0, ///< Last interaction with screen was a quick press E_TOUCH_PRESSED, ///< Last interaction with screen was a release - E_TOUCH_HELD ///< User is holding screen down + E_TOUCH_HELD, ///< User is holding screen down + E_TOUCH_ERROR ///< An error occured while taking/returning the mutex } last_touch_e_t; /** @@ -82,7 +83,7 @@ typedef struct screen_touch_status_s { #endif #endif -typedef void (*touch_event_cb_fn_t)(int16_t, int16_t); +typedef void (*touch_event_cb_fn_t)(); #ifdef __cplusplus namespace c { @@ -96,46 +97,86 @@ namespace c { /** * Set the pen color for subsequent graphics operations + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. * * \param color The pen color to set (it is recommended to use values * from the enum defined in colors.h) + * + * \return Returns 1 if the mutex was successfully returned, or PROS_ERR if + * there was an error either taking or returning the screen mutex. */ -void screen_set_pen(uint32_t color); +uint32_t screen_set_pen(uint32_t color); /** * Set the eraser color for erasing and the current background. * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param color The background color to set (it is recommended to use values * from the enum defined in colors.h) + * + * \return Returns 1 if the mutex was successfully returned, or + * PROS_ERR if there was an error either taking or returning the screen mutex. */ -void screen_set_eraser(uint32_t color); +uint32_t screen_set_eraser(uint32_t color); /** * Get the current pen color. + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. * - * \return The current pen color in the form of a value from the enum defined in colors.h. + * \return The current pen color in the form of a value from the enum defined + * in colors.h, or PROS_ERR if there was an error taking or returning + * the screen mutex. */ uint32_t screen_get_pen(void); /** * Get the current eraser color. * - * \return The current eraser color in the form of a value from the enum defined in colors.h. + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * + * \return The current eraser color in the form of a value from the enum + * defined in colors.h, or PROS_ERR if there was an error taking or + * returning the screen mutex. */ uint32_t screen_get_eraser(void); /** * Clear display with eraser color + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_erase(void); +uint32_t screen_erase(void); /** * Scroll lines on the display upwards. * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param start_line The line from which scrolling will start * \param lines The number of lines to scroll up + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_scroll(int16_t start_line, int16_t lines); +uint32_t screen_scroll(int16_t start_line, int16_t lines); /** * Scroll lines within a region on the display @@ -144,18 +185,29 @@ void screen_scroll(int16_t start_line, int16_t lines); * specify a rectangular region within which to scroll lines instead of a start * line. * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first corner of the * rectangular region * \param x1, y1 The (x,y) coordinates of the second corner of the * rectangular region * \param lines The number of lines to scroll upwards + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_scroll_area(int16_t x0, int16_t y0, int16_t x1, int16_t y1, int16_t lines); +uint32_t screen_scroll_area(int16_t x0, int16_t y0, int16_t x1, int16_t y1, int16_t lines); /** * Copy a screen region (designated by a rectangle) from an off-screen buffer * to the screen * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first corner of the * rectangular region of the screen * \param x1, y1 The (x,y) coordinates of the second corner of the @@ -163,88 +215,161 @@ void screen_scroll_area(int16_t x0, int16_t y0, int16_t x1, int16_t y1, int16_t * \param buf Off-screen buffer containing screen data * \param stride Off-screen buffer width in pixels, such that image size * is stride-padding + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_copy_area(int16_t x0, int16_t y0, int16_t x1, int16_t y1, uint32_t* buf, int32_t stride); +uint32_t screen_copy_area(int16_t x0, int16_t y0, int16_t x1, int16_t y1, uint32_t* buf, int32_t stride); /** * Draw a single pixel on the screen using the current pen color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x, y The (x,y) coordinates of the pixel + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_draw_pixel(int16_t x, int16_t y); +uint32_t screen_draw_pixel(int16_t x, int16_t y); /** * Erase a pixel from the screen (Sets the location) * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x, y The (x,y) coordinates of the erased + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_erase_pixel(int16_t x, int16_t y); +uint32_t screen_erase_pixel(int16_t x, int16_t y); /** * Draw a line on the screen using the current pen color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x, y) coordinates of the first point of the line * \param x1, y1 The (x, y) coordinates of the second point of the line + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_draw_line(int16_t x0, int16_t y0, int16_t x1, int16_t y1); +uint32_t screen_draw_line(int16_t x0, int16_t y0, int16_t x1, int16_t y1); /** * Erase a line on the screen using the current eraser color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x, y) coordinates of the first point of the line * \param x1, y1 The (x, y) coordinates of the second point of the line + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_erase_line(int16_t x0, int16_t y0, int16_t x1, int16_t y1); +uint32_t screen_erase_line(int16_t x0, int16_t y0, int16_t x1, int16_t y1); /** * Draw a rectangle on the screen using the current pen color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first point of the rectangle * \param x1, y1 The (x,y) coordinates of the second point of the rectangle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_draw_rect(int16_t x0, int16_t y0, int16_t x1, int16_t y1); +uint32_t screen_draw_rect(int16_t x0, int16_t y0, int16_t x1, int16_t y1); /** * Erase a rectangle on the screen using the current eraser color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first point of the rectangle * \param x1, y1 The (x,y) coordinates of the second point of the rectangle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_erase_rect(int16_t x0, int16_t y0, int16_t x1, int16_t y1); +uint32_t screen_erase_rect(int16_t x0, int16_t y0, int16_t x1, int16_t y1); /** * Fill a rectangular region of the screen using the current pen * color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first point of the rectangle * \param x1, y1 The (x,y) coordinates of the second point of the rectangle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_fill_rect(int16_t x0, int16_t y0, int16_t x1, int16_t y1); +uint32_t screen_fill_rect(int16_t x0, int16_t y0, int16_t x1, int16_t y1); /** * Draw a circle on the screen using the current pen color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x, y The (x,y) coordinates of the center of the circle * \param r The radius of the circle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_draw_circle(int16_t x, int16_t y, int16_t radius); +uint32_t screen_draw_circle(int16_t x, int16_t y, int16_t radius); /** * Erase a circle on the screen using the current eraser color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x, y The (x,y) coordinates of the center of the circle * \param r The radius of the circle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_erase_circle(int16_t x, int16_t y, int16_t radius); +uint32_t screen_erase_circle(int16_t x, int16_t y, int16_t radius); /** * Fill a circular region of the screen using the current pen * color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x, y The (x,y) coordinates of the center of the circle * \param r The radius of the circle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_fill_circle(int16_t x, int16_t y, int16_t radius); +uint32_t screen_fill_circle(int16_t x, int16_t y, int16_t radius); /******************************************************************************/ /** Screen Text Display Functions **/ @@ -261,8 +386,11 @@ void screen_fill_circle(int16_t x, int16_t y, int16_t radius); * \param line The line number on which to print * \param text Format string * \param ... Optional list of arguments for the format string + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_print(text_format_e_t txt_fmt, const int16_t line, const char* text, ...); +uint32_t screen_print(text_format_e_t txt_fmt, const int16_t line, const char* text, ...); /** * Print a formatted string to the screen at the specified point @@ -276,8 +404,11 @@ void screen_print(text_format_e_t txt_fmt, const int16_t line, const char* text, * \param y The x coordinate of the top left corner of the string * \param text Format string * \param ... Optional list of arguments for the format string + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ -void screen_print_at(text_format_e_t txt_fmt, const int16_t x, const int16_t y, const char* text, ...); +uint32_t screen_print_at(text_format_e_t txt_fmt, const int16_t x, const int16_t y, const char* text, ...); /** * Print a formatted string to the screen on the specified line @@ -287,13 +418,20 @@ void screen_print_at(text_format_e_t txt_fmt, const int16_t x, const int16_t y, * * Will default to a medium sized font by default if invalid txt_fmt is given. * Exposed mostly for writing libraries and custom functions. + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. * * \param txt_fmt Text format enum that determines if the text is medium, large, medium_center, or large_center. (DOES NOT SUPPORT SMALL) * \param line The line number on which to print * \param text Format string * \param args List of arguments for the format string + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * while taking or returning the screen mutex. */ -void screen_vprintf(text_format_e_t txt_fmt, const int16_t line, const char* text, va_list args); +uint32_t screen_vprintf(text_format_e_t txt_fmt, const int16_t line, const char* text, va_list args); /** * Print a formatted string to the screen at the specified coordinates @@ -305,13 +443,20 @@ void screen_vprintf(text_format_e_t txt_fmt, const int16_t line, const char* tex * * Text formats medium_center and large_center will default to medium and large respectively. * Exposed mostly for writing libraries and custom functions. + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. * * \param txt_fmt Text format enum that determines if the text is small, medium, or large. * \param x, y The (x,y) coordinates of the top left corner of the string * \param text Format string * \param args List of arguments for the format string + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * while taking or returning the screen mutex. */ -void screen_vprintf_at(text_format_e_t txt_fmt, const int16_t x, const int16_t y, const char* text, va_list args); +uint32_t screen_vprintf_at(text_format_e_t txt_fmt, const int16_t x, const int16_t y, const char* text, va_list args); /******************************************************************************/ /** Screen Touch Functions **/ @@ -325,16 +470,25 @@ void screen_vprintf_at(text_format_e_t txt_fmt, const int16_t x, const int16_t y * * \return The last_touch_e_t enum specifier that indicates the last touch status of the screen (E_TOUCH_EVENT_RELEASE, E_TOUCH_EVENT_PRESS, or E_TOUCH_EVENT_PRESS_AND_HOLD). * This will be released by default if no action was taken. + * If an error occured, the screen_touch_status_s_t will have its last_touch_e_t + * enum specifier set to E_TOUCH_ERR, and other values set to -1. */ screen_touch_status_s_t screen_touch_status(void); /** * Assigns a callback function to be called when a certain touch event happens. + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. * * \param cb Function pointer to callback when event type happens * \param event_type Touch event that will trigger the callback. + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * while taking or returning the screen mutex. */ -void screen_touch_callback(touch_event_cb_fn_t cb, last_touch_e_t event_type); +uint32_t screen_touch_callback(touch_event_cb_fn_t cb, last_touch_e_t event_type); #ifdef __cplusplus } //namespace c diff --git a/include/pros/screen.hpp b/include/pros/screen.hpp index 75e3a62f..3aecd188 100644 --- a/include/pros/screen.hpp +++ b/include/pros/screen.hpp @@ -45,46 +45,86 @@ const char* convert_args(const std::string& arg) { /** * Set the pen color for subsequent graphics operations + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. * * \param color The pen color to set (it is recommended to use values * from the enum defined in colors.h) + * + * \return Returns 1 if the mutex was successfully returned, or PROS_ERR if + * there was an error either taking or returning the screen mutex. */ - void set_pen(const std::uint32_t color); + std::uint32_t set_pen(const std::uint32_t color); /** - * Set the eraser color for clearing and the current background. + * Set the eraser color for erasing and the current background. * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param color The background color to set (it is recommended to use values * from the enum defined in colors.h) + * + * \return Returns 1 if the mutex was successfully returned, or PROS_ERR + * if there was an error either taking or returning the screen mutex. */ - void set_eraser(const std::uint32_t color); + std::uint32_t set_eraser(const std::uint32_t color); /** * Get the current pen color. + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. * - * \return The current pen color of the screen object in the form of a value from the enum defined in colors.h. + * \return The current pen color in the form of a value from the enum + * defined in colors.h, or PROS_ERR if there was an error taking or + * returning the screen mutex. */ std::uint32_t get_pen(); /** * Get the current eraser color. * - * \return The current eraser color of the screen object in the form of a value from the enum defined in colors.h. + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * + * \return The current eraser color in the form of a value from the enum + * defined in colors.h, or PROS_ERR if there was an error taking or + * returning the screen mutex. */ std::uint32_t get_eraser(); /** * Clear display with eraser color + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void erase(); + std::uint32_t erase(); /** * Scroll lines on the display upwards. * - * \param start_line The line from which scrolling will start + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * + * \param start_line The line from which scrolling will start * \param lines The number of lines to scroll up + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void scroll(const std::int16_t start_line, const std::int16_t lines); + std::uint32_t scroll(const std::int16_t start_line, const std::int16_t lines); /** * Scroll lines within a region on the display @@ -93,18 +133,29 @@ const char* convert_args(const std::string& arg) { * specify a rectangular region within which to scroll lines instead of a start * line. * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first corner of the * rectangular region * \param x1, y1 The (x,y) coordinates of the second corner of the * rectangular region * \param lines The number of lines to scroll upwards + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void scroll_area(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1, std::int16_t lines); + std::uint32_t scroll_area(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1, std::int16_t lines); /** * Copy a screen region (designated by a rectangle) from an off-screen buffer * to the screen * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first corner of the * rectangular region of the screen * \param x1, y1 The (x,y) coordinates of the second corner of the @@ -112,88 +163,161 @@ const char* convert_args(const std::string& arg) { * \param buf Off-screen buffer containing screen data * \param stride Off-screen buffer width in pixels, such that image size * is stride-padding + * + * \return 1 if there were no errors, or PROS_ERR if an error occured taking + * or returning the screen mutex. */ - void copy_area(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1, uint32_t* buf, const std::int32_t stride); + std::uint32_t copy_area(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1, uint32_t* buf, const std::int32_t stride); /** * Draw a single pixel on the screen using the current pen color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x, y The (x,y) coordinates of the pixel + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void draw_pixel(const std::int16_t x, const std::int16_t y); + std::uint32_t draw_pixel(const std::int16_t x, const std::int16_t y); /** * Erase a pixel from the screen (Sets the location) * - * \param x, y The (x,y) coordinates of the erased pixel + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * + * \param x, y The (x,y) coordinates of the erased + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void erase_pixel(const std::int16_t x, const std::int16_t y); + std::uint32_t erase_pixel(const std::int16_t x, const std::int16_t y); /** * Draw a line on the screen using the current pen color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x, y) coordinates of the first point of the line * \param x1, y1 The (x, y) coordinates of the second point of the line + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void draw_line(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); + std::uint32_t draw_line(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); /** * Erase a line on the screen using the current eraser color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x, y) coordinates of the first point of the line * \param x1, y1 The (x, y) coordinates of the second point of the line + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void erase_line(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); + std::uint32_t erase_line(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); /** * Draw a rectangle on the screen using the current pen color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first point of the rectangle * \param x1, y1 The (x,y) coordinates of the second point of the rectangle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void draw_rect(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); + std::uint32_t draw_rect(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); /** * Erase a rectangle on the screen using the current eraser color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first point of the rectangle * \param x1, y1 The (x,y) coordinates of the second point of the rectangle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void erase_rect(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); + std::uint32_t erase_rect(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); /** * Fill a rectangular region of the screen using the current pen * color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x0, y0 The (x,y) coordinates of the first point of the rectangle * \param x1, y1 The (x,y) coordinates of the second point of the rectangle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void fill_rect(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); + std::uint32_t fill_rect(const std::int16_t x0, const std::int16_t y0, const std::int16_t x1, const std::int16_t y1); /** * Draw a circle on the screen using the current pen color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x, y The (x,y) coordinates of the center of the circle * \param r The radius of the circle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void draw_circle(const std::int16_t x, const std::int16_t y, const std::int16_t radius); + std::uint32_t draw_circle(const std::int16_t x, const std::int16_t y, const std::int16_t radius); /** * Erase a circle on the screen using the current eraser color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x, y The (x,y) coordinates of the center of the circle * \param r The radius of the circle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void erase_circle(const std::int16_t x, const std::int16_t y, const std::int16_t radius); + std::uint32_t erase_circle(const std::int16_t x, const std::int16_t y, const std::int16_t radius); /** * Fill a circular region of the screen using the current pen * color * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. + * * \param x, y The (x,y) coordinates of the center of the circle * \param r The radius of the circle + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * taking or returning the screen mutex. */ - void fill_circle(const std::int16_t x, const std::int16_t y, const std::int16_t radius); + std::uint32_t fill_circle(const std::int16_t x, const std::int16_t y, const std::int16_t radius); /******************************************************************************/ /** Screen Text Display Functions **/ @@ -230,20 +354,30 @@ const char* convert_args(const std::string& arg) { /** information about screen touches **/ /******************************************************************************/ - /** - * Gets the touch status of the last touch of the screen. 0 by default. + /** + * Gets the touch status of the last touch of the screen. * - * \return The last_touch_e_t enum specifier that indicates the last touch status of the screen (E_TOUCH_EVENT_RELEASE, E_TOUCH_EVENT_PRESS, or E_TOUCH_EVENT_PRESS_AND_HOLD). + * \return The last_touch_e_t enum specifier that indicates the last touch status of the screen (E_TOUCH_EVENT_RELEASE, E_TOUCH_EVENT_PRESS, or E_TOUCH_EVENT_PRESS_AND_HOLD). + * This will be released by default if no action was taken. + * If an error occured, the screen_touch_status_s_t will have its + * last_touch_e_t enum specifier set to E_TOUCH_ERR, and other values set to -1. */ screen_touch_status_s_t touch_status(); /** * Assigns a callback function to be called when a certain touch event happens. + * + * This function uses the following values of errno when an error state is + * reached: + * EACCESS - Another resource is currently trying to access the screen mutex. * * \param cb Function pointer to callback when event type happens * \param event_type Touch event that will trigger the callback. + * + * \return 1 if there were no errors, or PROS_ERR if an error occured + * while taking or returning the screen mutex. */ - void touch_callback(touch_event_cb_fn_t cb, last_touch_e_t event_type); + std::uint32_t touch_callback(touch_event_cb_fn_t cb, last_touch_e_t event_type); } //namespace screen } //namespace pros diff --git a/include/pros/serial.h b/include/pros/serial.h index 62560454..6db69cd0 100644 --- a/include/pros/serial.h +++ b/include/pros/serial.h @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, 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 diff --git a/include/pros/vision.h b/include/pros/vision.h index f565255f..8464b6c3 100644 --- a/include/pros/vision.h +++ b/include/pros/vision.h @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, Purdue University ACM SIGBots. * All rights reserved. * * This Source Code Form is subject to the terms of the Mozilla Public diff --git a/include/pros/vision.hpp b/include/pros/vision.hpp index 05a4bd2e..eeb00462 100644 --- a/include/pros/vision.hpp +++ b/include/pros/vision.hpp @@ -9,7 +9,7 @@ * This file should not be modified by users, since it gets replaced whenever * a kernel upgrade occurs. * - * Copyright (c) 2017-2021, Purdue University ACM SIGBots. + * Copyright (c) 2017-2022, Purdue University ACM SIGBots. * All rights reserved. * * This Source Code Form is subject to the terms of the Mozilla Public diff --git a/project.pros b/project.pros index 0012d5c6..df6fe443 100644 --- a/project.pros +++ b/project.pros @@ -5,7 +5,7 @@ "target": "v5", "templates": { "kernel": { - "location": "C:\\Users\\union\\AppData\\Roaming\\PROS\\templates\\kernel@3.5.4", + "location": "C:\\Users\\cicad\\AppData\\Roaming\\PROS\\templates\\kernel@3.7.3", "metadata": { "cold_addr": "58720256", "cold_output": "bin/cold.package.bin", @@ -18,148 +18,152 @@ "py/object": "pros.conductor.templates.local_template.LocalTemplate", "supported_kernels": null, "system_files": [ - "include/display/lv_themes/lv_theme_night.h", - "include/display/lv_hal/lv_hal.h", - "include/display/lv_themes/lv_theme_templ.h", - "include/display/lv_objx/lv_imgbtn.h", - "include/display/lv_draw/lv_draw_img.h", - "include/display/lv_objx/lv_cont.h", - "include/display/lv_draw/lv_draw_arc.h", - "include/display/lv_version.h", - "include/display/lv_core/lv_style.h", - "include/display/lv_objx/lv_ddlist.h", - "include/display/lv_objx/lv_mbox.h", - "include/display/lv_objx/lv_spinbox.h", - "include/display/lv_objx/lv_objx_templ.h", - "include/display/lv_objx/lv_line.h", - "include/pros/adi.hpp", - "include/display/lv_misc/lv_task.h", - "include/pros/optical.hpp", - "include/pros/serial.h", - "include/pros/imu.hpp", - "include/display/lv_core/lv_group.h", - "include/display/lv_conf.h", - "include/pros/vision.hpp", - "include/pros/rtos.h", + "common.mk", + "include/display/lv_objx/lv_tileview.h", "firmware/libm.a", - "firmware/v5.ld", + "include/display/lv_hal/lv_hal_indev.h", "include/display/lv_objx/lv_bar.h", - "include/pros/motors.hpp", - "include/display/lv_misc/lv_fs.h", - "include/display/lv_misc/lv_templ.h", - "include/display/lv_draw/lv_draw_vbasic.h", - "include/display/lv_objx/lv_list.h", - "include/display/lv_themes/lv_theme.h", - "include/display/lv_objx/lv_chart.h", - "include/pros/motors.h", - "include/display/lv_objx/lv_arc.h", - "include/display/lv_core/lv_vdb.h", - "include/display/lv_misc/lv_txt.h", - "include/display/lvgl.h", - "include/display/lv_misc/lv_color.h", - "include/display/lv_core/lv_indev.h", - "include/display/lv_objx/lv_kb.h", - "include/pros/llemu.h", - "firmware/v5-common.ld", - "include/display/README.md", - "include/pros/misc.hpp", - "include/display/lv_objx/lv_tabview.h", - "include/display/lv_draw/lv_draw_rbasic.h", - "common.mk", + "include/pros/ext_adi.h", + "include/display/lv_fonts/lv_font_builtin.h", + "include/display/lv_draw/lv_draw_rect.h", + "include/display/lv_misc/lv_anim.h", "include/display/lv_misc/lv_font.h", - "include/display/lv_objx/lv_led.h", + "include/display/lv_misc/lv_color.h", + "include/display/lv_themes/lv_theme_zen.h", + "include/display/lv_misc/lv_symbol_def.h", + "include/display/lv_objx/lv_cb.h", + "include/pros/misc.h", + "include/display/lv_misc/lv_task.h", "include/display/lv_core/lv_obj.h", - "include/display/lv_draw/lv_draw_line.h", - "include/pros/rtos.hpp", - "include/pros/apix.h", - "include/display/lv_objx/lv_sw.h", - "include/display/lv_misc/lv_ll.h", - "include/pros/vision.h", - "include/display/lv_objx/lv_ta.h", - "include/display/lv_draw/lv_draw_label.h", - "include/display/lv_core/lv_refr.h", - "include/api.h", - "firmware/libpros.a", - "firmware/libc.a", - "include/pros/ext_adi.h", - "include/display/lv_hal/lv_hal.mk", + "include/display/lv_themes/lv_themes.mk", + "include/pros/adi.hpp", + "include/display/lv_objx/lv_line.h", + "include/display/lv_objx/lv_gauge.h", + "include/display/lv_objx/lv_arc.h", + "include/display/lv_core/lv_lang.h", "include/pros/colors.h", - "include/pros/distance.h", - "include/pros/screen.hpp", - "include/pros/distance.hpp", - "include/display/lv_themes/lv_theme_alien.h", + "include/display/lv_objx/lv_ta.h", "include/pros/gps.h", - "include/display/licence.txt", - "include/display/lv_misc/lv_gc.h", + "include/display/lv_objx/lv_lmeter.h", + "include/pros/optical.h", + "include/pros/screen.hpp", + "include/display/lv_hal/lv_hal.mk", + "include/pros/serial.h", + "include/pros/link.h", + "include/display/lv_hal/lv_hal.h", "include/display/lv_objx/lv_btnm.h", - "include/display/lv_objx/lv_page.h", - "include/pros/gps.hpp", + "include/display/lv_objx/lv_img.h", + "include/display/lv_objx/lv_label.h", + "include/display/lv_misc/lv_gc.h", + "include/display/lvgl.h", + "include/pros/adi.h", + "include/pros/optical.hpp", + "include/display/lv_objx/lv_sw.h", + "include/api.h", "include/pros/llemu.hpp", - "include/display/lv_hal/lv_hal_disp.h", - "include/display/lv_misc/lv_circ.h", - "include/display/lv_objx/lv_btn.h", - "include/display/lv_misc/lv_anim.h", + "include/display/lv_core/lv_style.h", + "include/pros/colors.hpp", + "firmware/v5.ld", + "include/display/lv_draw/lv_draw_vbasic.h", + "include/display/lv_misc/lv_fs.h", + "include/display/lv_objx/lv_page.h", "include/display/lv_draw/lv_draw.mk", - "include/display/lv_core/lv_lang.h", + "include/display/lv_objx/lv_calendar.h", + "include/display/lv_objx/lv_win.h", + "include/pros/rtos.h", + "include/display/lv_conf_checker.h", + "include/display/lv_themes/lv_theme_night.h", + "include/display/lv_objx/lv_cont.h", + "include/display/licence.txt", "include/pros/api_legacy.h", - "include/display/lv_themes/lv_theme_nemo.h", - "include/display/lv_misc/lv_math.h", - "include/display/lv_misc/lv_symbol_def.h", - "include/display/lv_draw/lv_draw_rect.h", + "include/display/lv_misc/lv_log.h", + "firmware/libc.a", + "include/pros/rtos.hpp", + "include/display/lv_objx/lv_roller.h", + "include/display/lv_draw/lv_draw_label.h", + "include/display/lv_objx/lv_spinbox.h", "include/display/lv_misc/lv_mem.h", - "include/display/lv_conf_checker.h", - "include/display/lv_fonts/lv_font_builtin.h", - "include/display/lv_objx/lv_table.h", - "include/pros/rotation.hpp", - "include/display/lv_themes/lv_theme_default.h", - "include/display/lv_core/lv_core.mk", + "include/display/lv_objx/lv_led.h", + "include/display/lv_objx/lv_canvas.h", + "include/display/lv_misc/lv_circ.h", "include/pros/screen.h", - "include/display/lv_draw/lv_draw_triangle.h", - "include/display/lv_objx/lv_lmeter.h", - "include/display/lv_hal/lv_hal_indev.h", + "include/pros/apix.h", "include/display/lv_objx/lv_objx.mk", - "include/display/lv_objx/lv_win.h", - "include/display/lv_themes/lv_theme_zen.h", - "include/pros/misc.h", - "include/display/lv_objx/lv_img.h", - "include/display/lv_themes/lv_theme_mono.h", - "include/display/lv_hal/lv_hal_tick.h", - "include/display/lv_fonts/lv_fonts.mk", - "include/pros/optical.h", - "include/display/lv_objx/lv_gauge.h", - "include/display/lv_misc/lv_ufs.h", - "include/display/lv_misc/lv_log.h", - "include/display/lv_objx/lv_canvas.h", - "include/display/lv_objx/lv_calendar.h", - "include/pros/adi.h", - "include/display/lv_themes/lv_theme_material.h", + "include/display/lv_misc/lv_txt.h", + "include/display/lv_draw/lv_draw_line.h", "include/display/lv_draw/lv_draw.h", - "include/display/lv_misc/lv_misc.mk", + "include/display/lv_objx/lv_preload.h", + "include/display/lv_themes/lv_theme_material.h", + "include/pros/distance.hpp", + "include/pros/rotation.hpp", + "include/display/lv_themes/lv_theme.h", + "include/display/lv_misc/lv_area.h", + "firmware/libpros.a", + "include/pros/motors.hpp", + "include/display/lv_misc/lv_ufs.h", + "include/display/lv_misc/lv_math.h", + "include/display/lv_core/lv_group.h", + "include/display/lv_objx/lv_chart.h", "include/display/lv_objx/lv_slider.h", - "include/display/lv_objx/lv_cb.h", - "include/pros/imu.h", - "include/display/lv_objx/lv_label.h", - "include/display/lv_objx/lv_roller.h", + "include/display/lv_draw/lv_draw_triangle.h", + "include/display/lv_objx/lv_mbox.h", + "include/display/lv_hal/lv_hal_disp.h", + "include/pros/misc.hpp", + "include/display/lv_objx/lv_list.h", "include/pros/serial.hpp", + "include/display/lv_objx/lv_imgbtn.h", + "include/pros/vision.h", + "include/display/lv_objx/lv_objx_templ.h", "firmware/v5-hot.ld", - "include/display/lv_misc/lv_area.h", + "include/display/lv_core/lv_indev.h", + "include/pros/llemu.h", + "include/pros/imu.h", + "include/display/README.md", "include/pros/rotation.h", - "include/display/lv_objx/lv_tileview.h", - "include/display/lv_objx/lv_preload.h", - "include/display/lv_themes/lv_themes.mk" + "include/display/lv_version.h", + "include/pros/vision.hpp", + "include/display/lv_themes/lv_theme_nemo.h", + "include/display/lv_core/lv_vdb.h", + "include/display/lv_objx/lv_ddlist.h", + "include/display/lv_core/lv_core.mk", + "include/pros/imu.hpp", + "include/display/lv_misc/lv_ll.h", + "include/display/lv_draw/lv_draw_rbasic.h", + "include/display/lv_themes/lv_theme_mono.h", + "include/display/lv_fonts/lv_fonts.mk", + "include/display/lv_misc/lv_templ.h", + "include/display/lv_themes/lv_theme_templ.h", + "include/display/lv_themes/lv_theme_default.h", + "include/display/lv_objx/lv_btn.h", + "include/display/lv_conf.h", + "include/display/lv_core/lv_refr.h", + "include/pros/motors.h", + "include/display/lv_objx/lv_tabview.h", + "include/pros/gps.hpp", + "include/display/lv_hal/lv_hal_tick.h", + "include/pros/error.h", + "firmware/v5-common.ld", + "include/display/lv_draw/lv_draw_arc.h", + "include/display/lv_themes/lv_theme_alien.h", + "include/pros/distance.h", + "include/display/lv_objx/lv_table.h", + "include/display/lv_misc/lv_misc.mk", + "include/display/lv_draw/lv_draw_img.h", + "include/display/lv_objx/lv_kb.h", + "include/pros/link.hpp" ], "target": "v5", "user_files": [ + ".gitignore", + "include/main.h", "Makefile", - "src/main.c", "src/main.cc", "include/main.hpp", - "include/main.hh", + "src/main.c", "src/main.cpp", - "include/main.h", - ".gitignore" + "include/main.hh" ], - "version": "3.5.4" + "version": "3.7.3" }, "okapilib": { "location": "C:\\Users\\union\\AppData\\Roaming\\PROS\\templates\\okapilib@4.2.0",