diff --git a/README.md b/README.md index f5bc8cad..1dcd7b26 100644 --- a/README.md +++ b/README.md @@ -11,7 +11,7 @@ permalink: / Simple plug-and-play PROS template that handles drive base functions for VEX robots. -[EZ-Template Version](https://github.com/EZ-Robotics/EZ-Template): 2.1.2-RC1 +[EZ-Template Version](https://github.com/EZ-Robotics/EZ-Template): 3.0.0-RC1 [Autonomous routines that used EZ-Template](https://photos.app.goo.gl/yRwuvmq7hDoM4f6EA) diff --git a/common.mk b/common.mk index 6341070a..10ab5d38 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 @@ -201,7 +201,7 @@ library: $(LIBAR) .PHONY: template template: clean-template $(LIBAR) - $Dprosv5 c create-template . $(LIBNAME) $(VERSION) $(foreach file,$(TEMPLATE_FILES) $(LIBAR),--system "$(file)") --target v5 $(CREATE_TEMPLATE_FLAGS) + $Dpros c create-template . $(LIBNAME) $(VERSION) $(foreach file,$(TEMPLATE_FILES) $(LIBAR),--system "$(file)") --target v5 $(CREATE_TEMPLATE_FLAGS) endif # if project is a library source, compile the archive and link output.elf against the archive rather than source objects @@ -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 = "$(wildcard $(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 4450b329..05399901 100644 Binary files a/firmware/libpros.a and b/firmware/libpros.a differ diff --git a/include/api.h b/include/api.h index 27a7b643..7e923199 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, Purdue University ACM SIGBots. * All rights reserved. * * This Source Code Form is subject to the terms of the Mozilla Public @@ -40,16 +40,14 @@ #endif /* __cplusplus */ #define PROS_VERSION_MAJOR 3 -#define PROS_VERSION_MINOR 6 -#define PROS_VERSION_PATCH 2 -#define PROS_VERSION_STRING "3.6.2" - -#define PROS_ERR (INT32_MAX) -#define PROS_ERR_F (INFINITY) +#define PROS_VERSION_MINOR 8 +#define PROS_VERSION_PATCH 0 +#define PROS_VERSION_STRING "3.8.0" #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" diff --git a/include/pros/adi.h b/include/pros/adi.h index abe7544d..8f0f556f 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 @@ -701,7 +701,7 @@ 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 gyro data in PROS 2. + * object to store potentiometer data in PROS 2. */ typedef int32_t adi_potentiometer_t; @@ -757,6 +757,115 @@ adi_potentiometer_t adi_potentiometer_type_init(uint8_t port, adi_potentiometer_ */ 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 d91ff7e7..c2fd258d 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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" @@ -493,10 +494,13 @@ class ADIEncoder : private ADIPort { * sensor with the removable cover side up, and the "bottom" wire from * the encoder sensor * \param reverse - * If "true", the sensor will count in theopposite direction + * If "true", the sensor will count in the opposite direction */ ADIEncoder(ext_adi_port_tuple_t port_tuple, bool reversed = false); + // Delete copy constructor to prevent a compilation error from the constructor above. + ADIEncoder(ADIEncoder &) = delete; + /** * Sets the encoder value to zero. * @@ -760,6 +764,134 @@ class ADIPotentiometer : public ADIAnalogIn { 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 068f7e8a..deb7d222 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 8e7d3068..876a98c8 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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/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 b7feda19..783da8fd 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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..a7e4e54e --- /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 Copyright (c) 2017-2023, 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 d4282761..f75ee051 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 @@ -645,8 +645,10 @@ typedef int32_t ext_adi_potentiometer_t; * reached: * ENXIO - The given value is not within the range of ADI Ports * EADDRINUSE - The port is not configured as a potentiometer - * - * \param port + * + * \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 @@ -674,6 +676,114 @@ ext_adi_potentiometer_t ext_adi_potentiometer_init(uint8_t smart_port, uint8_t a */ 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 1af417bc..1b2e7e7b 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 0d8b731c..fce40c2a 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 17f716a9..f5a1cdc3 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 dcf21f99..99b28c8d 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 index 26067b87..212834cc 100644 --- a/include/pros/link.h +++ b/include/pros/link.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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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,9 +29,25 @@ namespace pros { typedef enum link_type_e { E_LINK_RECIEVER = 0, - E_LINK_TRANSMITTER + 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 @@ -41,6 +57,7 @@ namespace c { /** * 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: @@ -66,6 +83,7 @@ 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: diff --git a/include/pros/link.hpp b/include/pros/link.hpp index d44c6bd5..d6c18f3a 100644 --- a/include/pros/link.hpp +++ b/include/pros/link.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 Copyright (c) 2017-2023, 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/llemu.h b/include/pros/llemu.h index 4cb792b3..8a6d7570 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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/llemu.hpp b/include/pros/llemu.hpp index 8818eddb..a4834e02 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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/misc.h b/include/pros/misc.h index c1a2cd44..16cba550 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 2415c2f1..7fcb4b54 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 d2246f5b..73710924 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 @@ -597,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; @@ -613,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 @@ -627,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 0da91883..10925990 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 * @@ -357,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; @@ -373,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; @@ -466,6 +461,7 @@ class Motor { * * \return The motor's voltage in mV or PROS_ERR_F if the operation failed, * setting errno. + * */ virtual std::int32_t get_voltage(void) const; @@ -583,8 +579,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. @@ -613,8 +610,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); /** @@ -634,8 +633,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. @@ -653,8 +653,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 @@ -673,8 +674,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. @@ -692,8 +694,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. @@ -792,8 +795,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 @@ -810,8 +815,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. @@ -851,6 +858,624 @@ class Motor { const std::uint8_t _port; }; +class Motor_Group { + public: + Motor_Group(const std::initializer_list motors); + explicit Motor_Group(const std::vector& motors); + explicit Motor_Group(const std::initializer_list motor_ports); + explicit Motor_Group(const std::vector motor_ports); // Pass by value to preserve ABI + + /****************************************************************************/ + /** 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); + + /* + * Gets the voltages delivered to the motors 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 + * + * \return The voltage of the motor in millivolts or PROS_ERR_F if the operation + * failed, setting errno. + * + * \b Example + * \code + * void opcontrol() { + * pros::Motor_Group motors({1, 2}); + * std::vector voltages; + * while (true) { + * voltages = motors.get_voltages(); + * + * for (uint32_t i = 0; i < voltages.size(); i++) { + * printf("Voltages: %ld\n", voltages[i]); + * } + * pros::delay(20); + * } + * } + * \endcode + * + */ + std::vector get_voltages(void); + + /* + * Get the voltage limits of the motors set by the user. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \return The voltage limit of the motor in millivolts or PROS_ERR_F if the operation + * failed, setting errno. + * + * \b Example + * \code + * void opcontrol() { + * pros::Motor_Group motors({1, 2}); + * std::vector voltage_limits; + * while (true) { + * voltage_limits = motors.get_voltage_limits(); + * + * for (uint32_t i = 0; i < voltage_limits.size(); i++) { + * printf("Voltage Limits: %ld\n", voltage_limits[i]); + * } + * pros::delay(20); + * } + * } + * \endcode + */ + std::vector get_voltage_limits(void); + + /* + * Gets the raw encoder positions of a motor group at a given timestamp. + * + * This function uses the following values of errno when an error state is + * reached: + * ENODEV - The port cannot be configured as a motor + * EACCESS - The Motor group mutex can't be taken or given + * + * \return A vector of the raw encoder positions of the motors in the motor group + * based on the timestamps passed in. If a timestamp is not found for a motor, the + * value at that index will be PROS_ERR. + * + * \b Example + * \code + * void opcontrol() { + * pros::Motor_Group motors({1, 2}); + * std::vector timestamps; + * std::vector positions; + * std::uint32_t temp = 0; + * std::uint32_t temp2 = 0; + * timestamps.push_back(&temp); + * timestamps.push_back(&temp2); + * + * while (true) { + * positions = motors.get_raw_positions(timestamps); + * + * printf("Position: %ld, Time: %ln\n", positions[0], timestamps[0]); + * printf("Position: %ld, Time: %ln\n", positions[1], timestamps[1]); + * + * pros::delay(20); + * } + * } + * \endcode + */ + std::vector get_raw_positions(std::vector ×tamps); + /****************************************************************************/ + /** 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. + * + * This function uses the following values of errno when an error state is + * reached: + * Throws an std::out_of_range error when indexing out of range + * + * \param i + * The index value in the motor group. + * + * \return the appropriate Motor reference. + */ + pros::Motor& at(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); + + /** + * 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 The vector filled with motors' temperature in degrees Celsius or PROS_ERR_F if the + * operation failed, setting errno. + */ + virtual std::vector get_temperatures(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 5fd12549..9dd1c1b0 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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; @@ -258,6 +265,39 @@ int32_t optical_enable_gesture(uint8_t port); */ int32_t optical_disable_gesture(uint8_t port); +/** + * Get integration time (update rate) of the optical sensor in milliseconds, with + * minimum time being + * + * 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 Optical Sensor + * + * \param port + * The V5 Optical Sensor port number from 1-21 + * \return Integration time in milliseconds if the operation is successful + * or PROS_ERR if the operation failed, setting errno. + */ +double optical_get_integration_time(uint8_t port); + +/** + * Set integration time (update rate) of the optical sensor in milliseconds. + * + * 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 Optical Sensor + * + * \param port + * The V5 Optical Sensor port number from 1-21 + * \param time + * The desired integration time in milliseconds + * \return 1 if the operation is successful or PROS_ERR if the operation failed, + * setting errno. + */ +int32_t optical_set_integration_time(uint8_t port, double time); + #ifdef __cplusplus } } diff --git a/include/pros/optical.hpp b/include/pros/optical.hpp index 783520d4..006108d6 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 @@ -41,6 +41,8 @@ class Optical { */ explicit Optical(const std::uint8_t port); + explicit Optical(std::uint8_t port, double time); + /** * Get the detected color hue * @@ -219,6 +221,36 @@ class Optical { */ virtual std::int32_t disable_gesture(); + /** + * Set integration time (update rate) of the optical sensor in milliseconds, with + * minimum time being 3 ms and maximum time being 712 ms. Default is 100 ms, with the + * optical sensor communciating with the V5 brain every 20 ms. + * + * 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 Optical Sensor + * + * \return 1 if the operation is successful or PROS_ERR_F if the operation failed, + * setting errno. + */ + double get_integration_time(); + + /** + * Get integration time (update rate) of the optical sensor in milliseconds. + * + * 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 Optical Sensor + * + * \param time + * The desired integration time in milliseconds + * \return Integration time in milliseconds if the operation is successful + * or PROS_ERR if the operation failed, setting errno. + */ + std::int32_t set_integration_time(double time); + /** * Gets the port number of the Optical Sensor. * diff --git a/include/pros/rotation.h b/include/pros/rotation.h index 197936ac..8daf2fd8 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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.hpp b/include/pros/rotation.hpp index c53ab7b1..a063eda2 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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/rtos.h b/include/pros/rtos.h index 3afdb24a..c0767342 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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/rtos.hpp b/include/pros/rtos.hpp index aa26d7b7..2505f1d1 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, Purdue University ACM SIGBots. * All rights reserved. * * This Source Code Form is subject to the terms of the Mozilla Public @@ -28,6 +28,7 @@ #include #include #include +#include #include namespace pros { @@ -59,7 +60,7 @@ class Task { * */ 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 = ""); + std::uint16_t stack_depth = TASK_STACK_DEPTH_DEFAULT, const char* name = ""); /** * Creates a new task and add it to the list of tasks that are ready to run. @@ -154,8 +155,8 @@ class Task { * */ template - explicit Task(F&& function, std::uint32_t prio = TASK_PRIORITY_DEFAULT, std::uint16_t stack_depth = TASK_STACK_DEPTH_DEFAULT, - const char* 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)}; @@ -280,8 +281,8 @@ class Task { 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++. + * 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. @@ -534,6 +535,99 @@ class Mutex { } }; +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}; + } +}; + /** * Gets the number of milliseconds since PROS initialized. * diff --git a/include/pros/screen.h b/include/pros/screen.h index ca72ee2d..8076daa9 100644 --- a/include/pros/screen.h +++ b/include/pros/screen.h @@ -5,7 +5,7 @@ * * Contains user calls to the v5 screen for touching and displaying graphics. * - * \copyright (c) 2017-2021, Purdue University ACM SIGBots. + * \copyright (c) 2017-2023, 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 @@ -83,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 { diff --git a/include/pros/screen.hpp b/include/pros/screen.hpp index 3aecd188..d7f6c08e 100644 --- a/include/pros/screen.hpp +++ b/include/pros/screen.hpp @@ -5,7 +5,7 @@ * * Contains user calls to the v5 screen for touching and displaying graphics. * - * \copyright (c) 2017, Purdue University ACM SIGBots. + * \copyright (c) 2017-2023, 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/serial.h b/include/pros/serial.h index 6db69cd0..357aa107 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 8464b6c3..33918c78 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 eeb00462..e40af9b8 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-2022, Purdue University ACM SIGBots. + * \copyright Copyright (c) 2017-2023, 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 e56422c0..d827947a 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.6.2", + "location": "C:\\Users\\union\\AppData\\Roaming\\PROS\\templates\\kernel@3.8.0", "metadata": { "cold_addr": "58720256", "cold_output": "bin/cold.package.bin", @@ -18,150 +18,152 @@ "py/object": "pros.conductor.templates.local_template.LocalTemplate", "supported_kernels": null, "system_files": [ - "include/display/lv_objx/lv_kb.h", - "include/display/lv_draw/lv_draw.mk", - "include/display/lv_objx/lv_ta.h", + "include/display/lv_core/lv_vdb.h", + "include/display/lv_core/lv_core.mk", "include/display/lv_misc/lv_math.h", - "include/pros/rtos.h", - "include/pros/distance.hpp", + "include/display/lv_objx/lv_tabview.h", + "include/display/lv_misc/lv_color.h", + "include/display/lv_hal/lv_hal_indev.h", + "include/display/lv_fonts/lv_fonts.mk", + "include/display/lv_misc/lv_symbol_def.h", + "include/display/lv_hal/lv_hal.mk", + "include/display/lv_themes/lv_theme_night.h", + "include/display/lv_draw/lv_draw_triangle.h", + "include/pros/optical.hpp", + "include/display/lv_draw/lv_draw_vbasic.h", + "include/display/lv_objx/lv_objx_templ.h", + "include/display/lv_core/lv_refr.h", + "include/pros/link.hpp", + "include/display/lv_objx/lv_btnm.h", + "include/display/lv_objx/lv_cb.h", + "firmware/v5-common.ld", + "include/pros/ext_adi.h", "include/pros/rotation.h", - "include/display/lv_conf_checker.h", - "include/display/lv_misc/lv_gc.h", - "include/display/lv_conf.h", - "include/display/lv_themes/lv_themes.mk", - "include/pros/llemu.h", + "include/display/lv_objx/lv_spinbox.h", + "include/display/lv_misc/lv_circ.h", + "include/display/lv_misc/lv_mem.h", + "include/display/lv_objx/lv_page.h", + "include/display/lv_objx/lv_ddlist.h", + "include/display/lv_core/lv_group.h", + "include/display/lvgl.h", + "include/display/lv_objx/lv_chart.h", + "include/pros/distance.h", + "include/display/lv_objx/lv_list.h", + "include/pros/vision.h", + "include/pros/misc.hpp", + "include/display/lv_draw/lv_draw.h", + "include/display/lv_objx/lv_label.h", + "include/display/lv_misc/lv_font.h", "include/display/lv_draw/lv_draw_img.h", + "include/display/lv_misc/lv_log.h", + "include/display/lv_misc/lv_templ.h", + "include/pros/llemu.h", + "include/display/lv_objx/lv_btn.h", + "include/display/lv_fonts/lv_font_builtin.h", + "include/display/lv_objx/lv_calendar.h", + "firmware/libm.a", + "include/display/lv_conf.h", + "include/display/lv_objx/lv_sw.h", + "include/display/lv_draw/lv_draw_rect.h", + "include/display/lv_objx/lv_cont.h", + "include/pros/vision.hpp", "include/display/lv_objx/lv_mbox.h", - "include/display/lv_misc/lv_area.h", + "include/pros/adi.hpp", "include/pros/imu.hpp", "include/display/lv_objx/lv_table.h", - "include/display/lv_objx/lv_list.h", + "include/pros/screen.hpp", + "include/display/lv_draw/lv_draw_label.h", "include/display/lv_misc/lv_txt.h", - "include/display/lv_fonts/lv_font_builtin.h", - "include/pros/optical.hpp", - "include/display/lv_objx/lv_gauge.h", - "include/display/lv_objx/lv_canvas.h", - "include/display/lv_hal/lv_hal_indev.h", - "include/pros/gps.hpp", - "include/pros/misc.hpp", - "include/display/lv_themes/lv_theme_default.h", + "include/pros/api_legacy.h", + "include/display/lv_objx/lv_lmeter.h", + "include/display/lv_themes/lv_theme_templ.h", + "include/pros/apix.h", + "include/display/lv_draw/lv_draw.mk", + "include/display/lv_themes/lv_theme_alien.h", + "include/pros/colors.hpp", + "include/display/lv_objx/lv_img.h", + "firmware/libc.a", "include/display/lv_themes/lv_theme_zen.h", - "include/pros/screen.h", - "include/pros/vision.h", - "include/pros/vision.hpp", - "include/display/lv_objx/lv_preload.h", - "firmware/libm.a", - "include/display/lv_objx/lv_page.h", - "include/pros/screen.hpp", - "include/display/lv_core/lv_style.h", - "include/pros/link.h", - "include/pros/ext_adi.h", - "include/pros/adi.hpp", - "include/display/lv_objx/lv_chart.h", - "include/display/lv_core/lv_refr.h", - "include/display/lv_core/lv_vdb.h", - "include/display/lv_misc/lv_mem.h", + "include/display/lv_themes/lv_theme_material.h", + "include/display/lv_draw/lv_draw_arc.h", + "include/display/lv_themes/lv_theme_mono.h", + "include/display/lv_themes/lv_themes.mk", + "include/display/lv_objx/lv_slider.h", "include/pros/serial.h", - "include/display/lv_objx/lv_imgbtn.h", - "include/pros/apix.h", + "include/display/lv_themes/lv_theme.h", + "include/display/README.md", + "include/display/lv_objx/lv_canvas.h", + "include/pros/misc.h", + "include/display/lv_misc/lv_fs.h", + "include/pros/rtos.h", + "include/display/lv_core/lv_indev.h", + "include/pros/motors.hpp", + "include/display/lv_core/lv_style.h", + "include/display/lv_version.h", "include/display/lv_core/lv_lang.h", - "include/display/lv_draw/lv_draw_vbasic.h", - "include/display/lv_misc/lv_symbol_def.h", - "include/display/lv_objx/lv_objx_templ.h", - "include/display/lv_misc/lv_ufs.h", - "firmware/libpros.a", + "include/api.h", + "include/display/lv_objx/lv_gauge.h", + "include/pros/rtos.hpp", + "include/display/lv_hal/lv_hal_disp.h", "include/pros/motors.h", - "include/display/lv_objx/lv_roller.h", - "common.mk", - "include/pros/adi.h", - "include/display/lv_objx/lv_label.h", - "include/display/lv_draw/lv_draw_triangle.h", - "include/display/lv_fonts/lv_fonts.mk", - "include/pros/gps.h", + "include/display/lv_objx/lv_led.h", + "include/display/lv_draw/lv_draw_rbasic.h", + "include/display/lv_objx/lv_kb.h", + "include/display/lv_conf_checker.h", + "include/display/lv_hal/lv_hal.h", + "include/display/lv_draw/lv_draw_line.h", + "include/pros/gps.hpp", "include/display/lv_objx/lv_objx.mk", - "include/display/lv_draw/lv_draw_rect.h", - "include/display/lv_objx/lv_img.h", - "include/display/lv_misc/lv_task.h", - "include/pros/serial.hpp", - "include/pros/misc.h", - "include/display/lv_themes/lv_theme_templ.h", + "include/display/lv_objx/lv_win.h", + "include/display/lv_core/lv_obj.h", + "include/display/lv_objx/lv_arc.h", + "include/pros/link.h", + "include/display/lv_objx/lv_preload.h", + "include/display/lv_misc/lv_area.h", "include/display/lv_misc/lv_ll.h", - "include/display/lv_draw/lv_draw.h", - "include/display/licence.txt", + "include/pros/optical.h", + "include/pros/serial.hpp", + "include/pros/screen.h", + "include/display/lv_themes/lv_theme_nemo.h", + "include/pros/llemu.hpp", + "firmware/libpros.a", + "include/display/lv_misc/lv_gc.h", "include/display/lv_misc/lv_anim.h", - "include/display/lv_objx/lv_btnm.h", - "include/display/lv_objx/lv_cb.h", - "include/api.h", - "include/display/lv_objx/lv_arc.h", - "include/display/lv_draw/lv_draw_label.h", - "include/display/lv_objx/lv_sw.h", - "include/display/lv_themes/lv_theme_night.h", - "include/display/lv_draw/lv_draw_arc.h", - "include/display/lv_themes/lv_theme_mono.h", - "include/display/lv_draw/lv_draw_rbasic.h", "include/display/lv_objx/lv_line.h", - "include/display/lv_misc/lv_templ.h", - "include/display/lv_objx/lv_lmeter.h", + "include/pros/distance.hpp", + "include/pros/rotation.hpp", + "include/pros/error.h", + "include/display/lv_objx/lv_tileview.h", + "include/pros/gps.h", + "include/display/lv_misc/lv_task.h", + "include/pros/imu.h", "firmware/v5-hot.ld", - "include/display/lv_objx/lv_calendar.h", - "include/display/lv_core/lv_indev.h", - "include/pros/colors.h", - "include/display/README.md", - "include/pros/link.hpp", "include/display/lv_misc/lv_misc.mk", - "include/pros/distance.h", - "include/pros/optical.h", + "include/pros/colors.h", + "common.mk", + "include/display/lv_objx/lv_roller.h", "include/display/lv_objx/lv_bar.h", - "include/display/lv_objx/lv_btn.h", - "include/display/lv_objx/lv_win.h", - "firmware/v5-common.ld", - "include/display/lv_core/lv_obj.h", - "include/pros/rotation.hpp", - "include/display/lv_objx/lv_cont.h", - "include/display/lv_misc/lv_circ.h", - "include/display/lv_hal/lv_hal_tick.h", - "include/display/lv_version.h", - "include/display/lv_objx/lv_spinbox.h", - "include/display/lv_objx/lv_led.h", - "include/display/lv_draw/lv_draw_line.h", - "include/display/lv_core/lv_core.mk", - "include/display/lv_hal/lv_hal.mk", - "include/pros/llemu.hpp", - "include/display/lv_hal/lv_hal_disp.h", - "include/display/lv_objx/lv_tileview.h", - "include/display/lv_themes/lv_theme_material.h", - "include/display/lv_misc/lv_log.h", - "include/pros/api_legacy.h", - "include/display/lv_misc/lv_font.h", - "include/display/lv_misc/lv_color.h", - "include/display/lvgl.h", - "include/display/lv_core/lv_group.h", - "firmware/libc.a", - "include/pros/rtos.hpp", + "include/display/lv_themes/lv_theme_default.h", "firmware/v5.ld", - "include/pros/motors.hpp", - "include/display/lv_objx/lv_slider.h", - "include/display/lv_hal/lv_hal.h", - "include/display/lv_themes/lv_theme.h", - "include/display/lv_objx/lv_ddlist.h", - "include/display/lv_misc/lv_fs.h", - "include/pros/imu.h", - "include/display/lv_objx/lv_tabview.h", - "include/display/lv_themes/lv_theme_nemo.h", - "include/display/lv_themes/lv_theme_alien.h" + "include/display/lv_misc/lv_ufs.h", + "include/display/lv_hal/lv_hal_tick.h", + "include/display/licence.txt", + "include/display/lv_objx/lv_ta.h", + "include/display/lv_objx/lv_imgbtn.h", + "include/pros/adi.h" ], "target": "v5", "user_files": [ - "src/main.c", - "include/main.hh", - "include/main.hpp", + "src/main.cc", + ".gitignore", "Makefile", "src/main.cpp", - "include/main.h", - ".gitignore", - "src/main.cc" + "src/main.c", + "include/main.hpp", + "include/main.hh", + "include/main.h" ], - "version": "3.6.2" + "version": "3.8.0" }, "okapilib": { "location": "C:\\Users\\union\\AppData\\Roaming\\PROS\\templates\\okapilib@4.8.0", diff --git a/src/EZ-Template/util.cpp b/src/EZ-Template/util.cpp index dd3f30b9..2b1a5ecc 100644 --- a/src/EZ-Template/util.cpp +++ b/src/EZ-Template/util.cpp @@ -25,7 +25,7 @@ void print_ez_template() { |_| )" << '\n'; - printf("Version: 2.2.0-RC2\n"); + printf("Version: 3.0.0-RC1\n"); } std::string get_last_word(std::string text) { std::string word = ""; diff --git a/src/main.cpp b/src/main.cpp index 5534f3d0..9cdde90c 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -5,29 +5,29 @@ Drive chassis ( // Left Chassis Ports (negative port will reverse it!) // the first port is the sensored port (when trackers are not used!) - {-11, -12, -13, -14} + {-10, -19, 20, 9} // Right Chassis Ports (negative port will reverse it!) // the first port is the sensored port (when trackers are not used!) - ,{20, 19, 18, 17} + ,{3, -4, -11, 12} // IMU Port - , 5 + ,6 // Wheel Diameter (Remember, 4" wheels are actually 4.125!) // (or tracking wheel diameter) - ,4.125 + ,3.25 // Cartridge RPM // (or tick per rotation if using tracking wheels) - ,420 + ,600 // External Gear Ratio (MUST BE DECIMAL) // (or gear ratio of tracking wheel) // eg. if your drive is 84:36 where the 36t is powered, your RATIO would be 2.333. // eg. if your drive is 36:60 where the 60t is powered, your RATIO would be 0.6. - ,1 + ,1.18343195266 // Uncomment if using tracking wheels /* diff --git a/version b/version index d1d0299f..e4ebb1de 100644 --- a/version +++ b/version @@ -1 +1 @@ -2.2.0-RC2 \ No newline at end of file +3.0.0-RC1 \ No newline at end of file