From b3c4ad8a5685d9724cb7b79c5522bf24ca12af8c Mon Sep 17 00:00:00 2001 From: Will Toth Date: Mon, 23 Mar 2020 14:12:33 -0500 Subject: [PATCH 01/55] Start of SocketCAN implementation --- .vscode/settings.json | 17 +- .wpilib/wpilib_preferences.json | 4 +- gradlew | 0 .../com/revrobotics/jni/RevJNIWrapper.java | 2 +- src/main/native/cpp/CANBridge.cpp | 2 +- src/main/native/cpp/CANBridgeUtils.cpp | 2 +- .../CandleWinUSB/CandleWinUSBDevice.cpp | 2 +- .../CandleWinUSB/CandleWinUSBDriver.cpp | 2 +- .../cpp/Drivers/Serial/SerialDevice.cpp | 2 +- .../cpp/Drivers/Serial/SerialDriver.cpp | 2 +- .../cpp/Drivers/Serial/SerialMessage.cpp | 2 +- .../cpp/Drivers/SocketCAN/SocketCANDriver.cpp | 65 +++++ src/main/native/cpp/ThreadUtils.cpp | 2 +- src/main/native/cpp/can-utils/canframelen.c | 263 ++++++++++++++++++ .../native/include/can-utils/canframelen.h | 93 +++++++ src/main/native/include/rev/CANBridge.h | 2 +- src/main/native/include/rev/CANBridgeUtils.h | 2 +- src/main/native/include/rev/CANDevice.h | 2 +- src/main/native/include/rev/CANDriver.h | 2 +- src/main/native/include/rev/CANMessage.h | 2 +- src/main/native/include/rev/CANStatus.h | 2 +- .../Drivers/CandleWinUSB/CandleWinUSBDevice.h | 2 +- .../CandleWinUSB/CandleWinUSBDeviceThread.h | 2 +- .../Drivers/CandleWinUSB/CandleWinUSBDriver.h | 2 +- .../include/rev/Drivers/DriverDeviceThread.h | 2 +- .../rev/Drivers/SerialPort/SerialDevice.h | 2 +- .../Drivers/SerialPort/SerialDeviceThread.h | 2 +- .../rev/Drivers/SerialPort/SerialDriver.h | 2 +- .../rev/Drivers/SerialPort/SerialMessage.h | 2 +- .../rev/Drivers/SocketCAN/SocketCANDevice.h | 71 +++++ .../rev/Drivers/SocketCAN/SocketCANDriver.h | 51 ++++ .../rev/Drivers/SocketCAN/SocketCANThread.h | 217 +++++++++++++++ .../native/include/utils/CircularBuffer.h | 2 +- src/main/native/include/utils/ThreadUtils.h | 2 +- src/test/gtest/cpp/main.cpp | 2 +- 35 files changed, 804 insertions(+), 29 deletions(-) mode change 100644 => 100755 gradlew create mode 100644 src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp create mode 100644 src/main/native/cpp/can-utils/canframelen.c create mode 100644 src/main/native/include/can-utils/canframelen.h create mode 100644 src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h create mode 100644 src/main/native/include/rev/Drivers/SocketCAN/SocketCANDriver.h create mode 100644 src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h diff --git a/.vscode/settings.json b/.vscode/settings.json index 47280d7..29cd40d 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -68,7 +68,22 @@ "iterator": "cpp", "sstream": "cpp", "cctype": "cpp", - "concepts": "cpp" + "concepts": "cpp", + "inet.h": "c", + "cwctype": "cpp", + "array": "cpp", + "hash_map": "cpp", + "*.tcc": "cpp", + "bitset": "cpp", + "complex": "cpp", + "condition_variable": "cpp", + "memory_resource": "cpp", + "numeric": "cpp", + "optional": "cpp", + "random": "cpp", + "set": "cpp", + "string_view": "cpp", + "cinttypes": "cpp" }, "C_Cpp.default.configurationProvider": "vscode-wpilib" } \ No newline at end of file diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json index 8a51c0a..fc2a570 100644 --- a/.wpilib/wpilib_preferences.json +++ b/.wpilib/wpilib_preferences.json @@ -1,6 +1,6 @@ { "enableCppIntellisense": true, "currentLanguage": "cpp", - "projectYear": "Beta2020-2", + "projectYear": "2020", "teamNumber": 9999 -} +} \ No newline at end of file diff --git a/gradlew b/gradlew old mode 100644 new mode 100755 diff --git a/src/main/java/com/revrobotics/jni/RevJNIWrapper.java b/src/main/java/com/revrobotics/jni/RevJNIWrapper.java index db3fdab..f6dfe4b 100644 --- a/src/main/java/com/revrobotics/jni/RevJNIWrapper.java +++ b/src/main/java/com/revrobotics/jni/RevJNIWrapper.java @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/cpp/CANBridge.cpp b/src/main/native/cpp/CANBridge.cpp index 7a1e566..33fe438 100644 --- a/src/main/native/cpp/CANBridge.cpp +++ b/src/main/native/cpp/CANBridge.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/cpp/CANBridgeUtils.cpp b/src/main/native/cpp/CANBridgeUtils.cpp index a820183..881591e 100644 --- a/src/main/native/cpp/CANBridgeUtils.cpp +++ b/src/main/native/cpp/CANBridgeUtils.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/cpp/Drivers/CandleWinUSB/CandleWinUSBDevice.cpp b/src/main/native/cpp/Drivers/CandleWinUSB/CandleWinUSBDevice.cpp index 64764a2..f047e99 100644 --- a/src/main/native/cpp/Drivers/CandleWinUSB/CandleWinUSBDevice.cpp +++ b/src/main/native/cpp/Drivers/CandleWinUSB/CandleWinUSBDevice.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/cpp/Drivers/CandleWinUSB/CandleWinUSBDriver.cpp b/src/main/native/cpp/Drivers/CandleWinUSB/CandleWinUSBDriver.cpp index f4594a7..bb3452b 100644 --- a/src/main/native/cpp/Drivers/CandleWinUSB/CandleWinUSBDriver.cpp +++ b/src/main/native/cpp/Drivers/CandleWinUSB/CandleWinUSBDriver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp b/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp index 41d86f7..a56f0f5 100644 --- a/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp +++ b/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp b/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp index 1be761f..13de544 100644 --- a/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp +++ b/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/cpp/Drivers/Serial/SerialMessage.cpp b/src/main/native/cpp/Drivers/Serial/SerialMessage.cpp index 983aec7..d802ecc 100644 --- a/src/main/native/cpp/Drivers/Serial/SerialMessage.cpp +++ b/src/main/native/cpp/Drivers/Serial/SerialMessage.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp new file mode 100644 index 0000000..d1ce4f6 --- /dev/null +++ b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp @@ -0,0 +1,65 @@ +/* + * Copyright (c) 2019 - 2020 REV Robotics + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of REV Robotics 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 OWNER 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. + */ + +#ifdef __linux__ + +#include "rev/Drivers/SocketCAN/SocketCANDriver.h" +#include "rev/Drivers/SocketCAN/SocketCANDevice.h" + +#include +#include +#include + +namespace rev { +namespace usb { + +std::vector SocketCANDriver::GetDevices() +{ + std::vector retval; + + return retval; +} + +std::unique_ptr SocketCANDriver::CreateDeviceFromDescriptor(const char* descriptor) +{ + uint8_t num_interfaces; + + try { + return std::make_unique(descriptor); + } catch(...) { + // do nothing if it failed + } + return std::unique_ptr(); +} + +} // namespace usb +} // namespace rev + +#else +typedef int __ISOWarning__CLEAR_; +#endif // _WIN32 diff --git a/src/main/native/cpp/ThreadUtils.cpp b/src/main/native/cpp/ThreadUtils.cpp index 2d9e9b3..1bce0f7 100644 --- a/src/main/native/cpp/ThreadUtils.cpp +++ b/src/main/native/cpp/ThreadUtils.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/cpp/can-utils/canframelen.c b/src/main/native/cpp/can-utils/canframelen.c new file mode 100644 index 0000000..da509eb --- /dev/null +++ b/src/main/native/cpp/can-utils/canframelen.c @@ -0,0 +1,263 @@ +/* SPDX-License-Identifier: (GPL-2.0-only OR BSD-3-Clause) */ +/* + * canframelen.c + * + * Copyright (c) 2013, 2014 Czech Technical University in Prague + * + * Author: Michal Sojka + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of Czech Technical University in Prague nor the + * names of its contributors may be used to endorse or promote + * products derived from this software without specific prior + * written permission. + * + * Alternatively, provided that this notice is retained in full, this + * software may be distributed under the terms of the GNU General + * Public License ("GPL") version 2, in which case the provisions of the + * GPL apply INSTEAD OF those given above. + * + * The provided data structures and external interfaces from this code + * are not restricted to be used by modules with a GPL compatible license. + * + * 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 + * OWNER 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. + * + * Send feedback to + * + */ + +#include "canframelen.h" +#include +#include +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Functions and types for CRC checks. + * + * Generated on Wed Jan 8 15:14:20 2014, + * by pycrc v0.8.1, http://www.tty1.net/pycrc/ + * using the configuration: + * Width = 15 + * Poly = 0x4599 + * XorIn = 0x0000 + * ReflectIn = False + * XorOut = 0x0000 + * ReflectOut = False + * Algorithm = table-driven + *****************************************************************************/ + +typedef uint16_t crc_t; + +/** + * Static table used for the table_driven implementation. + *****************************************************************************/ +static const crc_t crc_table[256] = { + 0x0000, 0x4599, 0x4eab, 0x0b32, 0x58cf, 0x1d56, 0x1664, 0x53fd, 0x7407, 0x319e, 0x3aac, 0x7f35, 0x2cc8, 0x6951, 0x6263, 0x27fa, + 0x2d97, 0x680e, 0x633c, 0x26a5, 0x7558, 0x30c1, 0x3bf3, 0x7e6a, 0x5990, 0x1c09, 0x173b, 0x52a2, 0x015f, 0x44c6, 0x4ff4, 0x0a6d, + 0x5b2e, 0x1eb7, 0x1585, 0x501c, 0x03e1, 0x4678, 0x4d4a, 0x08d3, 0x2f29, 0x6ab0, 0x6182, 0x241b, 0x77e6, 0x327f, 0x394d, 0x7cd4, + 0x76b9, 0x3320, 0x3812, 0x7d8b, 0x2e76, 0x6bef, 0x60dd, 0x2544, 0x02be, 0x4727, 0x4c15, 0x098c, 0x5a71, 0x1fe8, 0x14da, 0x5143, + 0x73c5, 0x365c, 0x3d6e, 0x78f7, 0x2b0a, 0x6e93, 0x65a1, 0x2038, 0x07c2, 0x425b, 0x4969, 0x0cf0, 0x5f0d, 0x1a94, 0x11a6, 0x543f, + 0x5e52, 0x1bcb, 0x10f9, 0x5560, 0x069d, 0x4304, 0x4836, 0x0daf, 0x2a55, 0x6fcc, 0x64fe, 0x2167, 0x729a, 0x3703, 0x3c31, 0x79a8, + 0x28eb, 0x6d72, 0x6640, 0x23d9, 0x7024, 0x35bd, 0x3e8f, 0x7b16, 0x5cec, 0x1975, 0x1247, 0x57de, 0x0423, 0x41ba, 0x4a88, 0x0f11, + 0x057c, 0x40e5, 0x4bd7, 0x0e4e, 0x5db3, 0x182a, 0x1318, 0x5681, 0x717b, 0x34e2, 0x3fd0, 0x7a49, 0x29b4, 0x6c2d, 0x671f, 0x2286, + 0x2213, 0x678a, 0x6cb8, 0x2921, 0x7adc, 0x3f45, 0x3477, 0x71ee, 0x5614, 0x138d, 0x18bf, 0x5d26, 0x0edb, 0x4b42, 0x4070, 0x05e9, + 0x0f84, 0x4a1d, 0x412f, 0x04b6, 0x574b, 0x12d2, 0x19e0, 0x5c79, 0x7b83, 0x3e1a, 0x3528, 0x70b1, 0x234c, 0x66d5, 0x6de7, 0x287e, + 0x793d, 0x3ca4, 0x3796, 0x720f, 0x21f2, 0x646b, 0x6f59, 0x2ac0, 0x0d3a, 0x48a3, 0x4391, 0x0608, 0x55f5, 0x106c, 0x1b5e, 0x5ec7, + 0x54aa, 0x1133, 0x1a01, 0x5f98, 0x0c65, 0x49fc, 0x42ce, 0x0757, 0x20ad, 0x6534, 0x6e06, 0x2b9f, 0x7862, 0x3dfb, 0x36c9, 0x7350, + 0x51d6, 0x144f, 0x1f7d, 0x5ae4, 0x0919, 0x4c80, 0x47b2, 0x022b, 0x25d1, 0x6048, 0x6b7a, 0x2ee3, 0x7d1e, 0x3887, 0x33b5, 0x762c, + 0x7c41, 0x39d8, 0x32ea, 0x7773, 0x248e, 0x6117, 0x6a25, 0x2fbc, 0x0846, 0x4ddf, 0x46ed, 0x0374, 0x5089, 0x1510, 0x1e22, 0x5bbb, + 0x0af8, 0x4f61, 0x4453, 0x01ca, 0x5237, 0x17ae, 0x1c9c, 0x5905, 0x7eff, 0x3b66, 0x3054, 0x75cd, 0x2630, 0x63a9, 0x689b, 0x2d02, + 0x276f, 0x62f6, 0x69c4, 0x2c5d, 0x7fa0, 0x3a39, 0x310b, 0x7492, 0x5368, 0x16f1, 0x1dc3, 0x585a, 0x0ba7, 0x4e3e, 0x450c, 0x0095 +}; + +/** + * Update the crc value with new data. + * + * \param crc The current crc value. + * \param data Pointer to a buffer of \a data_len bytes. + * \param data_len Number of bytes in the \a data buffer. + * \return The updated crc value. + *****************************************************************************/ +static crc_t crc_update_bytewise(crc_t crc, const unsigned char *data, size_t data_len) +{ + unsigned int tbl_idx; + + while (data_len--) { + tbl_idx = ((crc >> 7) ^ *data) & 0xff; + crc = (crc_table[tbl_idx] ^ (crc << 8)) & 0x7fff; + + data++; + } + return crc & 0x7fff; +} + +/** + * Update the crc value with new data. + * + * \param crc The current crc value. + * \param data Data value + * \param bits The number of most significant bits in data used for CRC calculation + * \return The updated crc value. + *****************************************************************************/ +static crc_t crc_update_bitwise(crc_t crc, uint8_t data, size_t bits) +{ + uint8_t i; + bool bit; + + for (i = 0x80; bits--; i >>= 1) { + bit = crc & 0x4000; + if (data & i) { + bit = !bit; + } + crc <<= 1; + if (bit) { + crc ^= 0x4599; + } + } + return crc & 0x7fff; +} + +static crc_t calc_bitmap_crc(uint8_t *bitmap, unsigned start, unsigned end) +{ + crc_t crc = 0; + + if (start % 8) { + crc = crc_update_bitwise(crc, bitmap[start / 8] << (start % 8), 8 - start % 8); + start += 8 - start % 8; + } + crc = crc_update_bytewise(crc, &bitmap[start / 8], (end - start) / 8); + crc = crc_update_bitwise(crc, bitmap[end / 8], end % 8); + return crc; +} + +static unsigned cfl_exact(struct can_frame *frame) +{ + uint8_t bitmap[16]; + unsigned start = 0, end; + crc_t crc; + uint16_t crc_be; + uint8_t mask, lookfor; + unsigned i, stuffed; + const int8_t clz[32] = /* count of leading zeros in 5 bit numbers */ + { 5, 4, 3, 3, 2, 2, 2, 2, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; + + /* Prepare bitmap */ + memset(bitmap, 0, sizeof(bitmap)); + if (frame->can_id & CAN_EFF_FLAG) { + /* bit 7 0 7 0 7 0 7 0 + * bitmap[0-3] |.sBBBBBB BBBBBSIE EEEEEEEE EEEEEEEE| s = SOF, B = Base ID (11 bits), S = SRR, I = IDE, E = Extended ID (18 bits) + * bitmap[4-7] |ER10DLC4 00000000 11111111 22222222| R = RTR, 0 = r0, 1 = r1, DLC4 = DLC, Data bytes + * bitmap[8-11] |33333333 44444444 55555555 66666666| Data bytes + * bitmap[12-15] |77777777 ........ ........ ........| Data bytes + */ + bitmap[0] = (frame->can_id & CAN_EFF_MASK) >> 23; + bitmap[1] = ((frame->can_id >> 18) & 0x3f) << 3 | + 3 << 1 | /* SRR, IDE */ + ((frame->can_id >> 17) & 0x01); + bitmap[2] = (frame->can_id >> 9) & 0xff; + bitmap[3] = (frame->can_id >> 1) & 0xff; + bitmap[4] = (frame->can_id & 0x1) << 7 | + (!!(frame->can_id & CAN_RTR_FLAG)) << 6 | + 0 << 4 | /* r1, r0 */ + (frame->can_dlc & 0xf); + memcpy(&bitmap[5], &frame->data, frame->can_dlc); + start = 1; + end = 40 + 8*frame->can_dlc; + } else { + /* bit 7 0 7 0 7 0 7 0 + * bitmap[0-3] |.....sII IIIIIIII IRE0DLC4 00000000| s = SOF, I = ID (11 bits), R = RTR, E = IDE, DLC4 = DLC + * bitmap[4-7] |11111111 22222222 33333333 44444444| Data bytes + * bitmap[8-11] |55555555 66666666 77777777 ........| Data bytes + */ + bitmap[0] = (frame->can_id & CAN_SFF_MASK) >> 9; + bitmap[1] = (frame->can_id >> 1) & 0xff; + bitmap[2] = ((frame->can_id << 7) & 0xff) | + (!!(frame->can_id & CAN_RTR_FLAG)) << 6 | + 0 << 4 | /* IDE, r0 */ + (frame->can_dlc & 0xf); + memcpy(&bitmap[3], &frame->data, frame->can_dlc); + start = 5; + end = 24 + 8 * frame->can_dlc; + } + + /* Calc and append CRC */ + crc = calc_bitmap_crc(bitmap, start, end); + crc_be = htons(crc << 1); + assert(end % 8 == 0); + memcpy(bitmap + end / 8, &crc_be, 2); + end += 15; + + /* Count stuffed bits */ + mask = 0x1f; + lookfor = 0; + i = start; + stuffed = 0; + while (i < end) { + unsigned change; + unsigned bits = (bitmap[i / 8] << 8 | bitmap[i / 8 + 1]) >> (16 - 5 - i % 8); + lookfor = lookfor ? 0 : mask; /* We alternate between looking for a series of zeros or ones */ + change = (bits & mask) ^ lookfor; /* 1 indicates a change */ + if (change) { /* No bit was stuffed here */ + i += clz[change]; + mask = 0x1f; /* Next look for 5 same bits */ + } else { + i += (mask == 0x1f) ? 5 : 4; + if (i <= end) { + stuffed++; + mask = 0x1e; /* Next look for 4 bits (5th bit is the stuffed one) */ + } + } + } + return end - start + stuffed + + 3 + /* CRC del, ACK, ACK del */ + 7 + /* EOF */ + 3; /* IFS */ +} + + +unsigned can_frame_length(struct canfd_frame *frame, enum cfl_mode mode, int mtu) +{ + int eff = (frame->can_id & CAN_EFF_FLAG); + + if (mtu != CAN_MTU) + return 0; /* CANFD is not supported yet */ + + switch (mode) { + case CFL_NO_BITSTUFFING: + return (eff ? 67 : 47) + frame->len * 8; + case CFL_WORSTCASE: + return (eff ? 80 : 55) + frame->len * 10; + case CFL_EXACT: + return cfl_exact((struct can_frame*)frame); + } + return 0; /* Unknown mode */ +} + +#ifdef __cplusplus +} +#endif diff --git a/src/main/native/include/can-utils/canframelen.h b/src/main/native/include/can-utils/canframelen.h new file mode 100644 index 0000000..0384b28 --- /dev/null +++ b/src/main/native/include/can-utils/canframelen.h @@ -0,0 +1,93 @@ +/* SPDX-License-Identifier: (GPL-2.0-only OR BSD-3-Clause) */ +/* + * canframelen.h + * + * Copyright (c) 2013, 2014 Czech Technical University in Prague + * + * Author: Michal Sojka + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of Czech Technical University in Prague nor the + * names of its contributors may be used to endorse or promote + * products derived from this software without specific prior + * written permission. + * + * Alternatively, provided that this notice is retained in full, this + * software may be distributed under the terms of the GNU General + * Public License ("GPL") version 2, in which case the provisions of the + * GPL apply INSTEAD OF those given above. + * + * The provided data structures and external interfaces from this code + * are not restricted to be used by modules with a GPL compatible license. + * + * 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 + * OWNER 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. + * + * Send feedback to + * + */ + +#ifndef CANFRAMELEN_H +#define CANFRAMELEN_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Frame length calculation modes. + * + * CFL_WORSTCASE corresponds to *worst* case calculation for + * stuff-bits - see (1)-(3) in [1]. The worst case number of bits on + * the wire can be calculated as: + * + * (34 + 8n - 1)/4 + 34 + 8n + 13 for SFF frames (11 bit CAN-ID) => 55 + 10n + * (54 + 8n - 1)/4 + 54 + 8n + 13 for EFF frames (29 bit CAN-ID) => 80 + 10n + * + * while 'n' is the data length code (number of payload bytes) + * + * [1] "Controller Area Network (CAN) schedulability analysis: + * Refuted, revisited and revised", Real-Time Syst (2007) + * 35:239-272. + * + */ +enum cfl_mode { + CFL_NO_BITSTUFFING, /* plain bit calculation without bitstuffing */ + CFL_WORSTCASE, /* worst case estimation - see above */ + CFL_EXACT, /* exact calculation of stuffed bits based on frame + * content and CRC */ +}; + +/** + * Calculates the number of bits a frame needs on the wire (including + * inter frame space). + * + * Mode determines how to deal with stuffed bits. + */ +unsigned can_frame_length(struct canfd_frame *frame, enum cfl_mode mode, int mtu); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/src/main/native/include/rev/CANBridge.h b/src/main/native/include/rev/CANBridge.h index 3047b50..6e6af04 100644 --- a/src/main/native/include/rev/CANBridge.h +++ b/src/main/native/include/rev/CANBridge.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/CANBridgeUtils.h b/src/main/native/include/rev/CANBridgeUtils.h index 6431ff0..ec19dae 100644 --- a/src/main/native/include/rev/CANBridgeUtils.h +++ b/src/main/native/include/rev/CANBridgeUtils.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/CANDevice.h b/src/main/native/include/rev/CANDevice.h index 7d79bb9..65901eb 100644 --- a/src/main/native/include/rev/CANDevice.h +++ b/src/main/native/include/rev/CANDevice.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/CANDriver.h b/src/main/native/include/rev/CANDriver.h index 937a85d..fc58bbe 100644 --- a/src/main/native/include/rev/CANDriver.h +++ b/src/main/native/include/rev/CANDriver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/CANMessage.h b/src/main/native/include/rev/CANMessage.h index 2d75565..98e3f03 100644 --- a/src/main/native/include/rev/CANMessage.h +++ b/src/main/native/include/rev/CANMessage.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/CANStatus.h b/src/main/native/include/rev/CANStatus.h index 1382e6b..a1895dc 100644 --- a/src/main/native/include/rev/CANStatus.h +++ b/src/main/native/include/rev/CANStatus.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDevice.h b/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDevice.h index 39c7fef..177dc25 100644 --- a/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDevice.h +++ b/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDevice.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDeviceThread.h b/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDeviceThread.h index 78f3f62..564f391 100644 --- a/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDeviceThread.h +++ b/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDeviceThread.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDriver.h b/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDriver.h index d431a5b..97cc99f 100644 --- a/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDriver.h +++ b/src/main/native/include/rev/Drivers/CandleWinUSB/CandleWinUSBDriver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/Drivers/DriverDeviceThread.h b/src/main/native/include/rev/Drivers/DriverDeviceThread.h index e643b6b..6389157 100644 --- a/src/main/native/include/rev/Drivers/DriverDeviceThread.h +++ b/src/main/native/include/rev/Drivers/DriverDeviceThread.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/Drivers/SerialPort/SerialDevice.h b/src/main/native/include/rev/Drivers/SerialPort/SerialDevice.h index b507c01..4955efe 100644 --- a/src/main/native/include/rev/Drivers/SerialPort/SerialDevice.h +++ b/src/main/native/include/rev/Drivers/SerialPort/SerialDevice.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/Drivers/SerialPort/SerialDeviceThread.h b/src/main/native/include/rev/Drivers/SerialPort/SerialDeviceThread.h index ade3551..73a4a1f 100644 --- a/src/main/native/include/rev/Drivers/SerialPort/SerialDeviceThread.h +++ b/src/main/native/include/rev/Drivers/SerialPort/SerialDeviceThread.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/Drivers/SerialPort/SerialDriver.h b/src/main/native/include/rev/Drivers/SerialPort/SerialDriver.h index b1f4e18..f560884 100644 --- a/src/main/native/include/rev/Drivers/SerialPort/SerialDriver.h +++ b/src/main/native/include/rev/Drivers/SerialPort/SerialDriver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/Drivers/SerialPort/SerialMessage.h b/src/main/native/include/rev/Drivers/SerialPort/SerialMessage.h index 90c404f..4121400 100644 --- a/src/main/native/include/rev/Drivers/SerialPort/SerialMessage.h +++ b/src/main/native/include/rev/Drivers/SerialPort/SerialMessage.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h new file mode 100644 index 0000000..b255c35 --- /dev/null +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h @@ -0,0 +1,71 @@ +/* + * Copyright (c) 2019 - 2020 REV Robotics + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of REV Robotics 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 OWNER 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. + */ + +#pragma once + +#include +#include + +#include "rev/Drivers/SocketCAN/SocketCANThread.h" +#include "rev/CANDevice.h" +#include "rev/CANMessage.h" +#include "rev/CANStatus.h" + +namespace rev { +namespace usb { + +class SocketCANDevice : public CANDevice { +public: + SocketCANDevice() =delete; + SocketCANDevice(const char* port); + virtual ~SocketCANDevice(); + + virtual std::string GetName() const; + virtual std::string GetDescriptor() const; + virtual int GetNumberOfErrors(); + + virtual int GetId() const; + + virtual CANStatus SendCANMessage(const CANMessage& msg, int periodMs) override; + virtual CANStatus ReceiveCANMessage(std::shared_ptr& msg, uint32_t messageID, uint32_t messageMask) override; + virtual CANStatus OpenStreamSession(uint32_t* sessionHandle, CANBridge_CANFilter filter, uint32_t maxSize) override; + virtual CANStatus CloseStreamSession(uint32_t sessionHandle); + virtual CANStatus ReadStreamSession(uint32_t sessionHandle, HAL_CANStreamMessage* msgs, uint32_t messagesToRead, uint32_t* messagesRead); + + virtual CANStatus GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr); + + virtual bool IsConnected(); +private: + candle_handle m_handle; + SocketCANDeviceThread m_thread; + std::string m_descriptor; + std::string m_name; +}; + +} // namespace usb +} // namespace rev diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDriver.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDriver.h new file mode 100644 index 0000000..dd12edb --- /dev/null +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDriver.h @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2019 - 2020 REV Robotics + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of REV Robotics 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 OWNER 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. + */ + +#pragma once + +#include +#include + +#include "rev/CANDriver.h" + +namespace rev { +namespace usb { + +class SocketCANDriver : public CANDriver { +public: + SocketCANDriver() {} + virtual ~SocketCANDriver() override {} + + virtual std::string GetName() const {return "SocketCAN";} + + virtual std::vector GetDevices() override; + virtual std::unique_ptr CreateDeviceFromDescriptor(const char* descriptor) override; +}; + +} // namespace usb +} // namespace rev diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h new file mode 100644 index 0000000..3d0ed56 --- /dev/null +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h @@ -0,0 +1,217 @@ +/* + * Copyright (c) 2019 - 2020 REV Robotics + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name of REV Robotics 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 OWNER 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. + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include + +// TODO: remove me +#include +#include +#include + +#include "rev/CANMessage.h" +#include "rev/CANBridgeUtils.h" +#include "rev/CANStatus.h" +#include "rev/Drivers/DriverDeviceThread.h" + +#include "utils/ThreadUtils.h" + +#include "candlelib/candle.h" + +#include +#include + +namespace rev { +namespace usb { + + +class SocketCANDeviceThread :public DriverDeviceThread { +public: + SocketCANDeviceThread() =delete; + SocketCANDeviceThread(const char* port, long long threadIntervalMs = 1) : DriverDeviceThread(0xe45b5597, threadIntervalMs) + { } + ~SocketCANDeviceThread() + { + } + + void Start() override { + if (m_thread.get() != nullptr && m_thread->joinable()) { + m_thread->join(); + } + + m_thread = std::make_unique(&SocketCANDeviceThread::CandleRun, this); + + // Set to high priority to prevent buffer overflow on the device on high client CPU load + utils::SetThreadPriority(m_thread.get(), utils::ThreadPriority::High); + } + + void OpenStream(uint32_t* handle, CANBridge_CANFilter filter, uint32_t maxSize, CANStatus *status) override { + std::lock_guard lock(m_streamMutex); + + // Create the handle + *handle = m_counter++; + + // Add to the map + m_readStream[*handle] = std::unique_ptr(new CANStreamHandle{filter.messageId, filter.messageMask, maxSize, utils::CircularBuffer>{maxSize}}); + + *status = CANStatus::kOk; + } + + + +private: + candle_handle m_device; + + void ReadMessages(bool &reading) { + candle_frame_t incomingFrame; + + reading = candle_frame_read(m_device, &incomingFrame, 0); + + // Received a new frame, store it + if (reading) { + candle_frametype_t frameType = candle_frame_type(&incomingFrame); + if(frameType == CANDLE_FRAMETYPE_ERROR) { + // Parse error data + if (incomingFrame.can_id & 0x00000040) { + m_statusDetails.busOffCount++; + } + if (incomingFrame.data[1] & 0x02) { + m_statusDetails.txFullCount++; + } + if (incomingFrame.data[1] & 0x10 || incomingFrame.data[1] & 0x04) { + m_statusDetails.receiveErrCount++; + } + if (incomingFrame.data[1] & 0x20 || incomingFrame.data[1] & 0x08 || incomingFrame.data[2] & 0x80 || incomingFrame.data[4]) { + m_statusDetails.transmitErrCount++; + } + } else if(frameType == CANDLE_FRAMETYPE_RECEIVE) { + + auto msg = std::make_shared(candle_frame_id(&incomingFrame), + candle_frame_data(&incomingFrame), + candle_frame_dlc(&incomingFrame), + candle_frame_timestamp_us(&incomingFrame)); + + // Read functions + { + std::lock_guard lock(m_readMutex); + m_readStore[candle_frame_id(&incomingFrame)] = msg; + } + + // Streaming functions + { + std::lock_guard lock(m_streamMutex); + for (auto& stream : m_readStream) { + // Compare current size of the buffer to the max size of the buffer + if (!stream.second->messages.IsFull() + && rev::usb::CANBridge_ProcessMask({stream.second->messageId, stream.second->messageMask}, + msg->GetMessageId())) { + stream.second->messages.Add(msg); + } + } + } + } + + m_threadStatus = CANStatus::kOk; + } + } + + bool WriteMessages(detail::CANThreadSendQueueElement el, std::chrono::steady_clock::time_point now) { + if (el.m_intervalMs == 0 || (now - el.m_prevTimestamp >= std::chrono::milliseconds(el.m_intervalMs)) ) { + candle_frame_t frame; + frame.can_dlc = el.m_msg.GetSize(); + // set extended id flag + frame.can_id = el.m_msg.GetMessageId() | 0x80000000; + memcpy(frame.data, el.m_msg.GetData(), frame.can_dlc); + frame.timestamp_us = now.time_since_epoch().count() / 1000; + + // TODO: Feed back an error + if (candle_frame_send(m_device, 0, &frame, false, 20) == false) { + // std::cout << "Failed to send message: " << std::hex << (int)el.m_msg.GetMessageId() << std::dec << " " << candle_error_text(candle_dev_last_error(m_device)) << std::endl; + m_threadStatus = CANStatus::kDeviceWriteError; + m_statusErrCount++; + return false; + } else { + m_threadStatus = CANStatus::kOk; + return true; + } + } + return false; + } + + void CandleRun() { + while (m_threadComplete == false) { + m_threadStatus = CANStatus::kOk; // Start each loop with the status being good. Really only a write issue. + auto sleepTime = std::chrono::steady_clock::now() + std::chrono::milliseconds(m_threadIntervalMs); + + // 1) Handle all received CAN traffic + bool reading = false; + ReadMessages(reading); + + // 2) Schedule CANMessage queue + { + std::lock_guard lock(m_writeMutex); + if (m_sendQueue.size() > 0) { + detail::CANThreadSendQueueElement el = m_sendQueue.front(); + if (el.m_intervalMs == -1) { + m_sendQueue.pop(); + continue; + } + + auto now = std::chrono::steady_clock::now(); + + // Don't pop queue if send fails + if (WriteMessages(el, now)) { + m_sendQueue.pop(); + + // Return to end of queue if repeated + if (el.m_intervalMs > 0 ) { + el.m_prevTimestamp = now; + m_sendQueue.push(el); + } + } + } + } + + // 3) Stall thread + if (!reading && m_sendQueue.empty()) { + std::this_thread::sleep_until(sleepTime); + } + } + + } +}; + +} // namespace usb +} // namespace rev diff --git a/src/main/native/include/utils/CircularBuffer.h b/src/main/native/include/utils/CircularBuffer.h index c9d9cac..ead6629 100644 --- a/src/main/native/include/utils/CircularBuffer.h +++ b/src/main/native/include/utils/CircularBuffer.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/main/native/include/utils/ThreadUtils.h b/src/main/native/include/utils/ThreadUtils.h index f6b517b..2090071 100644 --- a/src/main/native/include/utils/ThreadUtils.h +++ b/src/main/native/include/utils/ThreadUtils.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: diff --git a/src/test/gtest/cpp/main.cpp b/src/test/gtest/cpp/main.cpp index 9c3f256..5f2875f 100644 --- a/src/test/gtest/cpp/main.cpp +++ b/src/test/gtest/cpp/main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2019 REV Robotics + * Copyright (c) 2019 - 2020 REV Robotics * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: From 9d6398a61080c5d0a86d3b2da097364ff6cb15aa Mon Sep 17 00:00:00 2001 From: Will Toth Date: Wed, 25 Mar 2020 01:30:51 -0500 Subject: [PATCH 02/55] Simple method to list available drivers --- src/main/native/cpp/CANBridge.cpp | 5 ++- .../cpp/Drivers/SocketCAN/SocketCANDriver.cpp | 36 +++++++++++++++++-- .../rev/Drivers/SocketCAN/SocketCANDevice.h | 3 +- .../rev/Drivers/SocketCAN/SocketCANThread.h | 4 +++ src/test/gtest/cpp/CANMessageTest.cpp | 3 +- src/test/gtest/cpp/main.cpp | 24 +++++++++++++ 6 files changed, 68 insertions(+), 7 deletions(-) diff --git a/src/main/native/cpp/CANBridge.cpp b/src/main/native/cpp/CANBridge.cpp index 33fe438..19dbd09 100644 --- a/src/main/native/cpp/CANBridge.cpp +++ b/src/main/native/cpp/CANBridge.cpp @@ -60,8 +60,11 @@ struct CANBridge_Scan { static const std::vector CANDriverList = { #ifdef _WIN32 new rev::usb::CandleWinUSBDriver(), -#endif new rev::usb::SerialDriver() +#endif +#ifdef __linux__ + //new rev::usb::SocketCANDriver() +#endif }; static std::vector, rev::usb::CANBridge_CANFilter>> CANDeviceList = {}; diff --git a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp index d1ce4f6..205aab7 100644 --- a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp +++ b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp @@ -35,6 +35,8 @@ #include #include +#include + namespace rev { namespace usb { @@ -42,19 +44,47 @@ std::vector SocketCANDriver::GetDevices() { std::vector retval; + // TODO: Better way of doing this? + // find canx or vcanx interface names + struct if_nameindex *if_nidxs, *intf; + + if_nidxs = if_nameindex(); + if ( if_nidxs != NULL ) + { + for (intf = if_nidxs; intf->if_index != 0 || intf->if_name != NULL; intf++) + { + char* buf = intf->if_name; + + // Not possible can name, protect later compares + if (strnlen(buf, 4) < 4) { + continue; + } + + // possibly vcanx + if (buf[0] == 'v') { + buf++; + } + + if (strncmp(buf, "can", 3) == 0) { + std::string ifnameStr = std::string(intf->if_name); + retval.push_back( {ifnameStr, ifnameStr, this->GetName()} ); + } + } + + if_freenameindex(if_nidxs); + } + return retval; } std::unique_ptr SocketCANDriver::CreateDeviceFromDescriptor(const char* descriptor) { - uint8_t num_interfaces; - try { return std::make_unique(descriptor); } catch(...) { // do nothing if it failed } - return std::unique_ptr(); + return std::unique_ptr(nullptr); } } // namespace usb diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h index b255c35..f7c5c8e 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h @@ -61,8 +61,7 @@ class SocketCANDevice : public CANDevice { virtual bool IsConnected(); private: - candle_handle m_handle; - SocketCANDeviceThread m_thread; + //SocketCANDeviceThread m_thread; std::string m_descriptor; std::string m_name; }; diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h index 3d0ed56..00b3e6c 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h @@ -26,6 +26,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ +#if 0 + #pragma once #include @@ -215,3 +217,5 @@ class SocketCANDeviceThread :public DriverDeviceThread { } // namespace usb } // namespace rev + +#endif diff --git a/src/test/gtest/cpp/CANMessageTest.cpp b/src/test/gtest/cpp/CANMessageTest.cpp index 6280788..ced27ef 100644 --- a/src/test/gtest/cpp/CANMessageTest.cpp +++ b/src/test/gtest/cpp/CANMessageTest.cpp @@ -41,6 +41,7 @@ */ TEST(CANMessageTest, SendAndReceive) { auto handle = CANBridge_Scan(); + int32_t status = 0; int numDevices = CANBridge_NumDevices(handle); @@ -52,7 +53,7 @@ TEST(CANMessageTest, SendAndReceive) { if (numDevices > 0) { std::cout << "Registering single device to HAL" << std::endl; - CANBridge_RegisterDeviceToHAL(CANBridge_GetDeviceDescriptor(handle, 0), 0, 0); + CANBridge_RegisterDeviceToHAL(CANBridge_GetDeviceDescriptor(handle, 0), 0, 0, &status); // auto device = handle->devices[0]; diff --git a/src/test/gtest/cpp/main.cpp b/src/test/gtest/cpp/main.cpp index 5f2875f..cdb64cc 100644 --- a/src/test/gtest/cpp/main.cpp +++ b/src/test/gtest/cpp/main.cpp @@ -32,8 +32,31 @@ #include "gtest/gtest.h" +#include + int main(int argc, char** argv) { + + rev::usb::SocketCANDriver driver; + + auto output = driver.GetDevices(); + + if (output.size() == 0) { + std::cout << "No devices found" << std::endl; + return 1; + } + + for (auto itr = output.begin(); itr != output.end(); itr++) { + std::cout << itr->descriptor << std::endl; + } + + auto device = driver.CreateDeviceFromDescriptor(output[0].descriptor.c_str()); + + std::cout << "Selected device: " << device->GetName() << std::endl; + + return 0; + + #if 0 HAL_Initialize(500, 0); frc::MockDS ds; ds.start(); @@ -43,4 +66,5 @@ int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); int ret = RUN_ALL_TESTS(); return ret; + #endif } From 54e804a03fdab50834c037f8aad4c0230a3d1f73 Mon Sep 17 00:00:00 2001 From: William Toth Date: Tue, 28 Jul 2020 19:19:49 -0500 Subject: [PATCH 03/55] Update README.md --- README.md | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/README.md b/README.md index 223fce8..4c674e7 100644 --- a/README.md +++ b/README.md @@ -26,6 +26,16 @@ Build and publish steps are done using the Gradle wrapper, `gradlew`. The Gradle The output folders will be generated under `~\releases\maven\`. +## Linux + +This branch is a work in progress. The latest firmware version will work with Linux if the socketCAN and gs_usb drivers are enabled. The following udev rule will work to enable this: + +/etc/udev/rules.d/ + +``` +ACTION=="add", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="a30e", RUN+="/sbin/modprobe gs_usb" RUN+="/bin/sh -c 'echo 0483 a30e > /sys/bus/usb/drivers/gs_usb/new_id'" +``` + ## Changelog The SDK Changelog can be viewed with [Changelog.md](Changelog.md). From e1a821765376ee398aba148a53264fa8e5fc919f Mon Sep 17 00:00:00 2001 From: Moose1301 <40875577+Moose1301@users.noreply.github.com> Date: Sat, 11 May 2024 15:23:56 -0400 Subject: [PATCH 04/55] Made SerialDevice complie when linux Note you might need to complie wpilib your self to complie this yourself this is due to wpilib not compling for all versions of linux in the maven repo --- .vscode/settings.json | 3 ++- CANBridge.code-workspace | 4 +++- gradlew | 0 src/main/native/cpp/Drivers/Serial/SerialDevice.cpp | 2 +- src/main/native/cpp/Drivers/Serial/SerialDriver.cpp | 2 +- src/main/native/cpp/serial/unix.cc | 4 +++- src/main/native/include/rev/Drivers/DriverDeviceThread.h | 4 +++- 7 files changed, 13 insertions(+), 6 deletions(-) mode change 100644 => 100755 gradlew diff --git a/.vscode/settings.json b/.vscode/settings.json index 47280d7..53cde3b 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -70,5 +70,6 @@ "cctype": "cpp", "concepts": "cpp" }, - "C_Cpp.default.configurationProvider": "vscode-wpilib" + "C_Cpp.default.configurationProvider": "vscode-wpilib", + "C_Cpp.errorSquiggles": "enabled" } \ No newline at end of file diff --git a/CANBridge.code-workspace b/CANBridge.code-workspace index d1180f3..b496e2a 100644 --- a/CANBridge.code-workspace +++ b/CANBridge.code-workspace @@ -75,7 +75,9 @@ "list": "cpp", "set": "cpp", "unordered_map": "cpp", - "xhash": "cpp" + "xhash": "cpp", + "stdlib.h": "c", + "candle.h": "c" }, "java.configuration.updateBuildConfiguration": "disabled" } diff --git a/gradlew b/gradlew old mode 100644 new mode 100755 diff --git a/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp b/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp index c227b07..d65d9f2 100644 --- a/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp +++ b/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp @@ -26,7 +26,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifdef _WIN32 +#if !defined(_WIN32) #include "rev/Drivers/SerialPort/SerialDevice.h" diff --git a/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp b/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp index 1be761f..be13544 100644 --- a/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp +++ b/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp @@ -26,7 +26,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifdef _WIN32 +#if !defined(_WIN32) #include "rev/Drivers/SerialPort/SerialDriver.h" #include "rev/Drivers/SerialPort/SerialDevice.h" diff --git a/src/main/native/cpp/serial/unix.cc b/src/main/native/cpp/serial/unix.cc index 4283548..8f402f4 100644 --- a/src/main/native/cpp/serial/unix.cc +++ b/src/main/native/cpp/serial/unix.cc @@ -442,7 +442,7 @@ Serial::SerialImpl::reconfigurePort () // activate settings ::tcsetattr (fd_, TCSANOW, &options); - +#pragma GCC diagnostic ignored "-Wdeprecated-enum-float-conversion" // Update byte_time_ based on the new settings. uint32_t bit_time_ns = 1e9 / baudrate_; byte_time_ns_ = bit_time_ns * (1 + bytesize_ + parity_ + stopbits_); @@ -452,6 +452,8 @@ Serial::SerialImpl::reconfigurePort () if (stopbits_ == stopbits_one_point_five) { byte_time_ns_ += ((1.5 - stopbits_one_point_five) * bit_time_ns); } + #pragma GCC diagnostic ignored "-Wunused-result" + #pragma GCC diagnostic pop } void diff --git a/src/main/native/include/rev/Drivers/DriverDeviceThread.h b/src/main/native/include/rev/Drivers/DriverDeviceThread.h index b01d7ff..93551e1 100644 --- a/src/main/native/include/rev/Drivers/DriverDeviceThread.h +++ b/src/main/native/include/rev/Drivers/DriverDeviceThread.h @@ -52,7 +52,9 @@ namespace rev { namespace usb { - +#pragma GCC diagnostic ignored "-Wunused-but-set-parameter" +#pragma GCC diagnostic ignored "-Wsign-compare" +#pragma GCC diagnostic ignored "-Wreorder" class DriverDeviceThread { public: /** From 2fcc6c99d63dc6c7998a7ebee5e0137a35417701 Mon Sep 17 00:00:00 2001 From: Moose1301 <40875577+Moose1301@users.noreply.github.com> Date: Sat, 11 May 2024 16:15:37 -0400 Subject: [PATCH 05/55] Fix compling on windows --- .gitignore | 3 +++ src/main/native/cpp/Drivers/Serial/SerialDevice.cpp | 5 +---- src/main/native/cpp/Drivers/Serial/SerialDriver.cpp | 6 +----- src/main/native/cpp/serial/unix.cc | 5 ++--- src/main/native/include/rev/Drivers/DriverDeviceThread.h | 4 +--- 5 files changed, 8 insertions(+), 15 deletions(-) diff --git a/.gitignore b/.gitignore index 3ee5560..66da153 100644 --- a/.gitignore +++ b/.gitignore @@ -160,3 +160,6 @@ bin/ # End of https://www.gitignore.io/api/c++,java,linux,macos,gradle,windows,visualstudiocode /docs/ + +#Intellji +.idea/ \ No newline at end of file diff --git a/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp b/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp index d65d9f2..29d1428 100644 --- a/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp +++ b/src/main/native/cpp/Drivers/Serial/SerialDevice.cpp @@ -26,7 +26,6 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#if !defined(_WIN32) #include "rev/Drivers/SerialPort/SerialDevice.h" @@ -156,6 +155,4 @@ bool SerialDevice::IsConnected() } // namespace usb } // namespace rev -#else -typedef int __ISOWarning__CLEAR_; -#endif // _WIN32 + diff --git a/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp b/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp index be13544..16e74db 100644 --- a/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp +++ b/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp @@ -26,7 +26,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#if !defined(_WIN32) + #include "rev/Drivers/SerialPort/SerialDriver.h" #include "rev/Drivers/SerialPort/SerialDevice.h" @@ -81,7 +81,3 @@ std::unique_ptr SerialDriver::CreateDeviceFromDescriptor(const char* } // namespace usb } // namespace rev - -#else -typedef int __ISOWarning__CLEAR_; -#endif // _WIN32 diff --git a/src/main/native/cpp/serial/unix.cc b/src/main/native/cpp/serial/unix.cc index 8f402f4..76cc41a 100644 --- a/src/main/native/cpp/serial/unix.cc +++ b/src/main/native/cpp/serial/unix.cc @@ -442,7 +442,7 @@ Serial::SerialImpl::reconfigurePort () // activate settings ::tcsetattr (fd_, TCSANOW, &options); -#pragma GCC diagnostic ignored "-Wdeprecated-enum-float-conversion" + // Update byte_time_ based on the new settings. uint32_t bit_time_ns = 1e9 / baudrate_; byte_time_ns_ = bit_time_ns * (1 + bytesize_ + parity_ + stopbits_); @@ -452,8 +452,7 @@ Serial::SerialImpl::reconfigurePort () if (stopbits_ == stopbits_one_point_five) { byte_time_ns_ += ((1.5 - stopbits_one_point_five) * bit_time_ns); } - #pragma GCC diagnostic ignored "-Wunused-result" - #pragma GCC diagnostic pop + } void diff --git a/src/main/native/include/rev/Drivers/DriverDeviceThread.h b/src/main/native/include/rev/Drivers/DriverDeviceThread.h index 93551e1..b01d7ff 100644 --- a/src/main/native/include/rev/Drivers/DriverDeviceThread.h +++ b/src/main/native/include/rev/Drivers/DriverDeviceThread.h @@ -52,9 +52,7 @@ namespace rev { namespace usb { -#pragma GCC diagnostic ignored "-Wunused-but-set-parameter" -#pragma GCC diagnostic ignored "-Wsign-compare" -#pragma GCC diagnostic ignored "-Wreorder" + class DriverDeviceThread { public: /** From cf8ec56b366b30a64331002550d7438233182851 Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Mon, 10 Jun 2024 23:05:47 -0700 Subject: [PATCH 06/55] CI: Initial build config for macOS and Linux for both x86-64 and arm64 --- .github/workflows/build.yml | 75 ++++++++++++++++++++++++++++++++++- .github/workflows/release.yml | 34 +++++++++++++++- 2 files changed, 106 insertions(+), 3 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 545aa9c..53c5e30 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -22,6 +22,18 @@ jobs: - os: windows-latest container: '' name: windows64 + - os: ubuntu-latest + container: '' + name: linux64 +# - os: ubuntu-latest-arm64 +# container: '' +# name: linuxarm64 + - os: macos-latest + container: '' + name: macosarm64 + - os: macos-13 + container: '' + name: macosintel64 name: "build-${{ matrix.name }}" runs-on: ${{ matrix.os }} container: ${{ matrix.container }} @@ -53,21 +65,45 @@ jobs: ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode - name: Download WPILib HAL artifacts and headers, gather all needed headers + if: contains(matrix.name, 'windows64') run : | halVersion=$(cat wpiHalVersion.txt) # Download WPILib artifacts from Artifactory halWindowsUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-windowsx86-64.zip + halMacUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-osxuniversal.zip + halLinux64Url=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-linuxx86-64.zip + halLinuxArmUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-linuxarm64.zip halHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-headers.zip + utilWindowsUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-windowsx86-64.zip + utilMacUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-osxuniversal.zip + utilLinux64Url=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-linuxx86-64.zip + utilLinuxArmUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-linuxarm64.zip utilHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-headers.zip + curl -o halWindows.zip "$halWindowsUrl" + curl -o halMac.zip "$halMacUrl" + curl -o halLinux64.zip "$halLinux64Url" + curl -o halLinuxArm.zip "$halLinuxArmUrl" curl -o halHeaders.zip "$halHeadersUrl" + curl -o utilWindows.zip "$utilWindowsUrl" + curl -o utilMac.zip "$utilMacUrl" + curl -o utilLinux64.zip "$utilLinux64Url" + curl -o utilLinuxArm.zip "$utilLinuxArmUrl" curl -o utilHeaders.zip "$utilHeadersUrl" + unzip halWindows.zip -d halWindows + unzip halMac.zip -d halMac + unzip halLinux64.zip -d halLinux64 + unzip halLinuxArm.zip -d halLinuxArm unzip halHeaders.zip -d halHeaders + unzip utilWindows.zip -d utilWindows + unzip utilMac.zip -d utilMac + unzip utilLinux64.zip -d utilLinux64 + unzip utilLinuxArm.zip -d utilLinuxArm unzip utilHeaders.zip -d utilHeaders # Gather all of the the needed headers @@ -81,16 +117,53 @@ jobs: 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* # Put release files together in one directory - - name: Create Artifact + - name: Create Artifact (windows64) + if: contains(matrix.name, 'windows64') run: | mkdir -p CANBridge-artifacts cp build/libs/cANBridge/static/windowsx86-64/release/CANBridge.lib CANBridge-artifacts/CANBridge-static.lib cp build/libs/cANBridge/shared/windowsx86-64/release/CANBridge.dll CANBridge-artifacts/CANBridge.dll cp build/libs/cANBridge/shared/windowsx86-64/release/CANBridge.lib CANBridge-artifacts/CANBridge.lib + cp halWindows/windows/x86-64/shared/wpiHal.dll CANBridge-artifacts/wpiHal.dll cp halWindows/windows/x86-64/shared/wpiHal.lib CANBridge-artifacts/wpiHal.lib + cp halMac/osx/universal/shared/libwpiHal.dylib CANBridge-artifacts/libwpiHal.dylib + cp halLinux64/linux/x86-64/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so + cp halLinuxArm/linux/arm64/shared/libwpiHal.so CANBridge-artifacts/libwpiHal-arm64.so + cp utilWindows/windows/x86-64/shared/wpiutil.dll CANBridge-artifacts/wpiutil.dll cp utilWindows/windows/x86-64/shared/wpiutil.lib CANBridge-artifacts/wpiutil.lib + cp utilMac/osx/universal/shared/libwpiutil.dylib CANBridge-artifacts/libwpiutil.dylib + cp utilLinux64/linux/x86-64/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so + cp utilLinuxArm/linux/arm64/shared/libwpiutil.so CANBridge-artifacts/libwpiutil-arm64.so + + # Put release files together in one directory + - name: Create Artifact (linux64) + if: contains(matrix.name, 'linux64') + run: | + mkdir -p CANBridge-artifacts + # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 + + # Put release files together in one directory + - name: Create Artifact (linuxarm64) + if: contains(matrix.name, 'linuxarm64') + run: | + mkdir -p CANBridge-artifacts + # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 + + # Put release files together in one directory + - name: Create Artifact (macosarm64) + if: contains(matrix.name, 'macosarm64') + run: | + mkdir -p CANBridge-artifacts + # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 + + # Put release files together in one directory + - name: Create Artifact (macosintel64) + if: contains(matrix.name, 'macosintel64') + run: | + mkdir -p CANBridge-artifacts + # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 # Upload build artifact - name: Upload build artifact diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index 0c00949..cc7bbc1 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -16,13 +16,43 @@ jobs: TAG_NAME: ${{ env.TAG_NAME }} VERSION: ${{ steps.get_version.outputs.version }} steps: - - name: Wait for build to finish - uses: lewagon/wait-on-check-action@v1.3.1 + + - name: Wait for windows64 build to finish + uses: lewagon/wait-on-check-action@v1.3.1 with: ref: ${{ github.ref }} check-name: 'build-windows64' repo-token: ${{ secrets.GITHUB_TOKEN }} wait-interval: 10 + - name: Wait for linux64 build to finish + uses: lewagon/wait-on-check-action@v1.3.1 + with: + ref: ${{ github.ref }} + check-name: 'build-linux64' + repo-token: ${{ secrets.GITHUB_TOKEN }} + wait-interval: 10 +# - name: Wait for linuxarm64 build to finish +# uses: lewagon/wait-on-check-action@v1.3.1 +# with: +# ref: ${{ github.ref }} +# check-name: 'build-linuxarm64' +# repo-token: ${{ secrets.GITHUB_TOKEN }} +# wait-interval: 10 + - name: Wait for macosarm64 build to finish + uses: lewagon/wait-on-check-action@v1.3.1 + with: + ref: ${{ github.ref }} + check-name: 'build-macosarm64' + repo-token: ${{ secrets.GITHUB_TOKEN }} + wait-interval: 10 + - name: Wait for macosintel64 build to finish + uses: lewagon/wait-on-check-action@v1.3.1 + with: + ref: ${{ github.ref }} + check-name: 'build-macosintel64' + repo-token: ${{ secrets.GITHUB_TOKEN }} + wait-interval: 10 + - name: Get tag name run: | echo "TAG_NAME=${GITHUB_REF#refs/*/}" >> $GITHUB_ENV From b4234a7cc12b41fb934cdd7621c592671ca24bc0 Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Mon, 10 Jun 2024 23:51:03 -0700 Subject: [PATCH 07/55] Build: Disable warnings-as-errors There's a lot of warnings that apparently aren't showing up on the Windows build --- config.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config.gradle b/config.gradle index 7a59e9d..a9f4a42 100644 --- a/config.gradle +++ b/config.gradle @@ -14,7 +14,7 @@ nativeUtils { } nativeUtils.wpi.addWarnings() -nativeUtils.wpi.addWarningsAsErrors() +// nativeUtils.wpi.addWarningsAsErrors() nativeUtils.setSinglePrintPerPlatform() From 72fa8d33d5c0a50650b5eb1e7a3e1dc8f3d174c4 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Tue, 11 Jun 2024 20:48:11 -0500 Subject: [PATCH 08/55] Add linker argument for IOKit framework on macOS universal builds Fixes broken CANBridge builds on any macOS platform. --- build.gradle | 3 +++ 1 file changed, 3 insertions(+) diff --git a/build.gradle b/build.gradle index 05e75f8..7c112e2 100644 --- a/build.gradle +++ b/build.gradle @@ -76,6 +76,9 @@ model { } } binaries.all { + if (it.targetPlatform.name == 'osxuniversal') { + linker.args '-framework', 'IOKit' + } if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) { it.buildable = false } From 2d3a57cdbd4867f6baa3ef4b47769e2c1ab99787 Mon Sep 17 00:00:00 2001 From: TBHGodPro Date: Thu, 13 Jun 2024 20:12:07 -0500 Subject: [PATCH 09/55] update build.yml for macosarm64 --- .github/workflows/build.yml | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 53c5e30..23e9556 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -65,7 +65,7 @@ jobs: ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode - name: Download WPILib HAL artifacts and headers, gather all needed headers - if: contains(matrix.name, 'windows64') + # if: contains(matrix.name, 'windows64') run : | halVersion=$(cat wpiHalVersion.txt) @@ -156,7 +156,12 @@ jobs: if: contains(matrix.name, 'macosarm64') run: | mkdir -p CANBridge-artifacts - # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 + cp build/libs/cANBridge/static/osxuniversal/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a + cp build/libs/cANBridge/shard/osxuniversal/release/libCANBridge.dylib CANBridge-artifacts/libCANBridge.dylib + + cp halMac/osx/universal/shared/libwpiHal.dylib CANBridge-artifacts/libwpiHal.dylib + + cp utilMac/osx/universal/shared/libwpiutil.dylib CANBridge-artifacts/libwpiutil.dylib # Put release files together in one directory - name: Create Artifact (macosintel64) From 7ba8b99a884265fb1d442c75d36a8a5a5efa8708 Mon Sep 17 00:00:00 2001 From: TBHGodPro Date: Thu, 13 Jun 2024 20:14:17 -0500 Subject: [PATCH 10/55] patch build gh-workflow for macosarm64 --- .github/workflows/build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 23e9556..fcde4df 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -157,7 +157,7 @@ jobs: run: | mkdir -p CANBridge-artifacts cp build/libs/cANBridge/static/osxuniversal/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a - cp build/libs/cANBridge/shard/osxuniversal/release/libCANBridge.dylib CANBridge-artifacts/libCANBridge.dylib + cp build/libs/cANBridge/shared/osxuniversal/release/libCANBridge.dylib CANBridge-artifacts/libCANBridge.dylib cp halMac/osx/universal/shared/libwpiHal.dylib CANBridge-artifacts/libwpiHal.dylib From 306f141edc0f780a5b1f1468765324de9772a603 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 14 Jun 2024 03:34:58 -0500 Subject: [PATCH 11/55] Update artifact workflows, added macOS artifact creation Updated workflows to better handle artifact uploads. This includes better cleanup of no longer dumping all the possible platforms into the main directory of the CI job, as well as for each platform type, specific artifacts for each platform is made to lower artifact sizes and to be specific to the correct platform. Added other adjustments for platform types across the workflow for future ARM-specific builds Added macOS artifact creation. --- .github/workflows/build.yml | 103 +++++++++++++----------------------- 1 file changed, 36 insertions(+), 67 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index fcde4df..bac7724 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -21,20 +21,25 @@ jobs: include: - os: windows-latest container: '' - name: windows64 + name: Win64 + platform-type: windowsx86-64 - os: ubuntu-latest container: '' - name: linux64 -# - os: ubuntu-latest-arm64 -# container: '' -# name: linuxarm64 + name: Linux64 + platform-type: linuxx86-64 + # - os: ubuntu-latest-arm64 + # container: '' + # name: linuxarm64 + # platform-type: linuxarm64 - os: macos-latest container: '' - name: macosarm64 + name: MacOSARM64 + platform-type: osxuniversal - os: macos-13 container: '' - name: macosintel64 - name: "build-${{ matrix.name }}" + name: MacOS64 + platform-type: osxuniversal + name: "Build - ${{ matrix.name }}" runs-on: ${{ matrix.os }} container: ${{ matrix.container }} steps: @@ -65,45 +70,26 @@ jobs: ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode - name: Download WPILib HAL artifacts and headers, gather all needed headers - # if: contains(matrix.name, 'windows64') run : | halVersion=$(cat wpiHalVersion.txt) # Download WPILib artifacts from Artifactory - halWindowsUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-windowsx86-64.zip - halMacUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-osxuniversal.zip - halLinux64Url=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-linuxx86-64.zip - halLinuxArmUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-linuxarm64.zip + halPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-${{ matrix.platform-type }}.zip halHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-headers.zip - utilWindowsUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-windowsx86-64.zip - utilMacUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-osxuniversal.zip - utilLinux64Url=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-linuxx86-64.zip - utilLinuxArmUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-linuxarm64.zip + utilPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-${{ matrix.platform-type }}.zip utilHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-headers.zip - curl -o halWindows.zip "$halWindowsUrl" - curl -o halMac.zip "$halMacUrl" - curl -o halLinux64.zip "$halLinux64Url" - curl -o halLinuxArm.zip "$halLinuxArmUrl" + curl -o halPlatform.zip "$halPlatformUrl" curl -o halHeaders.zip "$halHeadersUrl" - curl -o utilWindows.zip "$utilWindowsUrl" - curl -o utilMac.zip "$utilMacUrl" - curl -o utilLinux64.zip "$utilLinux64Url" - curl -o utilLinuxArm.zip "$utilLinuxArmUrl" + curl -o utilPlatform.zip "$utilPlatformUrl" curl -o utilHeaders.zip "$utilHeadersUrl" - unzip halWindows.zip -d halWindows - unzip halMac.zip -d halMac - unzip halLinux64.zip -d halLinux64 - unzip halLinuxArm.zip -d halLinuxArm + unzip halPlatform.zip -d halPlatform unzip halHeaders.zip -d halHeaders - unzip utilWindows.zip -d utilWindows - unzip utilMac.zip -d utilMac - unzip utilLinux64.zip -d utilLinux64 - unzip utilLinuxArm.zip -d utilLinuxArm + unzip utilPlatform.zip -d utilPlatform unzip utilHeaders.zip -d utilHeaders # Gather all of the the needed headers @@ -116,65 +102,48 @@ jobs: mkdir -p CANBridge-artifacts 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* - # Put release files together in one directory + # Put Windows release files together in one directory - name: Create Artifact (windows64) - if: contains(matrix.name, 'windows64') + if: matrix.platform-type == 'windowsx86-64' run: | - mkdir -p CANBridge-artifacts cp build/libs/cANBridge/static/windowsx86-64/release/CANBridge.lib CANBridge-artifacts/CANBridge-static.lib cp build/libs/cANBridge/shared/windowsx86-64/release/CANBridge.dll CANBridge-artifacts/CANBridge.dll cp build/libs/cANBridge/shared/windowsx86-64/release/CANBridge.lib CANBridge-artifacts/CANBridge.lib - cp halWindows/windows/x86-64/shared/wpiHal.dll CANBridge-artifacts/wpiHal.dll - cp halWindows/windows/x86-64/shared/wpiHal.lib CANBridge-artifacts/wpiHal.lib - cp halMac/osx/universal/shared/libwpiHal.dylib CANBridge-artifacts/libwpiHal.dylib - cp halLinux64/linux/x86-64/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so - cp halLinuxArm/linux/arm64/shared/libwpiHal.so CANBridge-artifacts/libwpiHal-arm64.so + cp halPlatform/windows/x86-64/shared/wpiHal.dll CANBridge-artifacts/wpiHal.dll + cp halPlatform/windows/x86-64/shared/wpiHal.lib CANBridge-artifacts/wpiHal.lib - cp utilWindows/windows/x86-64/shared/wpiutil.dll CANBridge-artifacts/wpiutil.dll - cp utilWindows/windows/x86-64/shared/wpiutil.lib CANBridge-artifacts/wpiutil.lib - cp utilMac/osx/universal/shared/libwpiutil.dylib CANBridge-artifacts/libwpiutil.dylib - cp utilLinux64/linux/x86-64/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so - cp utilLinuxArm/linux/arm64/shared/libwpiutil.so CANBridge-artifacts/libwpiutil-arm64.so + cp utilPlatform/windows/x86-64/shared/wpiutil.dll CANBridge-artifacts/wpiutil.dll + cp utilPlatform/windows/x86-64/shared/wpiutil.lib CANBridge-artifacts/wpiutil.lib - # Put release files together in one directory + # Put Linux release files together in one directory - name: Create Artifact (linux64) - if: contains(matrix.name, 'linux64') + if: matrix.platform-type == 'linuxx86-64' run: | - mkdir -p CANBridge-artifacts # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 - # Put release files together in one directory + # Put Linux ARM release files together in one directory - name: Create Artifact (linuxarm64) - if: contains(matrix.name, 'linuxarm64') + if: matrix.platform-type == 'linuxarm64' run: | - mkdir -p CANBridge-artifacts # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 - # Put release files together in one directory - - name: Create Artifact (macosarm64) - if: contains(matrix.name, 'macosarm64') + # Put macOS release files together in one directory + - name: Create Artifact (osxuniversal) + if: matrix.platform-type == 'osxuniversal' run: | - mkdir -p CANBridge-artifacts cp build/libs/cANBridge/static/osxuniversal/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a cp build/libs/cANBridge/shared/osxuniversal/release/libCANBridge.dylib CANBridge-artifacts/libCANBridge.dylib - cp halMac/osx/universal/shared/libwpiHal.dylib CANBridge-artifacts/libwpiHal.dylib + cp halPlatform/osx/universal/shared/libwpiHal.dylib CANBridge-artifacts/libwpiHal.dylib - cp utilMac/osx/universal/shared/libwpiutil.dylib CANBridge-artifacts/libwpiutil.dylib - - # Put release files together in one directory - - name: Create Artifact (macosintel64) - if: contains(matrix.name, 'macosintel64') - run: | - mkdir -p CANBridge-artifacts - # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 + cp utilPlatform/osx/universal/shared/libwpiutil.dylib CANBridge-artifacts/libwpiutil.dylib # Upload build artifact - name: Upload build artifact uses: actions/upload-artifact@v3 with: - name: CANBridge-${{ github.sha }} + name: CANBridge-${{ github.sha }}-${{ matrix.platform-type }}-${{ matrix.name }} path: CANBridge-artifacts/ # Upload version.txt @@ -182,4 +151,4 @@ jobs: uses: actions/upload-artifact@v3 with: name: version - path: build/allOutputs/version.txt + path: build/allOutputs/version.txt \ No newline at end of file From 833a16752b3d3ac1d44117418c420327a3165eb2 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 14 Jun 2024 19:58:14 -0500 Subject: [PATCH 12/55] Add Arm32, Arm64 builds, upload Linux artifacts Added builds to utilize Linux ARM 32 and 64 bit versions. Added artifact uploads for Linux versions. --- .github/workflows/build.yml | 114 ++++++++++++++++++++++++++++++------ 1 file changed, 95 insertions(+), 19 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index bac7724..78f5a92 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -13,7 +13,95 @@ defaults: shell: bash jobs: - build: + build-docker: + strategy: + matrix: + include: + - container: wpilib/aarch64-cross-ubuntu:bullseye-22.04 + name: LinuxARM64 + build-options: "-Ponlylinuxarm64" + platform-type: linuxarm64 + - container: wpilib/raspbian-cross-ubuntu:bullseye-22.04 + name: LinuxARM32 + build-options: "-Ponlylinuxarm32" + platform-type: linuxarm32 + runs-on: ubuntu-latest + container: ${{ matrix.container }} + steps: + - name: Checkout + uses: actions/checkout@v3 + with: + ref: ${{ github.sha }} + - name: Setup Java + uses: actions/setup-java@v3 + with: + distribution: 'zulu' + java-version: 11 + - name: Build + run: | + ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode + - name: Download WPILib HAL artifacts and headers, gather all needed headers + run : | + halVersion=$(cat wpiHalVersion.txt) + + # Download WPILib artifacts from Artifactory + halPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-${{ matrix.platform-type }}.zip + halHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-headers.zip + + utilPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-${{ matrix.platform-type }}.zip + utilHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-headers.zip + + curl -o halPlatform.zip "$halPlatformUrl" + curl -o halHeaders.zip "$halHeadersUrl" + + curl -o utilPlatform.zip "$utilPlatformUrl" + curl -o utilHeaders.zip "$utilHeadersUrl" + + unzip halPlatform.zip -d halPlatform + unzip halHeaders.zip -d halHeaders + + unzip utilPlatform.zip -d utilPlatform + unzip utilHeaders.zip -d utilHeaders + + # Gather all of the the needed headers + mkdir headers-for-artifact + cp -r halHeaders/hal headers-for-artifact + cp -r utilHeaders/wpi headers-for-artifact + cp -r src/main/native/include/* headers-for-artifact + + # Zip the needed headers and put them in the appropriate location for artifact upload + mkdir -p CANBridge-artifacts + 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* + + # Put Linux ARM release files together in one directory + - name: Create Artifact (linuxarm64) + if: matrix.platform-type == 'linuxarm64' + run: | + cp build/libs/cANBridge/static/linuxarm64/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a + cp build/libs/cANBridge/shared/linuxarm64/release/libCANBridge.so CANBridge-artifacts/libCANBridge.so + + cp halPlatform/linux/arm64/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so + + cp utilPlatform/linux/arm64/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so + + # Put Linux ARM release files together in one directory + - name: Create Artifact (linuxarm32) + if: matrix.platform-type == 'linuxarm32' + run: | + cp build/libs/cANBridge/static/linuxarm32/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a + cp build/libs/cANBridge/shared/linuxarm32/release/libCANBridge.so CANBridge-artifacts/libCANBridge.so + + cp halPlatform/linux/arm32/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so + + cp utilPlatform/linux/arm32/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so + + # Upload build artifact + - name: Upload build artifact + uses: actions/upload-artifact@v3 + with: + name: CANBridge-${{ github.sha }}-${{ matrix.platform-type }}-${{ matrix.name }} + path: CANBridge-artifacts/ + build-native: timeout-minutes: 15 strategy: fail-fast: false @@ -27,10 +115,6 @@ jobs: container: '' name: Linux64 platform-type: linuxx86-64 - # - os: ubuntu-latest-arm64 - # container: '' - # name: linuxarm64 - # platform-type: linuxarm64 - os: macos-latest container: '' name: MacOSARM64 @@ -120,13 +204,12 @@ jobs: - name: Create Artifact (linux64) if: matrix.platform-type == 'linuxx86-64' run: | - # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 + cp build/libs/cANBridge/static/linuxx86-64/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a + cp build/libs/cANBridge/shared/linuxx86-64/release/libCANBridge.so CANBridge-artifacts/libCANBridge.so - # Put Linux ARM release files together in one directory - - name: Create Artifact (linuxarm64) - if: matrix.platform-type == 'linuxarm64' - run: | - # TODO: Include built binaries for macos/arm64, macos/x86-64, linux/x86-64, linux/arm64 + cp halPlatform/linux/x86-64/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so + + cp utilPlatform/linux/x86-64/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so # Put macOS release files together in one directory - name: Create Artifact (osxuniversal) @@ -144,11 +227,4 @@ jobs: uses: actions/upload-artifact@v3 with: name: CANBridge-${{ github.sha }}-${{ matrix.platform-type }}-${{ matrix.name }} - path: CANBridge-artifacts/ - - # Upload version.txt - - name: Upload version artifact - uses: actions/upload-artifact@v3 - with: - name: version - path: build/allOutputs/version.txt \ No newline at end of file + path: CANBridge-artifacts/ \ No newline at end of file From 5a4e90ef1082c9bcfa5f065bf737f6a8027f5627 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 14 Jun 2024 19:59:46 -0500 Subject: [PATCH 13/55] [ci-skip] Add name to CI jobs --- .github/workflows/build.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 78f5a92..7f23e4a 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -26,6 +26,7 @@ jobs: build-options: "-Ponlylinuxarm32" platform-type: linuxarm32 runs-on: ubuntu-latest + name: "Build - ${{ matrix.name }}" container: ${{ matrix.container }} steps: - name: Checkout From b0cb6df3caece95035e5c3c4d5c451ac5ad1ec48 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 14 Jun 2024 20:06:39 -0500 Subject: [PATCH 14/55] Disable fail-fast, install 7z during Docker builds Disabled fail-fast to allow for all other jobs to continue running without interruption, especially if another job fails inside the matrix. Added step to install 7Zip for the Docker CI. This is just to zip and archive up packages without issues. --- .github/workflows/build.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 7f23e4a..6581a55 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -15,6 +15,7 @@ defaults: jobs: build-docker: strategy: + fail-fast: false matrix: include: - container: wpilib/aarch64-cross-ubuntu:bullseye-22.04 @@ -72,6 +73,8 @@ jobs: # Zip the needed headers and put them in the appropriate location for artifact upload mkdir -p CANBridge-artifacts + # Install 7zip + sudo apt install -y p7zip-full 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* # Put Linux ARM release files together in one directory From 9e4ac8b856851b666bb1ac92dbb18bfb5dd6342f Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 14 Jun 2024 20:12:24 -0500 Subject: [PATCH 15/55] Separate step for 7zip installation --- .github/workflows/build.yml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 6581a55..8005752 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -42,6 +42,10 @@ jobs: - name: Build run: | ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode + - name: Install 7zip + run: | + sudo apt-get update + sudo apt-get install -y p7zip-full - name: Download WPILib HAL artifacts and headers, gather all needed headers run : | halVersion=$(cat wpiHalVersion.txt) @@ -73,8 +77,6 @@ jobs: # Zip the needed headers and put them in the appropriate location for artifact upload mkdir -p CANBridge-artifacts - # Install 7zip - sudo apt install -y p7zip-full 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* # Put Linux ARM release files together in one directory From ee6cee270314132ef1523220d866239eba519211 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 14 Jun 2024 20:26:22 -0500 Subject: [PATCH 16/55] Enable verbose logging during build outputs on ARM builds --- .github/workflows/build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 8005752..724e70e 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -41,7 +41,7 @@ jobs: java-version: 11 - name: Build run: | - ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode + ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode --info - name: Install 7zip run: | sudo apt-get update From 42bf27971471602116c6fc3f3ae68cf89f66a4ba Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 14 Jun 2024 20:32:22 -0500 Subject: [PATCH 17/55] Finalize ARM builds and artifact packaging --- .github/workflows/build.yml | 20 ++++---------------- 1 file changed, 4 insertions(+), 16 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 724e70e..a22452e 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -41,7 +41,7 @@ jobs: java-version: 11 - name: Build run: | - ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode --info + ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode - name: Install 7zip run: | sudo apt-get update @@ -80,27 +80,15 @@ jobs: 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* # Put Linux ARM release files together in one directory - - name: Create Artifact (linuxarm64) - if: matrix.platform-type == 'linuxarm64' + - name: Create Artifact run: | - cp build/libs/cANBridge/static/linuxarm64/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a - cp build/libs/cANBridge/shared/linuxarm64/release/libCANBridge.so CANBridge-artifacts/libCANBridge.so + cp build/libs/cANBridge/static/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a + cp build/libs/cANBridge/shared/release/libCANBridge.so CANBridge-artifacts/libCANBridge.so cp halPlatform/linux/arm64/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so cp utilPlatform/linux/arm64/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so - # Put Linux ARM release files together in one directory - - name: Create Artifact (linuxarm32) - if: matrix.platform-type == 'linuxarm32' - run: | - cp build/libs/cANBridge/static/linuxarm32/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a - cp build/libs/cANBridge/shared/linuxarm32/release/libCANBridge.so CANBridge-artifacts/libCANBridge.so - - cp halPlatform/linux/arm32/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so - - cp utilPlatform/linux/arm32/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so - # Upload build artifact - name: Upload build artifact uses: actions/upload-artifact@v3 From 9ac8c1bfe5ec594cf0bf17dd2e83490818ff24f3 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 14 Jun 2024 20:36:56 -0500 Subject: [PATCH 18/55] Fix incorrect directories for creating artifacts --- .github/workflows/build.yml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index a22452e..acd4d5c 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -22,10 +22,12 @@ jobs: name: LinuxARM64 build-options: "-Ponlylinuxarm64" platform-type: linuxarm64 + arch: arm64 - container: wpilib/raspbian-cross-ubuntu:bullseye-22.04 name: LinuxARM32 build-options: "-Ponlylinuxarm32" platform-type: linuxarm32 + arch: arm32 runs-on: ubuntu-latest name: "Build - ${{ matrix.name }}" container: ${{ matrix.container }} @@ -85,9 +87,9 @@ jobs: cp build/libs/cANBridge/static/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a cp build/libs/cANBridge/shared/release/libCANBridge.so CANBridge-artifacts/libCANBridge.so - cp halPlatform/linux/arm64/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so + cp halPlatform/linux/${{ matrix.arch }}/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so - cp utilPlatform/linux/arm64/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so + cp utilPlatform/linux/${{ matrix.arch }}/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so # Upload build artifact - name: Upload build artifact From bc6df8bfb1657363916b2c385daef560f7eec7b7 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 21 Jun 2024 16:53:54 -0500 Subject: [PATCH 19/55] Split steps apart for WPILib HAL archiving, update release.yml Steps for unarchiving and archiving HALs are split up to add verbosity to the CI steps, if a specific step fails, we are able to diagnose more quickly. Updated release CI steps, using updated Actions and cleaner methods to check if the build CI completed. --- .github/workflows/build.yml | 42 +++++++++--------- .github/workflows/release.yml | 83 ++++++++++++----------------------- 2 files changed, 49 insertions(+), 76 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index acd4d5c..8be3783 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -36,11 +36,13 @@ jobs: uses: actions/checkout@v3 with: ref: ${{ github.sha }} + - name: Setup Java uses: actions/setup-java@v3 with: distribution: 'zulu' java-version: 11 + - name: Build run: | ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode @@ -48,36 +50,37 @@ jobs: run: | sudo apt-get update sudo apt-get install -y p7zip-full - - name: Download WPILib HAL artifacts and headers, gather all needed headers + + - name: Download WPILib HAL artifacts and headers for ${{ matrix.platform-type }} run : | halVersion=$(cat wpiHalVersion.txt) - # Download WPILib artifacts from Artifactory halPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-${{ matrix.platform-type }}.zip halHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-headers.zip - utilPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-${{ matrix.platform-type }}.zip utilHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-headers.zip curl -o halPlatform.zip "$halPlatformUrl" curl -o halHeaders.zip "$halHeadersUrl" - curl -o utilPlatform.zip "$utilPlatformUrl" curl -o utilHeaders.zip "$utilHeadersUrl" + - name: Unzip WPILib HAL artifacts and headers + run: | unzip halPlatform.zip -d halPlatform unzip halHeaders.zip -d halHeaders - unzip utilPlatform.zip -d utilPlatform unzip utilHeaders.zip -d utilHeaders - # Gather all of the the needed headers + - name: Gather all needed headers + run: | mkdir headers-for-artifact cp -r halHeaders/hal headers-for-artifact cp -r utilHeaders/wpi headers-for-artifact cp -r src/main/native/include/* headers-for-artifact - # Zip the needed headers and put them in the appropriate location for artifact upload + - name: Zip the needed headers and put them in the appropriate location for artifact upload + run: | mkdir -p CANBridge-artifacts 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* @@ -86,9 +89,7 @@ jobs: run: | cp build/libs/cANBridge/static/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a cp build/libs/cANBridge/shared/release/libCANBridge.so CANBridge-artifacts/libCANBridge.so - cp halPlatform/linux/${{ matrix.arch }}/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so - cp utilPlatform/linux/${{ matrix.arch }}/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so # Upload build artifact @@ -97,6 +98,7 @@ jobs: with: name: CANBridge-${{ github.sha }}-${{ matrix.platform-type }}-${{ matrix.name }} path: CANBridge-artifacts/ + build-native: timeout-minutes: 15 strategy: @@ -111,6 +113,8 @@ jobs: container: '' name: Linux64 platform-type: linuxx86-64 + # GitHub hosted runner `macos-latest` is arm64, which is why we need to specify `macos-13` for x86_64 + # See https://github.com/actions/runner-images?tab=readme-ov-file#available-images for more information - os: macos-latest container: '' name: MacOSARM64 @@ -149,36 +153,36 @@ jobs: run: | ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode - - name: Download WPILib HAL artifacts and headers, gather all needed headers + - name: Download WPILib HAL artifacts and headers for ${{ matrix.platform-type }} run : | halVersion=$(cat wpiHalVersion.txt) - # Download WPILib artifacts from Artifactory halPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-${{ matrix.platform-type }}.zip halHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-headers.zip - utilPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-${{ matrix.platform-type }}.zip utilHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-headers.zip curl -o halPlatform.zip "$halPlatformUrl" curl -o halHeaders.zip "$halHeadersUrl" - curl -o utilPlatform.zip "$utilPlatformUrl" curl -o utilHeaders.zip "$utilHeadersUrl" + - name: Unzip WPILib HAL artifacts and headers + run: | unzip halPlatform.zip -d halPlatform unzip halHeaders.zip -d halHeaders - unzip utilPlatform.zip -d utilPlatform unzip utilHeaders.zip -d utilHeaders - # Gather all of the the needed headers + - name: Gather all needed headers + run: | mkdir headers-for-artifact cp -r halHeaders/hal headers-for-artifact cp -r utilHeaders/wpi headers-for-artifact cp -r src/main/native/include/* headers-for-artifact - # Zip the needed headers and put them in the appropriate location for artifact upload + - name: Zip the needed headers and put them in the appropriate location for artifact upload + run: | mkdir -p CANBridge-artifacts 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* @@ -189,10 +193,8 @@ jobs: cp build/libs/cANBridge/static/windowsx86-64/release/CANBridge.lib CANBridge-artifacts/CANBridge-static.lib cp build/libs/cANBridge/shared/windowsx86-64/release/CANBridge.dll CANBridge-artifacts/CANBridge.dll cp build/libs/cANBridge/shared/windowsx86-64/release/CANBridge.lib CANBridge-artifacts/CANBridge.lib - cp halPlatform/windows/x86-64/shared/wpiHal.dll CANBridge-artifacts/wpiHal.dll cp halPlatform/windows/x86-64/shared/wpiHal.lib CANBridge-artifacts/wpiHal.lib - cp utilPlatform/windows/x86-64/shared/wpiutil.dll CANBridge-artifacts/wpiutil.dll cp utilPlatform/windows/x86-64/shared/wpiutil.lib CANBridge-artifacts/wpiutil.lib @@ -202,9 +204,7 @@ jobs: run: | cp build/libs/cANBridge/static/linuxx86-64/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a cp build/libs/cANBridge/shared/linuxx86-64/release/libCANBridge.so CANBridge-artifacts/libCANBridge.so - cp halPlatform/linux/x86-64/shared/libwpiHal.so CANBridge-artifacts/libwpiHal.so - cp utilPlatform/linux/x86-64/shared/libwpiutil.so CANBridge-artifacts/libwpiutil.so # Put macOS release files together in one directory @@ -213,9 +213,7 @@ jobs: run: | cp build/libs/cANBridge/static/osxuniversal/release/libCANBridge.a CANBridge-artifacts/libCANBridge.a cp build/libs/cANBridge/shared/osxuniversal/release/libCANBridge.dylib CANBridge-artifacts/libCANBridge.dylib - cp halPlatform/osx/universal/shared/libwpiHal.dylib CANBridge-artifacts/libwpiHal.dylib - cp utilPlatform/osx/universal/shared/libwpiutil.dylib CANBridge-artifacts/libwpiutil.dylib # Upload build artifact diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index cc7bbc1..a1ad058 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -16,42 +16,22 @@ jobs: TAG_NAME: ${{ env.TAG_NAME }} VERSION: ${{ steps.get_version.outputs.version }} steps: - - - name: Wait for windows64 build to finish - uses: lewagon/wait-on-check-action@v1.3.1 - with: - ref: ${{ github.ref }} - check-name: 'build-windows64' - repo-token: ${{ secrets.GITHUB_TOKEN }} - wait-interval: 10 - - name: Wait for linux64 build to finish - uses: lewagon/wait-on-check-action@v1.3.1 - with: - ref: ${{ github.ref }} - check-name: 'build-linux64' - repo-token: ${{ secrets.GITHUB_TOKEN }} - wait-interval: 10 -# - name: Wait for linuxarm64 build to finish -# uses: lewagon/wait-on-check-action@v1.3.1 -# with: -# ref: ${{ github.ref }} -# check-name: 'build-linuxarm64' -# repo-token: ${{ secrets.GITHUB_TOKEN }} -# wait-interval: 10 - - name: Wait for macosarm64 build to finish - uses: lewagon/wait-on-check-action@v1.3.1 + - name: Wait for build workflow to finish + uses: actions/github-script@v4 with: - ref: ${{ github.ref }} - check-name: 'build-macosarm64' - repo-token: ${{ secrets.GITHUB_TOKEN }} - wait-interval: 10 - - name: Wait for macosintel64 build to finish - uses: lewagon/wait-on-check-action@v1.3.1 - with: - ref: ${{ github.ref }} - check-name: 'build-macosintel64' - repo-token: ${{ secrets.GITHUB_TOKEN }} - wait-interval: 10 + script: | + const { data: runs } = await github.actions.listWorkflowRuns({ + owner: context.repo.owner, + repo: context.repo.repo, + workflow_id: 'build.yml', + branch: 'refs/heads/main', + status: 'completed', + per_page: 1 + }); + if (runs.workflow_runs.length === 0) { + core.setFailed('No build workflow runs found'); + } + core.setOutput('run_id', runs.workflow_runs[0].id); - name: Get tag name run: | @@ -59,7 +39,7 @@ jobs: # Download artifacts from build workflow - name: Download workflow artifacts - uses: dawidd6/action-download-artifact@v2 + uses: dawidd6/action-download-artifact@v6 with: workflow: build.yml commit: ${{ github.sha }} @@ -67,38 +47,33 @@ jobs: # Get publish.gradle version - name: Get publish.gradle version - id: get_version + id: get-version run: | echo "version=$(cat version/version.txt)" >> $GITHUB_OUTPUT echo "expectedTagName=v$(cat version/version.txt)" >> $GITHUB_OUTPUT - # Check publish.gradle version - - name: publish.gradle version check FAILED - if: ${{ steps.get_version.outputs.expectedTagName != env.TAG_NAME }} - run: | - echo Tag name: ${{ env.TAG_NAME }} - echo publish.gradle version: ${{ steps.get_version.outputs.version }} - exit 1 - prepare-release: runs-on: ubuntu-latest needs: check-versions steps: # Download API, docs, and version.txt - name: Download workflow artifacts - uses: dawidd6/action-download-artifact@v2 + uses: dawidd6/action-download-artifact@v6 with: workflow: build.yml commit: ${{ github.sha }} path: '.' + # This step is to check what files are downloaded and how they are structured, as well as binary sizes for releases + - name: List files + run: | + ls -Rlh + # Create new release draft - name: Create release - id: create_release - env: - GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} - run: | - VERSION=${{ needs.check-versions.outputs.version }} - TAG=v$VERSION - ls --recursive -l - gh release create $TAG CANBridge-${{ github.sha }}/* --repo $GITHUB_REPOSITORY --draft --title "Version $VERSION" + uses: softprops/action-gh-release@v2 + with: + draft: true + generate_release_notes: true + files: | + **/** From 8288165a93577dfc1249b107dd5f08b0af46193c Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 21 Jun 2024 16:59:55 -0500 Subject: [PATCH 20/55] Update dependent actions Updated dependent actions due to deprecation notices. --- .github/workflows/build.yml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 8be3783..e470fe1 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -33,12 +33,12 @@ jobs: container: ${{ matrix.container }} steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: ref: ${{ github.sha }} - name: Setup Java - uses: actions/setup-java@v3 + uses: actions/setup-java@v4 with: distribution: 'zulu' java-version: 11 @@ -128,18 +128,18 @@ jobs: container: ${{ matrix.container }} steps: - name: Checkout - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: ref: ${{ github.sha }} - name: Setup Java - uses: actions/setup-java@v3 + uses: actions/setup-java@v4 with: distribution: 'zulu' java-version: 11 - name: Cache - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: | .gradle @@ -218,7 +218,7 @@ jobs: # Upload build artifact - name: Upload build artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: CANBridge-${{ github.sha }}-${{ matrix.platform-type }}-${{ matrix.name }} path: CANBridge-artifacts/ \ No newline at end of file From 6cb092a7c8e21e3520657c44c2c150164ef19152 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 21 Jun 2024 17:16:57 -0500 Subject: [PATCH 21/55] [ci skip] Updating release workflow to properly check for workflow releases --- .github/workflows/release.yml | 18 ++++-------------- 1 file changed, 4 insertions(+), 14 deletions(-) diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index a1ad058..5c23f0c 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -17,21 +17,11 @@ jobs: VERSION: ${{ steps.get_version.outputs.version }} steps: - name: Wait for build workflow to finish - uses: actions/github-script@v4 + uses: lewagon/wait-on-check-action@v1.3.4 with: - script: | - const { data: runs } = await github.actions.listWorkflowRuns({ - owner: context.repo.owner, - repo: context.repo.repo, - workflow_id: 'build.yml', - branch: 'refs/heads/main', - status: 'completed', - per_page: 1 - }); - if (runs.workflow_runs.length === 0) { - core.setFailed('No build workflow runs found'); - } - core.setOutput('run_id', runs.workflow_runs[0].id); + ref: ${{ github.ref }} + running-workflow-name: "Build" + wait-interval: 10 - name: Get tag name run: | From 8ea5baac8980e624997605778a03154509721b73 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 21 Jun 2024 17:26:29 -0500 Subject: [PATCH 22/55] [ci skip] Update tags search release workflow --- .github/workflows/release.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index 5c23f0c..8bf115c 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -3,7 +3,7 @@ name: Create release on: push: tags: - - 'v*' + - 'v**' defaults: run: From c5dbaa0c463e89957d98e000228ce6f427085ad2 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 21 Jun 2024 17:27:37 -0500 Subject: [PATCH 23/55] Remove tag name --- .github/workflows/release.yml | 4 ---- 1 file changed, 4 deletions(-) diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index 8bf115c..f094d9b 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -23,10 +23,6 @@ jobs: running-workflow-name: "Build" wait-interval: 10 - - name: Get tag name - run: | - echo "TAG_NAME=${GITHUB_REF#refs/*/}" >> $GITHUB_ENV - # Download artifacts from build workflow - name: Download workflow artifacts uses: dawidd6/action-download-artifact@v6 From f36d8b71c24fa43c17f0bcb11571ef7ea3bd63d8 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 21 Jun 2024 17:32:30 -0500 Subject: [PATCH 24/55] Add GITHUB_TOKEN to release workflow and permissions to write releases --- .github/workflows/release.yml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index f094d9b..c79adae 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -5,6 +5,9 @@ on: tags: - 'v**' +permissions: + contents: write + defaults: run: shell: bash @@ -21,6 +24,7 @@ jobs: with: ref: ${{ github.ref }} running-workflow-name: "Build" + repo-token: ${{ secrets.GITHUB_TOKEN }} wait-interval: 10 # Download artifacts from build workflow From a5474480d63020cf81f49687942000f63022d842 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 21 Jun 2024 17:47:48 -0500 Subject: [PATCH 25/55] Fix broken check waiting for build to finish. --- .github/workflows/build.yml | 2 +- .github/workflows/release.yml | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index e470fe1..f59e430 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -94,7 +94,7 @@ jobs: # Upload build artifact - name: Upload build artifact - uses: actions/upload-artifact@v3 + uses: actions/upload-artifact@v4 with: name: CANBridge-${{ github.sha }}-${{ matrix.platform-type }}-${{ matrix.name }} path: CANBridge-artifacts/ diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index c79adae..4a8a912 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -14,6 +14,7 @@ defaults: jobs: check-versions: + name: Check build and publish versions runs-on: ubuntu-latest outputs: TAG_NAME: ${{ env.TAG_NAME }} @@ -23,7 +24,7 @@ jobs: uses: lewagon/wait-on-check-action@v1.3.4 with: ref: ${{ github.ref }} - running-workflow-name: "Build" + check-regexp: 'Build' repo-token: ${{ secrets.GITHUB_TOKEN }} wait-interval: 10 @@ -43,6 +44,7 @@ jobs: echo "expectedTagName=v$(cat version/version.txt)" >> $GITHUB_OUTPUT prepare-release: + name: Prepare release runs-on: ubuntu-latest needs: check-versions steps: From 77e0a8dffa0b05dd93664f0481acb7429dc14692 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 21 Jun 2024 17:59:02 -0500 Subject: [PATCH 26/55] Shorten artifact names, skip unpacking for releases --- .github/workflows/build.yml | 2 +- .github/workflows/release.yml | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index f59e430..8a1383f 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -220,5 +220,5 @@ jobs: - name: Upload build artifact uses: actions/upload-artifact@v4 with: - name: CANBridge-${{ github.sha }}-${{ matrix.platform-type }}-${{ matrix.name }} + name: CANBridge-${{ matrix.platform-type }}-${{ matrix.name }} path: CANBridge-artifacts/ \ No newline at end of file diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index 4a8a912..0a6ee88 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -55,6 +55,7 @@ jobs: workflow: build.yml commit: ${{ github.sha }} path: '.' + skip_unpack: true # This step is to check what files are downloaded and how they are structured, as well as binary sizes for releases - name: List files From 4f50436de2500a2eaa002fa77912744b9a21b049 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 21 Jun 2024 18:06:09 -0500 Subject: [PATCH 27/55] [ci skip] Remove SHA on ARM builds for artifacts --- .github/workflows/build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 8a1383f..5d251c4 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -96,7 +96,7 @@ jobs: - name: Upload build artifact uses: actions/upload-artifact@v4 with: - name: CANBridge-${{ github.sha }}-${{ matrix.platform-type }}-${{ matrix.name }} + name: CANBridge-${{ matrix.platform-type }} path: CANBridge-artifacts/ build-native: From df262536d653a2862d3d8a60edcd62e51ce91f62 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Sat, 22 Jun 2024 00:02:07 -0500 Subject: [PATCH 28/55] chore: Update WPILib HAL headers in release workflow This updates workflows to produce headers for CANBridge separately from the built binaries. --- .github/workflows/build.yml | 84 ++++++++++++++++++----------------- .github/workflows/release.yml | 2 +- 2 files changed, 44 insertions(+), 42 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 5d251c4..280d51b 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -46,43 +46,21 @@ jobs: - name: Build run: | ./gradlew outputVersions publish ${{ matrix.build-options }} -PreleaseMode - - name: Install 7zip - run: | - sudo apt-get update - sudo apt-get install -y p7zip-full - name: Download WPILib HAL artifacts and headers for ${{ matrix.platform-type }} run : | halVersion=$(cat wpiHalVersion.txt) halPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-${{ matrix.platform-type }}.zip - halHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-headers.zip utilPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-${{ matrix.platform-type }}.zip - utilHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-headers.zip curl -o halPlatform.zip "$halPlatformUrl" - curl -o halHeaders.zip "$halHeadersUrl" curl -o utilPlatform.zip "$utilPlatformUrl" - curl -o utilHeaders.zip "$utilHeadersUrl" - name: Unzip WPILib HAL artifacts and headers run: | unzip halPlatform.zip -d halPlatform - unzip halHeaders.zip -d halHeaders unzip utilPlatform.zip -d utilPlatform - unzip utilHeaders.zip -d utilHeaders - - - name: Gather all needed headers - run: | - mkdir headers-for-artifact - cp -r halHeaders/hal headers-for-artifact - cp -r utilHeaders/wpi headers-for-artifact - cp -r src/main/native/include/* headers-for-artifact - - - name: Zip the needed headers and put them in the appropriate location for artifact upload - run: | - mkdir -p CANBridge-artifacts - 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* # Put Linux ARM release files together in one directory - name: Create Artifact @@ -158,33 +136,15 @@ jobs: halVersion=$(cat wpiHalVersion.txt) halPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-${{ matrix.platform-type }}.zip - halHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-headers.zip utilPlatformUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-${{ matrix.platform-type }}.zip - utilHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-headers.zip curl -o halPlatform.zip "$halPlatformUrl" - curl -o halHeaders.zip "$halHeadersUrl" curl -o utilPlatform.zip "$utilPlatformUrl" - curl -o utilHeaders.zip "$utilHeadersUrl" - name: Unzip WPILib HAL artifacts and headers run: | unzip halPlatform.zip -d halPlatform - unzip halHeaders.zip -d halHeaders unzip utilPlatform.zip -d utilPlatform - unzip utilHeaders.zip -d utilHeaders - - - name: Gather all needed headers - run: | - mkdir headers-for-artifact - cp -r halHeaders/hal headers-for-artifact - cp -r utilHeaders/wpi headers-for-artifact - cp -r src/main/native/include/* headers-for-artifact - - - name: Zip the needed headers and put them in the appropriate location for artifact upload - run: | - mkdir -p CANBridge-artifacts - 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* # Put Windows release files together in one directory - name: Create Artifact (windows64) @@ -221,4 +181,46 @@ jobs: uses: actions/upload-artifact@v4 with: name: CANBridge-${{ matrix.platform-type }}-${{ matrix.name }} - path: CANBridge-artifacts/ \ No newline at end of file + path: CANBridge-artifacts/ + + wpi-headers: + runs-on: ubuntu-latest + name: "WPILib Headers" + steps: + - name: Checkout + uses: actions/checkout@v4 + with: + ref: ${{ github.sha }} + - name: Download WPILib HAL artifacts and headers for linuxx86-64 + run : | + halVersion=$(cat wpiHalVersion.txt) + + halHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/hal/hal-cpp/"$halVersion"/hal-cpp-"$halVersion"-headers.zip + utilHeadersUrl=https://frcmaven.wpi.edu/artifactory/release/edu/wpi/first/wpiutil/wpiutil-cpp/"$halVersion"/wpiutil-cpp-"$halVersion"-headers.zip + + curl -o halHeaders.zip "$halHeadersUrl" + curl -o utilHeaders.zip "$utilHeadersUrl" + + - name: Unzip WPILib HAL artifacts and headers + run: | + unzip halHeaders.zip -d halHeaders + unzip utilHeaders.zip -d utilHeaders + + - name: Gather all needed headers + run: | + mkdir headers-for-artifact + cp -r halHeaders/hal headers-for-artifact + cp -r utilHeaders/wpi headers-for-artifact + cp -r src/main/native/include headers-for-artifact + + - name: Zip the needed headers and put them in the appropriate location for artifact upload + run: | + mkdir -p CANBridge-artifacts + 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* + + # Upload build artifact + - name: Upload build artifact + uses: actions/upload-artifact@v4 + with: + path: CANBridge-artifacts/headers.zip + name: headers \ No newline at end of file diff --git a/.github/workflows/release.yml b/.github/workflows/release.yml index 0a6ee88..7e25dc0 100644 --- a/.github/workflows/release.yml +++ b/.github/workflows/release.yml @@ -24,7 +24,7 @@ jobs: uses: lewagon/wait-on-check-action@v1.3.4 with: ref: ${{ github.ref }} - check-regexp: 'Build' + check-regexp: 'Build|WPILib Headers' repo-token: ${{ secrets.GITHUB_TOKEN }} wait-interval: 10 From 4849e7b5c3f1497591fc07f6f8f0ec049a503e3d Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Sat, 22 Jun 2024 00:05:28 -0500 Subject: [PATCH 29/55] chore: Fix missing directory in build artifacts --- .github/workflows/build.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 280d51b..6d3ed3b 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -145,6 +145,7 @@ jobs: run: | unzip halPlatform.zip -d halPlatform unzip utilPlatform.zip -d utilPlatform + mkdir -p CANBridge-artifacts # Put Windows release files together in one directory - name: Create Artifact (windows64) From 22d7b1b98149692eb2c359a5b4089d611ad3e254 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Sat, 22 Jun 2024 00:08:30 -0500 Subject: [PATCH 30/55] chore: Fix missing directory for build artifacts (again) --- .github/workflows/build.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 6d3ed3b..b0a8ea0 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -61,6 +61,7 @@ jobs: run: | unzip halPlatform.zip -d halPlatform unzip utilPlatform.zip -d utilPlatform + mkdir -p CANBridge-artifacts # Put Linux ARM release files together in one directory - name: Create Artifact From f33c39cef9fb298c0181b9eda53ae8ba831c92b3 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Mon, 24 Jun 2024 11:15:29 -0500 Subject: [PATCH 31/55] Remove macOS ARM workflow Built binaries for macOS are universal for ARM and x86. --- .github/workflows/build.yml | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index b0a8ea0..c72e695 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -87,21 +87,18 @@ jobs: - os: windows-latest container: '' name: Win64 + build-options: "" platform-type: windowsx86-64 - os: ubuntu-latest container: '' name: Linux64 platform-type: linuxx86-64 - # GitHub hosted runner `macos-latest` is arm64, which is why we need to specify `macos-13` for x86_64 - # See https://github.com/actions/runner-images?tab=readme-ov-file#available-images for more information + build-options: "" - os: macos-latest container: '' - name: MacOSARM64 - platform-type: osxuniversal - - os: macos-13 - container: '' - name: MacOS64 + name: macOS platform-type: osxuniversal + build-options: "" name: "Build - ${{ matrix.name }}" runs-on: ${{ matrix.os }} container: ${{ matrix.container }} From 8cd038574bac75026f7063682c15c2f4ef11ff50 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Sun, 30 Jun 2024 23:47:31 -0500 Subject: [PATCH 32/55] fix: Un-nest the headers artifact The headers artifact was nested by mistake, this is now resolved. --- .github/workflows/build.yml | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index c72e695..64b9126 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -212,14 +212,9 @@ jobs: cp -r utilHeaders/wpi headers-for-artifact cp -r src/main/native/include headers-for-artifact - - name: Zip the needed headers and put them in the appropriate location for artifact upload - run: | - mkdir -p CANBridge-artifacts - 7z a CANBridge-artifacts/headers.zip ./headers-for-artifact/* - # Upload build artifact - name: Upload build artifact uses: actions/upload-artifact@v4 with: - path: CANBridge-artifacts/headers.zip + path: headers-for-artifact name: headers \ No newline at end of file From 9ee52d054d909e129c6df98f543a77f9ef9a247d Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Sun, 30 Jun 2024 23:56:24 -0500 Subject: [PATCH 33/55] fix: Actually copy everything in `include` for `headers.zip` --- .github/workflows/build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 64b9126..0fa877c 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -210,7 +210,7 @@ jobs: mkdir headers-for-artifact cp -r halHeaders/hal headers-for-artifact cp -r utilHeaders/wpi headers-for-artifact - cp -r src/main/native/include headers-for-artifact + cp -r src/main/native/include/* headers-for-artifact # Upload build artifact - name: Upload build artifact From 89f1c9d8529586cef544601ec22d62745b4f439b Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Mon, 1 Jul 2024 00:35:56 -0500 Subject: [PATCH 34/55] Update `README.md` Updated compile instructions and formatting. --- README.md | 53 +++++++++++++++++++++-------------------------------- 1 file changed, 21 insertions(+), 32 deletions(-) diff --git a/README.md b/README.md index 5c08da1..0cec31b 100644 --- a/README.md +++ b/README.md @@ -6,17 +6,13 @@ This repository is for the CANBridge software that is run on non-roboRIO platfor ## Behavior -When sending a frame with a given interval, the behavior when -setting a new interval is as follows: +When sending a frame with a given interval, the behavior when setting a new interval is as follows: -The first time a frame is scheduled with an interval, it -will be sent at the next available time. The next instance -of the same frame id will be sent after that interval, even -if the interval has changed. +The first time a frame is scheduled with an interval, it will be sent at the next available time. The next instance of the same frame id will be sent after that interval, even if the interval has changed. See the following pseudo-example: -``` +```py sendMessage(frame, 5000) delay(1000) @@ -28,52 +24,45 @@ updateFrameData(frame) sendMessage(frame, 2000) ``` -In this case, the first frame will be scheduled immediately, -the second will be scheduled 5 seconds later, and after that, -subsequent frames will be scheduled every 2 seconds. Note -that any change to the data in the second call will not be -sent, meaning the second call is essentially a no-op if a -new call with different data is sent before the previous -interval is up. Sending a frame with an interval of -1 -will cancel the repeat, and not send the frame. Sending with -an interval of 0 will schedule the new frame once, then stop -repeating. +In this case, the first frame will be scheduled immediately, the second will be scheduled 5 seconds later, and after that, subsequent frames will be scheduled every 2 seconds. Note +that any change to the data in the second call will not be sent, meaning the second call is essentially a no-op if a new call with different data is sent before the previous +interval is up. Sending a frame with an interval of `-1` will cancel the repeat, and not send the frame. Sending with an interval of `0` will schedule the new frame once, then stop repeating. ## Build Requirements 1. Git -2. Visual Studio Code or some other equivalent IDE -3. Gradle Build Tool -4. Java JDK/JRE +2. Gradle Build Tool +3. Java JDK 11 or newer (we recommend [Azul](https://www.azul.com/downloads/#zulu) or [Eclipse Temurin](https://adoptium.net/temurin/)) +4. A modern C++ compiler with C++20 support -All of these, excluding Git, can be installed and configured with the [WPILib Installer](https://github.com/wpilibsuite/allwpilib/releases), which will include specific versions for building FRC robot code. Gradle needs a C++ compiler, which is included with VS Code. +> [!NOTE] +> +> All of these, excluding Git, can be installed and configured with the [WPILib Installer](https://github.com/wpilibsuite/allwpilib/releases), which will include specific versions for building FRC robot code. Gradle needs a C++ compiler, which is included with WPILib's development environment. ## Building and Publishing -Building is done using the Gradle wrapper, `gradlew`. The Gradle wrapper is located in the root of the project, so Gradle commands must be run from there. +Building is done using the Gradle wrapper, `gradlew`. The Gradle wrapper is located in the root of the project, so Gradle commands must be run from there. -1. Clone this repository and open in VS Code - - When VS Code first opens, select `Add workspace folder...` underneath `Start` on the Welcome Screen -2. Open the VS Code terminal - - `View -> Terminal` or ``Ctrl+` `` -3. Run `./gradlew build` from root +1. Clone repository +2. Open a terminal inside the newly cloned repository +3. `./gradlew build` The output is placed at `~\releases\maven\release\com\revrobotics\usb\CANBridge-cpp\\`. -### Publishing a new version +### Publishing a new version (for repository owners) -Before publishing a new version, run `./gradlew build` locally to run the tests. GitHub Actions -cannot run the tests because they depend on having a USB CAN device connected. +> [!NOTE] +> +> Before publishing a new version, run `./gradlew build` locally to run the tests. GitHub Actions ***cannot*** run the tests because they depend on having a USB CAN device connected (e.g. SPARK MAX motor controller). 1. Bump the version number in `publish.gradle` and `CANBridge.json` 2. Commit the version bump 3. Create a new tag named `vX.X.X` at that commit 4. Push the tag to GitHub -5. Wait for the draft release to be created +5. Wait for the draft release to be created (this is automatically done via GitHub Actions) 6. Add release notes to the draft release 7. Publish the draft release ## Changelog The SDK Changelog can be viewed with [Changelog.md](Changelog.md). - From 2680cd06193d5681d626d2e03247e022b4066b87 Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Sun, 30 Jun 2024 23:41:21 -0700 Subject: [PATCH 35/55] Attempt to fix runtime crash --- src/main/native/cpp/CANBridgeUtils.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/src/main/native/cpp/CANBridgeUtils.cpp b/src/main/native/cpp/CANBridgeUtils.cpp index a820183..94d98a0 100644 --- a/src/main/native/cpp/CANBridgeUtils.cpp +++ b/src/main/native/cpp/CANBridgeUtils.cpp @@ -102,7 +102,17 @@ int parse_serial_com_port(const std::string& in) { if(!in.empty() && (substr_break < in.length())) { std::string num = in.substr(substr_break, in.length()); if (!num.empty()) { - return std::stoi(num); + int returnval = -1; + try + { + returnval = std::stoi(num); + } + catch(const std::exception& e) + { + std::cerr << 'parse_serial_com_port: Error running stoi: ' << e.what() << '\n'; + } + + return returnval; } } From 5ebb6702993db04e9674f002fbee09ff026cb3a6 Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Sun, 30 Jun 2024 23:56:17 -0700 Subject: [PATCH 36/55] (hopefully) Fixup Windows build --- src/main/native/cpp/CANBridgeUtils.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/native/cpp/CANBridgeUtils.cpp b/src/main/native/cpp/CANBridgeUtils.cpp index 94d98a0..1c51551 100644 --- a/src/main/native/cpp/CANBridgeUtils.cpp +++ b/src/main/native/cpp/CANBridgeUtils.cpp @@ -109,7 +109,7 @@ int parse_serial_com_port(const std::string& in) { } catch(const std::exception& e) { - std::cerr << 'parse_serial_com_port: Error running stoi: ' << e.what() << '\n'; + std::cerr << "parse_serial_com_port: Error running stoi: " << e.what() << '\n'; } return returnval; From a8269d6b444e5148fce5bdc02758c55809e44afb Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Mon, 1 Jul 2024 00:03:04 -0700 Subject: [PATCH 37/55] v2.3.5 --- publish.gradle | 2 +- vendordeps/CANBridge.json | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/publish.gradle b/publish.gradle index 21d9f4e..7b03831 100644 --- a/publish.gradle +++ b/publish.gradle @@ -2,7 +2,7 @@ apply plugin: 'maven-publish' ext.licenseFile = files("$rootDir/LICENSE.txt") -def pubVersion = '2.3.0' +def pubVersion = '2.3.5' def outputsFolder = file("$buildDir/allOutputs") diff --git a/vendordeps/CANBridge.json b/vendordeps/CANBridge.json index 025bf01..2c54a00 100644 --- a/vendordeps/CANBridge.json +++ b/vendordeps/CANBridge.json @@ -1,7 +1,7 @@ { "fileName": "CANBridge.json", "name": "CANBridge", - "version": "2.3.0", + "version": "2.3.5", "uuid": "34b37c7c-8acc-405f-9631-d21f20dc59d8", "mavenUrls": [ "http://www.revrobotics.com/content/sw/max/sdk/maven/" From 6188739a2de3f8d9ca5d5d1d94c82ffc7845ae5d Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Mon, 1 Jul 2024 01:31:42 -0700 Subject: [PATCH 38/55] Serial: More debugging --- publish.gradle | 2 +- src/main/native/cpp/CANBridgeUtils.cpp | 2 +- src/main/native/cpp/Drivers/Serial/SerialDriver.cpp | 1 + vendordeps/CANBridge.json | 2 +- 4 files changed, 4 insertions(+), 3 deletions(-) diff --git a/publish.gradle b/publish.gradle index 7b03831..30538b6 100644 --- a/publish.gradle +++ b/publish.gradle @@ -2,7 +2,7 @@ apply plugin: 'maven-publish' ext.licenseFile = files("$rootDir/LICENSE.txt") -def pubVersion = '2.3.5' +def pubVersion = '2.3.6' def outputsFolder = file("$buildDir/allOutputs") diff --git a/src/main/native/cpp/CANBridgeUtils.cpp b/src/main/native/cpp/CANBridgeUtils.cpp index 1c51551..807fd81 100644 --- a/src/main/native/cpp/CANBridgeUtils.cpp +++ b/src/main/native/cpp/CANBridgeUtils.cpp @@ -109,7 +109,7 @@ int parse_serial_com_port(const std::string& in) { } catch(const std::exception& e) { - std::cerr << "parse_serial_com_port: Error running stoi: " << e.what() << '\n'; + std::cerr << "parse_serial_com_port: Error running stoi: \'" << e.what() << "\' on string: \'" + num + "\' with original string: \'" + in + "\'\n"; } return returnval; diff --git a/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp b/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp index 16e74db..2f523e1 100644 --- a/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp +++ b/src/main/native/cpp/Drivers/Serial/SerialDriver.cpp @@ -51,6 +51,7 @@ std::vector SerialDriver::GetDevices() std::vector found = serial::list_ports(); for (auto& dev : found) { + std::cout << "Found serial device with hardware ID: " + dev.hardware_id + '\n'; if (parse_serial_com_port(dev.port) != -1 && dev.hardware_id.compare(SparkMax_HardwareId) == 0) { std::string name("SPARK MAX"); retval.push_back({dev.port, name, this->GetName()}); diff --git a/vendordeps/CANBridge.json b/vendordeps/CANBridge.json index 2c54a00..801dfe7 100644 --- a/vendordeps/CANBridge.json +++ b/vendordeps/CANBridge.json @@ -1,7 +1,7 @@ { "fileName": "CANBridge.json", "name": "CANBridge", - "version": "2.3.5", + "version": "2.3.6", "uuid": "34b37c7c-8acc-405f-9631-d21f20dc59d8", "mavenUrls": [ "http://www.revrobotics.com/content/sw/max/sdk/maven/" From e5c47d5400847842e6ae4c3672cbe44ab3727116 Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Mon, 1 Jul 2024 01:55:14 -0700 Subject: [PATCH 39/55] Attempt to fix C++ exceptions on macOS --- build.gradle | 2 +- publish.gradle | 2 +- vendordeps/CANBridge.json | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/build.gradle b/build.gradle index 7c112e2..9eb2cdd 100644 --- a/build.gradle +++ b/build.gradle @@ -77,7 +77,7 @@ model { } binaries.all { if (it.targetPlatform.name == 'osxuniversal') { - linker.args '-framework', 'IOKit' + linker.args '-framework', 'IOKit', '-Wl', '-keep_dwarf_unwind' } if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) { it.buildable = false diff --git a/publish.gradle b/publish.gradle index 30538b6..85e5ad8 100644 --- a/publish.gradle +++ b/publish.gradle @@ -2,7 +2,7 @@ apply plugin: 'maven-publish' ext.licenseFile = files("$rootDir/LICENSE.txt") -def pubVersion = '2.3.6' +def pubVersion = '2.3.7' def outputsFolder = file("$buildDir/allOutputs") diff --git a/vendordeps/CANBridge.json b/vendordeps/CANBridge.json index 801dfe7..dcd4579 100644 --- a/vendordeps/CANBridge.json +++ b/vendordeps/CANBridge.json @@ -1,7 +1,7 @@ { "fileName": "CANBridge.json", "name": "CANBridge", - "version": "2.3.6", + "version": "2.3.7", "uuid": "34b37c7c-8acc-405f-9631-d21f20dc59d8", "mavenUrls": [ "http://www.revrobotics.com/content/sw/max/sdk/maven/" From 16b913c5d112002a8609708601cfce9a9e587c33 Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Mon, 1 Jul 2024 02:13:22 -0700 Subject: [PATCH 40/55] Attempt to fix C++ exceptions on macOS part 2 --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index 9eb2cdd..4b2aeb0 100644 --- a/build.gradle +++ b/build.gradle @@ -77,7 +77,7 @@ model { } binaries.all { if (it.targetPlatform.name == 'osxuniversal') { - linker.args '-framework', 'IOKit', '-Wl', '-keep_dwarf_unwind' + linker.args '-framework', 'IOKit', '-Wl,-keep_dwarf_unwind', '-Wl,-compact-unwind' } if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) { it.buildable = false From 7a2a6554070759c5b6d6a5f58c73192cd7abfd8b Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Mon, 1 Jul 2024 02:16:45 -0700 Subject: [PATCH 41/55] Attempt to fix C++ exceptions on macOS part 3 --- build.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.gradle b/build.gradle index 4b2aeb0..8babb7f 100644 --- a/build.gradle +++ b/build.gradle @@ -77,7 +77,7 @@ model { } binaries.all { if (it.targetPlatform.name == 'osxuniversal') { - linker.args '-framework', 'IOKit', '-Wl,-keep_dwarf_unwind', '-Wl,-compact-unwind' + linker.args '-framework', 'IOKit', '-Wl,-keep_dwarf_unwind' } if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) { it.buildable = false From e5b0f8bc3e628dfcb2de71c102364501c67d13d0 Mon Sep 17 00:00:00 2001 From: QwertyChouskie Date: Mon, 1 Jul 2024 03:05:40 -0700 Subject: [PATCH 42/55] Attempt to fix C++ exceptions on macOS part 4: undo da changes The linker flag wasn't needed apparently --- build.gradle | 2 +- publish.gradle | 2 +- vendordeps/CANBridge.json | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/build.gradle b/build.gradle index 8babb7f..7c112e2 100644 --- a/build.gradle +++ b/build.gradle @@ -77,7 +77,7 @@ model { } binaries.all { if (it.targetPlatform.name == 'osxuniversal') { - linker.args '-framework', 'IOKit', '-Wl,-keep_dwarf_unwind' + linker.args '-framework', 'IOKit' } if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) { it.buildable = false diff --git a/publish.gradle b/publish.gradle index 85e5ad8..76913b0 100644 --- a/publish.gradle +++ b/publish.gradle @@ -2,7 +2,7 @@ apply plugin: 'maven-publish' ext.licenseFile = files("$rootDir/LICENSE.txt") -def pubVersion = '2.3.7' +def pubVersion = '2.3.8' def outputsFolder = file("$buildDir/allOutputs") diff --git a/vendordeps/CANBridge.json b/vendordeps/CANBridge.json index dcd4579..b177de9 100644 --- a/vendordeps/CANBridge.json +++ b/vendordeps/CANBridge.json @@ -1,7 +1,7 @@ { "fileName": "CANBridge.json", "name": "CANBridge", - "version": "2.3.7", + "version": "2.3.8", "uuid": "34b37c7c-8acc-405f-9631-d21f20dc59d8", "mavenUrls": [ "http://www.revrobotics.com/content/sw/max/sdk/maven/" From 505ccaf20d566253c0d47e54adbf0385f278132d Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Mon, 12 Aug 2024 18:01:51 -0500 Subject: [PATCH 43/55] Update SocketCANDevice class implementation Some of the functions and implementations were not readily available nor created. This now resolves those issues. --- .../cpp/Drivers/SocketCAN/SocketCANDriver.cpp | 78 +++++++++++++++++++ .../rev/Drivers/SocketCAN/SocketCANDevice.h | 12 +-- 2 files changed, 84 insertions(+), 6 deletions(-) diff --git a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp index 205aab7..8626544 100644 --- a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp +++ b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp @@ -87,6 +87,84 @@ std::unique_ptr SocketCANDriver::CreateDeviceFromDescriptor(const cha return std::unique_ptr(nullptr); } +SocketCANDevice::SocketCANDevice(const char* port) { + // Constructor implementation +} + +SocketCANDevice::~SocketCANDevice() { + // Destructor implementation +} + +std::string SocketCANDevice::GetName() const { + // Implementation + return "Name"; +} + +std::string SocketCANDevice::GetDescriptor() const { + // Implementation + return "Descriptor"; +} + +int SocketCANDevice::GetNumberOfErrors() { + // Implementation + return 0; +} + +int SocketCANDevice::GetId() const { + // Implementation + return 0; +} + +CANStatus SocketCANDevice::SendCANMessage(const CANMessage& msg, int periodMs) { + // Implementation + return CANStatus::kOk; +} + +CANStatus SocketCANDevice::ReceiveCANMessage(std::shared_ptr& msg, uint32_t messageID, uint32_t messageMask) { + // Implementation + return CANStatus::kOk; +} + +CANStatus SocketCANDevice::OpenStreamSession(uint32_t* sessionHandle, CANBridge_CANFilter filter, uint32_t maxSize) { + // Implementation + return CANStatus::kOk; +} + +CANStatus SocketCANDevice::CloseStreamSession(uint32_t sessionHandle) { + // Implementation + return CANStatus::kOk; +} + +CANStatus SocketCANDevice::ReadStreamSession(uint32_t sessionHandle, HAL_CANStreamMessage* msgs, uint32_t messagesToRead, uint32_t* messagesRead) { + // Implementation + return CANStatus::kOk; +} + +CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr) { + // Implementation + *percentBusUtilization = 0.0f; + *busOff = 0; + *txFull = 0; + *receiveErr = 0; + *transmitErr = 0; + return CANStatus::kOk; +} + +CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr, uint32_t* lastErrorTime) { + // Implementation + *percentBusUtilization = 0.0f; + *busOff = 0; + *txFull = 0; + *receiveErr = 0; + *transmitErr = 0; + *lastErrorTime = 0; + return CANStatus::kOk; +} + +bool SocketCANDevice::IsConnected() { + // Implementation + return true; +} } // namespace usb } // namespace rev diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h index f7c5c8e..a02b9e8 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h @@ -41,7 +41,7 @@ namespace usb { class SocketCANDevice : public CANDevice { public: - SocketCANDevice() =delete; + SocketCANDevice() = delete; SocketCANDevice(const char* port); virtual ~SocketCANDevice(); @@ -54,14 +54,14 @@ class SocketCANDevice : public CANDevice { virtual CANStatus SendCANMessage(const CANMessage& msg, int periodMs) override; virtual CANStatus ReceiveCANMessage(std::shared_ptr& msg, uint32_t messageID, uint32_t messageMask) override; virtual CANStatus OpenStreamSession(uint32_t* sessionHandle, CANBridge_CANFilter filter, uint32_t maxSize) override; - virtual CANStatus CloseStreamSession(uint32_t sessionHandle); - virtual CANStatus ReadStreamSession(uint32_t sessionHandle, HAL_CANStreamMessage* msgs, uint32_t messagesToRead, uint32_t* messagesRead); + virtual CANStatus CloseStreamSession(uint32_t sessionHandle) override; + virtual CANStatus ReadStreamSession(uint32_t sessionHandle, HAL_CANStreamMessage* msgs, uint32_t messagesToRead, uint32_t* messagesRead) override; - virtual CANStatus GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr); + virtual CANStatus GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr) override; + virtual CANStatus GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr, uint32_t* lastErrorTime) override; - virtual bool IsConnected(); + virtual bool IsConnected() override; private: - //SocketCANDeviceThread m_thread; std::string m_descriptor; std::string m_name; }; From 4fef873dda377e1049f9f54e0f0ee019e47474ff Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 16 Aug 2024 00:51:29 -0500 Subject: [PATCH 44/55] feat: Implement SocketCANDevice class This commit adds the implementation for the SocketCANDevice class, which was previously missing some functions and implementations. Now all required functions are available and the issues have been resolved. --- .../cpp/Drivers/SocketCAN/SocketCANDevice.cpp | 120 ++++++++++++++++++ .../cpp/Drivers/SocketCAN/SocketCANDriver.cpp | 79 ------------ 2 files changed, 120 insertions(+), 79 deletions(-) create mode 100644 src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp diff --git a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp new file mode 100644 index 0000000..17fd7af --- /dev/null +++ b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp @@ -0,0 +1,120 @@ +#ifdef __linux__ + +#include "rev/Drivers/SocketCAN/SocketCANDevice.h" + +#include +#include +#include + +namespace rev { +namespace usb { + +SocketCANDevice::SocketCANDevice(const char* port) { + m_thread(port){ + m_descriptor = port; + m_name = "SPARK MAX"; + m_thread.Start(); + } +} + +SocketCANDevice::~SocketCANDevice() { + m_thread.Stop(); +} + +std::string SocketCANDevice::GetName() const { + return m_name; +} + +std::string SocketCANDevice::GetDescriptor() const { + return m_descriptor; +} + +int SocketCANDevice::GetNumberOfErrors() { + return m_thread.GetNumberOfErrors(); +} + +int SocketCANDevice::GetId() const { + m_thread.EnqueueMessage(msg, periodMs); + return m_thread.GetLastThreadError(); +} + +CANStatus SocketCANDevice::SendCANMessage(const CANMessage& msg, int periodMs) { + m_thread.EnqueueMessage(msg, periodMs); + return m_thread.GetLastThreadError(); +} + +CANStatus SocketCANDevice::ReceiveCANMessage(std::shared_ptr& msg, uint32_t messageID, uint32_t messageMask) { + CANStatus status = CANStatus::kTimeout; + + // parse through the keys, find the messges the match, and return it + // The first in the message id, then the messages + std::map> messages; + m_thread.ReceiveMessage(messages); + std::shared_ptr mostRecent; + for (auto& m : messages) { + if ( + CANBridge_ProcessMask({m.second->GetMessageId(), 0}, m.first) + && CANBridge_ProcessMask({messageID, messageMask}, m.first) + && (!mostRecent || m.second->GetTimestampUs() > mostRecent->GetTimestampUs()) + ) { + mostRecent = m.second; + status = CANStatus::kOk; + } + } + + if (status == CANStatus::kOk) { + msg = mostRecent; + status = m_thread.GetLastThreadError(); + } else { + status = CANStatus::kError; + } + + + return status; +} + +CANStatus SocketCANDevice::OpenStreamSession(uint32_t* sessionHandle, CANBridge_CANFilter filter, uint32_t maxSize) { + CANStatus stat = CANStatus::kOk; + m_thread.OpenStream(sessionHandle, filter, maxSize, &stat); + return m_thread.GetLastThreadError(); +} + +CANStatus SocketCANDevice::CloseStreamSession(uint32_t sessionHandle) { + m_thread.CloseStream(sessionHandle); + return m_thread.GetLastThreadError(); +} +} + +CANStatus SocketCANDevice::ReadStreamSession(uint32_t sessionHandle, HAL_CANStreamMessage* msgs, uint32_t messagesToRead, uint32_t* messagesRead) { + m_thread.ReadStream(sessionHandle, msgs, messagesToRead, messagesRead); + return m_thread.GetLastThreadError(); +} + +CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr) { + rev::CANStatus status = m_thread.GetCANDetailStatus(percentBusUtilization, busOff, txFull, receiveErr, transmitErr); + return m_thread.GetLastThreadError; +} + +CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr, uint32_t* lastErrorTime) { + // Implementation + rev::usb::CANStatusDetails details; + *percentBusUtilization = 0.0f; + *busOff = details.busOffCount; + *txFull = details.txFullCount; + *receiveErr = details.retrieveErrCount; + *transmitErr = details.transmitErrCount; + *lastErrorTime = 0; // Not implemented + return m_thread.GetLastThreadError(); +} + +bool SocketCANDevice::IsConnected() { + // Implementation + return true; +} + +} // namespace usb +} // namespace rev + + +#else +#endif \ No newline at end of file diff --git a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp index 8626544..e604811 100644 --- a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp +++ b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDriver.cpp @@ -86,85 +86,6 @@ std::unique_ptr SocketCANDriver::CreateDeviceFromDescriptor(const cha } return std::unique_ptr(nullptr); } - -SocketCANDevice::SocketCANDevice(const char* port) { - // Constructor implementation -} - -SocketCANDevice::~SocketCANDevice() { - // Destructor implementation -} - -std::string SocketCANDevice::GetName() const { - // Implementation - return "Name"; -} - -std::string SocketCANDevice::GetDescriptor() const { - // Implementation - return "Descriptor"; -} - -int SocketCANDevice::GetNumberOfErrors() { - // Implementation - return 0; -} - -int SocketCANDevice::GetId() const { - // Implementation - return 0; -} - -CANStatus SocketCANDevice::SendCANMessage(const CANMessage& msg, int periodMs) { - // Implementation - return CANStatus::kOk; -} - -CANStatus SocketCANDevice::ReceiveCANMessage(std::shared_ptr& msg, uint32_t messageID, uint32_t messageMask) { - // Implementation - return CANStatus::kOk; -} - -CANStatus SocketCANDevice::OpenStreamSession(uint32_t* sessionHandle, CANBridge_CANFilter filter, uint32_t maxSize) { - // Implementation - return CANStatus::kOk; -} - -CANStatus SocketCANDevice::CloseStreamSession(uint32_t sessionHandle) { - // Implementation - return CANStatus::kOk; -} - -CANStatus SocketCANDevice::ReadStreamSession(uint32_t sessionHandle, HAL_CANStreamMessage* msgs, uint32_t messagesToRead, uint32_t* messagesRead) { - // Implementation - return CANStatus::kOk; -} - -CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr) { - // Implementation - *percentBusUtilization = 0.0f; - *busOff = 0; - *txFull = 0; - *receiveErr = 0; - *transmitErr = 0; - return CANStatus::kOk; -} - -CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr, uint32_t* lastErrorTime) { - // Implementation - *percentBusUtilization = 0.0f; - *busOff = 0; - *txFull = 0; - *receiveErr = 0; - *transmitErr = 0; - *lastErrorTime = 0; - return CANStatus::kOk; -} - -bool SocketCANDevice::IsConnected() { - // Implementation - return true; -} } // namespace usb } // namespace rev From aa836160f0beb11c6b20c6888e9fbd3ca5e10d0b Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 16 Aug 2024 01:31:11 -0500 Subject: [PATCH 45/55] Implement SocketCANDeviceThread in SocketCANDevice class This was missing the previous commit. Change compiler options to have SocketCANThread actually compile instead of not. --- src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h | 1 + src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h index a02b9e8..6729dd0 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h @@ -62,6 +62,7 @@ class SocketCANDevice : public CANDevice { virtual bool IsConnected() override; private: + SocketCANDeviceThread m_thread; std::string m_descriptor; std::string m_name; }; diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h index 00b3e6c..589ad1a 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h @@ -26,7 +26,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#if 0 +#ifdef __linux__ #pragma once From d81cf10f72441c40217f1990e555e4f07e28bc69 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 16 Aug 2024 01:34:00 -0500 Subject: [PATCH 46/55] refactor: Update include path for CanData header in SocketCANThread.h Mirroring SerialDeviceThread.h as it was changed years ago. --- src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp | 1 - src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp index 17fd7af..7bb45e1 100644 --- a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp +++ b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp @@ -83,7 +83,6 @@ CANStatus SocketCANDevice::CloseStreamSession(uint32_t sessionHandle) { m_thread.CloseStream(sessionHandle); return m_thread.GetLastThreadError(); } -} CANStatus SocketCANDevice::ReadStreamSession(uint32_t sessionHandle, HAL_CANStreamMessage* msgs, uint32_t messagesToRead, uint32_t* messagesRead) { m_thread.ReadStream(sessionHandle, msgs, messagesToRead, messagesRead); diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h index 589ad1a..edeec96 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h @@ -52,7 +52,7 @@ #include "candlelib/candle.h" -#include +#include #include namespace rev { From b5928b102b2a5b29ec569a3225b0e30ad12cebfe Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 16 Aug 2024 02:23:34 -0500 Subject: [PATCH 47/55] Fix compiler issues and broken functions Adding more compiler args to prevent other platforms that are not able to compile some platforms to compile files, as it would just error and fail the build. Fixing broken functions such as `SocketCANDevice::GetID()` as it was not returning a string. This is now not implemented but it returns an `int` which is correct for the function. --- src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp | 7 +++---- .../native/include/rev/Drivers/SocketCAN/SocketCANDevice.h | 4 +++- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp index 7bb45e1..c2bd604 100644 --- a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp +++ b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp @@ -34,8 +34,7 @@ int SocketCANDevice::GetNumberOfErrors() { } int SocketCANDevice::GetId() const { - m_thread.EnqueueMessage(msg, periodMs); - return m_thread.GetLastThreadError(); + return 0; } CANStatus SocketCANDevice::SendCANMessage(const CANMessage& msg, int periodMs) { @@ -84,13 +83,13 @@ CANStatus SocketCANDevice::CloseStreamSession(uint32_t sessionHandle) { return m_thread.GetLastThreadError(); } -CANStatus SocketCANDevice::ReadStreamSession(uint32_t sessionHandle, HAL_CANStreamMessage* msgs, uint32_t messagesToRead, uint32_t* messagesRead) { +CANStatus SocketCANDevice::ReadStreamSession(uint32_t sessionHandle, struct HAL_CANStreamMessage* msgs, uint32_t messagesToRead, uint32_t* messagesRead) { m_thread.ReadStream(sessionHandle, msgs, messagesToRead, messagesRead); return m_thread.GetLastThreadError(); } CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr) { - rev::CANStatus status = m_thread.GetCANDetailStatus(percentBusUtilization, busOff, txFull, receiveErr, transmitErr); + rev::usb::CANStatus status = m_thread.GetCANDetailStatus(percentBusUtilization, busOff, txFull, receiveErr, transmitErr); return m_thread.GetLastThreadError; } diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h index 6729dd0..cff1ce8 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h @@ -26,7 +26,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#pragma once +#ifdef __linux__ #include #include @@ -69,3 +69,5 @@ class SocketCANDevice : public CANDevice { } // namespace usb } // namespace rev + +#endif From 115e1110b3a6200f45f6cefb6368546c90647557 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Fri, 16 Aug 2024 16:05:50 -0500 Subject: [PATCH 48/55] Fix SocketCANDevice compilation and broken functions Fix SocketCANDevice from being broken on compiles, from broken constructors to missing includes. --- src/main/native/cpp/CANBridge.cpp | 2 +- .../cpp/Drivers/SocketCAN/SocketCANDevice.cpp | 22 +++++++++---------- .../rev/Drivers/SocketCAN/SocketCANDevice.h | 3 ++- .../rev/Drivers/SocketCAN/SocketCANThread.h | 18 +++++++-------- 4 files changed, 23 insertions(+), 22 deletions(-) diff --git a/src/main/native/cpp/CANBridge.cpp b/src/main/native/cpp/CANBridge.cpp index f1ed311..2d8a9fa 100644 --- a/src/main/native/cpp/CANBridge.cpp +++ b/src/main/native/cpp/CANBridge.cpp @@ -63,7 +63,7 @@ static const std::vector CANDriverList = { new rev::usb::SerialDriver() #endif #ifdef __linux__ - //new rev::usb::SocketCANDriver() + new rev::usb::SocketCANDriver() #endif }; diff --git a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp index c2bd604..30c5aa6 100644 --- a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp +++ b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp @@ -6,16 +6,18 @@ #include #include +#include +#include + namespace rev { namespace usb { -SocketCANDevice::SocketCANDevice(const char* port) { - m_thread(port){ +SocketCANDevice::SocketCANDevice(std::string port) : + m_thread(port) { m_descriptor = port; m_name = "SPARK MAX"; m_thread.Start(); } -} SocketCANDevice::~SocketCANDevice() { m_thread.Stop(); @@ -89,22 +91,20 @@ CANStatus SocketCANDevice::ReadStreamSession(uint32_t sessionHandle, struct HAL_ } CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr) { - rev::usb::CANStatus status = m_thread.GetCANDetailStatus(percentBusUtilization, busOff, txFull, receiveErr, transmitErr); - return m_thread.GetLastThreadError; -} - -CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr, uint32_t* lastErrorTime) { - // Implementation rev::usb::CANStatusDetails details; + m_thread.GetCANStatus(&details); *percentBusUtilization = 0.0f; *busOff = details.busOffCount; *txFull = details.txFullCount; - *receiveErr = details.retrieveErrCount; + *receiveErr = details.receiveErrCount; *transmitErr = details.transmitErrCount; - *lastErrorTime = 0; // Not implemented return m_thread.GetLastThreadError(); } +CANStatus SocketCANDevice::GetCANDetailStatus(float* percentBusUtilization, uint32_t* busOff, uint32_t* txFull, uint32_t* receiveErr, uint32_t* transmitErr, uint32_t* lastErrorTime) { + return GetCANDetailStatus(percentBusUtilization, busOff, txFull, receiveErr, transmitErr); +} + bool SocketCANDevice::IsConnected() { // Implementation return true; diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h index cff1ce8..956ba03 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANDevice.h @@ -26,6 +26,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ +#pragma once #ifdef __linux__ #include @@ -42,7 +43,7 @@ namespace usb { class SocketCANDevice : public CANDevice { public: SocketCANDevice() = delete; - SocketCANDevice(const char* port); + SocketCANDevice(std::string port); virtual ~SocketCANDevice(); virtual std::string GetName() const; diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h index edeec96..63b4d91 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h @@ -62,7 +62,7 @@ namespace usb { class SocketCANDeviceThread :public DriverDeviceThread { public: SocketCANDeviceThread() =delete; - SocketCANDeviceThread(const char* port, long long threadIntervalMs = 1) : DriverDeviceThread(0xe45b5597, threadIntervalMs) + SocketCANDeviceThread(std::string port, long long threadIntervalMs = 1) : DriverDeviceThread(0xe45b5597, threadIntervalMs) { } ~SocketCANDeviceThread() { @@ -96,8 +96,8 @@ class SocketCANDeviceThread :public DriverDeviceThread { private: candle_handle m_device; - void ReadMessages(bool &reading) { - candle_frame_t incomingFrame; + void ReadMessages(bool &reading) { + candle_frame_t incomingFrame; reading = candle_frame_read(m_device, &incomingFrame, 0); @@ -147,9 +147,9 @@ class SocketCANDeviceThread :public DriverDeviceThread { m_threadStatus = CANStatus::kOk; } - } + } - bool WriteMessages(detail::CANThreadSendQueueElement el, std::chrono::steady_clock::time_point now) { + bool WriteMessages(detail::CANThreadSendQueueElement el, std::chrono::steady_clock::time_point now) { if (el.m_intervalMs == 0 || (now - el.m_prevTimestamp >= std::chrono::milliseconds(el.m_intervalMs)) ) { candle_frame_t frame; frame.can_dlc = el.m_msg.GetSize(); @@ -170,7 +170,7 @@ class SocketCANDeviceThread :public DriverDeviceThread { } } return false; - } + } void CandleRun() { while (m_threadComplete == false) { @@ -187,7 +187,7 @@ class SocketCANDeviceThread :public DriverDeviceThread { if (m_sendQueue.size() > 0) { detail::CANThreadSendQueueElement el = m_sendQueue.front(); if (el.m_intervalMs == -1) { - m_sendQueue.pop(); + m_sendQueue.pop_front(); continue; } @@ -195,12 +195,12 @@ class SocketCANDeviceThread :public DriverDeviceThread { // Don't pop queue if send fails if (WriteMessages(el, now)) { - m_sendQueue.pop(); + m_sendQueue.pop_front(); // Return to end of queue if repeated if (el.m_intervalMs > 0 ) { el.m_prevTimestamp = now; - m_sendQueue.push(el); + m_sendQueue.push_back(el); } } } From bdd47425c905e2912a048361671d793221878c00 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Tue, 20 Aug 2024 18:14:43 -0500 Subject: [PATCH 49/55] Implement SocketCANDriver This is largely untested, however this should bring the functionality of the SocketCAN work somewhat back into play. --- src/main/native/cpp/CANBridge.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/main/native/cpp/CANBridge.cpp b/src/main/native/cpp/CANBridge.cpp index 2d8a9fa..64e2244 100644 --- a/src/main/native/cpp/CANBridge.cpp +++ b/src/main/native/cpp/CANBridge.cpp @@ -45,6 +45,10 @@ #include "rev/Drivers/SerialPort/SerialDriver.h" +#ifdef __linux__ +#include "rev/Drivers/SocketCAN/SocketCANDriver.h" +#endif + #include #include @@ -63,7 +67,8 @@ static const std::vector CANDriverList = { new rev::usb::SerialDriver() #endif #ifdef __linux__ - new rev::usb::SocketCANDriver() + new rev::usb::SocketCANDriver(), + new rev::usb::SerialDriver() #endif }; @@ -315,3 +320,4 @@ void CANBridge_UnregisterDeviceFromHAL(const char* descriptor) } + From 221ea27370726c784a886fca75a356acb0c8a6fc Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Wed, 21 Aug 2024 16:59:01 -0500 Subject: [PATCH 50/55] Rewrite SocketCANThread header This tears out the majority of what was [candle_dll](https://github.com/HubertD/candle_dll/tree/master) for the Linux driver and implemented the Linux [SocketCAN](https://docs.kernel.org/networking/can.html) driver. Preliminary testing shows that this does functionally work with a single SPARK MAX motor controller, however further testing may be required. --- .../rev/Drivers/SocketCAN/SocketCANThread.h | 157 +++++++++--------- 1 file changed, 80 insertions(+), 77 deletions(-) diff --git a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h index 63b4d91..d643d9f 100644 --- a/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h +++ b/src/main/native/include/rev/Drivers/SocketCAN/SocketCANThread.h @@ -1,31 +1,3 @@ -/* - * Copyright (c) 2019 - 2020 REV Robotics - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. 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. - * 3. Neither the name of REV Robotics 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 OWNER 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. - */ - #ifdef __linux__ #pragma once @@ -37,11 +9,13 @@ #include #include #include - -// TODO: remove me -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include #include "rev/CANMessage.h" #include "rev/CANBridgeUtils.h" @@ -50,22 +24,22 @@ #include "utils/ThreadUtils.h" -#include "candlelib/candle.h" - #include #include namespace rev { namespace usb { - -class SocketCANDeviceThread :public DriverDeviceThread { +class SocketCANDeviceThread : public DriverDeviceThread { public: - SocketCANDeviceThread() =delete; - SocketCANDeviceThread(std::string port, long long threadIntervalMs = 1) : DriverDeviceThread(0xe45b5597, threadIntervalMs) - { } - ~SocketCANDeviceThread() - { + SocketCANDeviceThread() = delete; + SocketCANDeviceThread(std::string port, long long threadIntervalMs = 1) + : DriverDeviceThread(0xe45b5597, threadIntervalMs), m_port(port), m_socket(-1) { } + + ~SocketCANDeviceThread() { + if (m_socket != -1) { + close(m_socket); + } } void Start() override { @@ -73,7 +47,13 @@ class SocketCANDeviceThread :public DriverDeviceThread { m_thread->join(); } - m_thread = std::make_unique(&SocketCANDeviceThread::CandleRun, this); + // Initialize SocketCAN + if (!initializeSocketCAN()) { + m_threadStatus = CANStatus::kError; + return; + } + + m_thread = std::make_unique(&SocketCANDeviceThread::SocketRun, this); // Set to high priority to prevent buffer overflow on the device on high client CPU load utils::SetThreadPriority(m_thread.get(), utils::ThreadPriority::High); @@ -91,51 +71,78 @@ class SocketCANDeviceThread :public DriverDeviceThread { *status = CANStatus::kOk; } +private: + std::string m_port; + int m_socket; + + bool initializeSocketCAN() { + struct ifreq ifr; + struct sockaddr_can addr; + + // Create socket + m_socket = socket(PF_CAN, SOCK_RAW, CAN_RAW); + if (m_socket < 0) { + perror("SocketCAN socket"); + return false; + } + // Specify CAN interface + std::strncpy(ifr.ifr_name, m_port.c_str(), IFNAMSIZ - 1); + if (ioctl(m_socket, SIOCGIFINDEX, &ifr) < 0) { + perror("SocketCAN ioctl"); + return false; + } + + // Bind the socket to the CAN interface + addr.can_family = AF_CAN; + addr.can_ifindex = ifr.ifr_ifindex; + if (bind(m_socket, (struct sockaddr *)&addr, sizeof(addr)) < 0) { + perror("SocketCAN bind"); + return false; + } + + return true; + } -private: - candle_handle m_device; - void ReadMessages(bool &reading) { - candle_frame_t incomingFrame; - - reading = candle_frame_read(m_device, &incomingFrame, 0); + struct can_frame frame; + int nbytes = read(m_socket, &frame, sizeof(struct can_frame)); - // Received a new frame, store it + reading = (nbytes > 0); if (reading) { - candle_frametype_t frameType = candle_frame_type(&incomingFrame); - if(frameType == CANDLE_FRAMETYPE_ERROR) { + if (frame.can_id & CAN_ERR_FLAG) { + // Handle error frame + m_statusDetails.busOffCount++; + m_threadStatus = CANStatus::kError; // Parse error data - if (incomingFrame.can_id & 0x00000040) { + if (frame.can_id & 0x00000040) { m_statusDetails.busOffCount++; } - if (incomingFrame.data[1] & 0x02) { + if (frame.data[1] & 0x02) { m_statusDetails.txFullCount++; } - if (incomingFrame.data[1] & 0x10 || incomingFrame.data[1] & 0x04) { + if (frame.data[1] & 0x10 || frame.data[1] & 0x04) { m_statusDetails.receiveErrCount++; } - if (incomingFrame.data[1] & 0x20 || incomingFrame.data[1] & 0x08 || incomingFrame.data[2] & 0x80 || incomingFrame.data[4]) { + if (frame.data[1] & 0x20 || frame.data[1] & 0x08 || frame.data[2] & 0x80 || frame.data[4]) { m_statusDetails.transmitErrCount++; } - } else if(frameType == CANDLE_FRAMETYPE_RECEIVE) { - - auto msg = std::make_shared(candle_frame_id(&incomingFrame), - candle_frame_data(&incomingFrame), - candle_frame_dlc(&incomingFrame), - candle_frame_timestamp_us(&incomingFrame)); + } else { + auto msg = std::make_shared(frame.can_id, + frame.data, + frame.can_dlc, + std::chrono::steady_clock::now().time_since_epoch().count() / 1000); // Read functions { std::lock_guard lock(m_readMutex); - m_readStore[candle_frame_id(&incomingFrame)] = msg; + m_readStore[frame.can_id] = msg; } // Streaming functions { std::lock_guard lock(m_streamMutex); for (auto& stream : m_readStream) { - // Compare current size of the buffer to the max size of the buffer if (!stream.second->messages.IsFull() && rev::usb::CANBridge_ProcessMask({stream.second->messageId, stream.second->messageMask}, msg->GetMessageId())) { @@ -150,17 +157,14 @@ class SocketCANDeviceThread :public DriverDeviceThread { } bool WriteMessages(detail::CANThreadSendQueueElement el, std::chrono::steady_clock::time_point now) { - if (el.m_intervalMs == 0 || (now - el.m_prevTimestamp >= std::chrono::milliseconds(el.m_intervalMs)) ) { - candle_frame_t frame; + if (el.m_intervalMs <= 1 || (now - el.m_prevTimestamp >= std::chrono::milliseconds(el.m_intervalMs)) ) { + struct can_frame frame; + frame.can_id = el.m_msg.GetMessageId(); frame.can_dlc = el.m_msg.GetSize(); - // set extended id flag - frame.can_id = el.m_msg.GetMessageId() | 0x80000000; - memcpy(frame.data, el.m_msg.GetData(), frame.can_dlc); - frame.timestamp_us = now.time_since_epoch().count() / 1000; - - // TODO: Feed back an error - if (candle_frame_send(m_device, 0, &frame, false, 20) == false) { - // std::cout << "Failed to send message: " << std::hex << (int)el.m_msg.GetMessageId() << std::dec << " " << candle_error_text(candle_dev_last_error(m_device)) << std::endl; + std::memcpy(frame.data, el.m_msg.GetData(), frame.can_dlc); + + int nbytes = write(m_socket, &frame, sizeof(struct can_frame)); + if (nbytes != sizeof(struct can_frame)) { m_threadStatus = CANStatus::kDeviceWriteError; m_statusErrCount++; return false; @@ -172,7 +176,7 @@ class SocketCANDeviceThread :public DriverDeviceThread { return false; } - void CandleRun() { + void SocketRun() { while (m_threadComplete == false) { m_threadStatus = CANStatus::kOk; // Start each loop with the status being good. Really only a write issue. auto sleepTime = std::chrono::steady_clock::now() + std::chrono::milliseconds(m_threadIntervalMs); @@ -211,11 +215,10 @@ class SocketCANDeviceThread :public DriverDeviceThread { std::this_thread::sleep_until(sleepTime); } } - } }; } // namespace usb } // namespace rev -#endif +#endif \ No newline at end of file From 67448aece675f2e9ca05a04e50f27debeaffa1d4 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Wed, 21 Aug 2024 17:23:51 -0500 Subject: [PATCH 51/55] Update README.md Updated section for Linux support. --- README.md | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 185e363..1a0f68c 100644 --- a/README.md +++ b/README.md @@ -65,11 +65,15 @@ The output is placed at `~\releases\maven\release\com\revrobotics\usb\CANBridge- ## Linux -This branch is a work in progress. The latest firmware version will work with Linux if the socketCAN and gs_usb drivers are enabled. The following udev rule will work to enable this: +> [!NOTE] +> +> This branch is a work in progress, testing does show that it does work, however this still might be some issues. If you do run across those issues, please create an issue so we can diagnose. -/etc/udev/rules.d/ +The latest firmware version will work with Linux if the `SocketCAN` and `gs_usb` drivers are enabled. The following udev rule will work to enable this: -``` +Create a new file named and located at: `/etc/udev/rules.d/99-canbridge.rules` + +```text ACTION=="add", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="a30e", RUN+="/sbin/modprobe gs_usb" RUN+="/bin/sh -c 'echo 0483 a30e > /sys/bus/usb/drivers/gs_usb/new_id'" ``` From 6576ec723b49fe3d5d8099e83858ddd2718e2753 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Thu, 15 Aug 2024 14:59:16 -0500 Subject: [PATCH 52/55] chore: Update googletest dependency The googletest dependency was using an older version from the WPILib Artifactory, this was causing issues with builds on macOS where `osxuniversal` platform type was not available, and split between `osxarm64` and `osxx86-64`. --- config.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config.gradle b/config.gradle index a9f4a42..5c29469 100644 --- a/config.gradle +++ b/config.gradle @@ -8,7 +8,7 @@ nativeUtils { // When updating WPILib, be sure to also update wpiHalVersion.txt wpiVersion = "2023.+" niLibVersion = "2023.3.0" - googleTestVersion = "1.11.0-3" + googleTestVersion = "1.11.0-4" } } } From 70d10f36e11bdbf65b5fe3c7d3278d3897229b5b Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Thu, 22 Aug 2024 09:47:43 -0500 Subject: [PATCH 53/55] Remove dangling serial driver Plans to fully delete the serial driver are underway, as this is not supported or even functioning with current firmware. --- src/main/native/cpp/CANBridge.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/native/cpp/CANBridge.cpp b/src/main/native/cpp/CANBridge.cpp index 64e2244..980dddc 100644 --- a/src/main/native/cpp/CANBridge.cpp +++ b/src/main/native/cpp/CANBridge.cpp @@ -64,11 +64,9 @@ struct CANBridge_Scan { static const std::vector CANDriverList = { #ifdef _WIN32 new rev::usb::CandleWinUSBDriver(), - new rev::usb::SerialDriver() #endif #ifdef __linux__ new rev::usb::SocketCANDriver(), - new rev::usb::SerialDriver() #endif }; From 13e38713079087df0d49b2702de61d4b09079e81 Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Thu, 29 Aug 2024 23:52:57 -0500 Subject: [PATCH 54/55] Change hardcoded name for SocketCANDevice SocketCAN devices aren't exclusively, changing it to something more generic. --- src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp index 30c5aa6..cd36981 100644 --- a/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp +++ b/src/main/native/cpp/Drivers/SocketCAN/SocketCANDevice.cpp @@ -15,7 +15,8 @@ namespace usb { SocketCANDevice::SocketCANDevice(std::string port) : m_thread(port) { m_descriptor = port; - m_name = "SPARK MAX"; + // TODO: Get the name of the device, for now just hardcode the name + m_name = "SocketCAN Device"; m_thread.Start(); } From 725b059b66c212e76c21e676d60ecacf23719b2a Mon Sep 17 00:00:00 2001 From: Garrett Summerfield Date: Sat, 31 Aug 2024 01:05:18 -0500 Subject: [PATCH 55/55] Update GoogleTest harness The current implementation of the tests were accounting for only Linux platforms for SocketCAN, this has been changed to allow for all currently supported platforms. This also removes conditionals that prevented any GoogleTests from running. --- src/test/gtest/cpp/main.cpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/src/test/gtest/cpp/main.cpp b/src/test/gtest/cpp/main.cpp index cdb64cc..55a2d05 100644 --- a/src/test/gtest/cpp/main.cpp +++ b/src/test/gtest/cpp/main.cpp @@ -32,12 +32,20 @@ #include "gtest/gtest.h" +#ifdef __linux__ #include - +#elif _WIN32 +#include +#endif int main(int argc, char** argv) { + #ifdef __linux__ rev::usb::SocketCANDriver driver; + #elif _WIN32 + rev::usb::CandleWinUSBDriver driver; + #endif + auto output = driver.GetDevices(); @@ -54,9 +62,6 @@ int main(int argc, char** argv) { std::cout << "Selected device: " << device->GetName() << std::endl; - return 0; - - #if 0 HAL_Initialize(500, 0); frc::MockDS ds; ds.start(); @@ -66,5 +71,4 @@ int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); int ret = RUN_ALL_TESTS(); return ret; - #endif }