diff --git a/Firmware/CoverUI/CoverUI/.gitignore b/Firmware/CoverUI/CoverUI/.gitignore new file mode 100644 index 00000000..83abcf34 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/.gitignore @@ -0,0 +1,3 @@ +build/ +.idea/ +cmake-build-debug/ diff --git a/Firmware/CoverUI/CoverUI/.vscode/.cortex-debug.peripherals.state.json b/Firmware/CoverUI/CoverUI/.vscode/.cortex-debug.peripherals.state.json new file mode 100644 index 00000000..0637a088 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/.vscode/.cortex-debug.peripherals.state.json @@ -0,0 +1 @@ +[] \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUI/.vscode/.cortex-debug.registers.state.json b/Firmware/CoverUI/CoverUI/.vscode/.cortex-debug.registers.state.json new file mode 100644 index 00000000..0637a088 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/.vscode/.cortex-debug.registers.state.json @@ -0,0 +1 @@ +[] \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUI/.vscode/c_cpp_properties.json b/Firmware/CoverUI/CoverUI/.vscode/c_cpp_properties.json new file mode 100644 index 00000000..72579cea --- /dev/null +++ b/Firmware/CoverUI/CoverUI/.vscode/c_cpp_properties.json @@ -0,0 +1,17 @@ +{ + "configurations": [ + { + "name": "Linux", + "includePath": [ + "${workspaceFolder}/**" + ], + "defines": [], + "compilerPath": "/usr/local/bin/arm-none-eabi-gcc", + "cStandard": "c11", + "cppStandard": "gnu++14", + "intelliSenseMode": "linux-gcc-arm", + "compileCommands": "${workspaceFolder}/build/compile_commands.json" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUI/.vscode/launch.json b/Firmware/CoverUI/CoverUI/.vscode/launch.json new file mode 100644 index 00000000..3a8cd6a6 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/.vscode/launch.json @@ -0,0 +1,22 @@ +{ + // Verwendet IntelliSense zum Ermitteln möglicher Attribute. + // Zeigen Sie auf vorhandene Attribute, um die zugehörigen Beschreibungen anzuzeigen. + // Weitere Informationen finden Sie unter https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + { + "name": "PICO Debug", + "device": "RP2040", + "gdbPath": "gdb-multiarch", + "cwd": "${workspaceRoot}", + "executable": "${command:cmake.launchTargetPath}", + "request": "launch", + "type": "cortex-debug", + "servertype": "openocd", + "configFiles": ["interface/picoprobe.cfg", "target/rp2040-core0.cfg"], + "svdFile": "${env:PICO_SDK_PATH}/src/rp2040/hardware_regs/rp2040.svd", + "runToMain": true, + "postRestartCommands": ["break main", "continue"] + } + ] +} \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUI/.vscode/settings.json b/Firmware/CoverUI/CoverUI/.vscode/settings.json new file mode 100644 index 00000000..f4f42f7d --- /dev/null +++ b/Firmware/CoverUI/CoverUI/.vscode/settings.json @@ -0,0 +1,7 @@ +{ + "cortex-debug.variableUseNaturalFormat": true, + "files.associations": { + "initializer_list": "cpp", + "utility": "cpp" + } +} \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUI/.vscode/tasks.json b/Firmware/CoverUI/CoverUI/.vscode/tasks.json new file mode 100644 index 00000000..ed7a9ee5 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/.vscode/tasks.json @@ -0,0 +1,28 @@ +{ + "tasks": [ + { + "type": "cppbuild", + "label": "C/C++: arm-none-eabi-gcc Aktive Datei kompilieren", + "command": "/usr/bin/arm-none-eabi-gcc", + "args": [ + "-fdiagnostics-color=always", + "-g", + "${file}", + "-o", + "${fileDirname}/${fileBasenameNoExtension}" + ], + "options": { + "cwd": "${fileDirname}" + }, + "problemMatcher": [ + "$gcc" + ], + "group": { + "kind": "build", + "isDefault": true + }, + "detail": "Vom Debugger generierte Aufgabe." + } + ], + "version": "2.0.0" +} \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUI/BttnCtl.h b/Firmware/CoverUI/CoverUI/BttnCtl.h new file mode 100644 index 00000000..b6f58d10 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/BttnCtl.h @@ -0,0 +1,80 @@ +#ifndef _BttnCtl_HEADER_FILE_ +#define _BttnCtl_HEADER_FILE_ + + +// Protocol Header Info +enum TYPE +{ + Get_Version = 0xB0, + Set_Buzzer = 0xB1, + Set_LEDs = 0xB2, + Get_Button = 0xB3 +}; + + +enum LED_state { + LED_off = 0b000, + LED_blink_slow = 0b101, + LED_blink_fast = 0b110, + LED_on = 0b111 +}; + +#pragma pack(push, 1) +struct msg_get_version +{ + uint8_t type; // command type + uint8_t reserved; // padding + uint16_t version; + uint16_t crc; // CRC 16 +} __attribute__((packed)); +#pragma pack(pop) + + +#pragma pack(push, 1) +struct msg_set_buzzer +{ + uint8_t type; // command type + uint8_t repeat; // Repeat X times + uint8_t on_time; // Signal on time + uint8_t off_time; // Signal off time + uint16_t crc; // CRC 16 +} __attribute__((packed)); +#pragma pack(pop) + + +/** + * @brief Use this to update the LED matrix + * Each LED gets three bits with the following meaning: + * 0b000 = Off + * 0b001 = reserved for future use + * 0b010 = reserved for future use + * 0b011 = reserved for future use + * 0b100 = reserved for future use + * 0b101 = On slow blink + * 0b110 = On fast blink + * 0b111 = On + */ +#pragma pack(push, 1) +struct msg_set_leds +{ + uint8_t type; // command type + uint8_t reserved; // padding + uint64_t leds; + uint16_t crc; // CRC 16 +} __attribute__((packed)); +#pragma pack(pop) + +#pragma pack(push, 1) +struct msg_event_button +{ + uint8_t type; // command type + uint16_t button_id; + uint8_t press_duration; + uint16_t crc; // CRC 16 +} __attribute__((packed)); +#pragma pack(pop) + + + + +#endif // _BttnCtl_HEADER_FILE_ diff --git a/Firmware/CoverUI/CoverUI/CMakeLists.txt b/Firmware/CoverUI/CoverUI/CMakeLists.txt new file mode 100644 index 00000000..30ab5a19 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/CMakeLists.txt @@ -0,0 +1,46 @@ +cmake_minimum_required(VERSION 3.12) +include(pico_sdk_import.cmake) + +set(projname "mower-buttons") +add_executable(${projname}) + + + + + + +target_sources(${projname} PRIVATE main.cpp LEDcontrol.cpp statemachine.cpp buttonscan.cpp) + +#project(${projname} C CXX ASM) +project(pico_examples C CXX ASM) +set(CMAKE_C_STANDARD 11) +set(CMAKE_CXX_STANDARD 17) + +pico_sdk_init() + +#pico_generate_pio_header(${projname} ${CMAKE_CURRENT_LIST_DIR}/GPIO_prg.pio) +pico_generate_pio_header(${projname} ${CMAKE_CURRENT_LIST_DIR}/status_LED.pio) +pico_generate_pio_header(${projname} ${CMAKE_CURRENT_LIST_DIR}/LED_mux.pio) +pico_generate_pio_header(${projname} ${CMAKE_CURRENT_LIST_DIR}/buzzer.pio) + + + +#set(Mower_PATH ${PROJECT_SOURCE_DIR}) +set(PICO_EXAMPLES_PATH ${PROJECT_SOURCE_DIR}) + + + +# enable usb output, disable uart output + # pico_enable_stdio_usb(mower-buttons 0) + # pico_enable_stdio_uart(mower-buttons 1) + + + + +# main.c +# extrafunc.c +# ) + +target_link_libraries(${projname} pico_stdlib hardware_pio pico_multicore) + +pico_add_extra_outputs(${projname}) \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUI/COBS.h b/Firmware/CoverUI/CoverUI/COBS.h new file mode 100644 index 00000000..c0b979d7 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/COBS.h @@ -0,0 +1,127 @@ +// +// Copyright (c) 2011 Christopher Baker +// Copyright (c) 2011 Jacques Fortier +// +// SPDX-License-Identifier: MIT +// + + +#pragma once + + + +/// \brief A Consistent Overhead Byte Stuffing (COBS) Encoder. +/// +/// Consistent Overhead Byte Stuffing (COBS) is an encoding that removes all 0 +/// bytes from arbitrary binary data. The encoded data consists only of bytes +/// with values from 0x01 to 0xFF. This is useful for preparing data for +/// transmission over a serial link (RS-232 or RS-485 for example), as the 0 +/// byte can be used to unambiguously indicate packet boundaries. COBS also has +/// the advantage of adding very little overhead (at least 1 byte, plus up to an +/// additional byte per 254 bytes of data). For messages smaller than 254 bytes, +/// the overhead is constant. +/// +/// \sa http://conferences.sigcomm.org/sigcomm/1997/papers/p062.pdf +/// \sa http://en.wikipedia.org/wiki/Consistent_Overhead_Byte_Stuffing +/// \sa https://github.com/jacquesf/COBS-Consistent-Overhead-Byte-Stuffing +/// \sa http://www.jacquesf.com/2011/03/consistent-overhead-byte-stuffing +class COBS +{ +public: + /// \brief Encode a byte buffer with the COBS encoder. + /// \param buffer A pointer to the unencoded buffer to encode. + /// \param size The number of bytes in the \p buffer. + /// \param encodedBuffer The buffer for the encoded bytes. + /// \returns The number of bytes written to the \p encodedBuffer. + /// \warning The encodedBuffer must have at least getEncodedBufferSize() + /// allocated. + static size_t encode(const uint8_t* buffer, + size_t size, + uint8_t* encodedBuffer) + { + size_t read_index = 0; + size_t write_index = 1; + size_t code_index = 0; + uint8_t code = 1; + + while (read_index < size) + { + if (buffer[read_index] == 0) + { + encodedBuffer[code_index] = code; + code = 1; + code_index = write_index++; + read_index++; + } + else + { + encodedBuffer[write_index++] = buffer[read_index++]; + code++; + + if (code == 0xFF) + { + encodedBuffer[code_index] = code; + code = 1; + code_index = write_index++; + } + } + } + + encodedBuffer[code_index] = code; + + return write_index; + } + + + /// \brief Decode a COBS-encoded buffer. + /// \param encodedBuffer A pointer to the \p encodedBuffer to decode. + /// \param size The number of bytes in the \p encodedBuffer. + /// \param decodedBuffer The target buffer for the decoded bytes. + /// \returns The number of bytes written to the \p decodedBuffer. + /// \warning decodedBuffer must have a minimum capacity of size. + static size_t decode(const uint8_t* encodedBuffer, + size_t size, + uint8_t* decodedBuffer) + { + if (size == 0) + return 0; + + size_t read_index = 0; + size_t write_index = 0; + uint8_t code = 0; + uint8_t i = 0; + + while (read_index < size) + { + code = encodedBuffer[read_index]; + + if (read_index + code > size && code != 1) + { + return 0; + } + + read_index++; + + for (i = 1; i < code; i++) + { + decodedBuffer[write_index++] = encodedBuffer[read_index++]; + } + + if (code != 0xFF && read_index != size) + { + decodedBuffer[write_index++] = '\0'; + } + } + + return write_index; + } + + /// \brief Get the maximum encoded buffer size for an unencoded buffer size. + /// \param unencodedBufferSize The size of the buffer to be encoded. + /// \returns the maximum size of the required encoded buffer. + static size_t getEncodedBufferSize(size_t unencodedBufferSize) + { + return unencodedBufferSize + unencodedBufferSize / 254 + 1; + } + +}; diff --git a/Firmware/CoverUI/CoverUI/CRC.h b/Firmware/CoverUI/CoverUI/CRC.h new file mode 100644 index 00000000..e20db354 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/CRC.h @@ -0,0 +1,2066 @@ +/** + @file CRC.h + @author Daniel Bahr + @version 1.1.0.0 + @copyright + @parblock + CRC++ + Copyright (c) 2021, Daniel Bahr + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * Neither the name of CRC++ nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + @endparblock +*/ + +/* + CRC++ can be configured by setting various #defines before #including this header file: + + #define crcpp_uint8 - Specifies the type used to store CRCs that have a width of 8 bits or less. + This type is not used in CRC calculations. Defaults to ::std::uint8_t. + #define crcpp_uint16 - Specifies the type used to store CRCs that have a width between 9 and 16 bits (inclusive). + This type is not used in CRC calculations. Defaults to ::std::uint16_t. + #define crcpp_uint32 - Specifies the type used to store CRCs that have a width between 17 and 32 bits (inclusive). + This type is not used in CRC calculations. Defaults to ::std::uint32_t. + #define crcpp_uint64 - Specifies the type used to store CRCs that have a width between 33 and 64 bits (inclusive). + This type is not used in CRC calculations. Defaults to ::std::uint64_t. + #define crcpp_size - This type is used for loop iteration and function signatures only. Defaults to ::std::size_t. + #define CRCPP_USE_NAMESPACE - Define to place all CRC++ code within the ::CRCPP namespace. + #define CRCPP_BRANCHLESS - Define to enable a branchless CRC implementation. The branchless implementation uses a single integer + multiplication in the bit-by-bit calculation instead of a small conditional. The branchless implementation + may be faster on processor architectures which support single-instruction integer multiplication. + #define CRCPP_USE_CPP11 - Define to enables C++11 features (move semantics, constexpr, static_assert, etc.). + #define CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS - Define to include definitions for little-used CRCs. +*/ + +#ifndef CRCPP_CRC_H_ +#define CRCPP_CRC_H_ + +#include // Includes CHAR_BIT +#ifdef CRCPP_USE_CPP11 +#include // Includes ::std::size_t +#include // Includes ::std::uint8_t, ::std::uint16_t, ::std::uint32_t, ::std::uint64_t +#else +#include // Includes size_t +#include // Includes uint8_t, uint16_t, uint32_t, uint64_t +#endif +#include // Includes ::std::numeric_limits +#include // Includes ::std::move + +#ifndef crcpp_uint8 +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned 8-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint8 ::std::uint8_t +# else + /// @brief Unsigned 8-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint8 uint8_t +# endif +#endif + +#ifndef crcpp_uint16 +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned 16-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint16 ::std::uint16_t +# else + /// @brief Unsigned 16-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint16 uint16_t +# endif +#endif + +#ifndef crcpp_uint32 +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned 32-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint32 ::std::uint32_t +# else + /// @brief Unsigned 32-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint32 uint32_t +# endif +#endif + +#ifndef crcpp_uint64 +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned 64-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint64 ::std::uint64_t +# else + /// @brief Unsigned 64-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint64 uint64_t +# endif +#endif + +#ifndef crcpp_size +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned size definition, used for specifying data sizes. +# define crcpp_size ::std::size_t +# else + /// @brief Unsigned size definition, used for specifying data sizes. +# define crcpp_size size_t +# endif +#endif + +#ifdef CRCPP_USE_CPP11 + /// @brief Compile-time expression definition. +# define crcpp_constexpr constexpr +#else + /// @brief Compile-time expression definition. +# define crcpp_constexpr const +#endif + +#ifdef CRCPP_USE_NAMESPACE +namespace CRCPP +{ +#endif + +/** + @brief Static class for computing CRCs. + @note This class supports computation of full and multi-part CRCs, using a bit-by-bit algorithm or a + byte-by-byte lookup table. The CRCs are calculated using as many optimizations as is reasonable. + If compiling with C++11, the constexpr keyword is used liberally so that many calculations are + performed at compile-time instead of at runtime. +*/ +class CRC +{ +public: + // Forward declaration + template + struct Table; + + /** + @brief CRC parameters. + */ + template + struct Parameters + { + CRCType polynomial; ///< CRC polynomial + CRCType initialValue; ///< Initial CRC value + CRCType finalXOR; ///< Value to XOR with the final CRC + bool reflectInput; ///< true to reflect all input bytes + bool reflectOutput; ///< true to reflect the output CRC (reflection occurs before the final XOR) + + Table MakeTable() const; + }; + + /** + @brief CRC lookup table. After construction, the CRC parameters are fixed. + @note A CRC table can be used for multiple CRC calculations. + */ + template + struct Table + { + // Constructors are intentionally NOT marked explicit. + Table(const Parameters & parameters); + +#ifdef CRCPP_USE_CPP11 + Table(Parameters && parameters); +#endif + + const Parameters & GetParameters() const; + + const CRCType * GetTable() const; + + CRCType operator[](unsigned char index) const; + + private: + void InitTable(); + + Parameters parameters; ///< CRC parameters used to construct the table + CRCType table[1 << CHAR_BIT]; ///< CRC lookup table + }; + + // The number of bits in CRCType must be at least as large as CRCWidth. + // CRCType must be an unsigned integer type or a custom type with operator overloads. + template + static CRCType Calculate(const void * data, crcpp_size size, const Parameters & parameters); + + template + static CRCType Calculate(const void * data, crcpp_size size, const Parameters & parameters, CRCType crc); + + template + static CRCType Calculate(const void * data, crcpp_size size, const Table & lookupTable); + + template + static CRCType Calculate(const void * data, crcpp_size size, const Table & lookupTable, CRCType crc); + + template + static CRCType CalculateBits(const void * data, crcpp_size size, const Parameters & parameters); + + template + static CRCType CalculateBits(const void * data, crcpp_size size, const Parameters & parameters, CRCType crc); + + template + static CRCType CalculateBits(const void * data, crcpp_size size, const Table & lookupTable); + + template + static CRCType CalculateBits(const void * data, crcpp_size size, const Table & lookupTable, CRCType crc); + + // Common CRCs up to 64 bits. + // Note: Check values are the computed CRCs when given an ASCII input of "123456789" (without null terminator) +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters< crcpp_uint8, 4> & CRC_4_ITU(); + static const Parameters< crcpp_uint8, 5> & CRC_5_EPC(); + static const Parameters< crcpp_uint8, 5> & CRC_5_ITU(); + static const Parameters< crcpp_uint8, 5> & CRC_5_USB(); + static const Parameters< crcpp_uint8, 6> & CRC_6_CDMA2000A(); + static const Parameters< crcpp_uint8, 6> & CRC_6_CDMA2000B(); + static const Parameters< crcpp_uint8, 6> & CRC_6_ITU(); + static const Parameters< crcpp_uint8, 6> & CRC_6_NR(); + static const Parameters< crcpp_uint8, 7> & CRC_7(); +#endif + static const Parameters< crcpp_uint8, 8> & CRC_8(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters< crcpp_uint8, 8> & CRC_8_EBU(); + static const Parameters< crcpp_uint8, 8> & CRC_8_MAXIM(); + static const Parameters< crcpp_uint8, 8> & CRC_8_WCDMA(); + static const Parameters< crcpp_uint8, 8> & CRC_8_LTE(); + static const Parameters & CRC_10(); + static const Parameters & CRC_10_CDMA2000(); + static const Parameters & CRC_11(); + static const Parameters & CRC_11_NR(); + static const Parameters & CRC_12_CDMA2000(); + static const Parameters & CRC_12_DECT(); + static const Parameters & CRC_12_UMTS(); + static const Parameters & CRC_13_BBC(); + static const Parameters & CRC_15(); + static const Parameters & CRC_15_MPT1327(); +#endif + static const Parameters & CRC_16_ARC(); + static const Parameters & CRC_16_BUYPASS(); + static const Parameters & CRC_16_CCITTFALSE(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_16_CDMA2000(); + static const Parameters & CRC_16_CMS(); + static const Parameters & CRC_16_DECTR(); + static const Parameters & CRC_16_DECTX(); + static const Parameters & CRC_16_DNP(); +#endif + static const Parameters & CRC_16_GENIBUS(); + static const Parameters & CRC_16_KERMIT(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_16_MAXIM(); + static const Parameters & CRC_16_MODBUS(); + static const Parameters & CRC_16_T10DIF(); + static const Parameters & CRC_16_USB(); +#endif + static const Parameters & CRC_16_X25(); + static const Parameters & CRC_16_XMODEM(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_17_CAN(); + static const Parameters & CRC_21_CAN(); + static const Parameters & CRC_24(); + static const Parameters & CRC_24_FLEXRAYA(); + static const Parameters & CRC_24_FLEXRAYB(); + static const Parameters & CRC_24_LTEA(); + static const Parameters & CRC_24_LTEB(); + static const Parameters & CRC_24_NRC(); + static const Parameters & CRC_30(); +#endif + static const Parameters & CRC_32(); + static const Parameters & CRC_32_BZIP2(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_32_C(); +#endif + static const Parameters & CRC_32_MPEG2(); + static const Parameters & CRC_32_POSIX(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_32_Q(); + static const Parameters & CRC_40_GSM(); + static const Parameters & CRC_64(); +#endif + +#ifdef CRCPP_USE_CPP11 + CRC() = delete; + CRC(const CRC & other) = delete; + CRC & operator=(const CRC & other) = delete; + CRC(CRC && other) = delete; + CRC & operator=(CRC && other) = delete; +#endif + +private: +#ifndef CRCPP_USE_CPP11 + CRC(); + CRC(const CRC & other); + CRC & operator=(const CRC & other); +#endif + + template + static IntegerType Reflect(IntegerType value, crcpp_uint16 numBits); + + template + static CRCType Finalize(CRCType remainder, CRCType finalXOR, bool reflectOutput); + + template + static CRCType UndoFinalize(CRCType remainder, CRCType finalXOR, bool reflectOutput); + + template + static CRCType CalculateRemainder(const void * data, crcpp_size size, const Parameters & parameters, CRCType remainder); + + template + static CRCType CalculateRemainder(const void * data, crcpp_size size, const Table & lookupTable, CRCType remainder); + + template + static CRCType CalculateRemainderBits(unsigned char byte, crcpp_size numBits, const Parameters & parameters, CRCType remainder); +}; + +/** + @brief Returns a CRC lookup table construct using these CRC parameters. + @note This function primarily exists to allow use of the auto keyword instead of instantiating + a table directly, since template parameters are not inferred in constructors. + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC lookup table +*/ +template +inline CRC::Table CRC::Parameters::MakeTable() const +{ + // This should take advantage of RVO and optimize out the copy. + return CRC::Table(*this); +} + +/** + @brief Constructs a CRC table from a set of CRC parameters + @param[in] params CRC parameters + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC +*/ +template +inline CRC::Table::Table(const Parameters & params) : + parameters(params) +{ + InitTable(); +} + +#ifdef CRCPP_USE_CPP11 +/** + @brief Constructs a CRC table from a set of CRC parameters + @param[in] params CRC parameters + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC +*/ +template +inline CRC::Table::Table(Parameters && params) : + parameters(::std::move(params)) +{ + InitTable(); +} +#endif + +/** + @brief Gets the CRC parameters used to construct the CRC table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC parameters +*/ +template +inline const CRC::Parameters & CRC::Table::GetParameters() const +{ + return parameters; +} + +/** + @brief Gets the CRC table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC table +*/ +template +inline const CRCType * CRC::Table::GetTable() const +{ + return table; +} + +/** + @brief Gets an entry in the CRC table + @param[in] index Index into the CRC table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC table entry +*/ +template +inline CRCType CRC::Table::operator[](unsigned char index) const +{ + return table[index]; +} + +/** + @brief Initializes a CRC table. + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC +*/ +template +inline void CRC::Table::InitTable() +{ + // For masking off the bits for the CRC (in the event that the number of bits in CRCType is larger than CRCWidth) + static crcpp_constexpr CRCType BIT_MASK((CRCType(1) << (CRCWidth - CRCType(1))) | + ((CRCType(1) << (CRCWidth - CRCType(1))) - CRCType(1))); + + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CHAR_BIT >= CRCWidth) ? static_cast(CHAR_BIT - CRCWidth) : 0); + + CRCType crc; + unsigned char byte = 0; + + // Loop over each dividend (each possible number storable in an unsigned char) + do + { + crc = CRC::CalculateRemainder(&byte, sizeof(byte), parameters, CRCType(0)); + + // This mask might not be necessary; all unit tests pass with this line commented out, + // but that might just be a coincidence based on the CRC parameters used for testing. + // In any case, this is harmless to leave in and only adds a single machine instruction per loop iteration. + crc &= BIT_MASK; + + if (!parameters.reflectInput && CRCWidth < CHAR_BIT) + { + // Undo the special operation at the end of the CalculateRemainder() + // function for non-reflected CRCs < CHAR_BIT. + crc = static_cast(crc << SHIFT); + } + + table[byte] = crc; + } + while (++byte); +} + +/** + @brief Computes a CRC. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bytes + @param[in] parameters CRC parameters + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::Calculate(const void * data, crcpp_size size, const Parameters & parameters) +{ + CRCType remainder = CalculateRemainder(data, size, parameters, parameters.initialValue); + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} +/** + @brief Appends additional data to a previous CRC calculation. + @note This function can be used to compute multi-part CRCs. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bytes + @param[in] parameters CRC parameters + @param[in] crc CRC from a previous calculation + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::Calculate(const void * data, crcpp_size size, const Parameters & parameters, CRCType crc) +{ + CRCType remainder = UndoFinalize(crc, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); + + remainder = CalculateRemainder(data, size, parameters, remainder); + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Computes a CRC via a lookup table. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bytes + @param[in] lookupTable CRC lookup table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::Calculate(const void * data, crcpp_size size, const Table & lookupTable) +{ + const Parameters & parameters = lookupTable.GetParameters(); + + CRCType remainder = CalculateRemainder(data, size, lookupTable, parameters.initialValue); + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Appends additional data to a previous CRC calculation using a lookup table. + @note This function can be used to compute multi-part CRCs. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bytes + @param[in] lookupTable CRC lookup table + @param[in] crc CRC from a previous calculation + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::Calculate(const void * data, crcpp_size size, const Table & lookupTable, CRCType crc) +{ + const Parameters & parameters = lookupTable.GetParameters(); + + CRCType remainder = UndoFinalize(crc, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); + + remainder = CalculateRemainder(data, size, lookupTable, remainder); + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Computes a CRC. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bits + @param[in] parameters CRC parameters + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::CalculateBits(const void * data, crcpp_size size, const Parameters & parameters) +{ + CRCType remainder = parameters.initialValue; + + // Calculate the remainder on a whole number of bytes first, then call + // a special-case function for the remaining bits. + crcpp_size wholeNumberOfBytes = size / CHAR_BIT; + if (wholeNumberOfBytes > 0) + { + remainder = CalculateRemainder(data, wholeNumberOfBytes, parameters, remainder); + } + + crcpp_size remainingNumberOfBits = size % CHAR_BIT; + if (remainingNumberOfBits != 0) + { + unsigned char lastByte = *(reinterpret_cast(data) + wholeNumberOfBytes); + remainder = CalculateRemainderBits(lastByte, remainingNumberOfBits, parameters, remainder); + } + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} +/** + @brief Appends additional data to a previous CRC calculation. + @note This function can be used to compute multi-part CRCs. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bits + @param[in] parameters CRC parameters + @param[in] crc CRC from a previous calculation + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::CalculateBits(const void * data, crcpp_size size, const Parameters & parameters, CRCType crc) +{ + CRCType remainder = UndoFinalize(crc, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); + + // Calculate the remainder on a whole number of bytes first, then call + // a special-case function for the remaining bits. + crcpp_size wholeNumberOfBytes = size / CHAR_BIT; + if (wholeNumberOfBytes > 0) + { + remainder = CalculateRemainder(data, wholeNumberOfBytes, parameters, parameters.initialValue); + } + + crcpp_size remainingNumberOfBits = size % CHAR_BIT; + if (remainingNumberOfBits != 0) + { + unsigned char lastByte = *(reinterpret_cast(data) + wholeNumberOfBytes); + remainder = CalculateRemainderBits(lastByte, remainingNumberOfBits, parameters, remainder); + } + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Computes a CRC via a lookup table. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bits + @param[in] lookupTable CRC lookup table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::CalculateBits(const void * data, crcpp_size size, const Table & lookupTable) +{ + const Parameters & parameters = lookupTable.GetParameters(); + + CRCType remainder = parameters.initialValue; + + // Calculate the remainder on a whole number of bytes first, then call + // a special-case function for the remaining bits. + crcpp_size wholeNumberOfBytes = size / CHAR_BIT; + if (wholeNumberOfBytes > 0) + { + remainder = CalculateRemainder(data, wholeNumberOfBytes, lookupTable, remainder); + } + + crcpp_size remainingNumberOfBits = size % CHAR_BIT; + if (remainingNumberOfBits != 0) + { + unsigned char lastByte = *(reinterpret_cast(data) + wholeNumberOfBytes); + remainder = CalculateRemainderBits(lastByte, remainingNumberOfBits, parameters, remainder); + } + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Appends additional data to a previous CRC calculation using a lookup table. + @note This function can be used to compute multi-part CRCs. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bits + @param[in] lookupTable CRC lookup table + @param[in] crc CRC from a previous calculation + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::CalculateBits(const void * data, crcpp_size size, const Table & lookupTable, CRCType crc) +{ + const Parameters & parameters = lookupTable.GetParameters(); + + CRCType remainder = UndoFinalize(crc, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); + + // Calculate the remainder on a whole number of bytes first, then call + // a special-case function for the remaining bits. + crcpp_size wholeNumberOfBytes = size / CHAR_BIT; + if (wholeNumberOfBytes > 0) + { + remainder = CalculateRemainder(data, wholeNumberOfBytes, lookupTable, parameters.initialValue); + } + + crcpp_size remainingNumberOfBits = size % CHAR_BIT; + if (remainingNumberOfBits > 0) + { + unsigned char lastByte = *(reinterpret_cast(data) + wholeNumberOfBytes); + remainder = CalculateRemainderBits(lastByte, remainingNumberOfBits, parameters, remainder); + } + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Reflects (i.e. reverses the bits within) an integer value. + @param[in] value Value to reflect + @param[in] numBits Number of bits in the integer which will be reflected + @tparam IntegerType Integer type of the value being reflected + @return Reflected value +*/ +template +inline IntegerType CRC::Reflect(IntegerType value, crcpp_uint16 numBits) +{ + IntegerType reversedValue(0); + + for (crcpp_uint16 i = 0; i < numBits; ++i) + { + reversedValue = static_cast((reversedValue << 1) | (value & 1)); + value = static_cast(value >> 1); + } + + return reversedValue; +} + +/** + @brief Computes the final reflection and XOR of a CRC remainder. + @param[in] remainder CRC remainder to reflect and XOR + @param[in] finalXOR Final value to XOR with the remainder + @param[in] reflectOutput true to reflect each byte of the remainder before the XOR + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return Final CRC +*/ +template +inline CRCType CRC::Finalize(CRCType remainder, CRCType finalXOR, bool reflectOutput) +{ + // For masking off the bits for the CRC (in the event that the number of bits in CRCType is larger than CRCWidth) + static crcpp_constexpr CRCType BIT_MASK = (CRCType(1) << (CRCWidth - CRCType(1))) | + ((CRCType(1) << (CRCWidth - CRCType(1))) - CRCType(1)); + + if (reflectOutput) + { + remainder = Reflect(remainder, CRCWidth); + } + + return (remainder ^ finalXOR) & BIT_MASK; +} + +/** + @brief Undoes the process of computing the final reflection and XOR of a CRC remainder. + @note This function allows for computation of multi-part CRCs + @note Calling UndoFinalize() followed by Finalize() (or vice versa) will always return the original remainder value: + + CRCType x = ...; + CRCType y = Finalize(x, finalXOR, reflectOutput); + CRCType z = UndoFinalize(y, finalXOR, reflectOutput); + assert(x == z); + + @param[in] crc Reflected and XORed CRC + @param[in] finalXOR Final value XORed with the remainder + @param[in] reflectOutput true if the remainder is to be reflected + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return Un-finalized CRC remainder +*/ +template +inline CRCType CRC::UndoFinalize(CRCType crc, CRCType finalXOR, bool reflectOutput) +{ + // For masking off the bits for the CRC (in the event that the number of bits in CRCType is larger than CRCWidth) + static crcpp_constexpr CRCType BIT_MASK = (CRCType(1) << (CRCWidth - CRCType(1))) | + ((CRCType(1) << (CRCWidth - CRCType(1))) - CRCType(1)); + + crc = (crc & BIT_MASK) ^ finalXOR; + + if (reflectOutput) + { + crc = Reflect(crc, CRCWidth); + } + + return crc; +} + +/** + @brief Computes a CRC remainder. + @param[in] data Data over which the remainder will be computed + @param[in] size Size of the data, in bytes + @param[in] parameters CRC parameters + @param[in] remainder Running CRC remainder. Can be an initial value or the result of a previous CRC remainder calculation. + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC remainder +*/ +template +inline CRCType CRC::CalculateRemainder(const void * data, crcpp_size size, const Parameters & parameters, CRCType remainder) +{ +#ifdef CRCPP_USE_CPP11 + // This static_assert is put here because this function will always be compiled in no matter what + // the template parameters are and whether or not a table lookup or bit-by-bit algorithm is used. + static_assert(::std::numeric_limits::digits >= CRCWidth, "CRCType is too small to contain a CRC of width CRCWidth."); +#else + // Catching this compile-time error is very important. Sadly, the compiler error will be very cryptic, but it's + // better than nothing. + enum { static_assert_failed_CRCType_is_too_small_to_contain_a_CRC_of_width_CRCWidth = 1 / (::std::numeric_limits::digits >= CRCWidth ? 1 : 0) }; +#endif + + const unsigned char * current = reinterpret_cast(data); + + // Slightly different implementations based on the parameters. The current implementations try to eliminate as much + // computation from the inner loop (looping over each bit) as possible. + if (parameters.reflectInput) + { + CRCType polynomial = CRC::Reflect(parameters.polynomial, CRCWidth); + while (size--) + { + remainder = static_cast(remainder ^ *current++); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < CHAR_BIT; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & 1) + // remainder = (remainder >> 1) ^ polynomial; + // else + // remainder >>= 1; + remainder = static_cast((remainder >> 1) ^ ((remainder & 1) * polynomial)); +#else + remainder = static_cast((remainder & 1) ? ((remainder >> 1) ^ polynomial) : (remainder >> 1)); +#endif + } + } + } + else if (CRCWidth >= CHAR_BIT) + { + static crcpp_constexpr CRCType CRC_WIDTH_MINUS_ONE(CRCWidth - CRCType(1)); +#ifndef CRCPP_BRANCHLESS + static crcpp_constexpr CRCType CRC_HIGHEST_BIT_MASK(CRCType(1) << CRC_WIDTH_MINUS_ONE); +#endif + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CRCWidth >= CHAR_BIT) ? static_cast(CRCWidth - CHAR_BIT) : 0); + + while (size--) + { + remainder = static_cast(remainder ^ (static_cast(*current++) << SHIFT)); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < CHAR_BIT; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & CRC_HIGHEST_BIT_MASK) + // remainder = (remainder << 1) ^ parameters.polynomial; + // else + // remainder <<= 1; + remainder = static_cast((remainder << 1) ^ (((remainder >> CRC_WIDTH_MINUS_ONE) & 1) * parameters.polynomial)); +#else + remainder = static_cast((remainder & CRC_HIGHEST_BIT_MASK) ? ((remainder << 1) ^ parameters.polynomial) : (remainder << 1)); +#endif + } + } + } + else + { + static crcpp_constexpr CRCType CHAR_BIT_MINUS_ONE(CHAR_BIT - 1); +#ifndef CRCPP_BRANCHLESS + static crcpp_constexpr CRCType CHAR_BIT_HIGHEST_BIT_MASK(CRCType(1) << CHAR_BIT_MINUS_ONE); +#endif + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CHAR_BIT >= CRCWidth) ? static_cast(CHAR_BIT - CRCWidth) : 0); + + CRCType polynomial = static_cast(parameters.polynomial << SHIFT); + remainder = static_cast(remainder << SHIFT); + + while (size--) + { + remainder = static_cast(remainder ^ *current++); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < CHAR_BIT; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & CHAR_BIT_HIGHEST_BIT_MASK) + // remainder = (remainder << 1) ^ polynomial; + // else + // remainder <<= 1; + remainder = static_cast((remainder << 1) ^ (((remainder >> CHAR_BIT_MINUS_ONE) & 1) * polynomial)); +#else + remainder = static_cast((remainder & CHAR_BIT_HIGHEST_BIT_MASK) ? ((remainder << 1) ^ polynomial) : (remainder << 1)); +#endif + } + } + + remainder = static_cast(remainder >> SHIFT); + } + + return remainder; +} + +/** + @brief Computes a CRC remainder using lookup table. + @param[in] data Data over which the remainder will be computed + @param[in] size Size of the data, in bytes + @param[in] lookupTable CRC lookup table + @param[in] remainder Running CRC remainder. Can be an initial value or the result of a previous CRC remainder calculation. + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC remainder +*/ +template +inline CRCType CRC::CalculateRemainder(const void * data, crcpp_size size, const Table & lookupTable, CRCType remainder) +{ + const unsigned char * current = reinterpret_cast(data); + + if (lookupTable.GetParameters().reflectInput) + { + while (size--) + { +#if defined(WIN32) || defined(_WIN32) || defined(WINCE) + // Disable warning about data loss when doing (remainder >> CHAR_BIT) when + // remainder is one byte long. The algorithm is still correct in this case, + // though it's possible that one additional machine instruction will be executed. +# pragma warning (push) +# pragma warning (disable : 4333) +#endif + remainder = static_cast((remainder >> CHAR_BIT) ^ lookupTable[static_cast(remainder ^ *current++)]); +#if defined(WIN32) || defined(_WIN32) || defined(WINCE) +# pragma warning (pop) +#endif + } + } + else if (CRCWidth >= CHAR_BIT) + { + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CRCWidth >= CHAR_BIT) ? static_cast(CRCWidth - CHAR_BIT) : 0); + + while (size--) + { + remainder = static_cast((remainder << CHAR_BIT) ^ lookupTable[static_cast((remainder >> SHIFT) ^ *current++)]); + } + } + else + { + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CHAR_BIT >= CRCWidth) ? static_cast(CHAR_BIT - CRCWidth) : 0); + + remainder = static_cast(remainder << SHIFT); + + while (size--) + { + // Note: no need to mask here since remainder is guaranteed to fit in a single byte. + remainder = lookupTable[static_cast(remainder ^ *current++)]; + } + + remainder = static_cast(remainder >> SHIFT); + } + + return remainder; +} + +template +inline CRCType CRC::CalculateRemainderBits(unsigned char byte, crcpp_size numBits, const Parameters & parameters, CRCType remainder) +{ + // Slightly different implementations based on the parameters. The current implementations try to eliminate as much + // computation from the inner loop (looping over each bit) as possible. + if (parameters.reflectInput) + { + CRCType polynomial = CRC::Reflect(parameters.polynomial, CRCWidth); + remainder = static_cast(remainder ^ byte); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < numBits; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & 1) + // remainder = (remainder >> 1) ^ polynomial; + // else + // remainder >>= 1; + remainder = static_cast((remainder >> 1) ^ ((remainder & 1) * polynomial)); +#else + remainder = static_cast((remainder & 1) ? ((remainder >> 1) ^ polynomial) : (remainder >> 1)); +#endif + } + } + else if (CRCWidth >= CHAR_BIT) + { + static crcpp_constexpr CRCType CRC_WIDTH_MINUS_ONE(CRCWidth - CRCType(1)); +#ifndef CRCPP_BRANCHLESS + static crcpp_constexpr CRCType CRC_HIGHEST_BIT_MASK(CRCType(1) << CRC_WIDTH_MINUS_ONE); +#endif + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CRCWidth >= CHAR_BIT) ? static_cast(CRCWidth - CHAR_BIT) : 0); + + remainder = static_cast(remainder ^ (static_cast(byte) << SHIFT)); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < numBits; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & CRC_HIGHEST_BIT_MASK) + // remainder = (remainder << 1) ^ parameters.polynomial; + // else + // remainder <<= 1; + remainder = static_cast((remainder << 1) ^ (((remainder >> CRC_WIDTH_MINUS_ONE) & 1) * parameters.polynomial)); +#else + remainder = static_cast((remainder & CRC_HIGHEST_BIT_MASK) ? ((remainder << 1) ^ parameters.polynomial) : (remainder << 1)); +#endif + } + } + else + { + static crcpp_constexpr CRCType CHAR_BIT_MINUS_ONE(CHAR_BIT - 1); +#ifndef CRCPP_BRANCHLESS + static crcpp_constexpr CRCType CHAR_BIT_HIGHEST_BIT_MASK(CRCType(1) << CHAR_BIT_MINUS_ONE); +#endif + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CHAR_BIT >= CRCWidth) ? static_cast(CHAR_BIT - CRCWidth) : 0); + + CRCType polynomial = static_cast(parameters.polynomial << SHIFT); + remainder = static_cast((remainder << SHIFT) ^ byte); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < numBits; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & CHAR_BIT_HIGHEST_BIT_MASK) + // remainder = (remainder << 1) ^ polynomial; + // else + // remainder <<= 1; + remainder = static_cast((remainder << 1) ^ (((remainder >> CHAR_BIT_MINUS_ONE) & 1) * polynomial)); +#else + remainder = static_cast((remainder & CHAR_BIT_HIGHEST_BIT_MASK) ? ((remainder << 1) ^ polynomial) : (remainder << 1)); +#endif + } + + remainder = static_cast(remainder >> SHIFT); + } + + return remainder; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-4 ITU. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-4 ITU has the following parameters and check value: + - polynomial = 0x3 + - initial value = 0x0 + - final XOR = 0x0 + - reflect input = true + - reflect output = true + - check value = 0x7 + @return CRC-4 ITU parameters +*/ +inline const CRC::Parameters & CRC::CRC_4_ITU() +{ + static const Parameters parameters = { 0x3, 0x0, 0x0, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-5 EPC. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-5 EPC has the following parameters and check value: + - polynomial = 0x09 + - initial value = 0x09 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x00 + @return CRC-5 EPC parameters +*/ +inline const CRC::Parameters & CRC::CRC_5_EPC() +{ + static const Parameters parameters = { 0x09, 0x09, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-5 ITU. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-5 ITU has the following parameters and check value: + - polynomial = 0x15 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0x07 + @return CRC-5 ITU parameters +*/ +inline const CRC::Parameters & CRC::CRC_5_ITU() +{ + static const Parameters parameters = { 0x15, 0x00, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-5 USB. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-5 USB has the following parameters and check value: + - polynomial = 0x05 + - initial value = 0x1F + - final XOR = 0x1F + - reflect input = true + - reflect output = true + - check value = 0x19 + @return CRC-5 USB parameters +*/ +inline const CRC::Parameters & CRC::CRC_5_USB() +{ + static const Parameters parameters = { 0x05, 0x1F, 0x1F, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-6 CDMA2000-A. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-6 CDMA2000-A has the following parameters and check value: + - polynomial = 0x27 + - initial value = 0x3F + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x0D + @return CRC-6 CDMA2000-A parameters +*/ +inline const CRC::Parameters & CRC::CRC_6_CDMA2000A() +{ + static const Parameters parameters = { 0x27, 0x3F, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-6 CDMA2000-B. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-6 CDMA2000-A has the following parameters and check value: + - polynomial = 0x07 + - initial value = 0x3F + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x3B + @return CRC-6 CDMA2000-B parameters +*/ +inline const CRC::Parameters & CRC::CRC_6_CDMA2000B() +{ + static const Parameters parameters = { 0x07, 0x3F, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-6 ITU. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-6 ITU has the following parameters and check value: + - polynomial = 0x03 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0x06 + @return CRC-6 ITU parameters +*/ +inline const CRC::Parameters & CRC::CRC_6_ITU() +{ + static const Parameters parameters = { 0x03, 0x00, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-6 NR. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-6 NR has the following parameters and check value: + - polynomial = 0x21 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x15 + @return CRC-6 NR parameters +*/ +inline const CRC::Parameters & CRC::CRC_6_NR() +{ + static const Parameters parameters = { 0x21, 0x00, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-7 JEDEC. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-7 JEDEC has the following parameters and check value: + - polynomial = 0x09 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x75 + @return CRC-7 JEDEC parameters +*/ +inline const CRC::Parameters & CRC::CRC_7() +{ + static const Parameters parameters = { 0x09, 0x00, 0x00, false, false }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-8 SMBus. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 SMBus has the following parameters and check value: + - polynomial = 0x07 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0xF4 + @return CRC-8 SMBus parameters +*/ +inline const CRC::Parameters & CRC::CRC_8() +{ + static const Parameters parameters = { 0x07, 0x00, 0x00, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-8 EBU (aka CRC-8 AES). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 EBU has the following parameters and check value: + - polynomial = 0x1D + - initial value = 0xFF + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0x97 + @return CRC-8 EBU parameters +*/ +inline const CRC::Parameters & CRC::CRC_8_EBU() +{ + static const Parameters parameters = { 0x1D, 0xFF, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-8 MAXIM (aka CRC-8 DOW-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 MAXIM has the following parameters and check value: + - polynomial = 0x31 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0xA1 + @return CRC-8 MAXIM parameters +*/ +inline const CRC::Parameters & CRC::CRC_8_MAXIM() +{ + static const Parameters parameters = { 0x31, 0x00, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-8 WCDMA. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 WCDMA has the following parameters and check value: + - polynomial = 0x9B + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0x25 + @return CRC-8 WCDMA parameters +*/ +inline const CRC::Parameters & CRC::CRC_8_WCDMA() +{ + static const Parameters parameters = { 0x9B, 0x00, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-8 LTE. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 LTE has the following parameters and check value: + - polynomial = 0x9B + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0xEA + @return CRC-8 LTE parameters +*/ +inline const CRC::Parameters & CRC::CRC_8_LTE() +{ + static const Parameters parameters = { 0x9B, 0x00, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-10 ITU. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-10 ITU has the following parameters and check value: + - polynomial = 0x233 + - initial value = 0x000 + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0x199 + @return CRC-10 ITU parameters +*/ +inline const CRC::Parameters & CRC::CRC_10() +{ + static const Parameters parameters = { 0x233, 0x000, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-10 CDMA2000. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-10 CDMA2000 has the following parameters and check value: + - polynomial = 0x3D9 + - initial value = 0x3FF + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0x233 + @return CRC-10 CDMA2000 parameters +*/ +inline const CRC::Parameters & CRC::CRC_10_CDMA2000() +{ + static const Parameters parameters = { 0x3D9, 0x3FF, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-11 FlexRay. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-11 FlexRay has the following parameters and check value: + - polynomial = 0x385 + - initial value = 0x01A + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0x5A3 + @return CRC-11 FlexRay parameters +*/ +inline const CRC::Parameters & CRC::CRC_11() +{ + static const Parameters parameters = { 0x385, 0x01A, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-11 NR. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-11 NR has the following parameters and check value: + - polynomial = 0x621 + - initial value = 0x000 + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0x5CA + @return CRC-11 NR parameters +*/ +inline const CRC::Parameters & CRC::CRC_11_NR() +{ + static const Parameters parameters = { 0x621, 0x000, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-12 CDMA2000. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-12 CDMA2000 has the following parameters and check value: + - polynomial = 0xF13 + - initial value = 0xFFF + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0xD4D + @return CRC-12 CDMA2000 parameters +*/ +inline const CRC::Parameters & CRC::CRC_12_CDMA2000() +{ + static const Parameters parameters = { 0xF13, 0xFFF, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-12 DECT (aka CRC-12 X-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-12 DECT has the following parameters and check value: + - polynomial = 0x80F + - initial value = 0x000 + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0xF5B + @return CRC-12 DECT parameters +*/ +inline const CRC::Parameters & CRC::CRC_12_DECT() +{ + static const Parameters parameters = { 0x80F, 0x000, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-12 UMTS (aka CRC-12 3GPP). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-12 UMTS has the following parameters and check value: + - polynomial = 0x80F + - initial value = 0x000 + - final XOR = 0x000 + - reflect input = false + - reflect output = true + - check value = 0xDAF + @return CRC-12 UMTS parameters +*/ +inline const CRC::Parameters & CRC::CRC_12_UMTS() +{ + static const Parameters parameters = { 0x80F, 0x000, 0x000, false, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-13 BBC. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-13 BBC has the following parameters and check value: + - polynomial = 0x1CF5 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x04FA + @return CRC-13 BBC parameters +*/ +inline const CRC::Parameters & CRC::CRC_13_BBC() +{ + static const Parameters parameters = { 0x1CF5, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-15 CAN. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-15 CAN has the following parameters and check value: + - polynomial = 0x4599 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x059E + @return CRC-15 CAN parameters +*/ +inline const CRC::Parameters & CRC::CRC_15() +{ + static const Parameters parameters = { 0x4599, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-15 MPT1327. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-15 MPT1327 has the following parameters and check value: + - polynomial = 0x6815 + - initial value = 0x0000 + - final XOR = 0x0001 + - reflect input = false + - reflect output = false + - check value = 0x2566 + @return CRC-15 MPT1327 parameters +*/ +inline const CRC::Parameters & CRC::CRC_15_MPT1327() +{ + static const Parameters parameters = { 0x6815, 0x0000, 0x0001, false, false }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-16 ARC (aka CRC-16 IBM, CRC-16 LHA). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 ARC has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = true + - reflect output = true + - check value = 0xBB3D + @return CRC-16 ARC parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_ARC() +{ + static const Parameters parameters = { 0x8005, 0x0000, 0x0000, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 BUYPASS (aka CRC-16 VERIFONE, CRC-16 UMTS). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 BUYPASS has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0xFEE8 + @return CRC-16 BUYPASS parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_BUYPASS() +{ + static const Parameters parameters = { 0x8005, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 CCITT FALSE. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 CCITT FALSE has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0xFFFF + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x29B1 + @return CRC-16 CCITT FALSE parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_CCITTFALSE() +{ + static const Parameters parameters = { 0x1021, 0xFFFF, 0x0000, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-16 CDMA2000. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 CDMA2000 has the following parameters and check value: + - polynomial = 0xC867 + - initial value = 0xFFFF + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x4C06 + @return CRC-16 CDMA2000 parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_CDMA2000() +{ + static const Parameters parameters = { 0xC867, 0xFFFF, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 CMS. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 CMS has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0xFFFF + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0xAEE7 + @return CRC-16 CMS parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_CMS() +{ + static const Parameters parameters = { 0x8005, 0xFFFF, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 DECT-R (aka CRC-16 R-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 DECT-R has the following parameters and check value: + - polynomial = 0x0589 + - initial value = 0x0000 + - final XOR = 0x0001 + - reflect input = false + - reflect output = false + - check value = 0x007E + @return CRC-16 DECT-R parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_DECTR() +{ + static const Parameters parameters = { 0x0589, 0x0000, 0x0001, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 DECT-X (aka CRC-16 X-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 DECT-X has the following parameters and check value: + - polynomial = 0x0589 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x007F + @return CRC-16 DECT-X parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_DECTX() +{ + static const Parameters parameters = { 0x0589, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 DNP. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 DNP has the following parameters and check value: + - polynomial = 0x3D65 + - initial value = 0x0000 + - final XOR = 0xFFFF + - reflect input = true + - reflect output = true + - check value = 0xEA82 + @return CRC-16 DNP parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_DNP() +{ + static const Parameters parameters = { 0x3D65, 0x0000, 0xFFFF, true, true }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-16 GENIBUS (aka CRC-16 EPC, CRC-16 I-CODE, CRC-16 DARC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 GENIBUS has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0xFFFF + - final XOR = 0xFFFF + - reflect input = false + - reflect output = false + - check value = 0xD64E + @return CRC-16 GENIBUS parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_GENIBUS() +{ + static const Parameters parameters = { 0x1021, 0xFFFF, 0xFFFF, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 KERMIT (aka CRC-16 CCITT, CRC-16 CCITT-TRUE). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 KERMIT has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = true + - reflect output = true + - check value = 0x2189 + @return CRC-16 KERMIT parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_KERMIT() +{ + static const Parameters parameters = { 0x1021, 0x0000, 0x0000, true, true }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-16 MAXIM. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 MAXIM has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0x0000 + - final XOR = 0xFFFF + - reflect input = true + - reflect output = true + - check value = 0x44C2 + @return CRC-16 MAXIM parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_MAXIM() +{ + static const Parameters parameters = { 0x8005, 0x0000, 0xFFFF, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 MODBUS. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 MODBUS has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0xFFFF + - final XOR = 0x0000 + - reflect input = true + - reflect output = true + - check value = 0x4B37 + @return CRC-16 MODBUS parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_MODBUS() +{ + static const Parameters parameters = { 0x8005, 0xFFFF, 0x0000, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 T10-DIF. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 T10-DIF has the following parameters and check value: + - polynomial = 0x8BB7 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0xD0DB + @return CRC-16 T10-DIF parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_T10DIF() +{ + static const Parameters parameters = { 0x8BB7, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 USB. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 USB has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0xFFFF + - final XOR = 0xFFFF + - reflect input = true + - reflect output = true + - check value = 0xB4C8 + @return CRC-16 USB parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_USB() +{ + static const Parameters parameters = { 0x8005, 0xFFFF, 0xFFFF, true, true }; + return parameters; +} + +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-16 X-25 (aka CRC-16 IBM-SDLC, CRC-16 ISO-HDLC, CRC-16 B). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 X-25 has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0xFFFF + - final XOR = 0xFFFF + - reflect input = true + - reflect output = true + - check value = 0x906E + @return CRC-16 X-25 parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_X25() +{ + static const Parameters parameters = { 0x1021, 0xFFFF, 0xFFFF, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 XMODEM (aka CRC-16 ZMODEM, CRC-16 ACORN, CRC-16 LTE). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 XMODEM has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x31C3 + @return CRC-16 XMODEM parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_XMODEM() +{ + static const Parameters parameters = { 0x1021, 0x0000, 0x0000, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-17 CAN. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-17 CAN has the following parameters and check value: + - polynomial = 0x1685B + - initial value = 0x00000 + - final XOR = 0x00000 + - reflect input = false + - reflect output = false + - check value = 0x04F03 + @return CRC-17 CAN parameters +*/ +inline const CRC::Parameters & CRC::CRC_17_CAN() +{ + static const Parameters parameters = { 0x1685B, 0x00000, 0x00000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-21 CAN. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-21 CAN has the following parameters and check value: + - polynomial = 0x102899 + - initial value = 0x000000 + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x0ED841 + @return CRC-21 CAN parameters +*/ +inline const CRC::Parameters & CRC::CRC_21_CAN() +{ + static const Parameters parameters = { 0x102899, 0x000000, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 OPENPGP. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-24 OPENPGP has the following parameters and check value: + - polynomial = 0x864CFB + - initial value = 0xB704CE + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x21CF02 + @return CRC-24 OPENPGP parameters +*/ +inline const CRC::Parameters & CRC::CRC_24() +{ + static const Parameters parameters = { 0x864CFB, 0xB704CE, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 FlexRay-A. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-24 FlexRay-A has the following parameters and check value: + - polynomial = 0x5D6DCB + - initial value = 0xFEDCBA + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x7979BD + @return CRC-24 FlexRay-A parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_FLEXRAYA() +{ + static const Parameters parameters = { 0x5D6DCB, 0xFEDCBA, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 FlexRay-B. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-24 FlexRay-B has the following parameters and check value: + - polynomial = 0x5D6DCB + - initial value = 0xABCDEF + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x1F23B8 + @return CRC-24 FlexRay-B parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_FLEXRAYB() +{ + static const Parameters parameters = { 0x5D6DCB, 0xABCDEF, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 LTE-A/NR-A. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-24 LTE-A has the following parameters and check value: + - polynomial = 0x864CFB + - initial value = 0x000000 + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0xCDE703 + @return CRC-24 LTE-A parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_LTEA() +{ + static const Parameters parameters = { 0x864CFB, 0x000000, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 LTE-B/NR-B. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-24 LTE-B has the following parameters and check value: + - polynomial = 0x800063 + - initial value = 0x000000 + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x23EF52 + @return CRC-24 LTE-B parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_LTEB() +{ + static const Parameters parameters = { 0x800063, 0x000000, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 NR-C. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-24 NR-C has the following parameters and check value: + - polynomial = 0xB2B117 + - initial value = 0x000000 + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0xF48279 + @return CRC-24 NR-C parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_NRC() +{ + static const Parameters parameters = { 0xB2B117, 0x000000, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-30 CDMA. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-30 CDMA has the following parameters and check value: + - polynomial = 0x2030B9C7 + - initial value = 0x3FFFFFFF + - final XOR = 0x00000000 + - reflect input = false + - reflect output = false + - check value = 0x3B3CB540 + @return CRC-30 CDMA parameters +*/ +inline const CRC::Parameters & CRC::CRC_30() +{ + static const Parameters parameters = { 0x2030B9C7, 0x3FFFFFFF, 0x00000000, false, false }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-32 (aka CRC-32 ADCCP, CRC-32 PKZip). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 has the following parameters and check value: + - polynomial = 0x04C11DB7 + - initial value = 0xFFFFFFFF + - final XOR = 0xFFFFFFFF + - reflect input = true + - reflect output = true + - check value = 0xCBF43926 + @return CRC-32 parameters +*/ +inline const CRC::Parameters & CRC::CRC_32() +{ + static const Parameters parameters = { 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-32 BZIP2 (aka CRC-32 AAL5, CRC-32 DECT-B, CRC-32 B-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 BZIP2 has the following parameters and check value: + - polynomial = 0x04C11DB7 + - initial value = 0xFFFFFFFF + - final XOR = 0xFFFFFFFF + - reflect input = false + - reflect output = false + - check value = 0xFC891918 + @return CRC-32 BZIP2 parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_BZIP2() +{ + static const Parameters parameters = { 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-32 C (aka CRC-32 ISCSI, CRC-32 Castagnoli, CRC-32 Interlaken). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 C has the following parameters and check value: + - polynomial = 0x1EDC6F41 + - initial value = 0xFFFFFFFF + - final XOR = 0xFFFFFFFF + - reflect input = true + - reflect output = true + - check value = 0xE3069283 + @return CRC-32 C parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_C() +{ + static const Parameters parameters = { 0x1EDC6F41, 0xFFFFFFFF, 0xFFFFFFFF, true, true }; + return parameters; +} +#endif + +/** + @brief Returns a set of parameters for CRC-32 MPEG-2. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 MPEG-2 has the following parameters and check value: + - polynomial = 0x04C11DB7 + - initial value = 0xFFFFFFFF + - final XOR = 0x00000000 + - reflect input = false + - reflect output = false + - check value = 0x0376E6E7 + @return CRC-32 MPEG-2 parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_MPEG2() +{ + static const Parameters parameters = { 0x04C11DB7, 0xFFFFFFFF, 0x00000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-32 POSIX. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 POSIX has the following parameters and check value: + - polynomial = 0x04C11DB7 + - initial value = 0x00000000 + - final XOR = 0xFFFFFFFF + - reflect input = false + - reflect output = false + - check value = 0x765E7680 + @return CRC-32 POSIX parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_POSIX() +{ + static const Parameters parameters = { 0x04C11DB7, 0x00000000, 0xFFFFFFFF, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-32 Q. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 Q has the following parameters and check value: + - polynomial = 0x814141AB + - initial value = 0x00000000 + - final XOR = 0x00000000 + - reflect input = false + - reflect output = false + - check value = 0x3010BF7F + @return CRC-32 Q parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_Q() +{ + static const Parameters parameters = { 0x814141AB, 0x00000000, 0x00000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-40 GSM. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-40 GSM has the following parameters and check value: + - polynomial = 0x0004820009 + - initial value = 0x0000000000 + - final XOR = 0xFFFFFFFFFF + - reflect input = false + - reflect output = false + - check value = 0xD4164FC646 + @return CRC-40 GSM parameters +*/ +inline const CRC::Parameters & CRC::CRC_40_GSM() +{ + static const Parameters parameters = { 0x0004820009, 0x0000000000, 0xFFFFFFFFFF, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-64 ECMA. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-64 ECMA has the following parameters and check value: + - polynomial = 0x42F0E1EBA9EA3693 + - initial value = 0x0000000000000000 + - final XOR = 0x0000000000000000 + - reflect input = false + - reflect output = false + - check value = 0x6C40DF5F0B497347 + @return CRC-64 ECMA parameters +*/ +inline const CRC::Parameters & CRC::CRC_64() +{ + static const Parameters parameters = { 0x42F0E1EBA9EA3693, 0x0000000000000000, 0x0000000000000000, false, false }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +#ifdef CRCPP_USE_NAMESPACE +} +#endif + +#endif // CRCPP_CRC_H_ diff --git a/Firmware/CoverUI/CoverUI/LED_mux.pio b/Firmware/CoverUI/CoverUI/LED_mux.pio new file mode 100644 index 00000000..699a9737 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/LED_mux.pio @@ -0,0 +1,105 @@ +; +; Copyright (c) 2020 Raspberry Pi (Trading) Ltd. +; +; SPDX-License-Identifier: BSD-3-Clause +; + +/* + +LA1 = SIN = GP 10 = PIN 14 +LA2 = BLANK = GP 11 = PIN 15 +LA3 = LAT = GP 12 = PIN 16 +LA4 = SCLK = GP 13 = PIN 17 + + +Byte to output : 0b00010101 rihht shift 8 bit + +Bitstream pin_SIN: _|---|___|---|___|---|__________________________ +pin_SCLK; __|-|_|-|_|-|_|-|_|-|_|-|_|-|_|-|_______________ +pin_LAT: _________________________________ |--|__________ +pin_BLANK: -|______________________________________________ + + + +31 30 29 28 27 26 25 24 23 22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + x x x x x x x x x x x x x x x x x x x x x x x x x x x x x x x x + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + | 0 | | 0 | | 0 | | 0 | | 0 | | 0 | | 0 | | 0 | + +*/ + + +.define public PIN_SIN 10 +.define public PIN_BLANK 11 +.define public PIN_LAT 12 +.define public PIN_SCLK 13 + +.define public SM_CYCLE 1000000 // State machine cycle frequency + + + + +.program LED_mux + +.side_set 1 opt + + + +.wrap_target + + set PINS 0 +serialout: + out pins, 1 side 0 [1] ; Shift 1 bit from OSR to the first OUT pin + set PINS, 2 + JMP !OSRE serialout + set PINS, 1 [1] + + +.wrap + + +% c-sdk { +#include "hardware/clocks.h" + +void static inline LED_mux_program_init(PIO pio, uint sm, uint offset, uint pin_SIN, uint freq) +{ + + // set pins and prindirs for init + pio_sm_set_pins_with_mask(pio, sm,0x0000,0x3c00 ); + pio_sm_set_pindirs_with_mask(pio, sm, 0x3c01,0x3c01); + + + // init pin for pio + pio_gpio_init(pio, PIN_SIN); + pio_gpio_init(pio, PIN_BLANK); + pio_gpio_init(pio, PIN_LAT); + pio_gpio_init(pio, PIN_SCLK); + + // config properties + pio_sm_config c = LED_mux_program_get_default_config(offset); + + // OUT shifts to right, autopull shift 18 bits + sm_config_set_out_shift(&c, true, true, 18); + + // We are mapping both OUT and side-set to the same pin, because sometimes + // we need to assert user data onto the pin (with OUT) and sometimes + // assert constant values (start/stop bit) + + sm_config_set_out_pins(&c, PIN_SIN, 1); + sm_config_set_sideset_pins(&c, PIN_SCLK); + sm_config_set_set_pins(&c, PIN_LAT,2); + + // We only need TX, so get an 8-deep FIFO! + sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX); + + // define sm cycletime reduce with counter div 125 000 000 is factor 1 + float div = (float)clock_get_hz(clk_sys) / (freq); + sm_config_set_clkdiv(&c, div); + + pio_sm_init(pio, sm, offset, &c); + pio_sm_set_enabled(pio, sm, true); +} + + +%} + diff --git a/Firmware/CoverUI/CoverUI/LEDcontrol.cpp b/Firmware/CoverUI/CoverUI/LEDcontrol.cpp new file mode 100644 index 00000000..e5b75319 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/LEDcontrol.cpp @@ -0,0 +1,138 @@ +/**************************************** + * LEDcontrol.c + * rev 0.0 El 2022-04-04 + * deals with the LEDs on the mowerboard + * **************************************/ + +#include "LEDcontrol.h" + +#define HIGH 1 +#define LOW 0 + +// each LED gets three bits for the current state (see BtnCtrl.h) +uint64_t LED_activity = 0; +uint32_t force_led_on = 0; +uint32_t force_led_off = 0; + +/********************************************* + * + * init LED status array + * + **********************************************/ + +void init_LED_activity() +{ + // Set all LEDs to off + LED_activity = 0; + force_led_on = 0; + force_led_off = 0; +} + +void LED_animation(PIO pioBlock, int statemachine) +{ + LED_activity = 0; + int on_leds = 4; + + for (int led = 0; led < 18; led++) + { + LED_activity ^= (uint64_t)(0b111) << (3 * led); + LEDs_refresh(pioBlock, statemachine); + sleep_ms(15); + } + + for (int led = 0; led < 18; led++) + { + LED_activity ^= (uint64_t)(0b111) << (3 * led); + LEDs_refresh(pioBlock, statemachine); + sleep_ms(15); + } + + LED_activity = 0; + LEDs_refresh(pioBlock, statemachine); +} + +/** + * @brief Transmits the current state of the LEDs to the PIO output. This currently only supports ON, OFF and the blinking state, no dimming + * + * @param fast true, if we're in a "fast" blinking time slot + * @param slow true, if we're in a "slow" blinking time slot + * @param pioBlock the pio block for the state machine + * @param statemachine the statemachine inside the block + */ +void LEDs_refresh(PIO pioBlock, int statemachine) +{ + uint32_t now = to_ms_since_boot(get_absolute_time()); + bool fast = (now / 100) & 1; + bool slow = (now / 500) & 1; + + // Bitmask for the PIO + uint32_t LED_mirror = 0; + for (uint led = 0; led < 18; led++) + { + bool force_on = (force_led_on >> led) & 1; + bool force_off = (force_led_off >> led) & 1; + // fetch the current state of the LED + uint8_t led_state = (LED_activity >> (3 * led)) & 0b111; + if (!force_off) + { + if (led_state == LED_on || force_on) + LED_mirror = LED_mirror | 0b00000000000001000000000000000000; + else if ((led_state == LED_blink_fast) && fast) + LED_mirror = LED_mirror | 0b00000000000001000000000000000000; + else if ((led_state == LED_blink_slow) && slow) + LED_mirror = LED_mirror | 0b00000000000001000000000000000000; + } + LED_mirror = LED_mirror >> 1; + } + + // Write the current state to the state machine + pioBlock->txf[statemachine] = LED_mirror; +} + +void Blink_LED(PIO pioBlock, int statemachine, int led) +{ + + printf("flashing led %d\n", led); + Force_LED_off(led, false); + Force_LED_on(led, true); + for (int i = 0; i < 10; i++) + { + LEDs_refresh(pioBlock, statemachine); + sleep_ms(10); + } + Force_LED_off(led, true); + Force_LED_on(led, false); + for (int i = 0; i < 10; i++) + { + LEDs_refresh(pioBlock, statemachine); + sleep_ms(10); + } + // stop with forced off + Force_LED_off(led, true); + Force_LED_on(led, false); +} + +void Force_LED_off(int led, bool force) +{ + // TODO might allow more than one LED also, but we don't need it + if (force) + { + force_led_off = 1 << led; + } + else + { + force_led_off = 0; + } +} +void Force_LED_on(int led, bool force) +{ + // TODO might allow more than one LED also, but we don't need it + if (force) + { + force_led_on = 1 << led; + } + else + { + force_led_on = 0; + } +} \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUI/LEDcontrol.h b/Firmware/CoverUI/CoverUI/LEDcontrol.h new file mode 100644 index 00000000..204a9266 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/LEDcontrol.h @@ -0,0 +1,38 @@ +#ifndef _LEDcontrol_HEADER_FILE_ +#define _LEDcontrol_HEADER_FILE_ + + +#include + +#include "pico/stdlib.h" +#include "hardware/pio.h" +#include "BttnCtl.h" + + + +/*********************************** + * LEDcontrol.h + * rev 0.0 - El 2022-04-04 + * + * *********************************/ + +// define the Ports +#define out_LED_SIN 10 +#define out_LED_BLANK 11 +#define out_LED_LAT 12 +#define out_LED_CLK 13 + +extern uint64_t LED_activity; + + + + +void init_LED_activity(void); // Init LED array all LEDs off +void LED_animation(PIO pioBlock, int statemachine); +void LEDs_refresh(PIO pioBlock, int statemachine); // refresh pio state machine + void Blink_LED(PIO pioBlock, int statemachine, int led); + void Force_LED_off(int led, bool force); + void Force_LED_on(int led, bool force); + + +#endif // _LEDcontrol_HEADER_FILE_ diff --git a/Firmware/CoverUI/CoverUI/buttonscan.cpp b/Firmware/CoverUI/CoverUI/buttonscan.cpp new file mode 100644 index 00000000..0beff6c6 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/buttonscan.cpp @@ -0,0 +1,172 @@ +/**************************************** + * buttonscan.c + * rev 0.0 El 2022-04-04 + * get button pressed + * **************************************/ + + +#include "buttonscan.h" + + + +/****************************************************************** +* +* init and Hardware, define input, output ans set output to init values +* +*******************************************************************/ + + +void init_button_scan() + { + + + // Init gpios + + // Button output row + gpio_init(out_buttonRow1); + gpio_init(out_buttonRow2); + gpio_init(out_buttonRow3); + gpio_init(out_buttonRow4); + // Button output column + gpio_init(in_buttonColumn1); + gpio_init(in_buttonColumn2); + gpio_init(in_buttonColumn3); + gpio_init(in_buttonColumn4); + + // set port direction + // Button Matrix out + gpio_set_dir(out_buttonRow1, GPIO_OUT); + gpio_set_dir(out_buttonRow2, GPIO_OUT); + gpio_set_dir(out_buttonRow3, GPIO_OUT); + gpio_set_dir(out_buttonRow4, GPIO_OUT); + + // Button Matrix in + gpio_set_dir(in_buttonColumn1, GPIO_IN); + gpio_set_dir(in_buttonColumn2, GPIO_IN); + gpio_set_dir(in_buttonColumn3, GPIO_IN); + gpio_set_dir(in_buttonColumn4, GPIO_IN); + + + // pull down inputs + gpio_pull_down(in_buttonColumn1); + gpio_pull_down(in_buttonColumn2); + gpio_pull_down(in_buttonColumn3); + gpio_pull_down(in_buttonColumn4); + + + + // Init output row level to Low + gpio_put(out_buttonRow1, LOW); + gpio_put(out_buttonRow2, LOW); + gpio_put(out_buttonRow3, LOW); + gpio_put(out_buttonRow4, LOW); + + } + + + + + + + +/****************************************************************** +* +* set the output, read input an check whether button is pressed, return buttonnr +* +*******************************************************************/ + + + +unsigned int bit_getbutton(uint32_t press_timeout, bool &still_pressed) + { + still_pressed = false; + unsigned int retval = 0; + // converts button nr to linear order + // cross reference Hardware position to logical position in one column + unsigned int buttonNr[15]= {0 , 1, 2, 3, 4, 5, 6, 7, 14, 8, 9, 10, 11, 12, 13}; + + + for (int i = out_buttonRow1; i <= out_buttonRow4; i++) + { + retval = 0; + gpio_put(i, HIGH); + sleep_ms(1); + for (int j = in_buttonColumn1; j <= in_buttonColumn4; j++) + { + if (gpio_get(j)) + { + // start time measurement + uint32_t start = to_ms_since_boot(get_absolute_time()); + // wait because button oszillation + sleep_ms(1); + if (gpio_get(j)) + { + retval = buttonNr[(i-15)*4 + (j-18)]; + //wait for button released + while(gpio_get(j) && (press_timeout == 0 || (to_ms_since_boot(get_absolute_time()) - start) < press_timeout)); + if(gpio_get(j)) { + still_pressed = true; + } else { + still_pressed = false; + } + gpio_put(i, LOW); + return(retval); + } + + } + } + + gpio_put(i, LOW); + sleep_ms(1); + } + return(0); + + + // todo reactivate keypressed + + } + + + + + + // check for key pressed, don wait until released returns number of the first key seen pressed + unsigned int keypressed() + { + unsigned int retval = 0; + + // converts button nr to linear order + // cross reference Hardware position to logical position in one column + unsigned int buttonNr[15]= {0 , 1, 2, 3, 4, 5, 6, 7, 14, 8, 9, 10, 11, 12, 13}; + + + for (int i = out_buttonRow1; i <= out_buttonRow4; i++) + { + retval = 0; + gpio_put(i, HIGH); + sleep_ms(5); + for (int j = in_buttonColumn1; j <= in_buttonColumn4; j++) + { + if (gpio_get(j)) + { + // wait 10 ms because button oszillation + sleep_ms(10); + if (gpio_get(j)) + { + retval = buttonNr[(i-15)*4 + (j-18)]; + gpio_put(i, LOW); + return (retval); + } + + } + gpio_put(i, LOW); + } + + + + } + + return(0); + + } + diff --git a/Firmware/CoverUI/CoverUI/buttonscan.h b/Firmware/CoverUI/CoverUI/buttonscan.h new file mode 100644 index 00000000..d98fe200 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/buttonscan.h @@ -0,0 +1,51 @@ +#ifndef _buttonscan_HEADER_FILE_ +#define _buttonscan_HEADER_FILE_ + + +#include "pico/stdlib.h" +#include +#include "hardware/pio.h" + +//include the state machine programs +#include "status_LED.pio.h" +#include "LED_mux.pio.h" +#include "buzzer.pio.h" + + + + +/*********************************** + * buttonscan.h + * rev 0.0 - El 2022-04-04 + * + * *********************************/ + + + +// assign output and input to hardware ports +#define out_buttonRow1 15 +#define out_buttonRow2 16 +#define out_buttonRow3 17 +#define out_buttonRow4 18 + +#define in_buttonColumn1 19 +#define in_buttonColumn2 20 +#define in_buttonColumn3 21 +#define in_buttonColumn4 22 + +#define HIGH 1 +#define LOW 0 + + + + +void init_button_scan(); // Init Hardwareports + +unsigned int bit_getbutton(uint32_t press_timeout, bool &still_pressed); // scan for a pressed button, retrun button nr or 0. + +unsigned int keypressed(); // Check for key pressed + + + + +#endif // _buttonscan_HEADER_FILE_ diff --git a/Firmware/CoverUI/CoverUI/buzzer.pio b/Firmware/CoverUI/CoverUI/buzzer.pio new file mode 100644 index 00000000..cbd2c5b8 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/buzzer.pio @@ -0,0 +1,96 @@ +; +; Copyright (c) 2020 Raspberry Pi (Trading) Ltd. +; +; SPDX-License-Identifier: BSD-3-Clause +; + +; SET pin 0 should be mapped to your LED GPIO + +.program buzzer +;.origin 0 + +.define public Out_PIN 26 +.define public SM_CYCLE 10800 // 4 * resonance frequency = State machine cycle frequency + + +.wrap_target + pull block + out y, 32 + pull block + out ISR, 32 + pull block + lp2: + mov x, ISR + lp1: + set pins, 1 [1] ; Turn LED on + set pins, 0 ;[7] ; Turn LED off + + jmp x-- lp1 ; Delay for (x + 1) cycles, x is a 32 bit number + + mov x, OSR + lp3: + nop [31] + jmp x-- lp3 + jmp y-- lp2 + + mov y, OSR + lp4: + nop [31] + nop [31] + nop [31] + nop [31] + nop [31] + ;nop [31] + ;nop [31] + ;nop [31] + ;nop [31] + ;nop [31] + ;nop [31] + ;nop [31] + jmp y-- lp4 + + + + + + +.wrap + + +% c-sdk { +// this is a raw helper function for use by the user which sets up the GPIO output, and configures the SM to output on a particular pin +#include "hardware/clocks.h" +void static inline buzzer_program_init(PIO pio, uint sm, uint offset, uint pin, uint freq) // frequency in kHz +{ + // Initialise pin clear output enable and output valúe + pio_gpio_init(pio, pin); + + //set consecutive pin direction + pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, true); + + // get pio_sm_config + pio_sm_config c = buzzer_program_get_default_config(offset); + + //calculate divisor to reduce state machine cycle + float div = (float)clock_get_hz(clk_sys) / (freq); + + + sm_config_set_clkdiv(&c, div); + + sm_config_set_set_pins(&c, pin, 1); + pio_sm_init(pio, sm, offset, &c); +} + +static inline void buzzer_program_put_words(PIO pio, uint sm, uint32_t repeat, uint32_t duration, uint32_t gap) +{ + pio_sm_put_blocking(pio, sm, repeat-1); + pio_sm_put_blocking(pio, sm, duration); + pio_sm_put_blocking(pio, sm, gap); + + +} + + + + +%} diff --git a/Firmware/CoverUI/CoverUI/main.cpp b/Firmware/CoverUI/CoverUI/main.cpp new file mode 100644 index 00000000..4cb7b9f2 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/main.cpp @@ -0,0 +1,401 @@ +// control to print out serial information in debug state via usb serial +#define _serial_debug_ + +#include + +#include "pico/stdlib.h" +#include "hardware/pio.h" +#include "hardware/clocks.h" +#include "pico/multicore.h" +#include "hardware/uart.h" +#include "hardware/irq.h" + +#include +#include "COBS.h" +#include "CRC.h" + +#include + +#include "LEDcontrol.h" +#include "statemachine.h" +#include "buttonscan.h" +#include "BttnCtl.h" + +#define bufflen 1000 + +#define FIRMWARE_VERSION 200 +// V 2.00 v. 11.10.2022 new protocol implementation for less messages on the bus + +// buzzer ontime in ms +#define shortbeep 50 + +// 2cnd UART +#define UART_1 uart1 +#define BAUD_RATE 115200 +#define UART_TX_PIN 4 +#define UART_RX_PIN 5 + +// write & read pointer serial interrupt buffer +static uint write = 0; + +// serial buffer +static uint8_t buffer_serial[bufflen]; +// count values in COBS-Buffer +static uint8_t decoded_buffer[bufflen]; +// buffer for encoded output messages +static uint8_t out_buf[bufflen]; + +COBS cobs; + +// defintion PIO-block and uses statemachines +PIO pio_Block1 = pio0; +PIO pio_Block2 = pio1; +int sm_blink; // Statemachine onboard LED blinking +int sm_LEDmux; // Statemachine control LEDSs +int sm_buzz; // Statemachine control Buzzer + +auto_init_mutex(mx1); + +/**************************************************************************************************** + * + * interface to the statemachine, control buzzer + * + *****************************************************************************************************/ + +void Buzzer_set(uint32_t anz, uint32_t timeON, uint32_t timeOFF) +{ + mutex_enter_blocking(&mx1); + buzzer_program_put_words(pio_Block2, sm_buzz, anz, timeON * buzzer_SM_CYCLE / 4000, timeOFF); + mutex_exit(&mx1); +} + +/**************************************************************************************************** + * + * sendMessage send the command strucutre via COBS and serial Port and wait for reply + * + *****************************************************************************************************/ + +void sendMessage(void *message, size_t size) +{ + mutex_enter_blocking(&mx1); + + // packages need to be at least 1 byte of type, 1 byte of data and 2 bytes of CRC + if (size < 4) + { + mutex_exit(&mx1); + return; + } + + uint8_t *data_pointer = (uint8_t *)message; + uint16_t *crc_pointer = (uint16_t *)(data_pointer + (size - 2)); + + // calculate the CRC + *crc_pointer = CRC::Calculate(message, size - 2, CRC::CRC_16_CCITTFALSE()); + // structure is filled and CRC calculated, so print out, what should be encoded + +#ifdef _serial_debug_ + printf("\nprint struct before encoding %d byte : ", (int)size); + uint8_t *temp = data_pointer; + for (int i = 0; i < size; i++) + { + printf("0x%02x , ", *temp); + temp++; + } +#endif + + // encode message + + size_t encoded_size = cobs.encode((uint8_t *)message, size, out_buf); + out_buf[encoded_size] = 0; + encoded_size++; + +#ifdef _serial_debug_ + printf("\nencoded message %d byte : ", (int)encoded_size); + for (uint i = 0; i < encoded_size; i++) + { + printf("0x%02x , ", out_buf[i]); + } +#endif + + for (uint i = 0; i < encoded_size; i++) + { + uart_putc(UART_1, out_buf[i]); + } + mutex_exit(&mx1); +} + +/**************************************************************************************************** + * + * PacketReceived() there is a serial stream in the buffer + * decode it with cobs, calc crc and decode into the messagestruct + *****************************************************************************************************/ + +void PacketReceived() +{ + size_t data_size = cobs.decode(buffer_serial, write - 1, (uint8_t *)decoded_buffer); + + // calculate the CRC only if we have at least three bytes (two CRC, one data) + if (data_size < 3) + return; + + uint16_t calc_crc = CRC::Calculate(decoded_buffer, data_size - 2, CRC::CRC_16_CCITTFALSE()); + + // struct mower_com *struct_CRC = (struct mower_com *) encoded_buffer; + + if (decoded_buffer[0] == Get_Version && data_size == sizeof(struct msg_get_version)) + { + struct msg_get_version *message = (struct msg_get_version *)decoded_buffer; + if (message->crc == calc_crc) + { + // valid get_version request, send reply + struct msg_get_version reply; + reply.type = Get_Version; + reply.version = FIRMWARE_VERSION; + sendMessage(&reply, sizeof(reply)); + } + } + else if (decoded_buffer[0] == Set_Buzzer && data_size == sizeof(struct msg_set_buzzer)) + { + struct msg_set_buzzer *message = (struct msg_set_buzzer *)decoded_buffer; + if (message->crc == calc_crc) + { + // valid set_buzzer request + Buzzer_set(message->repeat, message->on_time, message->off_time); + } + } + else if (decoded_buffer[0] == Set_LEDs && data_size == sizeof(struct msg_set_leds)) + { + struct msg_set_leds *message = (struct msg_set_leds *)decoded_buffer; + if (message->crc == calc_crc) + { + // valid set_leds request + printf("Got valid setled call\n"); + mutex_enter_blocking(&mx1); + LED_activity = message->leds; + LEDs_refresh(pio_Block1, sm_LEDmux); + mutex_exit(&mx1); + } + else + { + printf("Got setled call with crc error\n"); + } + } + else + { + printf("some invalid packet\n"); + } + +#ifdef _serial_debug_ + printf("packet received with %d bytes : ", (int)data_size); + uint8_t *temp = decoded_buffer; + for (int i = 0; i < data_size; i++) + { + printf("0x%02x , ", *temp); + temp++; + } + printf("\n"); +#endif +} + +/**************************************************************************************************** + * + * getDataFromBuffer() read bytes from serial interrupt controlled buffer and couple a string with endcode "00" + * out to buffer_serial + *****************************************************************************************************/ + +void getDataFromBuffer() +{ + while (uart_is_readable(UART_1)) + { + u_int8_t readbyte = uart_getc(UART_1); + buffer_serial[write] = readbyte; + write++; + if (write >= bufflen) + { + // buffer is full, but no separator. Reset + write = 0; + return; + } + if (readbyte == 0) + { + // we have found the packet marker, notify the other core + PacketReceived(); + write = 0; + return; + } + } +} + +int getLedForButton(int button) +{ + if (button >= 4 && button <= 6) + return 13 - (button - 4); + if (button >= 8 && button <= 14) + return 10 - (button - 8); + return 0; +} + +void core1() +{ + printf("Core 1 started\n"); + while (true) + { + // Scan Buttons + bool pressed = false; + unsigned int button = 0; + int pressed_count = 0; + bool allow_hold; + + button = bit_getbutton(1, pressed); + + // Buttons where we allow the hold. The reason for this is, that we have an indicator LED for these buttons. + allow_hold = (button >= 4 && button <= 6) || (button >= 8 && button <= 14); + + if (button && allow_hold) + { + int led = getLedForButton(button); + // force led off + mutex_enter_blocking(&mx1); + Force_LED_off(led, true); + mutex_exit(&mx1); + do + { + // allow hold, wait for user to hold + button = bit_getbutton(1000, pressed); + if (pressed) + { + // user indeed held the button + pressed_count++; + // if button is still held, we flash and rety + for (int i = 0; i < pressed_count; i++) + { + mutex_enter_blocking(&mx1); + Blink_LED(pio_Block1, sm_LEDmux, led); + mutex_exit(&mx1); + } + } + } while (pressed && button != 0 && pressed_count < 2); + + // yes that's a duplicate but we want to wait before releasing the LED, so that's intended. + if (button && pressed) + { + // we're still holding, wait for the button to release. We don't care about the result here. + bool tmp; + bit_getbutton(0, tmp); + } + + mutex_enter_blocking(&mx1); + Force_LED_off(led, false); + mutex_exit(&mx1); + } + else + { + if (button && pressed) + { + // we're still holding, wait for the button to release. We don't care about the result here. + bool tmp; + bit_getbutton(0, tmp); + } + } + + if (button > 0) + { + + struct msg_event_button button_msg; + button_msg.type = Get_Button; + button_msg.button_id = button; + button_msg.press_duration = pressed_count; + + sendMessage(&button_msg, sizeof(button_msg)); + + // confirm pressed button with buzzer. + // TODO: on rapid button presses, the FIFO gets full and therefore this call is blocking for a long time. + mutex_enter_blocking(&mx1); + buzzer_program_put_words(pio_Block2, sm_buzz, 1, shortbeep * buzzer_SM_CYCLE / 4000, 40); + mutex_exit(&mx1); + + printf("\n\rsend Button Nr.: %d with count %d", button, pressed_count); + } + } +} + +int main(void) +{ + uint32_t last_led_update = 0; + + stdio_init_all(); + + // setup the second UART 1 + uart_init(UART_1, BAUD_RATE); + gpio_set_function(UART_TX_PIN, GPIO_FUNC_UART); + gpio_set_function(UART_RX_PIN, GPIO_FUNC_UART); + // no flow control + uart_set_hw_flow(UART_1, false, false); + uart_set_fifo_enabled(UART_1, true); + + init_button_scan(); // Init hardware for button matix + // init_LED_driver(); + + float ver = (float)FIRMWARE_VERSION / 100.0; + printf("\n\n\n\rMower Button-LED-Control Version %2.2f\n", ver); + + // initialise state machines + sm_blink = init_run_StateMachine_blink(pio_Block1); // on board led alive blink + sm_LEDmux = init_run_StateMachine_LED_mux(pio_Block1); // LED multiplexer + sm_buzz = init_run_StateMachine_buzzer(pio_Block2); // Beeper control + + mutex_enter_blocking(&mx1); + init_LED_activity(); // init LED statusmatrix all LEDs off + LEDs_refresh(pio_Block1, sm_LEDmux); // LED-state to Hardware + mutex_exit(&mx1); + sleep_ms(1000); + + // LED blink to say it's alive + LED_animation(pio_Block1, sm_LEDmux); + + // buzzer say hello + Buzzer_set(1, 50, 40); + + // Check for button ins permanently pressed e.g. while mounting + + u_int32_t n = keypressed(); + while (n > 0) + { + mutex_enter_blocking(&mx1); + LED_activity = -1; + LEDs_refresh(pio_Block1, sm_LEDmux); + mutex_exit(&mx1); + Buzzer_set(n, 250, 100); + + sleep_ms(10000); + n = keypressed(); + } + + mutex_enter_blocking(&mx1); + LED_activity = 0; + LEDs_refresh(pio_Block1, sm_LEDmux); + mutex_exit(&mx1); + + // enable other core for button detection + multicore_reset_core1(); + multicore_launch_core1(core1); + + printf("\n\n waiting for commands or button press"); + + while (true) + { + + getDataFromBuffer(); + + uint32_t now = to_ms_since_boot(get_absolute_time()); + + // Update the LEDs and their blinking states + if (now - last_led_update > 10) + { + mutex_enter_blocking(&mx1); + LEDs_refresh(pio_Block1, sm_LEDmux); + mutex_exit(&mx1); + last_led_update = now; + } + } +} diff --git a/Firmware/CoverUI/CoverUI/pico_sdk_import.cmake b/Firmware/CoverUI/CoverUI/pico_sdk_import.cmake new file mode 100644 index 00000000..f63ee3f8 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/pico_sdk_import.cmake @@ -0,0 +1,64 @@ +# This is a copy of /external/pico_sdk_import.cmake + +# This can be dropped into an external project to help locate this SDK +# It should be include()ed prior to project() + +# todo document + +if (DEFINED ENV{PICO_SDK_PATH} AND (NOT PICO_SDK_PATH)) + set(PICO_SDK_PATH $ENV{PICO_SDK_PATH}) + message("Using PICO_SDK_PATH from environment ('${PICO_SDK_PATH}')") +endif () + +if (DEFINED ENV{PICO_SDK_FETCH_FROM_GIT} AND (NOT PICO_SDK_FETCH_FROM_GIT)) + set(PICO_SDK_FETCH_FROM_GIT $ENV{PICO_SDK_FETCH_FROM_GIT}) + message("Using PICO_SDK_FETCH_FROM_GIT from environment ('${PICO_SDK_FETCH_FROM_GIT}')") +endif () + +if (DEFINED ENV{PICO_SDK_FETCH_FROM_GIT_PATH} AND (NOT PICO_SDK_FETCH_FROM_GIT_PATH)) + set(PICO_SDK_FETCH_FROM_GIT_PATH $ENV{PICO_SDK_FETCH_FROM_GIT_PATH}) + message("Using PICO_SDK_FETCH_FROM_GIT_PATH from environment ('${PICO_SDK_FETCH_FROM_GIT_PATH}')") +endif () + +set(PICO_SDK_PATH "${PICO_SDK_PATH}" CACHE PATH "Path to the PICO SDK") +set(PICO_SDK_FETCH_FROM_GIT "${PICO_SDK_FETCH_FROM_GIT}" CACHE BOOL "Set to ON to fetch copy of PICO SDK from git if not otherwise locatable") +set(PICO_SDK_FETCH_FROM_GIT_PATH "${PICO_SDK_FETCH_FROM_GIT_PATH}" CACHE FILEPATH "location to download SDK") + +if (NOT PICO_SDK_PATH) + if (PICO_SDK_FETCH_FROM_GIT) + include(FetchContent) + set(FETCHCONTENT_BASE_DIR_SAVE ${FETCHCONTENT_BASE_DIR}) + if (PICO_SDK_FETCH_FROM_GIT_PATH) + get_filename_component(FETCHCONTENT_BASE_DIR "${PICO_SDK_FETCH_FROM_GIT_PATH}" REALPATH BASE_DIR "${CMAKE_SOURCE_DIR}") + endif () + FetchContent_Declare( + pico_sdk + GIT_REPOSITORY https://github.com/raspberrypi/pico-sdk + GIT_TAG master + ) + if (NOT pico_sdk) + message("Downloading PICO SDK") + FetchContent_Populate(pico_sdk) + set(PICO_SDK_PATH ${pico_sdk_SOURCE_DIR}) + endif () + set(FETCHCONTENT_BASE_DIR ${FETCHCONTENT_BASE_DIR_SAVE}) + else () + message(FATAL_ERROR + "PICO SDK location was not specified. Please set PICO_SDK_PATH or set PICO_SDK_FETCH_FROM_GIT to on to fetch from git." + ) + endif () +endif () + +get_filename_component(PICO_SDK_PATH "${PICO_SDK_PATH}" REALPATH BASE_DIR "${CMAKE_BINARY_DIR}") +if (NOT EXISTS ${PICO_SDK_PATH}) + message(FATAL_ERROR "Directory '${PICO_SDK_PATH}' not found") +endif () + +set(PICO_SDK_INIT_CMAKE_FILE ${PICO_SDK_PATH}/pico_sdk_init.cmake) +if (NOT EXISTS ${PICO_SDK_INIT_CMAKE_FILE}) + message(FATAL_ERROR "Directory '${PICO_SDK_PATH}' does not appear to contain the PICO SDK") +endif () + +set(PICO_SDK_PATH ${PICO_SDK_PATH} CACHE PATH "Path to the PICO SDK" FORCE) + +include(${PICO_SDK_INIT_CMAKE_FILE}) diff --git a/Firmware/CoverUI/CoverUI/statemachine.cpp b/Firmware/CoverUI/CoverUI/statemachine.cpp new file mode 100644 index 00000000..8dd660a2 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/statemachine.cpp @@ -0,0 +1,190 @@ +/**************************************** + * statemachine.c + * rev 0.0 El 2022-04-04 + * interface to the state machines + * **************************************/ + +#define _serial_debug_ + + +#include "statemachine.h" + + + + +/****************************************************************** +* +* init and run statemachine flashing on boar LED asl alive signal +* +*******************************************************************/ + + +int init_run_StateMachine_blink(PIO pio_Block) + { + int retval = -1; + u_int freq = 1; // Blinkrate 1 Hz + + #ifdef _serial_debug_ + printf("\n\nStarting statemachine Blink"); + #endif + + // check whether programm can be loaded + if (pio_can_add_program(pio_Block, &blink_program)) + { + #ifdef _serial_debug_ + printf("\nPIO Program can be loadet"); + #endif + } + else + { + #ifdef _serial_debug_ + printf("\nPIO *** ERROR *** ont enought space to load Program "); + #endif + return(retval); + } + + // get the offset = startadress in 32 bit Area for assembler code + uint offset = pio_add_program(pio_Block, &blink_program); + + // find a free state machine + uint sm = pio_claim_unused_sm(pio_Block, true); + #ifdef _serial_debug_ + printf("\nfound free Statemachine : %d Startadress Programm : %d",sm,offset); + #endif + + // run helperfunktion to load program into memory + blink_program_init(pio_Block, sm, offset, LED_PIN, 125000); + + // run statemachine + pio_sm_set_enabled(pio_Block, sm, true); + + // Blink forever + #ifdef _serial_debug_ + printf("\nStatemachine blink running on pin: %d with %d Hz", LED_PIN, freq); + #endif + + + + // push frequency to statmachine + pio_Block->txf[sm] = clock_get_hz(clk_sys) / (freq); + pio_Block->txf[sm] = clock_get_hz(clk_sys) / (256 * freq); + + return (sm); + } + + + +/****************************************************************** +* +* init and run statemachine to control the buzzer +* +*******************************************************************/ + + + + int init_run_StateMachine_buzzer(PIO pio_Block) + { + int retval = -1; + + + #ifdef _serial_debug_ + printf("\n\nStarting statemachine buzzer"); + #endif + // check whether programm can bel loaded + if (pio_can_add_program(pio_Block, &buzzer_program)) + { + #ifdef _serial_debug_ + printf("\nPIO Program can be loadet"); + #endif + } + + else + { + #ifdef _serial_debug_ + printf("\nPIO *** ERROR *** ont enought space to load Program "); + #endif + return(retval); + } + + // get the offset = startadress in 32 bit Area for assembler code + uint offset = pio_add_program(pio_Block, &buzzer_program); + + // find a free state machine + uint sm = pio_claim_unused_sm(pio_Block, true); + #ifdef _serial_debug_ + printf("\nfound free Statemachine : %d Startadress Programm : %d",sm,offset); + #endif + + // run helperfunktion to load program into memory + buzzer_program_init(pio_Block, sm, offset, buzzer_Out_PIN ,buzzer_SM_CYCLE ); + + // run statemachine + pio_sm_set_enabled(pio_Block, sm, true); + + // Blink forever + #ifdef _serial_debug_ + printf("\nStatemachine buzzer running on pin: %d with %d Hz", buzzer_Out_PIN, buzzer_SM_CYCLE); + #endif + + + + + + return (sm); + } + + + + +/****************************************************************** +* +* init and run statemachine LED Mux +* +*******************************************************************/ + + + + + +int init_run_StateMachine_LED_mux(PIO pio_Block) + { + + int retval = -1; + #ifdef _serial_debug_ + printf("\n\nStarting statemachine LED-MUX"); + #endif + // check whether programm can bel loaded + if (pio_can_add_program(pio_Block, &LED_mux_program)) + { + #ifdef _serial_debug_ + printf("\nPIO Program can be loadet"); + #endif + } + + else + { + #ifdef _serial_debug_ + printf("\nPIO *** ERROR *** ont enought space to load Program "); + #endif + return(retval); + } + + // get the offset = startadress in 32 bit Area for assembler code + uint offset = pio_add_program(pio_Block, &LED_mux_program); + + // find a free state machine + uint sm = pio_claim_unused_sm(pio_Block, true); + + #ifdef _serial_debug_ + printf("\nfound free Statemachine : %d Startadress Programm : %d",sm,offset); + + printf("\nStatemachine LED-mux running with %d Hz",PIN_SIN, SM_CYCLE); + #endif + + // init and start statemachine + LED_mux_program_init(pio_Block, sm, offset, PIN_SIN, SM_CYCLE); + return(sm); + + } + + diff --git a/Firmware/CoverUI/CoverUI/statemachine.h b/Firmware/CoverUI/CoverUI/statemachine.h new file mode 100644 index 00000000..1dbf24d5 --- /dev/null +++ b/Firmware/CoverUI/CoverUI/statemachine.h @@ -0,0 +1,38 @@ +#ifndef _statemachine_HEADER_FILE_ +#define _statemachine_HEADER_FILE_ + + +#include "pico/stdlib.h" +#include +#include "hardware/pio.h" + +//include the state machine programs +#include "status_LED.pio.h" +#include "LED_mux.pio.h" +#include "buzzer.pio.h" + + +#define LED_PIN 25 // Port onboard led + +/*********************************** + * statemachine.h + * rev 0.0 - El 2022-04-04 + * + * *********************************/ + + + + + +int init_run_StateMachine_blink(PIO pio_Block); //run statemachine live blink onboard LED + +int init_run_StateMachine_buzzer(PIO pio_Block); //run statemachine waiting for commands to buzz + +int init_run_StateMachine_LED_mux(PIO pio_Block); //run statemachine waiting for commands to light the leds + + + + + + +#endif // _statemachine_HEADER_FILE_ diff --git a/Firmware/CoverUI/CoverUI/status_LED.pio b/Firmware/CoverUI/CoverUI/status_LED.pio new file mode 100644 index 00000000..0c4e511a --- /dev/null +++ b/Firmware/CoverUI/CoverUI/status_LED.pio @@ -0,0 +1,58 @@ +; +; Copyright (c) 2020 Raspberry Pi (Trading) Ltd. +; +; SPDX-License-Identifier: BSD-3-Clause +; + +; SET pin 0 should be mapped to your LED GPIO + +.program blink +;.origin 0 + + + +.define public SM_CYCLE 1000000 +.define public Out_PIN 25 + + + + pull block + out y, 32 + pull block + out ISR, 32 +.wrap_target + mov x, ISR + set pins, 1 ; Turn LED on +lp1: + jmp x-- lp1 ; Delay for (x + 1) cycles, x is a 32 bit number + mov x, Y + set pins, 0 ; Turn LED off +lp2: + jmp x-- lp2 ; Delay for the same number of cycles again +.wrap ; Blink forever! + + +% c-sdk { +// this is a raw helper function for use by the user which sets up the GPIO output, and configures the SM to output on a particular pin +#include "hardware/clocks.h" +void static inline blink_program_init(PIO pio, uint sm, uint offset, uint pin, uint freq) // frequency in kHz +{ + // Initialise pin clear output enable and output valúe + pio_gpio_init(pio, pin); + + //set consecutive pin direction + pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, true); + + // get pio_sm_config + pio_sm_config c = blink_program_get_default_config(offset); + + //calculate divisor to reduce state machine cycle + float div = (float)clock_get_hz(clk_sys) / (freq*1000); + + + sm_config_set_clkdiv(&c, div); + + sm_config_set_set_pins(&c, pin, 1); + pio_sm_init(pio, sm, offset, &c); +} +%} diff --git a/Firmware/CoverUI/CoverUITest/.gitignore b/Firmware/CoverUI/CoverUITest/.gitignore new file mode 100644 index 00000000..83abcf34 --- /dev/null +++ b/Firmware/CoverUI/CoverUITest/.gitignore @@ -0,0 +1,3 @@ +build/ +.idea/ +cmake-build-debug/ diff --git a/Firmware/CoverUI/CoverUITest/.vscode/launch.json b/Firmware/CoverUI/CoverUITest/.vscode/launch.json new file mode 100644 index 00000000..83c73d54 --- /dev/null +++ b/Firmware/CoverUI/CoverUITest/.vscode/launch.json @@ -0,0 +1,17 @@ +{ + // Verwendet IntelliSense zum Ermitteln möglicher Attribute. + // Zeigen Sie auf vorhandene Attribute, um die zugehörigen Beschreibungen anzuzeigen. + // Weitere Informationen finden Sie unter https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + { + + "name": "C/C++: g++ build and debug active file", + "type": "cppdbg", + "request": "launch", + "program": "${fileDirname}/${fileBasenameNoExtension}", + "cwd": "${workspaceFolder}", + "args": ["/dev/ttyUSB0"] + } + ] +} \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUITest/.vscode/tasks.json b/Firmware/CoverUI/CoverUITest/.vscode/tasks.json new file mode 100644 index 00000000..06ef6b51 --- /dev/null +++ b/Firmware/CoverUI/CoverUITest/.vscode/tasks.json @@ -0,0 +1,28 @@ +{ + "tasks": [ + { + "type": "cppbuild", + "label": "C/C++: g++ Aktive Datei kompilieren", + "command": "/usr/bin/g++", + "args": [ + "-fdiagnostics-color=always", + "-g", + "${file}", + "-o", + "${fileDirname}/${fileBasenameNoExtension}" + ], + "options": { + "cwd": "${fileDirname}" + }, + "problemMatcher": [ + "$gcc" + ], + "group": { + "kind": "build", + "isDefault": true + }, + "detail": "Vom Debugger generierte Aufgabe." + } + ], + "version": "2.0.0" +} \ No newline at end of file diff --git a/Firmware/CoverUI/CoverUITest/BttnCtl.h b/Firmware/CoverUI/CoverUITest/BttnCtl.h new file mode 100644 index 00000000..85552c00 --- /dev/null +++ b/Firmware/CoverUI/CoverUITest/BttnCtl.h @@ -0,0 +1,112 @@ +#ifndef _BttnCtl_HEADER_FILE_ +#define _BttnCtl_HEADER_FILE_ + + + +/************************************************************** + * BttnCtl.h + * rev 0.0 - El 2022-04-06 + * ENUMs for communication between Mainboard and Buttonboard + * + * *************************************************************/ + +// Protocol Header Info +enum TYPE +{ + Get_Version = 0xB0, + Set_Buzzer = 0xB1, + Set_LEDs = 0xB2, + Get_Button = 0xB3 +}; + + +// Function definiton for the 18 LEDS +enum LED_id +{ + MOWER_LIFTED = 0, + POOR_GPS = 1, + BATTERY_LOW = 2, + CHARGING = 3, + LED5 = 4, + LED6 = 5, + LED7 = 6, + LED8 = 7, + LED9 = 8, + LED10 = 9, + LED11 = 10, + LED12 = 11, + LED13 = 12, + LED14 = 13, + LED15 = 14, + LED16 = 15, + LED17 = 16, + LED18 = 17, + LED_BAR = 18, + LED_BAR1 = 19 +}; + +enum LED_state { + LED_off = 0b000, + LED_blink_slow = 0b101, + LED_blink_fast = 0b110, + LED_on = 0b111 +}; +#pragma pack(push, 1) +struct msg_get_version +{ + uint8_t type; // command type + uint8_t reserved; // padding + uint16_t version; + uint16_t crc; // CRC 16 +} __attribute__((packed)); +#pragma pack(pop) + + +#pragma pack(push, 1) +struct msg_set_buzzer +{ + uint8_t type; // command type + uint8_t repeat; // Repeat X times + uint8_t on_time; // Signal on time + uint8_t off_time; // Signal off time + uint16_t crc; // CRC 16 +} __attribute__((packed)); +#pragma pack(pop) + + +/** + * @brief Use this to update the LED matrix + * Each LED gets three bits with the following meaning: + * 0b000 = Off + * 0b001 = reserved for future use + * 0b010 = reserved for future use + * 0b011 = reserved for future use + * 0b100 = reserved for future use + * 0b101 = On slow blink + * 0b110 = On fast blink + * 0b111 = On + */ +#pragma pack(push, 1) +struct msg_set_leds +{ + uint8_t type; // command type + uint8_t reserved; // padding + uint64_t leds; + uint16_t crc; // CRC 16 +} __attribute__((packed)); +#pragma pack(pop) + +#pragma pack(push, 1) +struct msg_event_button +{ + uint8_t type; // command type + uint16_t button_id; + uint8_t press_duration; + uint16_t crc; // CRC 16 +} __attribute__((packed)); +#pragma pack(pop) + + + + +#endif // _BttnCtl_HEADER_FILE_ diff --git a/Firmware/CoverUI/CoverUITest/CMakeLists.txt b/Firmware/CoverUI/CoverUITest/CMakeLists.txt new file mode 100644 index 00000000..b242f127 --- /dev/null +++ b/Firmware/CoverUI/CoverUITest/CMakeLists.txt @@ -0,0 +1,6 @@ +cmake_minimum_required(VERSION 3.21) +project(UIButtonTest) + +set(CMAKE_CXX_STANDARD 14) + +add_executable(UIButtonTest main.cpp) diff --git a/Firmware/CoverUI/CoverUITest/COBS.h b/Firmware/CoverUI/CoverUITest/COBS.h new file mode 100644 index 00000000..c0b979d7 --- /dev/null +++ b/Firmware/CoverUI/CoverUITest/COBS.h @@ -0,0 +1,127 @@ +// +// Copyright (c) 2011 Christopher Baker +// Copyright (c) 2011 Jacques Fortier +// +// SPDX-License-Identifier: MIT +// + + +#pragma once + + + +/// \brief A Consistent Overhead Byte Stuffing (COBS) Encoder. +/// +/// Consistent Overhead Byte Stuffing (COBS) is an encoding that removes all 0 +/// bytes from arbitrary binary data. The encoded data consists only of bytes +/// with values from 0x01 to 0xFF. This is useful for preparing data for +/// transmission over a serial link (RS-232 or RS-485 for example), as the 0 +/// byte can be used to unambiguously indicate packet boundaries. COBS also has +/// the advantage of adding very little overhead (at least 1 byte, plus up to an +/// additional byte per 254 bytes of data). For messages smaller than 254 bytes, +/// the overhead is constant. +/// +/// \sa http://conferences.sigcomm.org/sigcomm/1997/papers/p062.pdf +/// \sa http://en.wikipedia.org/wiki/Consistent_Overhead_Byte_Stuffing +/// \sa https://github.com/jacquesf/COBS-Consistent-Overhead-Byte-Stuffing +/// \sa http://www.jacquesf.com/2011/03/consistent-overhead-byte-stuffing +class COBS +{ +public: + /// \brief Encode a byte buffer with the COBS encoder. + /// \param buffer A pointer to the unencoded buffer to encode. + /// \param size The number of bytes in the \p buffer. + /// \param encodedBuffer The buffer for the encoded bytes. + /// \returns The number of bytes written to the \p encodedBuffer. + /// \warning The encodedBuffer must have at least getEncodedBufferSize() + /// allocated. + static size_t encode(const uint8_t* buffer, + size_t size, + uint8_t* encodedBuffer) + { + size_t read_index = 0; + size_t write_index = 1; + size_t code_index = 0; + uint8_t code = 1; + + while (read_index < size) + { + if (buffer[read_index] == 0) + { + encodedBuffer[code_index] = code; + code = 1; + code_index = write_index++; + read_index++; + } + else + { + encodedBuffer[write_index++] = buffer[read_index++]; + code++; + + if (code == 0xFF) + { + encodedBuffer[code_index] = code; + code = 1; + code_index = write_index++; + } + } + } + + encodedBuffer[code_index] = code; + + return write_index; + } + + + /// \brief Decode a COBS-encoded buffer. + /// \param encodedBuffer A pointer to the \p encodedBuffer to decode. + /// \param size The number of bytes in the \p encodedBuffer. + /// \param decodedBuffer The target buffer for the decoded bytes. + /// \returns The number of bytes written to the \p decodedBuffer. + /// \warning decodedBuffer must have a minimum capacity of size. + static size_t decode(const uint8_t* encodedBuffer, + size_t size, + uint8_t* decodedBuffer) + { + if (size == 0) + return 0; + + size_t read_index = 0; + size_t write_index = 0; + uint8_t code = 0; + uint8_t i = 0; + + while (read_index < size) + { + code = encodedBuffer[read_index]; + + if (read_index + code > size && code != 1) + { + return 0; + } + + read_index++; + + for (i = 1; i < code; i++) + { + decodedBuffer[write_index++] = encodedBuffer[read_index++]; + } + + if (code != 0xFF && read_index != size) + { + decodedBuffer[write_index++] = '\0'; + } + } + + return write_index; + } + + /// \brief Get the maximum encoded buffer size for an unencoded buffer size. + /// \param unencodedBufferSize The size of the buffer to be encoded. + /// \returns the maximum size of the required encoded buffer. + static size_t getEncodedBufferSize(size_t unencodedBufferSize) + { + return unencodedBufferSize + unencodedBufferSize / 254 + 1; + } + +}; diff --git a/Firmware/CoverUI/CoverUITest/CRC.h b/Firmware/CoverUI/CoverUITest/CRC.h new file mode 100644 index 00000000..e20db354 --- /dev/null +++ b/Firmware/CoverUI/CoverUITest/CRC.h @@ -0,0 +1,2066 @@ +/** + @file CRC.h + @author Daniel Bahr + @version 1.1.0.0 + @copyright + @parblock + CRC++ + Copyright (c) 2021, Daniel Bahr + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * Neither the name of CRC++ nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + @endparblock +*/ + +/* + CRC++ can be configured by setting various #defines before #including this header file: + + #define crcpp_uint8 - Specifies the type used to store CRCs that have a width of 8 bits or less. + This type is not used in CRC calculations. Defaults to ::std::uint8_t. + #define crcpp_uint16 - Specifies the type used to store CRCs that have a width between 9 and 16 bits (inclusive). + This type is not used in CRC calculations. Defaults to ::std::uint16_t. + #define crcpp_uint32 - Specifies the type used to store CRCs that have a width between 17 and 32 bits (inclusive). + This type is not used in CRC calculations. Defaults to ::std::uint32_t. + #define crcpp_uint64 - Specifies the type used to store CRCs that have a width between 33 and 64 bits (inclusive). + This type is not used in CRC calculations. Defaults to ::std::uint64_t. + #define crcpp_size - This type is used for loop iteration and function signatures only. Defaults to ::std::size_t. + #define CRCPP_USE_NAMESPACE - Define to place all CRC++ code within the ::CRCPP namespace. + #define CRCPP_BRANCHLESS - Define to enable a branchless CRC implementation. The branchless implementation uses a single integer + multiplication in the bit-by-bit calculation instead of a small conditional. The branchless implementation + may be faster on processor architectures which support single-instruction integer multiplication. + #define CRCPP_USE_CPP11 - Define to enables C++11 features (move semantics, constexpr, static_assert, etc.). + #define CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS - Define to include definitions for little-used CRCs. +*/ + +#ifndef CRCPP_CRC_H_ +#define CRCPP_CRC_H_ + +#include // Includes CHAR_BIT +#ifdef CRCPP_USE_CPP11 +#include // Includes ::std::size_t +#include // Includes ::std::uint8_t, ::std::uint16_t, ::std::uint32_t, ::std::uint64_t +#else +#include // Includes size_t +#include // Includes uint8_t, uint16_t, uint32_t, uint64_t +#endif +#include // Includes ::std::numeric_limits +#include // Includes ::std::move + +#ifndef crcpp_uint8 +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned 8-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint8 ::std::uint8_t +# else + /// @brief Unsigned 8-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint8 uint8_t +# endif +#endif + +#ifndef crcpp_uint16 +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned 16-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint16 ::std::uint16_t +# else + /// @brief Unsigned 16-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint16 uint16_t +# endif +#endif + +#ifndef crcpp_uint32 +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned 32-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint32 ::std::uint32_t +# else + /// @brief Unsigned 32-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint32 uint32_t +# endif +#endif + +#ifndef crcpp_uint64 +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned 64-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint64 ::std::uint64_t +# else + /// @brief Unsigned 64-bit integer definition, used primarily for parameter definitions. +# define crcpp_uint64 uint64_t +# endif +#endif + +#ifndef crcpp_size +# ifdef CRCPP_USE_CPP11 + /// @brief Unsigned size definition, used for specifying data sizes. +# define crcpp_size ::std::size_t +# else + /// @brief Unsigned size definition, used for specifying data sizes. +# define crcpp_size size_t +# endif +#endif + +#ifdef CRCPP_USE_CPP11 + /// @brief Compile-time expression definition. +# define crcpp_constexpr constexpr +#else + /// @brief Compile-time expression definition. +# define crcpp_constexpr const +#endif + +#ifdef CRCPP_USE_NAMESPACE +namespace CRCPP +{ +#endif + +/** + @brief Static class for computing CRCs. + @note This class supports computation of full and multi-part CRCs, using a bit-by-bit algorithm or a + byte-by-byte lookup table. The CRCs are calculated using as many optimizations as is reasonable. + If compiling with C++11, the constexpr keyword is used liberally so that many calculations are + performed at compile-time instead of at runtime. +*/ +class CRC +{ +public: + // Forward declaration + template + struct Table; + + /** + @brief CRC parameters. + */ + template + struct Parameters + { + CRCType polynomial; ///< CRC polynomial + CRCType initialValue; ///< Initial CRC value + CRCType finalXOR; ///< Value to XOR with the final CRC + bool reflectInput; ///< true to reflect all input bytes + bool reflectOutput; ///< true to reflect the output CRC (reflection occurs before the final XOR) + + Table MakeTable() const; + }; + + /** + @brief CRC lookup table. After construction, the CRC parameters are fixed. + @note A CRC table can be used for multiple CRC calculations. + */ + template + struct Table + { + // Constructors are intentionally NOT marked explicit. + Table(const Parameters & parameters); + +#ifdef CRCPP_USE_CPP11 + Table(Parameters && parameters); +#endif + + const Parameters & GetParameters() const; + + const CRCType * GetTable() const; + + CRCType operator[](unsigned char index) const; + + private: + void InitTable(); + + Parameters parameters; ///< CRC parameters used to construct the table + CRCType table[1 << CHAR_BIT]; ///< CRC lookup table + }; + + // The number of bits in CRCType must be at least as large as CRCWidth. + // CRCType must be an unsigned integer type or a custom type with operator overloads. + template + static CRCType Calculate(const void * data, crcpp_size size, const Parameters & parameters); + + template + static CRCType Calculate(const void * data, crcpp_size size, const Parameters & parameters, CRCType crc); + + template + static CRCType Calculate(const void * data, crcpp_size size, const Table & lookupTable); + + template + static CRCType Calculate(const void * data, crcpp_size size, const Table & lookupTable, CRCType crc); + + template + static CRCType CalculateBits(const void * data, crcpp_size size, const Parameters & parameters); + + template + static CRCType CalculateBits(const void * data, crcpp_size size, const Parameters & parameters, CRCType crc); + + template + static CRCType CalculateBits(const void * data, crcpp_size size, const Table & lookupTable); + + template + static CRCType CalculateBits(const void * data, crcpp_size size, const Table & lookupTable, CRCType crc); + + // Common CRCs up to 64 bits. + // Note: Check values are the computed CRCs when given an ASCII input of "123456789" (without null terminator) +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters< crcpp_uint8, 4> & CRC_4_ITU(); + static const Parameters< crcpp_uint8, 5> & CRC_5_EPC(); + static const Parameters< crcpp_uint8, 5> & CRC_5_ITU(); + static const Parameters< crcpp_uint8, 5> & CRC_5_USB(); + static const Parameters< crcpp_uint8, 6> & CRC_6_CDMA2000A(); + static const Parameters< crcpp_uint8, 6> & CRC_6_CDMA2000B(); + static const Parameters< crcpp_uint8, 6> & CRC_6_ITU(); + static const Parameters< crcpp_uint8, 6> & CRC_6_NR(); + static const Parameters< crcpp_uint8, 7> & CRC_7(); +#endif + static const Parameters< crcpp_uint8, 8> & CRC_8(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters< crcpp_uint8, 8> & CRC_8_EBU(); + static const Parameters< crcpp_uint8, 8> & CRC_8_MAXIM(); + static const Parameters< crcpp_uint8, 8> & CRC_8_WCDMA(); + static const Parameters< crcpp_uint8, 8> & CRC_8_LTE(); + static const Parameters & CRC_10(); + static const Parameters & CRC_10_CDMA2000(); + static const Parameters & CRC_11(); + static const Parameters & CRC_11_NR(); + static const Parameters & CRC_12_CDMA2000(); + static const Parameters & CRC_12_DECT(); + static const Parameters & CRC_12_UMTS(); + static const Parameters & CRC_13_BBC(); + static const Parameters & CRC_15(); + static const Parameters & CRC_15_MPT1327(); +#endif + static const Parameters & CRC_16_ARC(); + static const Parameters & CRC_16_BUYPASS(); + static const Parameters & CRC_16_CCITTFALSE(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_16_CDMA2000(); + static const Parameters & CRC_16_CMS(); + static const Parameters & CRC_16_DECTR(); + static const Parameters & CRC_16_DECTX(); + static const Parameters & CRC_16_DNP(); +#endif + static const Parameters & CRC_16_GENIBUS(); + static const Parameters & CRC_16_KERMIT(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_16_MAXIM(); + static const Parameters & CRC_16_MODBUS(); + static const Parameters & CRC_16_T10DIF(); + static const Parameters & CRC_16_USB(); +#endif + static const Parameters & CRC_16_X25(); + static const Parameters & CRC_16_XMODEM(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_17_CAN(); + static const Parameters & CRC_21_CAN(); + static const Parameters & CRC_24(); + static const Parameters & CRC_24_FLEXRAYA(); + static const Parameters & CRC_24_FLEXRAYB(); + static const Parameters & CRC_24_LTEA(); + static const Parameters & CRC_24_LTEB(); + static const Parameters & CRC_24_NRC(); + static const Parameters & CRC_30(); +#endif + static const Parameters & CRC_32(); + static const Parameters & CRC_32_BZIP2(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_32_C(); +#endif + static const Parameters & CRC_32_MPEG2(); + static const Parameters & CRC_32_POSIX(); +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + static const Parameters & CRC_32_Q(); + static const Parameters & CRC_40_GSM(); + static const Parameters & CRC_64(); +#endif + +#ifdef CRCPP_USE_CPP11 + CRC() = delete; + CRC(const CRC & other) = delete; + CRC & operator=(const CRC & other) = delete; + CRC(CRC && other) = delete; + CRC & operator=(CRC && other) = delete; +#endif + +private: +#ifndef CRCPP_USE_CPP11 + CRC(); + CRC(const CRC & other); + CRC & operator=(const CRC & other); +#endif + + template + static IntegerType Reflect(IntegerType value, crcpp_uint16 numBits); + + template + static CRCType Finalize(CRCType remainder, CRCType finalXOR, bool reflectOutput); + + template + static CRCType UndoFinalize(CRCType remainder, CRCType finalXOR, bool reflectOutput); + + template + static CRCType CalculateRemainder(const void * data, crcpp_size size, const Parameters & parameters, CRCType remainder); + + template + static CRCType CalculateRemainder(const void * data, crcpp_size size, const Table & lookupTable, CRCType remainder); + + template + static CRCType CalculateRemainderBits(unsigned char byte, crcpp_size numBits, const Parameters & parameters, CRCType remainder); +}; + +/** + @brief Returns a CRC lookup table construct using these CRC parameters. + @note This function primarily exists to allow use of the auto keyword instead of instantiating + a table directly, since template parameters are not inferred in constructors. + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC lookup table +*/ +template +inline CRC::Table CRC::Parameters::MakeTable() const +{ + // This should take advantage of RVO and optimize out the copy. + return CRC::Table(*this); +} + +/** + @brief Constructs a CRC table from a set of CRC parameters + @param[in] params CRC parameters + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC +*/ +template +inline CRC::Table::Table(const Parameters & params) : + parameters(params) +{ + InitTable(); +} + +#ifdef CRCPP_USE_CPP11 +/** + @brief Constructs a CRC table from a set of CRC parameters + @param[in] params CRC parameters + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC +*/ +template +inline CRC::Table::Table(Parameters && params) : + parameters(::std::move(params)) +{ + InitTable(); +} +#endif + +/** + @brief Gets the CRC parameters used to construct the CRC table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC parameters +*/ +template +inline const CRC::Parameters & CRC::Table::GetParameters() const +{ + return parameters; +} + +/** + @brief Gets the CRC table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC table +*/ +template +inline const CRCType * CRC::Table::GetTable() const +{ + return table; +} + +/** + @brief Gets an entry in the CRC table + @param[in] index Index into the CRC table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC table entry +*/ +template +inline CRCType CRC::Table::operator[](unsigned char index) const +{ + return table[index]; +} + +/** + @brief Initializes a CRC table. + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC +*/ +template +inline void CRC::Table::InitTable() +{ + // For masking off the bits for the CRC (in the event that the number of bits in CRCType is larger than CRCWidth) + static crcpp_constexpr CRCType BIT_MASK((CRCType(1) << (CRCWidth - CRCType(1))) | + ((CRCType(1) << (CRCWidth - CRCType(1))) - CRCType(1))); + + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CHAR_BIT >= CRCWidth) ? static_cast(CHAR_BIT - CRCWidth) : 0); + + CRCType crc; + unsigned char byte = 0; + + // Loop over each dividend (each possible number storable in an unsigned char) + do + { + crc = CRC::CalculateRemainder(&byte, sizeof(byte), parameters, CRCType(0)); + + // This mask might not be necessary; all unit tests pass with this line commented out, + // but that might just be a coincidence based on the CRC parameters used for testing. + // In any case, this is harmless to leave in and only adds a single machine instruction per loop iteration. + crc &= BIT_MASK; + + if (!parameters.reflectInput && CRCWidth < CHAR_BIT) + { + // Undo the special operation at the end of the CalculateRemainder() + // function for non-reflected CRCs < CHAR_BIT. + crc = static_cast(crc << SHIFT); + } + + table[byte] = crc; + } + while (++byte); +} + +/** + @brief Computes a CRC. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bytes + @param[in] parameters CRC parameters + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::Calculate(const void * data, crcpp_size size, const Parameters & parameters) +{ + CRCType remainder = CalculateRemainder(data, size, parameters, parameters.initialValue); + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} +/** + @brief Appends additional data to a previous CRC calculation. + @note This function can be used to compute multi-part CRCs. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bytes + @param[in] parameters CRC parameters + @param[in] crc CRC from a previous calculation + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::Calculate(const void * data, crcpp_size size, const Parameters & parameters, CRCType crc) +{ + CRCType remainder = UndoFinalize(crc, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); + + remainder = CalculateRemainder(data, size, parameters, remainder); + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Computes a CRC via a lookup table. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bytes + @param[in] lookupTable CRC lookup table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::Calculate(const void * data, crcpp_size size, const Table & lookupTable) +{ + const Parameters & parameters = lookupTable.GetParameters(); + + CRCType remainder = CalculateRemainder(data, size, lookupTable, parameters.initialValue); + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Appends additional data to a previous CRC calculation using a lookup table. + @note This function can be used to compute multi-part CRCs. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bytes + @param[in] lookupTable CRC lookup table + @param[in] crc CRC from a previous calculation + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::Calculate(const void * data, crcpp_size size, const Table & lookupTable, CRCType crc) +{ + const Parameters & parameters = lookupTable.GetParameters(); + + CRCType remainder = UndoFinalize(crc, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); + + remainder = CalculateRemainder(data, size, lookupTable, remainder); + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Computes a CRC. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bits + @param[in] parameters CRC parameters + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::CalculateBits(const void * data, crcpp_size size, const Parameters & parameters) +{ + CRCType remainder = parameters.initialValue; + + // Calculate the remainder on a whole number of bytes first, then call + // a special-case function for the remaining bits. + crcpp_size wholeNumberOfBytes = size / CHAR_BIT; + if (wholeNumberOfBytes > 0) + { + remainder = CalculateRemainder(data, wholeNumberOfBytes, parameters, remainder); + } + + crcpp_size remainingNumberOfBits = size % CHAR_BIT; + if (remainingNumberOfBits != 0) + { + unsigned char lastByte = *(reinterpret_cast(data) + wholeNumberOfBytes); + remainder = CalculateRemainderBits(lastByte, remainingNumberOfBits, parameters, remainder); + } + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} +/** + @brief Appends additional data to a previous CRC calculation. + @note This function can be used to compute multi-part CRCs. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bits + @param[in] parameters CRC parameters + @param[in] crc CRC from a previous calculation + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::CalculateBits(const void * data, crcpp_size size, const Parameters & parameters, CRCType crc) +{ + CRCType remainder = UndoFinalize(crc, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); + + // Calculate the remainder on a whole number of bytes first, then call + // a special-case function for the remaining bits. + crcpp_size wholeNumberOfBytes = size / CHAR_BIT; + if (wholeNumberOfBytes > 0) + { + remainder = CalculateRemainder(data, wholeNumberOfBytes, parameters, parameters.initialValue); + } + + crcpp_size remainingNumberOfBits = size % CHAR_BIT; + if (remainingNumberOfBits != 0) + { + unsigned char lastByte = *(reinterpret_cast(data) + wholeNumberOfBytes); + remainder = CalculateRemainderBits(lastByte, remainingNumberOfBits, parameters, remainder); + } + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Computes a CRC via a lookup table. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bits + @param[in] lookupTable CRC lookup table + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::CalculateBits(const void * data, crcpp_size size, const Table & lookupTable) +{ + const Parameters & parameters = lookupTable.GetParameters(); + + CRCType remainder = parameters.initialValue; + + // Calculate the remainder on a whole number of bytes first, then call + // a special-case function for the remaining bits. + crcpp_size wholeNumberOfBytes = size / CHAR_BIT; + if (wholeNumberOfBytes > 0) + { + remainder = CalculateRemainder(data, wholeNumberOfBytes, lookupTable, remainder); + } + + crcpp_size remainingNumberOfBits = size % CHAR_BIT; + if (remainingNumberOfBits != 0) + { + unsigned char lastByte = *(reinterpret_cast(data) + wholeNumberOfBytes); + remainder = CalculateRemainderBits(lastByte, remainingNumberOfBits, parameters, remainder); + } + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Appends additional data to a previous CRC calculation using a lookup table. + @note This function can be used to compute multi-part CRCs. + @param[in] data Data over which CRC will be computed + @param[in] size Size of the data, in bits + @param[in] lookupTable CRC lookup table + @param[in] crc CRC from a previous calculation + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC +*/ +template +inline CRCType CRC::CalculateBits(const void * data, crcpp_size size, const Table & lookupTable, CRCType crc) +{ + const Parameters & parameters = lookupTable.GetParameters(); + + CRCType remainder = UndoFinalize(crc, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); + + // Calculate the remainder on a whole number of bytes first, then call + // a special-case function for the remaining bits. + crcpp_size wholeNumberOfBytes = size / CHAR_BIT; + if (wholeNumberOfBytes > 0) + { + remainder = CalculateRemainder(data, wholeNumberOfBytes, lookupTable, parameters.initialValue); + } + + crcpp_size remainingNumberOfBits = size % CHAR_BIT; + if (remainingNumberOfBits > 0) + { + unsigned char lastByte = *(reinterpret_cast(data) + wholeNumberOfBytes); + remainder = CalculateRemainderBits(lastByte, remainingNumberOfBits, parameters, remainder); + } + + // No need to mask the remainder here; the mask will be applied in the Finalize() function. + + return Finalize(remainder, parameters.finalXOR, parameters.reflectInput != parameters.reflectOutput); +} + +/** + @brief Reflects (i.e. reverses the bits within) an integer value. + @param[in] value Value to reflect + @param[in] numBits Number of bits in the integer which will be reflected + @tparam IntegerType Integer type of the value being reflected + @return Reflected value +*/ +template +inline IntegerType CRC::Reflect(IntegerType value, crcpp_uint16 numBits) +{ + IntegerType reversedValue(0); + + for (crcpp_uint16 i = 0; i < numBits; ++i) + { + reversedValue = static_cast((reversedValue << 1) | (value & 1)); + value = static_cast(value >> 1); + } + + return reversedValue; +} + +/** + @brief Computes the final reflection and XOR of a CRC remainder. + @param[in] remainder CRC remainder to reflect and XOR + @param[in] finalXOR Final value to XOR with the remainder + @param[in] reflectOutput true to reflect each byte of the remainder before the XOR + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return Final CRC +*/ +template +inline CRCType CRC::Finalize(CRCType remainder, CRCType finalXOR, bool reflectOutput) +{ + // For masking off the bits for the CRC (in the event that the number of bits in CRCType is larger than CRCWidth) + static crcpp_constexpr CRCType BIT_MASK = (CRCType(1) << (CRCWidth - CRCType(1))) | + ((CRCType(1) << (CRCWidth - CRCType(1))) - CRCType(1)); + + if (reflectOutput) + { + remainder = Reflect(remainder, CRCWidth); + } + + return (remainder ^ finalXOR) & BIT_MASK; +} + +/** + @brief Undoes the process of computing the final reflection and XOR of a CRC remainder. + @note This function allows for computation of multi-part CRCs + @note Calling UndoFinalize() followed by Finalize() (or vice versa) will always return the original remainder value: + + CRCType x = ...; + CRCType y = Finalize(x, finalXOR, reflectOutput); + CRCType z = UndoFinalize(y, finalXOR, reflectOutput); + assert(x == z); + + @param[in] crc Reflected and XORed CRC + @param[in] finalXOR Final value XORed with the remainder + @param[in] reflectOutput true if the remainder is to be reflected + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return Un-finalized CRC remainder +*/ +template +inline CRCType CRC::UndoFinalize(CRCType crc, CRCType finalXOR, bool reflectOutput) +{ + // For masking off the bits for the CRC (in the event that the number of bits in CRCType is larger than CRCWidth) + static crcpp_constexpr CRCType BIT_MASK = (CRCType(1) << (CRCWidth - CRCType(1))) | + ((CRCType(1) << (CRCWidth - CRCType(1))) - CRCType(1)); + + crc = (crc & BIT_MASK) ^ finalXOR; + + if (reflectOutput) + { + crc = Reflect(crc, CRCWidth); + } + + return crc; +} + +/** + @brief Computes a CRC remainder. + @param[in] data Data over which the remainder will be computed + @param[in] size Size of the data, in bytes + @param[in] parameters CRC parameters + @param[in] remainder Running CRC remainder. Can be an initial value or the result of a previous CRC remainder calculation. + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC remainder +*/ +template +inline CRCType CRC::CalculateRemainder(const void * data, crcpp_size size, const Parameters & parameters, CRCType remainder) +{ +#ifdef CRCPP_USE_CPP11 + // This static_assert is put here because this function will always be compiled in no matter what + // the template parameters are and whether or not a table lookup or bit-by-bit algorithm is used. + static_assert(::std::numeric_limits::digits >= CRCWidth, "CRCType is too small to contain a CRC of width CRCWidth."); +#else + // Catching this compile-time error is very important. Sadly, the compiler error will be very cryptic, but it's + // better than nothing. + enum { static_assert_failed_CRCType_is_too_small_to_contain_a_CRC_of_width_CRCWidth = 1 / (::std::numeric_limits::digits >= CRCWidth ? 1 : 0) }; +#endif + + const unsigned char * current = reinterpret_cast(data); + + // Slightly different implementations based on the parameters. The current implementations try to eliminate as much + // computation from the inner loop (looping over each bit) as possible. + if (parameters.reflectInput) + { + CRCType polynomial = CRC::Reflect(parameters.polynomial, CRCWidth); + while (size--) + { + remainder = static_cast(remainder ^ *current++); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < CHAR_BIT; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & 1) + // remainder = (remainder >> 1) ^ polynomial; + // else + // remainder >>= 1; + remainder = static_cast((remainder >> 1) ^ ((remainder & 1) * polynomial)); +#else + remainder = static_cast((remainder & 1) ? ((remainder >> 1) ^ polynomial) : (remainder >> 1)); +#endif + } + } + } + else if (CRCWidth >= CHAR_BIT) + { + static crcpp_constexpr CRCType CRC_WIDTH_MINUS_ONE(CRCWidth - CRCType(1)); +#ifndef CRCPP_BRANCHLESS + static crcpp_constexpr CRCType CRC_HIGHEST_BIT_MASK(CRCType(1) << CRC_WIDTH_MINUS_ONE); +#endif + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CRCWidth >= CHAR_BIT) ? static_cast(CRCWidth - CHAR_BIT) : 0); + + while (size--) + { + remainder = static_cast(remainder ^ (static_cast(*current++) << SHIFT)); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < CHAR_BIT; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & CRC_HIGHEST_BIT_MASK) + // remainder = (remainder << 1) ^ parameters.polynomial; + // else + // remainder <<= 1; + remainder = static_cast((remainder << 1) ^ (((remainder >> CRC_WIDTH_MINUS_ONE) & 1) * parameters.polynomial)); +#else + remainder = static_cast((remainder & CRC_HIGHEST_BIT_MASK) ? ((remainder << 1) ^ parameters.polynomial) : (remainder << 1)); +#endif + } + } + } + else + { + static crcpp_constexpr CRCType CHAR_BIT_MINUS_ONE(CHAR_BIT - 1); +#ifndef CRCPP_BRANCHLESS + static crcpp_constexpr CRCType CHAR_BIT_HIGHEST_BIT_MASK(CRCType(1) << CHAR_BIT_MINUS_ONE); +#endif + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CHAR_BIT >= CRCWidth) ? static_cast(CHAR_BIT - CRCWidth) : 0); + + CRCType polynomial = static_cast(parameters.polynomial << SHIFT); + remainder = static_cast(remainder << SHIFT); + + while (size--) + { + remainder = static_cast(remainder ^ *current++); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < CHAR_BIT; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & CHAR_BIT_HIGHEST_BIT_MASK) + // remainder = (remainder << 1) ^ polynomial; + // else + // remainder <<= 1; + remainder = static_cast((remainder << 1) ^ (((remainder >> CHAR_BIT_MINUS_ONE) & 1) * polynomial)); +#else + remainder = static_cast((remainder & CHAR_BIT_HIGHEST_BIT_MASK) ? ((remainder << 1) ^ polynomial) : (remainder << 1)); +#endif + } + } + + remainder = static_cast(remainder >> SHIFT); + } + + return remainder; +} + +/** + @brief Computes a CRC remainder using lookup table. + @param[in] data Data over which the remainder will be computed + @param[in] size Size of the data, in bytes + @param[in] lookupTable CRC lookup table + @param[in] remainder Running CRC remainder. Can be an initial value or the result of a previous CRC remainder calculation. + @tparam CRCType Integer type for storing the CRC result + @tparam CRCWidth Number of bits in the CRC + @return CRC remainder +*/ +template +inline CRCType CRC::CalculateRemainder(const void * data, crcpp_size size, const Table & lookupTable, CRCType remainder) +{ + const unsigned char * current = reinterpret_cast(data); + + if (lookupTable.GetParameters().reflectInput) + { + while (size--) + { +#if defined(WIN32) || defined(_WIN32) || defined(WINCE) + // Disable warning about data loss when doing (remainder >> CHAR_BIT) when + // remainder is one byte long. The algorithm is still correct in this case, + // though it's possible that one additional machine instruction will be executed. +# pragma warning (push) +# pragma warning (disable : 4333) +#endif + remainder = static_cast((remainder >> CHAR_BIT) ^ lookupTable[static_cast(remainder ^ *current++)]); +#if defined(WIN32) || defined(_WIN32) || defined(WINCE) +# pragma warning (pop) +#endif + } + } + else if (CRCWidth >= CHAR_BIT) + { + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CRCWidth >= CHAR_BIT) ? static_cast(CRCWidth - CHAR_BIT) : 0); + + while (size--) + { + remainder = static_cast((remainder << CHAR_BIT) ^ lookupTable[static_cast((remainder >> SHIFT) ^ *current++)]); + } + } + else + { + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CHAR_BIT >= CRCWidth) ? static_cast(CHAR_BIT - CRCWidth) : 0); + + remainder = static_cast(remainder << SHIFT); + + while (size--) + { + // Note: no need to mask here since remainder is guaranteed to fit in a single byte. + remainder = lookupTable[static_cast(remainder ^ *current++)]; + } + + remainder = static_cast(remainder >> SHIFT); + } + + return remainder; +} + +template +inline CRCType CRC::CalculateRemainderBits(unsigned char byte, crcpp_size numBits, const Parameters & parameters, CRCType remainder) +{ + // Slightly different implementations based on the parameters. The current implementations try to eliminate as much + // computation from the inner loop (looping over each bit) as possible. + if (parameters.reflectInput) + { + CRCType polynomial = CRC::Reflect(parameters.polynomial, CRCWidth); + remainder = static_cast(remainder ^ byte); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < numBits; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & 1) + // remainder = (remainder >> 1) ^ polynomial; + // else + // remainder >>= 1; + remainder = static_cast((remainder >> 1) ^ ((remainder & 1) * polynomial)); +#else + remainder = static_cast((remainder & 1) ? ((remainder >> 1) ^ polynomial) : (remainder >> 1)); +#endif + } + } + else if (CRCWidth >= CHAR_BIT) + { + static crcpp_constexpr CRCType CRC_WIDTH_MINUS_ONE(CRCWidth - CRCType(1)); +#ifndef CRCPP_BRANCHLESS + static crcpp_constexpr CRCType CRC_HIGHEST_BIT_MASK(CRCType(1) << CRC_WIDTH_MINUS_ONE); +#endif + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CRCWidth >= CHAR_BIT) ? static_cast(CRCWidth - CHAR_BIT) : 0); + + remainder = static_cast(remainder ^ (static_cast(byte) << SHIFT)); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < numBits; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & CRC_HIGHEST_BIT_MASK) + // remainder = (remainder << 1) ^ parameters.polynomial; + // else + // remainder <<= 1; + remainder = static_cast((remainder << 1) ^ (((remainder >> CRC_WIDTH_MINUS_ONE) & 1) * parameters.polynomial)); +#else + remainder = static_cast((remainder & CRC_HIGHEST_BIT_MASK) ? ((remainder << 1) ^ parameters.polynomial) : (remainder << 1)); +#endif + } + } + else + { + static crcpp_constexpr CRCType CHAR_BIT_MINUS_ONE(CHAR_BIT - 1); +#ifndef CRCPP_BRANCHLESS + static crcpp_constexpr CRCType CHAR_BIT_HIGHEST_BIT_MASK(CRCType(1) << CHAR_BIT_MINUS_ONE); +#endif + // The conditional expression is used to avoid a -Wshift-count-overflow warning. + static crcpp_constexpr CRCType SHIFT((CHAR_BIT >= CRCWidth) ? static_cast(CHAR_BIT - CRCWidth) : 0); + + CRCType polynomial = static_cast(parameters.polynomial << SHIFT); + remainder = static_cast((remainder << SHIFT) ^ byte); + + // An optimizing compiler might choose to unroll this loop. + for (crcpp_size i = 0; i < numBits; ++i) + { +#ifdef CRCPP_BRANCHLESS + // Clever way to avoid a branch at the expense of a multiplication. This code is equivalent to the following: + // if (remainder & CHAR_BIT_HIGHEST_BIT_MASK) + // remainder = (remainder << 1) ^ polynomial; + // else + // remainder <<= 1; + remainder = static_cast((remainder << 1) ^ (((remainder >> CHAR_BIT_MINUS_ONE) & 1) * polynomial)); +#else + remainder = static_cast((remainder & CHAR_BIT_HIGHEST_BIT_MASK) ? ((remainder << 1) ^ polynomial) : (remainder << 1)); +#endif + } + + remainder = static_cast(remainder >> SHIFT); + } + + return remainder; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-4 ITU. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-4 ITU has the following parameters and check value: + - polynomial = 0x3 + - initial value = 0x0 + - final XOR = 0x0 + - reflect input = true + - reflect output = true + - check value = 0x7 + @return CRC-4 ITU parameters +*/ +inline const CRC::Parameters & CRC::CRC_4_ITU() +{ + static const Parameters parameters = { 0x3, 0x0, 0x0, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-5 EPC. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-5 EPC has the following parameters and check value: + - polynomial = 0x09 + - initial value = 0x09 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x00 + @return CRC-5 EPC parameters +*/ +inline const CRC::Parameters & CRC::CRC_5_EPC() +{ + static const Parameters parameters = { 0x09, 0x09, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-5 ITU. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-5 ITU has the following parameters and check value: + - polynomial = 0x15 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0x07 + @return CRC-5 ITU parameters +*/ +inline const CRC::Parameters & CRC::CRC_5_ITU() +{ + static const Parameters parameters = { 0x15, 0x00, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-5 USB. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-5 USB has the following parameters and check value: + - polynomial = 0x05 + - initial value = 0x1F + - final XOR = 0x1F + - reflect input = true + - reflect output = true + - check value = 0x19 + @return CRC-5 USB parameters +*/ +inline const CRC::Parameters & CRC::CRC_5_USB() +{ + static const Parameters parameters = { 0x05, 0x1F, 0x1F, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-6 CDMA2000-A. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-6 CDMA2000-A has the following parameters and check value: + - polynomial = 0x27 + - initial value = 0x3F + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x0D + @return CRC-6 CDMA2000-A parameters +*/ +inline const CRC::Parameters & CRC::CRC_6_CDMA2000A() +{ + static const Parameters parameters = { 0x27, 0x3F, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-6 CDMA2000-B. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-6 CDMA2000-A has the following parameters and check value: + - polynomial = 0x07 + - initial value = 0x3F + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x3B + @return CRC-6 CDMA2000-B parameters +*/ +inline const CRC::Parameters & CRC::CRC_6_CDMA2000B() +{ + static const Parameters parameters = { 0x07, 0x3F, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-6 ITU. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-6 ITU has the following parameters and check value: + - polynomial = 0x03 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0x06 + @return CRC-6 ITU parameters +*/ +inline const CRC::Parameters & CRC::CRC_6_ITU() +{ + static const Parameters parameters = { 0x03, 0x00, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-6 NR. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-6 NR has the following parameters and check value: + - polynomial = 0x21 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x15 + @return CRC-6 NR parameters +*/ +inline const CRC::Parameters & CRC::CRC_6_NR() +{ + static const Parameters parameters = { 0x21, 0x00, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-7 JEDEC. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-7 JEDEC has the following parameters and check value: + - polynomial = 0x09 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0x75 + @return CRC-7 JEDEC parameters +*/ +inline const CRC::Parameters & CRC::CRC_7() +{ + static const Parameters parameters = { 0x09, 0x00, 0x00, false, false }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-8 SMBus. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 SMBus has the following parameters and check value: + - polynomial = 0x07 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0xF4 + @return CRC-8 SMBus parameters +*/ +inline const CRC::Parameters & CRC::CRC_8() +{ + static const Parameters parameters = { 0x07, 0x00, 0x00, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-8 EBU (aka CRC-8 AES). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 EBU has the following parameters and check value: + - polynomial = 0x1D + - initial value = 0xFF + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0x97 + @return CRC-8 EBU parameters +*/ +inline const CRC::Parameters & CRC::CRC_8_EBU() +{ + static const Parameters parameters = { 0x1D, 0xFF, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-8 MAXIM (aka CRC-8 DOW-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 MAXIM has the following parameters and check value: + - polynomial = 0x31 + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0xA1 + @return CRC-8 MAXIM parameters +*/ +inline const CRC::Parameters & CRC::CRC_8_MAXIM() +{ + static const Parameters parameters = { 0x31, 0x00, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-8 WCDMA. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 WCDMA has the following parameters and check value: + - polynomial = 0x9B + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = true + - reflect output = true + - check value = 0x25 + @return CRC-8 WCDMA parameters +*/ +inline const CRC::Parameters & CRC::CRC_8_WCDMA() +{ + static const Parameters parameters = { 0x9B, 0x00, 0x00, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-8 LTE. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-8 LTE has the following parameters and check value: + - polynomial = 0x9B + - initial value = 0x00 + - final XOR = 0x00 + - reflect input = false + - reflect output = false + - check value = 0xEA + @return CRC-8 LTE parameters +*/ +inline const CRC::Parameters & CRC::CRC_8_LTE() +{ + static const Parameters parameters = { 0x9B, 0x00, 0x00, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-10 ITU. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-10 ITU has the following parameters and check value: + - polynomial = 0x233 + - initial value = 0x000 + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0x199 + @return CRC-10 ITU parameters +*/ +inline const CRC::Parameters & CRC::CRC_10() +{ + static const Parameters parameters = { 0x233, 0x000, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-10 CDMA2000. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-10 CDMA2000 has the following parameters and check value: + - polynomial = 0x3D9 + - initial value = 0x3FF + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0x233 + @return CRC-10 CDMA2000 parameters +*/ +inline const CRC::Parameters & CRC::CRC_10_CDMA2000() +{ + static const Parameters parameters = { 0x3D9, 0x3FF, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-11 FlexRay. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-11 FlexRay has the following parameters and check value: + - polynomial = 0x385 + - initial value = 0x01A + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0x5A3 + @return CRC-11 FlexRay parameters +*/ +inline const CRC::Parameters & CRC::CRC_11() +{ + static const Parameters parameters = { 0x385, 0x01A, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-11 NR. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-11 NR has the following parameters and check value: + - polynomial = 0x621 + - initial value = 0x000 + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0x5CA + @return CRC-11 NR parameters +*/ +inline const CRC::Parameters & CRC::CRC_11_NR() +{ + static const Parameters parameters = { 0x621, 0x000, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-12 CDMA2000. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-12 CDMA2000 has the following parameters and check value: + - polynomial = 0xF13 + - initial value = 0xFFF + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0xD4D + @return CRC-12 CDMA2000 parameters +*/ +inline const CRC::Parameters & CRC::CRC_12_CDMA2000() +{ + static const Parameters parameters = { 0xF13, 0xFFF, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-12 DECT (aka CRC-12 X-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-12 DECT has the following parameters and check value: + - polynomial = 0x80F + - initial value = 0x000 + - final XOR = 0x000 + - reflect input = false + - reflect output = false + - check value = 0xF5B + @return CRC-12 DECT parameters +*/ +inline const CRC::Parameters & CRC::CRC_12_DECT() +{ + static const Parameters parameters = { 0x80F, 0x000, 0x000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-12 UMTS (aka CRC-12 3GPP). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-12 UMTS has the following parameters and check value: + - polynomial = 0x80F + - initial value = 0x000 + - final XOR = 0x000 + - reflect input = false + - reflect output = true + - check value = 0xDAF + @return CRC-12 UMTS parameters +*/ +inline const CRC::Parameters & CRC::CRC_12_UMTS() +{ + static const Parameters parameters = { 0x80F, 0x000, 0x000, false, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-13 BBC. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-13 BBC has the following parameters and check value: + - polynomial = 0x1CF5 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x04FA + @return CRC-13 BBC parameters +*/ +inline const CRC::Parameters & CRC::CRC_13_BBC() +{ + static const Parameters parameters = { 0x1CF5, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-15 CAN. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-15 CAN has the following parameters and check value: + - polynomial = 0x4599 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x059E + @return CRC-15 CAN parameters +*/ +inline const CRC::Parameters & CRC::CRC_15() +{ + static const Parameters parameters = { 0x4599, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-15 MPT1327. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-15 MPT1327 has the following parameters and check value: + - polynomial = 0x6815 + - initial value = 0x0000 + - final XOR = 0x0001 + - reflect input = false + - reflect output = false + - check value = 0x2566 + @return CRC-15 MPT1327 parameters +*/ +inline const CRC::Parameters & CRC::CRC_15_MPT1327() +{ + static const Parameters parameters = { 0x6815, 0x0000, 0x0001, false, false }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-16 ARC (aka CRC-16 IBM, CRC-16 LHA). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 ARC has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = true + - reflect output = true + - check value = 0xBB3D + @return CRC-16 ARC parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_ARC() +{ + static const Parameters parameters = { 0x8005, 0x0000, 0x0000, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 BUYPASS (aka CRC-16 VERIFONE, CRC-16 UMTS). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 BUYPASS has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0xFEE8 + @return CRC-16 BUYPASS parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_BUYPASS() +{ + static const Parameters parameters = { 0x8005, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 CCITT FALSE. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 CCITT FALSE has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0xFFFF + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x29B1 + @return CRC-16 CCITT FALSE parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_CCITTFALSE() +{ + static const Parameters parameters = { 0x1021, 0xFFFF, 0x0000, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-16 CDMA2000. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 CDMA2000 has the following parameters and check value: + - polynomial = 0xC867 + - initial value = 0xFFFF + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x4C06 + @return CRC-16 CDMA2000 parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_CDMA2000() +{ + static const Parameters parameters = { 0xC867, 0xFFFF, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 CMS. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 CMS has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0xFFFF + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0xAEE7 + @return CRC-16 CMS parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_CMS() +{ + static const Parameters parameters = { 0x8005, 0xFFFF, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 DECT-R (aka CRC-16 R-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 DECT-R has the following parameters and check value: + - polynomial = 0x0589 + - initial value = 0x0000 + - final XOR = 0x0001 + - reflect input = false + - reflect output = false + - check value = 0x007E + @return CRC-16 DECT-R parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_DECTR() +{ + static const Parameters parameters = { 0x0589, 0x0000, 0x0001, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 DECT-X (aka CRC-16 X-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 DECT-X has the following parameters and check value: + - polynomial = 0x0589 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x007F + @return CRC-16 DECT-X parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_DECTX() +{ + static const Parameters parameters = { 0x0589, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 DNP. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 DNP has the following parameters and check value: + - polynomial = 0x3D65 + - initial value = 0x0000 + - final XOR = 0xFFFF + - reflect input = true + - reflect output = true + - check value = 0xEA82 + @return CRC-16 DNP parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_DNP() +{ + static const Parameters parameters = { 0x3D65, 0x0000, 0xFFFF, true, true }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-16 GENIBUS (aka CRC-16 EPC, CRC-16 I-CODE, CRC-16 DARC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 GENIBUS has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0xFFFF + - final XOR = 0xFFFF + - reflect input = false + - reflect output = false + - check value = 0xD64E + @return CRC-16 GENIBUS parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_GENIBUS() +{ + static const Parameters parameters = { 0x1021, 0xFFFF, 0xFFFF, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 KERMIT (aka CRC-16 CCITT, CRC-16 CCITT-TRUE). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 KERMIT has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = true + - reflect output = true + - check value = 0x2189 + @return CRC-16 KERMIT parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_KERMIT() +{ + static const Parameters parameters = { 0x1021, 0x0000, 0x0000, true, true }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-16 MAXIM. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 MAXIM has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0x0000 + - final XOR = 0xFFFF + - reflect input = true + - reflect output = true + - check value = 0x44C2 + @return CRC-16 MAXIM parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_MAXIM() +{ + static const Parameters parameters = { 0x8005, 0x0000, 0xFFFF, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 MODBUS. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 MODBUS has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0xFFFF + - final XOR = 0x0000 + - reflect input = true + - reflect output = true + - check value = 0x4B37 + @return CRC-16 MODBUS parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_MODBUS() +{ + static const Parameters parameters = { 0x8005, 0xFFFF, 0x0000, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 T10-DIF. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 T10-DIF has the following parameters and check value: + - polynomial = 0x8BB7 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0xD0DB + @return CRC-16 T10-DIF parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_T10DIF() +{ + static const Parameters parameters = { 0x8BB7, 0x0000, 0x0000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 USB. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 USB has the following parameters and check value: + - polynomial = 0x8005 + - initial value = 0xFFFF + - final XOR = 0xFFFF + - reflect input = true + - reflect output = true + - check value = 0xB4C8 + @return CRC-16 USB parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_USB() +{ + static const Parameters parameters = { 0x8005, 0xFFFF, 0xFFFF, true, true }; + return parameters; +} + +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-16 X-25 (aka CRC-16 IBM-SDLC, CRC-16 ISO-HDLC, CRC-16 B). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 X-25 has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0xFFFF + - final XOR = 0xFFFF + - reflect input = true + - reflect output = true + - check value = 0x906E + @return CRC-16 X-25 parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_X25() +{ + static const Parameters parameters = { 0x1021, 0xFFFF, 0xFFFF, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-16 XMODEM (aka CRC-16 ZMODEM, CRC-16 ACORN, CRC-16 LTE). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-16 XMODEM has the following parameters and check value: + - polynomial = 0x1021 + - initial value = 0x0000 + - final XOR = 0x0000 + - reflect input = false + - reflect output = false + - check value = 0x31C3 + @return CRC-16 XMODEM parameters +*/ +inline const CRC::Parameters & CRC::CRC_16_XMODEM() +{ + static const Parameters parameters = { 0x1021, 0x0000, 0x0000, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-17 CAN. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-17 CAN has the following parameters and check value: + - polynomial = 0x1685B + - initial value = 0x00000 + - final XOR = 0x00000 + - reflect input = false + - reflect output = false + - check value = 0x04F03 + @return CRC-17 CAN parameters +*/ +inline const CRC::Parameters & CRC::CRC_17_CAN() +{ + static const Parameters parameters = { 0x1685B, 0x00000, 0x00000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-21 CAN. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-21 CAN has the following parameters and check value: + - polynomial = 0x102899 + - initial value = 0x000000 + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x0ED841 + @return CRC-21 CAN parameters +*/ +inline const CRC::Parameters & CRC::CRC_21_CAN() +{ + static const Parameters parameters = { 0x102899, 0x000000, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 OPENPGP. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-24 OPENPGP has the following parameters and check value: + - polynomial = 0x864CFB + - initial value = 0xB704CE + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x21CF02 + @return CRC-24 OPENPGP parameters +*/ +inline const CRC::Parameters & CRC::CRC_24() +{ + static const Parameters parameters = { 0x864CFB, 0xB704CE, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 FlexRay-A. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-24 FlexRay-A has the following parameters and check value: + - polynomial = 0x5D6DCB + - initial value = 0xFEDCBA + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x7979BD + @return CRC-24 FlexRay-A parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_FLEXRAYA() +{ + static const Parameters parameters = { 0x5D6DCB, 0xFEDCBA, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 FlexRay-B. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-24 FlexRay-B has the following parameters and check value: + - polynomial = 0x5D6DCB + - initial value = 0xABCDEF + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x1F23B8 + @return CRC-24 FlexRay-B parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_FLEXRAYB() +{ + static const Parameters parameters = { 0x5D6DCB, 0xABCDEF, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 LTE-A/NR-A. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-24 LTE-A has the following parameters and check value: + - polynomial = 0x864CFB + - initial value = 0x000000 + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0xCDE703 + @return CRC-24 LTE-A parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_LTEA() +{ + static const Parameters parameters = { 0x864CFB, 0x000000, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 LTE-B/NR-B. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-24 LTE-B has the following parameters and check value: + - polynomial = 0x800063 + - initial value = 0x000000 + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0x23EF52 + @return CRC-24 LTE-B parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_LTEB() +{ + static const Parameters parameters = { 0x800063, 0x000000, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-24 NR-C. + @note The parameters are static and are delayed-constructed to reduce memory + footprint. + @note CRC-24 NR-C has the following parameters and check value: + - polynomial = 0xB2B117 + - initial value = 0x000000 + - final XOR = 0x000000 + - reflect input = false + - reflect output = false + - check value = 0xF48279 + @return CRC-24 NR-C parameters +*/ +inline const CRC::Parameters & CRC::CRC_24_NRC() +{ + static const Parameters parameters = { 0xB2B117, 0x000000, 0x000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-30 CDMA. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-30 CDMA has the following parameters and check value: + - polynomial = 0x2030B9C7 + - initial value = 0x3FFFFFFF + - final XOR = 0x00000000 + - reflect input = false + - reflect output = false + - check value = 0x3B3CB540 + @return CRC-30 CDMA parameters +*/ +inline const CRC::Parameters & CRC::CRC_30() +{ + static const Parameters parameters = { 0x2030B9C7, 0x3FFFFFFF, 0x00000000, false, false }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +/** + @brief Returns a set of parameters for CRC-32 (aka CRC-32 ADCCP, CRC-32 PKZip). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 has the following parameters and check value: + - polynomial = 0x04C11DB7 + - initial value = 0xFFFFFFFF + - final XOR = 0xFFFFFFFF + - reflect input = true + - reflect output = true + - check value = 0xCBF43926 + @return CRC-32 parameters +*/ +inline const CRC::Parameters & CRC::CRC_32() +{ + static const Parameters parameters = { 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, true, true }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-32 BZIP2 (aka CRC-32 AAL5, CRC-32 DECT-B, CRC-32 B-CRC). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 BZIP2 has the following parameters and check value: + - polynomial = 0x04C11DB7 + - initial value = 0xFFFFFFFF + - final XOR = 0xFFFFFFFF + - reflect input = false + - reflect output = false + - check value = 0xFC891918 + @return CRC-32 BZIP2 parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_BZIP2() +{ + static const Parameters parameters = { 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-32 C (aka CRC-32 ISCSI, CRC-32 Castagnoli, CRC-32 Interlaken). + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 C has the following parameters and check value: + - polynomial = 0x1EDC6F41 + - initial value = 0xFFFFFFFF + - final XOR = 0xFFFFFFFF + - reflect input = true + - reflect output = true + - check value = 0xE3069283 + @return CRC-32 C parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_C() +{ + static const Parameters parameters = { 0x1EDC6F41, 0xFFFFFFFF, 0xFFFFFFFF, true, true }; + return parameters; +} +#endif + +/** + @brief Returns a set of parameters for CRC-32 MPEG-2. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 MPEG-2 has the following parameters and check value: + - polynomial = 0x04C11DB7 + - initial value = 0xFFFFFFFF + - final XOR = 0x00000000 + - reflect input = false + - reflect output = false + - check value = 0x0376E6E7 + @return CRC-32 MPEG-2 parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_MPEG2() +{ + static const Parameters parameters = { 0x04C11DB7, 0xFFFFFFFF, 0x00000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-32 POSIX. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 POSIX has the following parameters and check value: + - polynomial = 0x04C11DB7 + - initial value = 0x00000000 + - final XOR = 0xFFFFFFFF + - reflect input = false + - reflect output = false + - check value = 0x765E7680 + @return CRC-32 POSIX parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_POSIX() +{ + static const Parameters parameters = { 0x04C11DB7, 0x00000000, 0xFFFFFFFF, false, false }; + return parameters; +} + +#ifdef CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS +/** + @brief Returns a set of parameters for CRC-32 Q. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-32 Q has the following parameters and check value: + - polynomial = 0x814141AB + - initial value = 0x00000000 + - final XOR = 0x00000000 + - reflect input = false + - reflect output = false + - check value = 0x3010BF7F + @return CRC-32 Q parameters +*/ +inline const CRC::Parameters & CRC::CRC_32_Q() +{ + static const Parameters parameters = { 0x814141AB, 0x00000000, 0x00000000, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-40 GSM. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-40 GSM has the following parameters and check value: + - polynomial = 0x0004820009 + - initial value = 0x0000000000 + - final XOR = 0xFFFFFFFFFF + - reflect input = false + - reflect output = false + - check value = 0xD4164FC646 + @return CRC-40 GSM parameters +*/ +inline const CRC::Parameters & CRC::CRC_40_GSM() +{ + static const Parameters parameters = { 0x0004820009, 0x0000000000, 0xFFFFFFFFFF, false, false }; + return parameters; +} + +/** + @brief Returns a set of parameters for CRC-64 ECMA. + @note The parameters are static and are delayed-constructed to reduce memory footprint. + @note CRC-64 ECMA has the following parameters and check value: + - polynomial = 0x42F0E1EBA9EA3693 + - initial value = 0x0000000000000000 + - final XOR = 0x0000000000000000 + - reflect input = false + - reflect output = false + - check value = 0x6C40DF5F0B497347 + @return CRC-64 ECMA parameters +*/ +inline const CRC::Parameters & CRC::CRC_64() +{ + static const Parameters parameters = { 0x42F0E1EBA9EA3693, 0x0000000000000000, 0x0000000000000000, false, false }; + return parameters; +} +#endif // CRCPP_INCLUDE_ESOTERIC_CRC_DEFINITIONS + +#ifdef CRCPP_USE_NAMESPACE +} +#endif + +#endif // CRCPP_CRC_H_ diff --git a/Firmware/CoverUI/CoverUITest/main.cpp b/Firmware/CoverUI/CoverUITest/main.cpp new file mode 100644 index 00000000..fd209ea2 --- /dev/null +++ b/Firmware/CoverUI/CoverUITest/main.cpp @@ -0,0 +1,562 @@ +/* Version 0.91 v. 27.05.2022 schnelles Blinken von ontime 500 auf 250 ms verkleinert +*/ + + + + +//#define _serial_debug_ +//#define _testCOBS_ + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + + +// Linux headers +#include // Contains file controls like O_RDWR +#include // Error integer and strerror() function +#include // Contains POSIX terminal control definitions +#include // write(), read(), close() + +#include "COBS.h" +#include "BttnCtl.h" +#include "CRC.h" +#include +using namespace std; + +COBS cobs; +#define buffersize 256 + + +static string VERSION = "V 0.91"; +char DEFAULT_SERIAL[] = "/dev/ttyUSB0"; + + +static uint number_inbuffer = 0; +uint8_t read_buf [buffersize]; +uint8_t serial_buf [buffersize]; +uint32_t read_ptr = 0; +uint32_t write_ptr = 0; +uint8_t COBS_buf [buffersize]; + + +/**************************************************************************************************** + * + * PacketReceived() there is a serial stream in the buffer + * decode it with cobs, calc crc and decode into the messagestruct + *****************************************************************************************************/ + + +void PacketReceived() +{ +#ifdef _serial_debug_ + printf("\nPacketReceived()"); + printf("\nbefore decode count = %d values are ",number_inbuffer); + for (int i=0; icrc == calc_crc) { + printf("button board has version: %d\n", message->version); + } else { + printf("GetVersion invalid CRC"); + } + }else if(decoded_buffer[0] == Get_Button && data_size == sizeof(struct msg_event_button)) { + struct msg_event_button *message = (struct msg_event_button*)decoded_buffer; + if(message->crc == calc_crc) { + printf("button %d was pressed with duration %d\n", message->button_id, message->press_duration); + } else { + printf("GetVersion invalid CRC"); + } + } +} + + + + +/**************************************************************************************************** + * + * reply wait for timeout ms if return with result + * + *****************************************************************************************************/ + +#define timeout 100 + +void reply(int com_port) +{ + number_inbuffer=0; + std::this_thread::sleep_for(std::chrono::milliseconds(timeout)); + int num_bytes=0; + try + { + num_bytes = read(com_port, &read_buf, sizeof(read_buf)); + } + catch(...) + { + std::cout << "Serial error check cable " << '\n'; + return; + } + + + + + // printf("*** Error *** no connection to target, check cable"); + + + + + if (num_bytes !=0) + { + for (int i=0; i= buffersize) write_ptr = 0; + } + + + + +#ifdef _serial_debug_ + +#endif + + while (write_ptr != read_ptr ) + { + COBS_buf[number_inbuffer]=serial_buf[read_ptr]; + number_inbuffer++; + read_ptr++; + if (read_ptr >= buffersize) read_ptr = 0; + +#ifdef _serial_debug_ + printf("\ncount %d , value 0x%2x ",number_inbuffer,COBS_buf[number_inbuffer-1]); +#endif + + if (COBS_buf[number_inbuffer-1] == 0 ) + { + PacketReceived(); + number_inbuffer=0; + + } + + } + + } + + +} + + +/**************************************************************************************************** + * + * sendMessage send the command strucutre via COBS and serial Port and wait for reply + * + *****************************************************************************************************/ + + +void sendMessage(void *message, size_t size, int serial_port) +{ + // packages need to be at least 1 byte of type, 1 byte of data and 2 bytes of CRC + + if (size < 4) + { + return; + } + uint8_t *data_pointer = (uint8_t *)message; + uint16_t *crc_pointer = (uint16_t *)(data_pointer + (size - 2)); + + // calculate the CRC + *crc_pointer = CRC::Calculate(message, size - 2, CRC::CRC_16_CCITTFALSE()); + // structure is filled and CRC calculated, so print out, what should be encoded + // + +#ifdef _serial_debug_ + printf("\nprint struct before encoding %d byte : ",(int)size); + uint8_t *temp = data_pointer; + for (int i = 0; i < size; i++) + { + printf("0x%02x , ", *temp); + temp++; + } +#endif + + // encode message + uint8_t out_buf[100]; + size_t encoded_size = cobs.encode((uint8_t *)message, size, out_buf); + out_buf[encoded_size] = 0; + encoded_size++; + +#ifdef _serial_debug_ + printf("\nencoded message byte : "); + for (uint i = 0; i < encoded_size; i++) + { + printf("0x%02x , ", out_buf[i]); + } +#endif + write(serial_port, out_buf, encoded_size); + //if (!reply(serial_port)) printf("\n*** got no answer ***"); + +} + + + + +/**************************************************************************************************** + * + * Init Serial Port 115200 baud, 8,n,n + * + *****************************************************************************************************/ + +int Init_serial_board(char *channel) +{ + // Init serial port + int ret_val = -1; + struct termios tty; + + int serial_port = open(channel, O_RDWR); + if (serial_port < 0) + { +#ifdef _serial_debug_ + printf("Error %i from open: \n", errno); +#endif + return (ret_val); + } + + if (tcgetattr(serial_port, &tty) != 0) + { +#ifdef _serial_debug_ + printf("Error %i from tcgetattr: \n", errno); +#endif + return (ret_val); + } + + + tty.c_cflag &= ~PARENB; // Clear parity bit, disabling parity (most common) + tty.c_cflag &= ~CSTOPB; // Clear stop field, only one stop bit used in communication (most common) + tty.c_cflag &= ~CSIZE; // Clear all bits that set the data size + tty.c_cflag |= CS8; // 8 bits per byte (most common) + tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control (most common) + tty.c_cflag |= CREAD | CLOCAL; // Turn on READ & ignore ctrl lines (CLOCAL = 1) + + tty.c_lflag &= ~ICANON; + tty.c_lflag &= ~ECHO; // Disable echo + tty.c_lflag &= ~ECHOE; // Disable erasure + tty.c_lflag &= ~ECHONL; // Disable new-line echo + tty.c_lflag &= ~ISIG; // Disable interpretation of INTR, QUIT and SUSP + tty.c_iflag &= ~(IXON | IXOFF | IXANY); // Turn off s/w flow ctrl + tty.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL); // Disable any special handling of received bytes + + tty.c_oflag &= ~OPOST; // Prevent special interpretation of output bytes (e.g. newline chars) + tty.c_oflag &= ~ONLCR; // Prevent conversion of newline to carriage return/line feed + // tty.c_oflag &= ~OXTABS; // Prevent conversion of tabs to spaces (NOT PRESENT ON LINUX) + // tty.c_oflag &= ~ONOEOT; // Prevent removal of C-d chars (0x004) in output (NOT PRESENT ON LINUX) + + tty.c_cc[VTIME] = 10; // Wait for up to 1s (10 deciseconds), returning as soon as any data is received. + tty.c_cc[VMIN] = 0; + + // Set in/out baud rate to be 9600 + cfsetispeed(&tty, B115200); + cfsetospeed(&tty, B115200); + + // Save tty settings, also checking for error + if (tcsetattr(serial_port, TCSANOW, &tty) != 0) + { +#ifdef _serial_debug_ + printf("Error %i from tcsetattr: \n", errno); +#endif + return (ret_val); + } + return (ret_val=serial_port); +} + + +/**************************************************************************************************** + * + * fill command structure LED command and send via serial port + * + *****************************************************************************************************/ + + +void set_LED_state(int com_port, uint cmd1, uint cmd2, uid_t cmd3) +{ + + + + +} + + +/**************************************************************************************************** + * + * fill command structure getversion and send via serial port + * + *****************************************************************************************************/ + +/**************************************************************************************************** + * + * fill command structure buzzercommand and send via serial port + * + *****************************************************************************************************/ + + +void set_buzzer(int com_port, uint ontime, uint offtime, uint count) +{ + + +} + + +void getversion(int com_port) +{ + printf("Get Version\n"); + // Fill structure + struct msg_get_version msg; + msg.type = Get_Version; + + sendMessage(&msg, sizeof(msg), com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + reply(com_port); + +} + + +void setLed(struct msg_set_leds &msg, int led, uint8_t state) { + // mask the current led state + uint64_t mask = ~(((uint64_t)0b111) << (led*3)); + msg.leds &= mask; + msg.leds |= ((uint64_t)(state&0b111)) << (led*3); +} + +void setBars7(struct msg_set_leds &msg, double value) { + int on_leds = round(value * 7.0); + for(int i = 0; i < 7; i++) { + setLed(msg, 4+i, i < on_leds ? LED_on : LED_off); + } +} + +void setBars4(struct msg_set_leds &msg, double value) { + int on_leds = round(value * 4.0); + for(int i = 0; i < 7; i++) { + setLed(msg, i, i < on_leds ? LED_on : LED_off); + } +} + +void LEDstatic(int com_port) +{ + + struct msg_set_leds msg; + msg.type = Set_LEDs; + msg.leds = 0; + + for(int led = 0; led < 18; led++) { + setLed(msg, led, LED_on); + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + sendMessage(&msg, sizeof(msg), com_port); + setLed(msg, led, LED_off); + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + sendMessage(&msg, sizeof(msg), com_port); + } + +} + + +void LEDfastblink(int com_port) +{ + struct msg_set_leds msg; + msg.type = Set_LEDs; + msg.leds = 0; + + for(int led = 0; led < 18; led++) { + setLed(msg, led, LED_blink_fast); + sendMessage(&msg, sizeof(msg), com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + + } + for(int led = 0; led < 18; led++) { + setLed(msg, led, LED_off); + sendMessage(&msg, sizeof(msg), com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + + } + + +} + +void LEDslowblink(int com_port) +{ + struct msg_set_leds msg; + msg.type = Set_LEDs; + msg.leds = 0; + + for(int led = 0; led < 18; led++) { + setLed(msg, led, LED_blink_slow); + sendMessage(&msg, sizeof(msg), com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + + } + + std::this_thread::sleep_for(std::chrono::milliseconds(5000)); + for(int led = 0; led < 18; led++) { + setLed(msg, led, LED_off); + sendMessage(&msg, sizeof(msg), com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + + } +} + + +void Buzzertest(int com_port) +{ + printf("Test Buzzer\n"); + set_buzzer(com_port,100,40,3); + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + reply(com_port); + set_buzzer(com_port,100,40,5); + reply(com_port); +} + + +void LEDBar7test(int com_port) +{ + struct msg_set_leds msg; + msg.type = Set_LEDs; + msg.leds = 0; + + for(int i = 0; i < 10; i++) { + for (double d = 0; d < 1.0; d += 0.05) { + setBars7(msg, d); + sendMessage(&msg, sizeof(msg), com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(20)); + } + for (double d = 0; d < 1.0; d += 0.05) { + setBars7(msg, 1.0 - d); + sendMessage(&msg, sizeof(msg), com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(20)); + } + } +} + +void LEDBar4test(int com_port) +{ + struct msg_set_leds msg; + msg.type = Set_LEDs; + msg.leds = 0; + + for(int i = 0; i < 10; i++) { + for (double d = 0; d < 1.0; d += 0.05) { + setBars4(msg, d); + sendMessage(&msg, sizeof(msg), com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(20)); + } + + for (double d = 0; d < 1.0; d += 0.05) { + setBars4(msg, 1.0 - d); + sendMessage(&msg, sizeof(msg), com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(20)); + } + } +} + + + +/**************************************************************************************************** + * + * main + * + *****************************************************************************************************/ + + +int main(int argc, char *argv[]) +{ + + printf("Testprogramm OpnMower UI-Board Version %s\n",VERSION.c_str() ); + + + char serialchannel[80]; + if ( argc == 1) + { + printf("No command line parameter for serial channel, using default value : %s\n",DEFAULT_SERIAL); + strcpy(serialchannel,DEFAULT_SERIAL); + + } + else if (argc > 2) + { + printf("To many agruments, try cobstest \n"); + } + else + { + strcpy(serialchannel,argv[1]); + printf("using serial channel: %s \n",serialchannel); + + + } + + + int com_port = Init_serial_board(serialchannel); + if (com_port < 0) + { + printf("\n\n\r*** ERROR *** can't open serial port. Serial cable connected ? Program aborted"); + return 1; + } + + + //set_LED_state(com_port , 0 ,LED_on , 0); + + //reply(com_port); + + + getversion(com_port); + + LEDstatic(com_port); + + LEDfastblink(com_port); + + LEDslowblink(com_port); + + Buzzertest(com_port); + + + LEDBar4test(com_port); + + LEDBar7test(com_port); + + + printf("Test Buttons\n"); + while (true) + { + + + reply(com_port); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + +} \ No newline at end of file