From 322aa0c6f1596462f5248843bdc9a5f6859eb0db Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Sat, 12 Aug 2023 22:58:37 +0200 Subject: [PATCH 01/11] [Telemetry] Fix clang-tidy issues --- .clang-tidy | 7 ++ telemetry/lib/Crc/Crc.cpp | 98 ++++++++++----------- telemetry/lib/Crc/Crc.hpp | 2 +- telemetry/lib/LqCalculator/LqCalculator.hpp | 2 +- telemetry/lib/Random/Random.cpp | 9 +- telemetry/lib/Random/Random.hpp | 14 +-- telemetry/lib/Thermistor/Thermistor.hpp | 7 +- telemetry/lib/TinyGps/TinyGps.hpp | 5 +- telemetry/src/Common.cpp | 3 +- telemetry/src/Common.hpp | 3 +- telemetry/src/Fhss/Fhss.cpp | 82 +++++++++-------- telemetry/src/Fhss/Fhss.hpp | 22 +++-- telemetry/src/Gps/Gps.cpp | 29 +++--- telemetry/src/Main.cpp | 76 +++++++++------- telemetry/src/SerialComm/Parser.cpp | 61 ++++++++----- telemetry/src/SerialComm/Parser.hpp | 58 ++++++------ telemetry/src/SerialComm/Serial.hpp | 4 +- telemetry/src/Transmission/Transmission.cpp | 78 +++++++++------- telemetry/src/Transmission/Transmission.hpp | 42 ++++----- 19 files changed, 332 insertions(+), 270 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 22f5ffdf..09cf1563 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -11,6 +11,10 @@ # - hicpp-deprecated-headers,modernize-deprecated-headers # - hicpp-use-nullptr,modernize-use-nullptr +# Reasons for disabling certain checks: +# - llvm-header-guard: Giving false positives, either because of the copyright lines or because we're using #pragma once +# - performance-no-int-to-ptr,cppcoreguidelines-pro-type-cstyle-cast: HAL library relies on int to ptr conversions heavily + Checks: > bugprone-*, -bugprone-easily-swappable-parameters, @@ -24,6 +28,7 @@ Checks: > -cppcoreguidelines-pro-bounds-array-to-pointer-decay, -cppcoreguidelines-pro-bounds-pointer-arithmetic, -cppcoreguidelines-narrowing-conversions, + -cppcoreguidelines-pro-type-cstyle-cast, google-*, -google-readability-todo, -google-readability-braces-around-statements, @@ -42,6 +47,7 @@ Checks: > -hicpp-use-equals-default, llvm-*, -llvm-else-after-return, + -llvm-header-guard, misc-*, -misc-non-private-member-variables-in-classes, modernize-*, @@ -49,6 +55,7 @@ Checks: > -modernize-avoid-c-arrays, -modernize-macro-to-enum, performance-*, + -performance-no-int-to-ptr, portability-*, readability-*, -readability-magic-numbers, diff --git a/telemetry/lib/Crc/Crc.cpp b/telemetry/lib/Crc/Crc.cpp index d1ddd820..056c5e84 100644 --- a/telemetry/lib/Crc/Crc.cpp +++ b/telemetry/lib/Crc/Crc.cpp @@ -18,64 +18,58 @@ #include static const std::array crc32_tab = { - 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3, - 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, - 0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7, - 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5, - 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, - 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59, - 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f, - 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d, - 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433, - 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01, - 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, - 0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65, - 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb, - 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, - 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f, - 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad, - 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683, - 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1, - 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7, - 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, - 0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b, - 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79, - 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, - 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d, - 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713, - 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21, - 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777, - 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45, - 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, - 0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9, - 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf, - 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d}; + 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3, 0x0edb8832, + 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, 0x1db71064, 0x6ab020f2, + 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7, 0x136c9856, 0x646ba8c0, 0xfd62f97a, + 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5, 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, + 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, + 0x45df5c75, 0xdcd60dcf, 0xabd13d59, 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, + 0xcfba9599, 0xb8bda50f, 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, + 0xb6662d3d, 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433, + 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01, 0x6b6b51f4, + 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, 0x65b0d9c6, 0x12b7e950, + 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65, 0x4db26158, 0x3ab551ce, 0xa3bc0074, + 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb, 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, + 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, + 0x206f85b3, 0xb966d409, 0xce61e49f, 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, + 0xb7bd5c3b, 0xc0ba6cad, 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, + 0x73dc1683, 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1, + 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7, 0xfed41b76, + 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, 0xd6d6a3e8, 0xa1d1937e, + 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b, 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, + 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79, 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, + 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, + 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d, 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, + 0x72076785, 0x05005713, 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, + 0x0bdbdf21, 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777, + 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45, 0xa00ae278, + 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, 0xaed16a4a, 0xd9d65adc, + 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9, 0xbdbdf21c, 0xcabac28a, 0x53b39330, + 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf, 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, + 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d}; static const std::array crc8_tab = { - 0x00, 0x31, 0x62, 0x53, 0xc4, 0xf5, 0xa6, 0x97, 0xb9, 0x88, 0xdb, 0xea, 0x7d, 0x4c, 0x1f, 0x2e, - 0x43, 0x72, 0x21, 0x10, 0x87, 0xb6, 0xe5, 0xd4, 0xfa, 0xcb, 0x98, 0xa9, 0x3e, 0x0f, 0x5c, 0x6d, - 0x86, 0xb7, 0xe4, 0xd5, 0x42, 0x73, 0x20, 0x11, 0x3f, 0x0e, 0x5d, 0x6c, 0xfb, 0xca, 0x99, 0xa8, - 0xc5, 0xf4, 0xa7, 0x96, 0x01, 0x30, 0x63, 0x52, 0x7c, 0x4d, 0x1e, 0x2f, 0xb8, 0x89, 0xda, 0xeb, - 0x3d, 0x0c, 0x5f, 0x6e, 0xf9, 0xc8, 0x9b, 0xaa, 0x84, 0xb5, 0xe6, 0xd7, 0x40, 0x71, 0x22, 0x13, - 0x7e, 0x4f, 0x1c, 0x2d, 0xba, 0x8b, 0xd8, 0xe9, 0xc7, 0xf6, 0xa5, 0x94, 0x03, 0x32, 0x61, 0x50, - 0xbb, 0x8a, 0xd9, 0xe8, 0x7f, 0x4e, 0x1d, 0x2c, 0x02, 0x33, 0x60, 0x51, 0xc6, 0xf7, 0xa4, 0x95, - 0xf8, 0xc9, 0x9a, 0xab, 0x3c, 0x0d, 0x5e, 0x6f, 0x41, 0x70, 0x23, 0x12, 0x85, 0xb4, 0xe7, 0xd6, - 0x7a, 0x4b, 0x18, 0x29, 0xbe, 0x8f, 0xdc, 0xed, 0xc3, 0xf2, 0xa1, 0x90, 0x07, 0x36, 0x65, 0x54, - 0x39, 0x08, 0x5b, 0x6a, 0xfd, 0xcc, 0x9f, 0xae, 0x80, 0xb1, 0xe2, 0xd3, 0x44, 0x75, 0x26, 0x17, - 0xfc, 0xcd, 0x9e, 0xaf, 0x38, 0x09, 0x5a, 0x6b, 0x45, 0x74, 0x27, 0x16, 0x81, 0xb0, 0xe3, 0xd2, - 0xbf, 0x8e, 0xdd, 0xec, 0x7b, 0x4a, 0x19, 0x28, 0x06, 0x37, 0x64, 0x55, 0xc2, 0xf3, 0xa0, 0x91, - 0x47, 0x76, 0x25, 0x14, 0x83, 0xb2, 0xe1, 0xd0, 0xfe, 0xcf, 0x9c, 0xad, 0x3a, 0x0b, 0x58, 0x69, - 0x04, 0x35, 0x66, 0x57, 0xc0, 0xf1, 0xa2, 0x93, 0xbd, 0x8c, 0xdf, 0xee, 0x79, 0x48, 0x1b, 0x2a, - 0xc1, 0xf0, 0xa3, 0x92, 0x05, 0x34, 0x67, 0x56, 0x78, 0x49, 0x1a, 0x2b, 0xbc, 0x8d, 0xde, 0xef, - 0x82, 0xb3, 0xe0, 0xd1, 0x46, 0x77, 0x24, 0x15, 0x3b, 0x0a, 0x59, 0x68, 0xff, 0xce, 0x9d, 0xac}; + 0x00, 0x31, 0x62, 0x53, 0xc4, 0xf5, 0xa6, 0x97, 0xb9, 0x88, 0xdb, 0xea, 0x7d, 0x4c, 0x1f, 0x2e, 0x43, 0x72, 0x21, + 0x10, 0x87, 0xb6, 0xe5, 0xd4, 0xfa, 0xcb, 0x98, 0xa9, 0x3e, 0x0f, 0x5c, 0x6d, 0x86, 0xb7, 0xe4, 0xd5, 0x42, 0x73, + 0x20, 0x11, 0x3f, 0x0e, 0x5d, 0x6c, 0xfb, 0xca, 0x99, 0xa8, 0xc5, 0xf4, 0xa7, 0x96, 0x01, 0x30, 0x63, 0x52, 0x7c, + 0x4d, 0x1e, 0x2f, 0xb8, 0x89, 0xda, 0xeb, 0x3d, 0x0c, 0x5f, 0x6e, 0xf9, 0xc8, 0x9b, 0xaa, 0x84, 0xb5, 0xe6, 0xd7, + 0x40, 0x71, 0x22, 0x13, 0x7e, 0x4f, 0x1c, 0x2d, 0xba, 0x8b, 0xd8, 0xe9, 0xc7, 0xf6, 0xa5, 0x94, 0x03, 0x32, 0x61, + 0x50, 0xbb, 0x8a, 0xd9, 0xe8, 0x7f, 0x4e, 0x1d, 0x2c, 0x02, 0x33, 0x60, 0x51, 0xc6, 0xf7, 0xa4, 0x95, 0xf8, 0xc9, + 0x9a, 0xab, 0x3c, 0x0d, 0x5e, 0x6f, 0x41, 0x70, 0x23, 0x12, 0x85, 0xb4, 0xe7, 0xd6, 0x7a, 0x4b, 0x18, 0x29, 0xbe, + 0x8f, 0xdc, 0xed, 0xc3, 0xf2, 0xa1, 0x90, 0x07, 0x36, 0x65, 0x54, 0x39, 0x08, 0x5b, 0x6a, 0xfd, 0xcc, 0x9f, 0xae, + 0x80, 0xb1, 0xe2, 0xd3, 0x44, 0x75, 0x26, 0x17, 0xfc, 0xcd, 0x9e, 0xaf, 0x38, 0x09, 0x5a, 0x6b, 0x45, 0x74, 0x27, + 0x16, 0x81, 0xb0, 0xe3, 0xd2, 0xbf, 0x8e, 0xdd, 0xec, 0x7b, 0x4a, 0x19, 0x28, 0x06, 0x37, 0x64, 0x55, 0xc2, 0xf3, + 0xa0, 0x91, 0x47, 0x76, 0x25, 0x14, 0x83, 0xb2, 0xe1, 0xd0, 0xfe, 0xcf, 0x9c, 0xad, 0x3a, 0x0b, 0x58, 0x69, 0x04, + 0x35, 0x66, 0x57, 0xc0, 0xf1, 0xa2, 0x93, 0xbd, 0x8c, 0xdf, 0xee, 0x79, 0x48, 0x1b, 0x2a, 0xc1, 0xf0, 0xa3, 0x92, + 0x05, 0x34, 0x67, 0x56, 0x78, 0x49, 0x1a, 0x2b, 0xbc, 0x8d, 0xde, 0xef, 0x82, 0xb3, 0xe0, 0xd1, 0x46, 0x77, 0x24, + 0x15, 0x3b, 0x0a, 0x59, 0x68, 0xff, 0xce, 0x9d, 0xac}; uint32_t crc32(const uint8_t *buf, size_t size) { const uint8_t *p = buf; - uint32_t crc; + uint32_t crc = ~0U; - crc = ~0U; - while (size--) { - crc = crc32_tab[(crc ^ *p++) & 0xFF] ^ (crc >> 8); + while (size-- > 0) { + crc = crc32_tab[(crc ^ *p++) & 0xFFU] ^ (crc >> 8U); } return crc ^ ~0U; } diff --git a/telemetry/lib/Crc/Crc.hpp b/telemetry/lib/Crc/Crc.hpp index 2f63319b..dd0bc069 100644 --- a/telemetry/lib/Crc/Crc.hpp +++ b/telemetry/lib/Crc/Crc.hpp @@ -16,8 +16,8 @@ #pragma once -#include #include +#include uint32_t crc32(const uint8_t *buf, size_t size); uint8_t crc8(const uint8_t *buf, size_t size); diff --git a/telemetry/lib/LqCalculator/LqCalculator.hpp b/telemetry/lib/LqCalculator/LqCalculator.hpp index b9c0ae1b..c80018ee 100644 --- a/telemetry/lib/LqCalculator/LqCalculator.hpp +++ b/telemetry/lib/LqCalculator/LqCalculator.hpp @@ -16,7 +16,7 @@ #pragma once -#include +#include template class LqCalculator { diff --git a/telemetry/lib/Random/Random.cpp b/telemetry/lib/Random/Random.cpp index 3aabe44b..da3ba8ca 100644 --- a/telemetry/lib/Random/Random.cpp +++ b/telemetry/lib/Random/Random.cpp @@ -16,17 +16,18 @@ #include "Random.hpp" +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static uint32_t seed = 0; // returns values between 0 and 0x7FFF // NB rngN depends on this output range, so if we change the // behaviour rngN will need updating -uint16_t rng(void) { +uint16_t rng() { const uint32_t m = 2147483648; const uint32_t a = 214013; const uint32_t c = 2531011; seed = (a * seed + c) % m; - return seed >> 16; + return seed >> 16U; } void rngSeed(const uint32_t newSeed) { seed = newSeed; } @@ -35,7 +36,7 @@ void rngSeed(const uint32_t newSeed) { seed = newSeed; } uint8_t rngN(const uint8_t max) { return rng() % max; } // 0..255 returned -uint8_t rng8Bit(void) { return rng() & 0xff; } +uint8_t rng8Bit() { return rng() & 0xFFU; } // 0..31 returned -uint8_t rng5Bit(void) { return rng() & 0x1F; } +uint8_t rng5Bit() { return rng() & 0x1FU; } diff --git a/telemetry/lib/Random/Random.hpp b/telemetry/lib/Random/Random.hpp index 7ec7a105..53568660 100644 --- a/telemetry/lib/Random/Random.hpp +++ b/telemetry/lib/Random/Random.hpp @@ -16,18 +16,18 @@ #pragma once -#include +#include // the max value returned by rng -#define RNG_MAX 0x7FFF +constexpr uint16_t kRngMax = 0x7FFF; -uint16_t rng(void); +uint16_t rng(); void rngSeed(uint32_t newSeed); // 0..255 returned -uint8_t rng8Bit(void); +uint8_t rng8Bit(); // 0..31 returned -uint8_t rng5Bit(void); +uint8_t rng5Bit(); -// returns 0 <= x < upper where n < 256 -uint8_t rngN(uint8_t upper); +// returns 0 <= x < max where n < 256 +uint8_t rngN(uint8_t max); diff --git a/telemetry/lib/Thermistor/Thermistor.hpp b/telemetry/lib/Thermistor/Thermistor.hpp index 63ecc201..a4307c03 100644 --- a/telemetry/lib/Thermistor/Thermistor.hpp +++ b/telemetry/lib/Thermistor/Thermistor.hpp @@ -16,14 +16,15 @@ #pragma once -#include -#include #include +#include + +#include template class Thermistor { public: - Thermistor(ADC_HandleTypeDef *adc) : adcHandle(adc) { HAL_ADC_Start_DMA(adc, &rawAdcValue, 1); } + explicit Thermistor(ADC_HandleTypeDef *adc) : adcHandle(adc) { HAL_ADC_Start_DMA(adc, &rawAdcValue, 1); } float getTemperature() { float resistance = 10000.0F / ((65535.0F / static_cast((uint16_t)rawAdcValue)) - 1.0F); diff --git a/telemetry/lib/TinyGps/TinyGps.hpp b/telemetry/lib/TinyGps/TinyGps.hpp index 0f73189a..3e340b0a 100644 --- a/telemetry/lib/TinyGps/TinyGps.hpp +++ b/telemetry/lib/TinyGps/TinyGps.hpp @@ -24,8 +24,9 @@ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA #ifndef __TinyGPSPlus_h #define __TinyGPSPlus_h -#include -#include +#include +#include + #include #define _GPS_VERSION "1.0.2" // software version of this library diff --git a/telemetry/src/Common.cpp b/telemetry/src/Common.cpp index 1e4de65d..e685e89a 100644 --- a/telemetry/src/Common.cpp +++ b/telemetry/src/Common.cpp @@ -16,6 +16,7 @@ #include "Common.hpp" +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) Transmission link; - bool send_version_num = false; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) diff --git a/telemetry/src/Common.hpp b/telemetry/src/Common.hpp index b0705f94..bd8fe4b8 100644 --- a/telemetry/src/Common.hpp +++ b/telemetry/src/Common.hpp @@ -18,6 +18,7 @@ #include "Transmission/Transmission.hpp" +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) extern Transmission link; - extern bool send_version_num; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) diff --git a/telemetry/src/Fhss/Fhss.cpp b/telemetry/src/Fhss/Fhss.cpp index c23de87d..ece1d106 100644 --- a/telemetry/src/Fhss/Fhss.cpp +++ b/telemetry/src/Fhss/Fhss.cpp @@ -15,70 +15,72 @@ /// along with this program. If not, see . #include "Fhss.hpp" -#include +#include + #define RADIO_SX128X #define Regulatory_Domain_ISM_2400 -const uint32_t FHSSfreqs[] = { - FREQ_HZ_TO_REG_VAL(2400400000), FREQ_HZ_TO_REG_VAL(2401400000), FREQ_HZ_TO_REG_VAL(2402400000), - FREQ_HZ_TO_REG_VAL(2403400000), FREQ_HZ_TO_REG_VAL(2404400000), +const uint32_t FHSSfreqs[] = {FreqHzToRegVal(2400400000), FreqHzToRegVal(2401400000), FreqHzToRegVal(2402400000), + FreqHzToRegVal(2403400000), FreqHzToRegVal(2404400000), - FREQ_HZ_TO_REG_VAL(2405400000), FREQ_HZ_TO_REG_VAL(2406400000), FREQ_HZ_TO_REG_VAL(2407400000), - FREQ_HZ_TO_REG_VAL(2408400000), FREQ_HZ_TO_REG_VAL(2409400000), + FreqHzToRegVal(2405400000), FreqHzToRegVal(2406400000), FreqHzToRegVal(2407400000), + FreqHzToRegVal(2408400000), FreqHzToRegVal(2409400000), - FREQ_HZ_TO_REG_VAL(2410400000), FREQ_HZ_TO_REG_VAL(2411400000), FREQ_HZ_TO_REG_VAL(2412400000), - FREQ_HZ_TO_REG_VAL(2413400000), FREQ_HZ_TO_REG_VAL(2414400000), + FreqHzToRegVal(2410400000), FreqHzToRegVal(2411400000), FreqHzToRegVal(2412400000), + FreqHzToRegVal(2413400000), FreqHzToRegVal(2414400000), - FREQ_HZ_TO_REG_VAL(2415400000), FREQ_HZ_TO_REG_VAL(2416400000), FREQ_HZ_TO_REG_VAL(2417400000), - FREQ_HZ_TO_REG_VAL(2418400000), FREQ_HZ_TO_REG_VAL(2419400000), + FreqHzToRegVal(2415400000), FreqHzToRegVal(2416400000), FreqHzToRegVal(2417400000), + FreqHzToRegVal(2418400000), FreqHzToRegVal(2419400000), - FREQ_HZ_TO_REG_VAL(2420400000), FREQ_HZ_TO_REG_VAL(2421400000), FREQ_HZ_TO_REG_VAL(2422400000), - FREQ_HZ_TO_REG_VAL(2423400000), FREQ_HZ_TO_REG_VAL(2424400000), + FreqHzToRegVal(2420400000), FreqHzToRegVal(2421400000), FreqHzToRegVal(2422400000), + FreqHzToRegVal(2423400000), FreqHzToRegVal(2424400000), - FREQ_HZ_TO_REG_VAL(2425400000), FREQ_HZ_TO_REG_VAL(2426400000), FREQ_HZ_TO_REG_VAL(2427400000), - FREQ_HZ_TO_REG_VAL(2428400000), FREQ_HZ_TO_REG_VAL(2429400000), + FreqHzToRegVal(2425400000), FreqHzToRegVal(2426400000), FreqHzToRegVal(2427400000), + FreqHzToRegVal(2428400000), FreqHzToRegVal(2429400000), - FREQ_HZ_TO_REG_VAL(2430400000), FREQ_HZ_TO_REG_VAL(2431400000), FREQ_HZ_TO_REG_VAL(2432400000), - FREQ_HZ_TO_REG_VAL(2433400000), FREQ_HZ_TO_REG_VAL(2434400000), + FreqHzToRegVal(2430400000), FreqHzToRegVal(2431400000), FreqHzToRegVal(2432400000), + FreqHzToRegVal(2433400000), FreqHzToRegVal(2434400000), - FREQ_HZ_TO_REG_VAL(2435400000), FREQ_HZ_TO_REG_VAL(2436400000), FREQ_HZ_TO_REG_VAL(2437400000), - FREQ_HZ_TO_REG_VAL(2438400000), FREQ_HZ_TO_REG_VAL(2439400000), + FreqHzToRegVal(2435400000), FreqHzToRegVal(2436400000), FreqHzToRegVal(2437400000), + FreqHzToRegVal(2438400000), FreqHzToRegVal(2439400000), - FREQ_HZ_TO_REG_VAL(2440400000), FREQ_HZ_TO_REG_VAL(2441400000), FREQ_HZ_TO_REG_VAL(2442400000), - FREQ_HZ_TO_REG_VAL(2443400000), FREQ_HZ_TO_REG_VAL(2444400000), + FreqHzToRegVal(2440400000), FreqHzToRegVal(2441400000), FreqHzToRegVal(2442400000), + FreqHzToRegVal(2443400000), FreqHzToRegVal(2444400000), - FREQ_HZ_TO_REG_VAL(2445400000), FREQ_HZ_TO_REG_VAL(2446400000), FREQ_HZ_TO_REG_VAL(2447400000), - FREQ_HZ_TO_REG_VAL(2448400000), FREQ_HZ_TO_REG_VAL(2449400000), + FreqHzToRegVal(2445400000), FreqHzToRegVal(2446400000), FreqHzToRegVal(2447400000), + FreqHzToRegVal(2448400000), FreqHzToRegVal(2449400000), - FREQ_HZ_TO_REG_VAL(2450400000), FREQ_HZ_TO_REG_VAL(2451400000), FREQ_HZ_TO_REG_VAL(2452400000), - FREQ_HZ_TO_REG_VAL(2453400000), FREQ_HZ_TO_REG_VAL(2454400000), + FreqHzToRegVal(2450400000), FreqHzToRegVal(2451400000), FreqHzToRegVal(2452400000), + FreqHzToRegVal(2453400000), FreqHzToRegVal(2454400000), - FREQ_HZ_TO_REG_VAL(2455400000), FREQ_HZ_TO_REG_VAL(2456400000), FREQ_HZ_TO_REG_VAL(2457400000), - FREQ_HZ_TO_REG_VAL(2458400000), FREQ_HZ_TO_REG_VAL(2459400000), + FreqHzToRegVal(2455400000), FreqHzToRegVal(2456400000), FreqHzToRegVal(2457400000), + FreqHzToRegVal(2458400000), FreqHzToRegVal(2459400000), - FREQ_HZ_TO_REG_VAL(2460400000), FREQ_HZ_TO_REG_VAL(2461400000), FREQ_HZ_TO_REG_VAL(2462400000), - FREQ_HZ_TO_REG_VAL(2463400000), FREQ_HZ_TO_REG_VAL(2464400000), + FreqHzToRegVal(2460400000), FreqHzToRegVal(2461400000), FreqHzToRegVal(2462400000), + FreqHzToRegVal(2463400000), FreqHzToRegVal(2464400000), - FREQ_HZ_TO_REG_VAL(2465400000), FREQ_HZ_TO_REG_VAL(2466400000), FREQ_HZ_TO_REG_VAL(2467400000), - FREQ_HZ_TO_REG_VAL(2468400000), FREQ_HZ_TO_REG_VAL(2469400000), + FreqHzToRegVal(2465400000), FreqHzToRegVal(2466400000), FreqHzToRegVal(2467400000), + FreqHzToRegVal(2468400000), FreqHzToRegVal(2469400000), - FREQ_HZ_TO_REG_VAL(2470400000), FREQ_HZ_TO_REG_VAL(2471400000), FREQ_HZ_TO_REG_VAL(2472400000), - FREQ_HZ_TO_REG_VAL(2473400000), FREQ_HZ_TO_REG_VAL(2474400000), + FreqHzToRegVal(2470400000), FreqHzToRegVal(2471400000), FreqHzToRegVal(2472400000), + FreqHzToRegVal(2473400000), FreqHzToRegVal(2474400000), - FREQ_HZ_TO_REG_VAL(2475400000), FREQ_HZ_TO_REG_VAL(2476400000), FREQ_HZ_TO_REG_VAL(2477400000), - FREQ_HZ_TO_REG_VAL(2478400000), FREQ_HZ_TO_REG_VAL(2479400000)}; + FreqHzToRegVal(2475400000), FreqHzToRegVal(2476400000), FreqHzToRegVal(2477400000), + FreqHzToRegVal(2478400000), FreqHzToRegVal(2479400000)}; // Number of FHSS frequencies in the table constexpr uint32_t FHSS_FREQ_CNT = (sizeof(FHSSfreqs) / sizeof(uint32_t)); // Number of hops in the FHSSsequence list before circling back around, even // multiple of the number of frequencies -constexpr uint8_t FHSS_SEQUENCE_CNT = 20; //(256 / FHSS_FREQ_CNT) * FHSS_FREQ_CNT; + +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) // Actual sequence of hops as indexes into the frequency list -uint8_t FHSSsequence[20]; +uint8_t FHSSsequence[FHSS_SEQUENCE_CNT]; // Which entry in the sequence we currently are on uint8_t volatile FHSSptr; // Channel for sync packets and initial connection establishment uint_fast8_t sync_channel; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) /** Requirements: @@ -98,7 +100,9 @@ uint16_t crc16(uint8_t const *data, int32_t size); uint8_t contains(int current_pos, uint8_t value) { for (int i = 0; i < current_pos; i++) { - if (FHSSsequence[i] == value) return 1; + if (FHSSsequence[i] == value) { + return 1; + } } return 0; } @@ -107,7 +111,7 @@ void FHSSrandomiseFHSSsequence(uint32_t crc) { rngSeed(crc); int i = 0; while (i < FHSS_SEQUENCE_CNT) { - uint8_t next_freq = (uint8_t)rngN(FHSS_FREQ_CNT); + const uint8_t next_freq = rngN(FHSS_FREQ_CNT); if (contains(i, next_freq) == 0) { FHSSsequence[i] = next_freq; i++; @@ -116,4 +120,4 @@ void FHSSrandomiseFHSSsequence(uint32_t crc) { sync_channel = FHSSsequence[0]; } -uint32_t FHSSgetChannelCount(void) { return FHSS_FREQ_CNT; } +uint32_t FHSSgetChannelCount() { return FHSS_FREQ_CNT; } diff --git a/telemetry/src/Fhss/Fhss.hpp b/telemetry/src/Fhss/Fhss.hpp index a6d7e088..8960889c 100644 --- a/telemetry/src/Fhss/Fhss.hpp +++ b/telemetry/src/Fhss/Fhss.hpp @@ -16,24 +16,31 @@ #pragma once +#include + #include #include -#define FreqCorrectionMax ((int32_t)(100000 / FREQ_STEP)) -#define FreqCorrectionMin ((int32_t)(-100000 / FREQ_STEP)) +constexpr int32_t kFreqCorrectionMax = static_cast(100'000 / FREQ_STEP); +constexpr int32_t kFreqCorrectionMin = static_cast(-100'000 / FREQ_STEP); -#define FREQ_HZ_TO_REG_VAL(freq) ((uint32_t)((double)(freq) / (double)FREQ_STEP)) +consteval uint32_t FreqHzToRegVal(uint32_t freq) { + return static_cast(static_cast(freq) / static_cast(FREQ_STEP)); +} +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) extern volatile uint8_t FHSSptr; extern uint8_t FHSSsequence[]; -extern const uint32_t FHSSfreqs[]; extern uint_fast8_t sync_channel; -extern const uint8_t FHSS_SEQUENCE_CNT; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) +extern const uint32_t FHSSfreqs[]; +// NOLINTNEXTLINE(clang-diagnostic-c++17-extensions) not sure why this is needed; all source files are compiled as C++20 +inline constexpr uint8_t FHSS_SEQUENCE_CNT = 20; //(256 / FHSS_FREQ_CNT) * FHSS_FREQ_CNT; // create and randomise an FHSS sequence void FHSSrandomiseFHSSsequence(uint32_t crc); // The number of frequencies for this regulatory domain -uint32_t FHSSgetChannelCount(void); +uint32_t FHSSgetChannelCount(); // get the initial frequency, which is also the sync channel static inline uint32_t GetInitialFreq() { return FHSSfreqs[sync_channel]; } @@ -47,8 +54,7 @@ static inline void FHSSsetCurrIndex(const uint8_t value) { FHSSptr = value % FHS // Advance the pointer to the next hop and return the frequency of that channel static inline uint32_t FHSSgetNextFreq() { FHSSptr = (FHSSptr + 1) % FHSS_SEQUENCE_CNT; - uint32_t freq = FHSSfreqs[FHSSsequence[FHSSptr]]; - return freq; + return FHSSfreqs[FHSSsequence[FHSSptr]]; } // get the number of entries in the FHSS sequence diff --git a/telemetry/src/Gps/Gps.cpp b/telemetry/src/Gps/Gps.cpp index 6cc3182f..abd06ca6 100644 --- a/telemetry/src/Gps/Gps.cpp +++ b/telemetry/src/Gps/Gps.cpp @@ -17,30 +17,31 @@ #include "Gps.hpp" #include "Main.hpp" -#include +#include -uint8_t c1; -uint32_t lr1; - -static uint8_t ublox_request_115200_baud[] = { +constexpr static uint8_t ublox_request_115200_baud[] = { 0xb5, 0x62, 0x06, 0x00, 0x14, 0x00, 0x01, 0x00, 0x00, 0x00, 0xd0, 0x08, 0x00, 0x00, 0x00, 0xc2, 0x01, 0x00, 0x07, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc4, 0x96, 0xb5, 0x62, 0x06, 0x00, 0x01, 0x00, 0x01, 0x08, 0x22}; -static uint8_t ublox_request_5Hz[] = {0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, - 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A}; +constexpr static uint8_t ublox_request_5Hz[] = {0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, + 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A}; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern UART_HandleTypeDef huart1; void gpsSetup() { uint8_t command[20]; // Check hardware version - if (HAL_GPIO_ReadPin(HARDWARE_ID_GPIO_Port, HARDWARE_ID_Pin)) { + if (HAL_GPIO_ReadPin(HARDWARE_ID_GPIO_Port, HARDWARE_ID_Pin) == GPIO_PIN_SET) { // Flight computer - HAL_UART_Transmit(&huart1, ublox_request_115200_baud, sizeof(ublox_request_115200_baud), 100); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-const-cast) safe to cast as transmitted data is not changed + HAL_UART_Transmit(&huart1, const_cast(ublox_request_115200_baud), sizeof(ublox_request_115200_baud), + 100); } else { // Groundstation /* Request UART speed of 115200 */ - snprintf((char *)command, 15, "$PCAS01,5*19\r\n"); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) fine to cast since char is 8 bits on this platform + snprintf(reinterpret_cast(command), 15, "$PCAS01,5*19\r\n"); HAL_UART_Transmit(&huart1, command, 14, 100); } @@ -54,17 +55,19 @@ void gpsSetup() { HAL_Delay(200); // Check hardware version - if (HAL_GPIO_ReadPin(HARDWARE_ID_GPIO_Port, HARDWARE_ID_Pin)) { + if (HAL_GPIO_ReadPin(HARDWARE_ID_GPIO_Port, HARDWARE_ID_Pin) == GPIO_PIN_SET) { // Flight computer /* Request 5 Hz mode */ - HAL_UART_Transmit(&huart1, ublox_request_5Hz, sizeof(ublox_request_5Hz), 100); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-const-cast) safe to cast as transmitted data is not changed + HAL_UART_Transmit(&huart1, const_cast(ublox_request_5Hz), sizeof(ublox_request_5Hz), 100); /* Request airbourne, not working yet */ // HAL_UART_Transmit(&huart1, ublox_request_airbourne, // sizeof(ublox_request_airbourne), 100); } else { // Groundstation /* Request 10Hz update rate */ - snprintf((char *)command, 17, "$PCAS02,100*1E\r\n"); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) fine to cast since char is 8 bits on this platform + snprintf(reinterpret_cast(command), 17, "$PCAS02,100*1E\r\n"); HAL_UART_Transmit(&huart1, command, 16, 100); } } diff --git a/telemetry/src/Main.cpp b/telemetry/src/Main.cpp index 0c4ebf48..565c323b 100644 --- a/telemetry/src/Main.cpp +++ b/telemetry/src/Main.cpp @@ -26,9 +26,11 @@ #include #include #include +#include #include /* Private variables ---------------------------------------------------------*/ +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) ADC_HandleTypeDef hadc1; DMA_HandleTypeDef hdma_adc1; @@ -40,22 +42,23 @@ UART_HandleTypeDef huart1; UART_HandleTypeDef huart2; DMA_HandleTypeDef hdma_usart1_rx; DMA_HandleTypeDef hdma_usart2_rx; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) /* Private function prototypes -----------------------------------------------*/ -void SystemClock_Config(void); -static void MX_GPIO_Init(void); -static void MX_ADC1_Init(void); -static void MX_SPI1_Init(void); -static void MX_USART1_UART_Init(void); -static void MX_USART2_UART_Init(void); -static void MX_DMA_Init(void); -static void MX_TIM2_Init(void); +void SystemClock_Config(); +static void MX_GPIO_Init(); +static void MX_ADC1_Init(); +static void MX_SPI1_Init(); +static void MX_USART1_UART_Init(); +static void MX_USART2_UART_Init(); +static void MX_DMA_Init(); +static void MX_TIM2_Init(); /** * @brief The application entry point. * @retval int */ -int main(void) { +int main() { /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ HAL_Init(); @@ -74,8 +77,9 @@ int main(void) { /* Set code version */ const char *telemetry_code_version = FIRMWARE_VERSION; - uint8_t code_version_size = strlen(telemetry_code_version); - const uint8_t *code_version = reinterpret_cast(telemetry_code_version); + const uint8_t code_version_size = strlen(telemetry_code_version); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) fine to cast since char is 8 bits on this platform + const auto *code_version = reinterpret_cast(telemetry_code_version); /* Wait for the GNSS module to initialize*/ HAL_Delay(4000); @@ -96,7 +100,7 @@ int main(void) { TinyGps gps; /* Initalize the radio module */ - while (link.begin(&htim2) == false) { + while (!link.begin(&htim2)) { HAL_Delay(10); } @@ -104,7 +108,7 @@ int main(void) { uint8_t oldSecond = 0; uint32_t lastTemperatureUpdate = HAL_GetTick(); - while (1) { + while (true) { uint8_t uartOutBuffer[20]; /* Check if we received data from the GNSS module */ @@ -119,7 +123,7 @@ int main(void) { /* Transmit Link Information*/ if (link.infoAvailable()) { - linkInfo_t info; + linkInfo_t info{}; link.readInfo(&info); uartOutBuffer[0] = CMD_INFO; uartOutBuffer[1] = 3; @@ -127,7 +131,7 @@ int main(void) { uartOutBuffer[3] = info.rssi; uartOutBuffer[4] = info.snr; - uint8_t crc = crc8(uartOutBuffer, 5); + const uint8_t crc = crc8(uartOutBuffer, 5); uartOutBuffer[5] = crc; HAL_UART_Transmit(&huart2, uartOutBuffer, 6, 2); @@ -141,7 +145,7 @@ int main(void) { uartOutBuffer[0] = CMD_RX; uartOutBuffer[1] = 16; memcpy(&uartOutBuffer[2], rx_data, 16); - uint8_t crc = crc8(uartOutBuffer, 18); + const uint8_t crc = crc8(uartOutBuffer, 18); uartOutBuffer[18] = crc; HAL_UART_Transmit(&huart2, uartOutBuffer, 19, 2); @@ -149,9 +153,9 @@ int main(void) { /* Transmit GPS Location */ if (gps.location.isValid() && gps.location.isUpdated()) { - float lat = gps.location.lat(); - float lng = gps.location.lng(); - int32_t altitude = gps.altitude.meters(); + auto lat = static_cast(gps.location.lat()); + auto lng = static_cast(gps.location.lng()); + int32_t altitude = std::lround(gps.altitude.meters()); if (lat != 0) { uartOutBuffer[0] = CMD_GNSS_LOC; @@ -159,7 +163,7 @@ int main(void) { memcpy(&uartOutBuffer[2], &lat, 4); memcpy(&uartOutBuffer[2 + 4], &lng, 4); memcpy(&uartOutBuffer[2 + 4 + 4], &altitude, 4); - uint8_t crc = crc8(uartOutBuffer, 14); + const uint8_t crc = crc8(uartOutBuffer, 14); uartOutBuffer[14] = crc; HAL_UART_Transmit(&huart2, uartOutBuffer, 15, 2); @@ -173,7 +177,7 @@ int main(void) { uartOutBuffer[0] = CMD_GNSS_INFO; uartOutBuffer[1] = 1; uartOutBuffer[2] = gps.satellites.value(); - uint8_t crc = crc8(uartOutBuffer, 3); + const uint8_t crc = crc8(uartOutBuffer, 3); uartOutBuffer[3] = crc; HAL_UART_Transmit(&huart2, uartOutBuffer, 4, 2); @@ -189,7 +193,7 @@ int main(void) { uartOutBuffer[2] = gps.time.second(); uartOutBuffer[3] = gps.time.minute(); uartOutBuffer[4] = gps.time.hour(); - uint8_t crc = crc8(uartOutBuffer, 5); + const uint8_t crc = crc8(uartOutBuffer, 5); uartOutBuffer[5] = crc; HAL_UART_Transmit(&huart2, uartOutBuffer, 6, 2); } @@ -203,7 +207,7 @@ int main(void) { uartOutBuffer[0] = CMD_TEMP_INFO; uartOutBuffer[1] = 4; memcpy(&uartOutBuffer[2], &temperature, 4); - uint8_t crc = crc8(uartOutBuffer, 6); + const uint8_t crc = crc8(uartOutBuffer, 6); uartOutBuffer[6] = crc; HAL_UART_Transmit(&huart2, uartOutBuffer, 7, 2); } @@ -213,7 +217,7 @@ int main(void) { uartOutBuffer[0] = CMD_VERSION_INFO; uartOutBuffer[1] = code_version_size; memcpy(&uartOutBuffer[2], code_version, code_version_size); - uint8_t crc = crc8(uartOutBuffer, code_version_size + 2); + const uint8_t crc = crc8(uartOutBuffer, code_version_size + 2); uartOutBuffer[code_version_size + 2] = crc; HAL_UART_Transmit(&huart2, uartOutBuffer, code_version_size + 3, 2); @@ -226,7 +230,7 @@ int main(void) { * @brief System Clock Configuration * @retval None */ -void SystemClock_Config(void) { +void SystemClock_Config() { RCC_OscInitTypeDef RCC_OscInitStruct = {0}; RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; @@ -267,7 +271,7 @@ void SystemClock_Config(void) { * @param None * @retval None */ -static void MX_ADC1_Init(void) { +static void MX_ADC1_Init() { ADC_ChannelConfTypeDef sConfig = {0}; /** Configure the global features of the ADC (Clock, Resolution, Data @@ -313,7 +317,7 @@ static void MX_ADC1_Init(void) { * @param None * @retval None */ -static void MX_SPI1_Init(void) { +static void MX_SPI1_Init() { /* SPI1 parameter configuration*/ hspi1.Instance = SPI1; hspi1.Init.Mode = SPI_MODE_MASTER; @@ -339,7 +343,7 @@ static void MX_SPI1_Init(void) { * @param None * @retval None */ -static void MX_TIM2_Init(void) { +static void MX_TIM2_Init() { TIM_ClockConfigTypeDef sClockSourceConfig = {0}; TIM_MasterConfigTypeDef sMasterConfig = {0}; @@ -368,7 +372,7 @@ static void MX_TIM2_Init(void) { * @param None * @retval None */ -static void MX_USART1_UART_Init(void) { +static void MX_USART1_UART_Init() { huart1.Instance = USART1; huart1.Init.BaudRate = 9600; huart1.Init.WordLength = UART_WORDLENGTH_8B; @@ -399,7 +403,7 @@ static void MX_USART1_UART_Init(void) { * @param None * @retval None */ -static void MX_USART2_UART_Init(void) { +static void MX_USART2_UART_Init() { huart2.Instance = USART2; huart2.Init.BaudRate = 115200; huart2.Init.WordLength = UART_WORDLENGTH_8B; @@ -428,7 +432,7 @@ static void MX_USART2_UART_Init(void) { /** * Enable DMA controller clock */ -static void MX_DMA_Init(void) { +static void MX_DMA_Init() { /* DMA controller clock enable */ __HAL_RCC_DMA1_CLK_ENABLE(); @@ -449,7 +453,7 @@ static void MX_DMA_Init(void) { * @param None * @retval None */ -static void MX_GPIO_Init(void) { +static void MX_GPIO_Init() { GPIO_InitTypeDef GPIO_InitStruct = {0}; /* GPIO Ports Clock Enable */ @@ -458,9 +462,11 @@ static void MX_GPIO_Init(void) { __HAL_RCC_GPIOC_CLK_ENABLE(); /*Configure GPIO pin Output Level */ + // NOLINTNEXTLINE(hicpp-signed-bitwise) HAL_GPIO_WritePin(GPIOB, CS_Pin | INT2_Pin | INT1_Pin, GPIO_PIN_RESET); /*Configure GPIO pin Output Level */ + // NOLINTNEXTLINE(hicpp-signed-bitwise) HAL_GPIO_WritePin(GPIOA, FE_EN_Pin | RX_EN_Pin | N_RST_Pin | LED_Pin, GPIO_PIN_RESET); /*Configure GPIO pin Output Level */ @@ -473,6 +479,7 @@ static void MX_GPIO_Init(void) { HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); /*Configure GPIO pins : CS_Pin INT2_Pin INT1_Pin */ + // NOLINTNEXTLINE(hicpp-signed-bitwise) GPIO_InitStruct.Pin = CS_Pin | INT2_Pin | INT1_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; @@ -486,6 +493,7 @@ static void MX_GPIO_Init(void) { HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); /*Configure GPIO pins : FE_EN_Pin RX_EN_Pin N_RST_Pin LED_Pin */ + // NOLINTNEXTLINE(hicpp-signed-bitwise) GPIO_InitStruct.Pin = FE_EN_Pin | RX_EN_Pin | N_RST_Pin | LED_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; @@ -508,8 +516,8 @@ static void MX_GPIO_Init(void) { * @brief This function is executed in case of error occurrence. * @retval None */ -void Error_Handler(void) { +void Error_Handler() { __disable_irq(); - while (1) { + while (true) { } } diff --git a/telemetry/src/SerialComm/Parser.cpp b/telemetry/src/SerialComm/Parser.cpp index 6954aa9c..33f2988d 100644 --- a/telemetry/src/SerialComm/Parser.cpp +++ b/telemetry/src/SerialComm/Parser.cpp @@ -14,9 +14,10 @@ /// You should have received a copy of the GNU General Public License /// along with this program. If not, see . -#include "Parser.hpp" #include + #include "Common.hpp" +#include "Parser.hpp" void Parser::parse() { cmd_table[opCodeIndex].cmd(&buffer[2], dataIndex); @@ -27,7 +28,9 @@ void Parser::parse() { int32_t Parser::getOpCodeIndex(uint8_t opCode) { for (int32_t i = 0; i < CMD_NUMBER; i++) { - if (opCode == cmd_table[i].identifier) return i; + if (opCode == cmd_table[i].identifier) { + return i; + } } return -1; } @@ -61,7 +64,7 @@ void Parser::process(uint8_t ch) { } break; case STATE_CRC: { - uint8_t crc = crc8(buffer, dataIndex + 2); + const uint8_t crc = crc8(buffer, dataIndex + 2); if (crc == ch) { parse(); } else { @@ -74,62 +77,80 @@ void Parser::process(uint8_t ch) { } void Parser::cmdDirection(uint8_t *args, uint32_t length) { - if (length != 1) return; + if (length != 1) { + return; + } if (args[0] == TX || args[0] == RX) { - link.setDirection((transmission_direction_e)args[0]); + link.setDirection(static_cast(args[0])); } } void Parser::cmdPAGain(uint8_t *args, uint32_t length) { - if (length != 1) return; + if (length != 1) { + return; + } if (args[0] < 50) { - link.setPAGain(args[0]); + link.setPAGain(static_cast(args[0])); } } void Parser::cmdPowerLevel(uint8_t *args, uint32_t length) { - if (length != 1) return; + if (length != 1) { + return; + } - link.setPowerLevel(args[0]); + link.setPowerLevel(static_cast(args[0])); } void Parser::cmdMode(uint8_t *args, uint32_t length) { - if (length != 1) return; + if (length != 1) { + return; + } - link.setMode((transmission_mode_e)args[0]); + link.setMode(static_cast(args[0])); } void Parser::cmdModeIndex(uint8_t *args, uint32_t length) { // UNUSED } +// NOLINTNEXTLINE(readability-non-const-parameter) can't be const since the function pointer has a non-const param void Parser::cmdLinkPhrase(uint8_t *args, uint32_t length) { - if (length != 4) return; + if (length != 4) { + return; + } if (args[0] != 0) { - uint32_t phrasecrc = args[0] << 24; - phrasecrc += args[1] << 16; - phrasecrc += args[2] << 8; + uint32_t phrasecrc = args[0] << 24U; + phrasecrc += args[1] << 16U; + phrasecrc += args[2] << 8U; phrasecrc += args[3]; link.setLinkPhraseCrc(phrasecrc); } } -void Parser::cmdEnable(uint8_t *args, uint32_t length) { - if (length != 0) return; +void Parser::cmdEnable([[maybe_unused]] uint8_t *args, uint32_t length) { + if (length != 0) { + return; + } link.enableTransmission(); } -void Parser::cmdDisable(uint8_t *args, uint32_t length) { - if (length != 0) return; +void Parser::cmdDisable([[maybe_unused]] uint8_t *args, uint32_t length) { + if (length != 0) { + return; + } + link.disableTransmission(); } void Parser::cmdTX(uint8_t *args, uint32_t length) { link.writeBytes(args, length); } -void Parser::cmdVersionNum(uint8_t *args, uint32_t length) { send_version_num = true; } +void Parser::cmdVersionNum([[maybe_unused]] uint8_t *args, [[maybe_unused]] uint32_t length) { + send_version_num = true; +} void Parser::cmdBootloader(uint8_t *args, uint32_t length) { // UNUSED diff --git a/telemetry/src/SerialComm/Parser.hpp b/telemetry/src/SerialComm/Parser.hpp index 072baa48..61737e3a 100644 --- a/telemetry/src/SerialComm/Parser.hpp +++ b/telemetry/src/SerialComm/Parser.hpp @@ -15,19 +15,17 @@ /// along with this program. If not, see . #include + #include "Telemetry_reg.h" -typedef void cmd_fn(uint8_t *args, uint32_t length); +using cmd_fn = void (*)(uint8_t *args, uint32_t length); -typedef struct { +struct cmd_t { const uint8_t identifier; - cmd_fn *cmd; -} cmd_t; - -#define MAX_CMD_BUFFER 20 + cmd_fn cmd; +}; -#define CMD_DEF(identifier, cmd) \ - { identifier, cmd } +constexpr uint8_t kMaxCmdBuffer = 20; /* The parser is not interrupt safe! */ @@ -69,17 +67,17 @@ class Parser { private: int32_t getOpCodeIndex(uint8_t opCode); - uint8_t buffer[MAX_CMD_BUFFER]; + uint8_t buffer[kMaxCmdBuffer]; uint32_t dataIndex = 0; int32_t opCodeIndex = -1; - typedef enum { + enum state_e { STATE_OP, STATE_LEN, STATE_DATA, STATE_CRC, - } state_e; + }; enum { INDEX_OP = 0, @@ -93,24 +91,24 @@ class Parser { }; const cmd_t cmd_table[CMD_NUMBER] = { - CMD_DEF(CMD_DIRECTION, cmdDirection), - CMD_DEF(CMD_PA_GAIN, cmdPAGain), - CMD_DEF(CMD_POWER_LEVEL, cmdPowerLevel), - CMD_DEF(CMD_MODE, cmdMode), - CMD_DEF(CMD_MODE_INDEX, cmdModeIndex), - CMD_DEF(CMD_LINK_PHRASE, cmdLinkPhrase), - CMD_DEF(CMD_ENABLE, cmdEnable), - CMD_DEF(CMD_DISBALE, cmdDisable), - - CMD_DEF(CMD_TX, cmdTX), - CMD_DEF(CMD_RX, cmdRX), - CMD_DEF(CMD_INFO, cmdInfo), - - CMD_DEF(CMD_GNSS_LOC, cmdGNSSLoc), - CMD_DEF(CMD_GNSS_TIME, cmdGNSSTime), - CMD_DEF(CMD_GNSS_INFO, cmdGNSSInfo), - CMD_DEF(CMD_VERSION_INFO, cmdVersionNum), - - CMD_DEF(CMD_BOOTLOADER, cmdBootloader), + {CMD_DIRECTION, cmdDirection}, + {CMD_PA_GAIN, cmdPAGain}, + {CMD_POWER_LEVEL, cmdPowerLevel}, + {CMD_MODE, cmdMode}, + {CMD_MODE_INDEX, cmdModeIndex}, + {CMD_LINK_PHRASE, cmdLinkPhrase}, + {CMD_ENABLE, cmdEnable}, + {CMD_DISBALE, cmdDisable}, + + {CMD_TX, cmdTX}, + {CMD_RX, cmdRX}, + {CMD_INFO, cmdInfo}, + + {CMD_GNSS_LOC, cmdGNSSLoc}, + {CMD_GNSS_TIME, cmdGNSSTime}, + {CMD_GNSS_INFO, cmdGNSSInfo}, + {CMD_VERSION_INFO, cmdVersionNum}, + + {CMD_BOOTLOADER, cmdBootloader}, }; }; diff --git a/telemetry/src/SerialComm/Serial.hpp b/telemetry/src/SerialComm/Serial.hpp index abb956fc..69811327 100644 --- a/telemetry/src/SerialComm/Serial.hpp +++ b/telemetry/src/SerialComm/Serial.hpp @@ -23,7 +23,9 @@ void start_serial(); template class Serial { public: - Serial(UART_HandleTypeDef *handle) : tail(0U), uart(handle), buffer{} { HAL_UART_Receive_DMA(uart, buffer, N); } + explicit Serial(UART_HandleTypeDef *handle) : tail(0U), uart(handle), buffer{} { + HAL_UART_Receive_DMA(uart, buffer, N); + } uint32_t available() { volatile uint32_t head = N - uart->hdmarx->Instance->CNDTR; diff --git a/telemetry/src/Transmission/Transmission.cpp b/telemetry/src/Transmission/Transmission.cpp index 6f44bc23..b1c4d5d6 100644 --- a/telemetry/src/Transmission/Transmission.cpp +++ b/telemetry/src/Transmission/Transmission.cpp @@ -21,6 +21,7 @@ #include #include +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static Transmission *pTransmission; static inline void rxCallback() { pTransmission->rxDoneISR(); } @@ -29,14 +30,16 @@ static inline void txCallback() { pTransmission->txDoneISR(); } bool Transmission::begin(TIM_HandleTypeDef *t) { /* Catch if already initalized */ - if (radioInitialized == true) return radioInitialized; + if (radioInitialized) { + return radioInitialized; + } timer = t; pTransmission = this; Radio.RXdoneCallback = &rxCallback; Radio.TXdoneCallback = &txCallback; - if (Radio.Begin() == true) { + if (Radio.Begin()) { radioInitialized = true; HAL_GPIO_WritePin(LED_GPIO_Port, LED_Pin, GPIO_PIN_SET); } @@ -76,20 +79,22 @@ void Transmission::setPAGain(int8_t gain) { Settings.paGain = gain; if (Settings.transmissionEnabled) { - Radio.SetOutputPower(Settings.powerLevel - Settings.paGain); + Radio.SetOutputPower(static_cast(Settings.powerLevel - Settings.paGain)); } } void Transmission::setPowerLevel(int8_t gain) { Settings.powerLevel = gain; } -void Transmission::writeBytes(const uint8_t *data, uint32_t length) { - if (length > payloadLength) return; - memcpy(txData, data, length); +void Transmission::writeBytes(const uint8_t *buffer, uint32_t length) { + if (length > payloadLength) { + return; + } + memcpy(txData, buffer, length); } -bool Transmission::available() { return dataAvailable; } +bool Transmission::available() const { return dataAvailable; } -bool Transmission::infoAvailable() { return linkInfoAvailable; } +bool Transmission::infoAvailable() const { return linkInfoAvailable; } bool Transmission::readBytes(uint8_t *buffer, uint32_t length) { if (dataAvailable) { @@ -101,27 +106,29 @@ bool Transmission::readBytes(uint8_t *buffer, uint32_t length) { } bool Transmission::readInfo(linkInfo_t *info) { - info->lq = LqCalc.getLQ(); - info->rssi = Radio.LastPacketRSSI; - info->snr = Radio.LastPacketSNR; + *info = {.rssi = Radio.LastPacketRSSI, .lq = LqCalc.getLQ(), .snr = Radio.LastPacketSNR}; linkInfoAvailable = false; return true; } void Transmission::enableTransmission() { - if (radioInitialized == false) return; + if (!radioInitialized) { + return; + } - if (Settings.transmissionEnabled) return; + if (Settings.transmissionEnabled) { + return; + } Settings.transmissionEnabled = true; linkCRC = Settings.linkPhraseCrC; - linkXOR[0] = (linkCRC >> 8) & 0xFF; - linkXOR[1] = linkCRC & 0xFF; + linkXOR[0] = (linkCRC >> 8U) & 0xFFU; + linkXOR[1] = linkCRC & 0xFFU; FHSSrandomiseFHSSsequence(linkCRC); - Radio.SetOutputPower(Settings.powerLevel - Settings.paGain); + Radio.SetOutputPower(static_cast(Settings.powerLevel - Settings.paGain)); HAL_Delay(10); @@ -129,10 +136,10 @@ void Transmission::enableTransmission() { modulation_settings_s *const modParams = &Settings.modulationConfig[Settings.modeIndex]; if (Settings.transmissionDirection == TX) { - Radio.Config(modParams->bw, modParams->sf, modParams->cr, GetInitialFreq(), modParams->PreambleLen, 0, + Radio.Config(modParams->bw, modParams->sf, modParams->cr, GetInitialFreq(), modParams->PreambleLen, false, modParams->PayloadLength, modParams->interval); } else { - Radio.Config(modParams->bw, modParams->sf, modParams->cr, GetInitialFreq(), modParams->PreambleLen, 0, + Radio.Config(modParams->bw, modParams->sf, modParams->cr, GetInitialFreq(), modParams->PreambleLen, false, modParams->PayloadLength, 0); } @@ -152,10 +159,12 @@ void Transmission::enableTransmission() { void Transmission::disableTransmission() { /* Wait until done transmitting / receiving*/ - while (busyTransmitting) - ; + while (busyTransmitting) { + }; - if (!Settings.transmissionEnabled) return; + if (!Settings.transmissionEnabled) { + return; + } Settings.transmissionEnabled = false; @@ -179,21 +188,24 @@ void Transmission::disableTransmission() { bool Transmission::processRFPacket() { LqCalc.inc(); - uint16_t crc = (uint16_t)crc32((const uint8_t *)Radio.RXdataBuffer, payloadLength - 2); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-const-cast) safe to cast as RXdataBuffer is updated only in the ISR + const auto crc = static_cast(crc32(const_cast(Radio.RXdataBuffer), payloadLength - 2)); - bool is_valid = (linkXOR[0] ^ (uint8_t)(crc >> 8)) == Radio.RXdataBuffer[payloadLength - 2]; - is_valid &= (linkXOR[1] ^ (uint8_t)crc) == Radio.RXdataBuffer[payloadLength - 1]; + bool is_valid = (linkXOR[0] ^ static_cast(crc >> 8U)) == Radio.RXdataBuffer[payloadLength - 2]; + is_valid &= (linkXOR[1] ^ static_cast(crc)) == Radio.RXdataBuffer[payloadLength - 1]; if (is_valid) { - if (connectionState == tentative) + if (connectionState == tentative) { connectionState = connected; - else if (connectionState == disconnected) + } else if (connectionState == disconnected) { connectionState = tentative; + } dataAvailable = true; linkInfoAvailable = true; timeout = 0; - memcpy(rxData, (const uint8_t *)Radio.RXdataBuffer, payloadLength); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-const-cast) safe to cast as RXdataBuffer is updated only in the ISR + memcpy(rxData, const_cast(Radio.RXdataBuffer), payloadLength); LqCalc.add(); return true; @@ -279,15 +291,17 @@ void Transmission::txTransmit() { } /* Calculate CRC and store in last position */ - uint16_t crc = (uint16_t)crc32((const uint8_t *)txData, payloadLength - 2); - Radio.TXdataBuffer[payloadLength - 2] = linkXOR[0] ^ (uint8_t)(crc >> 8); - Radio.TXdataBuffer[payloadLength - 1] = linkXOR[1] ^ (uint8_t)crc; + const auto crc = static_cast(crc32(static_cast(txData), payloadLength - 2)); + Radio.TXdataBuffer[payloadLength - 2] = linkXOR[0] ^ static_cast(crc >> 8U); + Radio.TXdataBuffer[payloadLength - 1] = linkXOR[1] ^ static_cast(crc); /* Transmit message */ - if (!busyTransmitting) Radio.TXnb(); + if (!busyTransmitting) { + Radio.TXnb(); + } } -transmission_direction_e Transmission::getDirection() { return Settings.transmissionDirection; } +transmission_direction_e Transmission::getDirection() const { return Settings.transmissionDirection; } void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { (void)htim; diff --git a/telemetry/src/Transmission/Transmission.hpp b/telemetry/src/Transmission/Transmission.hpp index c285f93b..da1852ad 100644 --- a/telemetry/src/Transmission/Transmission.hpp +++ b/telemetry/src/Transmission/Transmission.hpp @@ -22,13 +22,11 @@ #include #include -#define MAX_PAYLOAD_SIZE 20 - -typedef struct { - uint8_t rssi; +struct linkInfo_t { + int8_t rssi; uint8_t lq; int8_t snr; -} linkInfo_t; +}; class Transmission { public: @@ -38,16 +36,16 @@ class Transmission { void setMode(transmission_mode_e transmissionMode); void setPAGain(int8_t gain); void setPowerLevel(int8_t gain); - void setLinkPhraseCrc(const uint32_t phraseCrc); + void setLinkPhraseCrc(uint32_t phraseCrc); /* Functions to read and write transmission data */ - bool available(); + [[nodiscard]] bool available() const; void writeBytes(const uint8_t *buffer, uint32_t length); bool readBytes(uint8_t *buffer, uint32_t length); - bool infoAvailable(); + [[nodiscard]] bool infoAvailable() const; bool readInfo(linkInfo_t *info); - transmission_direction_e getDirection(); + [[nodiscard]] transmission_direction_e getDirection() const; void enableTransmission(); void disableTransmission(); @@ -71,19 +69,21 @@ class Transmission { LqCalculator<30> LqCalc; TransmissionSettings Settings; - TIM_HandleTypeDef *timer; - uint32_t timeout = 0; + TIM_HandleTypeDef *timer{nullptr}; + uint32_t timeout{0}; - bool radioInitialized = false; + bool radioInitialized{false}; connectionState_e connectionState = disconnected; - volatile bool busyTransmitting; - uint8_t linkXOR[2]; - uint32_t linkCRC; - - volatile bool dataAvailable = false; - volatile bool linkInfoAvailable = false; - uint32_t payloadLength = 0; - uint8_t txData[MAX_PAYLOAD_SIZE]; - uint8_t rxData[MAX_PAYLOAD_SIZE]; + volatile bool busyTransmitting{false}; + uint8_t linkXOR[2]{}; + uint32_t linkCRC{0}; + + volatile bool dataAvailable{false}; + volatile bool linkInfoAvailable{false}; + uint32_t payloadLength{0}; + + constexpr static uint8_t kMaxPayloadSize{20}; + uint8_t txData[kMaxPayloadSize]{}; + uint8_t rxData[kMaxPayloadSize]{}; }; From bc36d0c82f2bc8e4f3bba90ee7b7369f6d0512f5 Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Wed, 23 Aug 2023 23:12:22 +0200 Subject: [PATCH 02/11] [GS] Fix clang-tidy issues --- .github/workflows/merge-criteria.yml | 2 +- ground_station/platformio.ini | 3 +- ground_station/post_config.py | 10 + ground_station/pre_config.py | 2 + ground_station/src/USB.cpp | 75 ++-- ground_station/src/USBCDC.cpp | 149 ++++--- ground_station/src/config.cpp | 18 +- ground_station/src/config.hpp | 10 +- ground_station/src/console.cpp | 96 +++-- ground_station/src/console.hpp | 100 +++-- ground_station/src/hmi/hmi.cpp | 90 ++-- ground_station/src/hmi/hmi.hpp | 10 +- ground_station/src/hmi/settings.hpp | 30 +- ground_station/src/hmi/window.cpp | 394 ++++++++++-------- ground_station/src/hmi/window.hpp | 70 ++-- ground_station/src/logging/recorder.cpp | 12 +- ground_station/src/logging/recorder.hpp | 6 +- ground_station/src/main.cpp | 11 +- ground_station/src/navigation.cpp | 40 +- ground_station/src/navigation.hpp | 41 +- ground_station/src/systemParser.cpp | 19 +- ground_station/src/systemParser.hpp | 12 +- ground_station/src/telemetry/crc.cpp | 12 +- ground_station/src/telemetry/parser.cpp | 15 +- ground_station/src/telemetry/parser.hpp | 37 +- ground_station/src/telemetry/telemetry.cpp | 38 +- ground_station/src/telemetry/telemetry.hpp | 31 +- .../src/telemetry/telemetryData.hpp | 87 ++-- .../src/telemetry/telemetry_reg.hpp | 10 +- ground_station/src/utils.cpp | 74 ++-- ground_station/src/utils.hpp | 28 +- telemetry/lib/LqCalculator/LqCalculator.hpp | 41 +- telemetry/lib/Thermistor/Thermistor.hpp | 4 +- telemetry/src/SerialComm/Serial.hpp | 8 +- 34 files changed, 859 insertions(+), 726 deletions(-) create mode 100644 ground_station/post_config.py diff --git a/.github/workflows/merge-criteria.yml b/.github/workflows/merge-criteria.yml index 289bea3a..91bff9fa 100644 --- a/.github/workflows/merge-criteria.yml +++ b/.github/workflows/merge-criteria.yml @@ -73,7 +73,7 @@ jobs: name: Build + Lint # We are running this on windows because the users get binaries compiled on windows. # The code should also be tested in a linux build. - runs-on: windows-latest + runs-on: ubuntu-latest timeout-minutes: 60 strategy: fail-fast: false diff --git a/ground_station/platformio.ini b/ground_station/platformio.ini index 9d777dcc..c6464373 100644 --- a/ground_station/platformio.ini +++ b/ground_station/platformio.ini @@ -109,6 +109,7 @@ debug_load_mode = always extra_scripts = pre:pre_config.py + post:post_config.py upload_script.py upload_protocol = custom @@ -129,4 +130,4 @@ check_src_filters = + # TODO: check_skip_packages should be removed once the clang-tidy command length is reduced. # Because of this flag clang-tidy complains it can't find library files such as "Arduino.h" -check_skip_packages = yes +; check_skip_packages = yes diff --git a/ground_station/post_config.py b/ground_station/post_config.py new file mode 100644 index 00000000..e12f9406 --- /dev/null +++ b/ground_station/post_config.py @@ -0,0 +1,10 @@ +Import("projenv") + +include_flags = [] +for path in projenv["CPPPATH"]: + if path != projenv["PROJECT_INCLUDE_DIR"]: + include_flags.append(["-isystem", path]) + +projenv.Append( + CXXFLAGS = include_flags +) diff --git a/ground_station/pre_config.py b/ground_station/pre_config.py index fe0419db..ad4257a0 100644 --- a/ground_station/pre_config.py +++ b/ground_station/pre_config.py @@ -62,6 +62,8 @@ def src_file_config(env, node): "-Wformat-truncation=2", "-Wformat-overflow", "-Wformat-signedness", + "-Wattributes", + "-Wextra", "-Werror", ] diff --git a/ground_station/src/USB.cpp b/ground_station/src/USB.cpp index a196eb15..cbe8c034 100644 --- a/ground_station/src/USB.cpp +++ b/ground_station/src/USB.cpp @@ -51,6 +51,7 @@ #define USB_WEBUSB_ENABLED false #endif #ifndef USB_WEBUSB_URL +// NOLINTNEXTLINE(cppcoreguidelines-macro-usage) #define USB_WEBUSB_URL "https://espressif.github.io/arduino-esp32/webusb.html" #endif @@ -58,33 +59,35 @@ static uint16_t load_dfu_descriptor(uint8_t *dst, uint8_t *itf) { #define DFU_ATTRS (DFU_ATTR_CAN_DOWNLOAD | DFU_ATTR_CAN_UPLOAD | DFU_ATTR_MANIFESTATION_TOLERANT) - uint8_t str_index = tinyusb_add_string_descriptor("TinyUSB DFU_RT"); + const uint8_t str_index = tinyusb_add_string_descriptor("TinyUSB DFU_RT"); uint8_t descriptor[TUD_DFU_RT_DESC_LEN] = { // Interface number, string index, attributes, detach timeout, transfer size */ - TUD_DFU_RT_DESCRIPTOR(*itf, str_index, DFU_ATTRS, 700, 64)}; + // NOLINTNEXTLINE(hicpp-signed-bitwise) + TUD_DFU_RT_DESCRIPTOR(*itf, str_index, DFU_ATTRS, 700U, 64U)}; *itf += 1; memcpy(dst, descriptor, TUD_DFU_RT_DESC_LEN); return TUD_DFU_RT_DESC_LEN; } // Invoked on DFU_DETACH request to reboot to the bootloader -void tud_dfu_runtime_reboot_to_dfu_cb(void) { +void tud_dfu_runtime_reboot_to_dfu_cb() { // MODIFICATION: If DFU Detach request gets received, UF2-Bootloader instead of ROM-Bootloader gets launched! // usb_persist_restart(RESTART_BOOTLOADER_DFU); const uint16_t APP_REQUEST_UF2_RESET_HINT = 0x11F2; esp_reset_reason(); - esp_reset_reason_set_hint((esp_reset_reason_t)APP_REQUEST_UF2_RESET_HINT); + esp_reset_reason_set_hint(static_cast(APP_REQUEST_UF2_RESET_HINT)); esp_restart(); } #endif /* CFG_TUD_DFU_RUNTIME */ +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) ESP_EVENT_DEFINE_BASE(ARDUINO_USB_EVENTS); - -static esp_event_loop_handle_t arduino_usb_event_loop_handle = NULL; +static esp_event_loop_handle_t arduino_usb_event_loop_handle = nullptr; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) esp_err_t arduino_usb_event_post(esp_event_base_t event_base, int32_t event_id, void *event_data, size_t event_data_size, TickType_t ticks_to_wait) { - if (arduino_usb_event_loop_handle == NULL) { + if (arduino_usb_event_loop_handle == nullptr) { return ESP_FAIL; } return esp_event_post_to(arduino_usb_event_loop_handle, event_base, event_id, event_data, event_data_size, @@ -92,18 +95,20 @@ esp_err_t arduino_usb_event_post(esp_event_base_t event_base, int32_t event_id, } esp_err_t arduino_usb_event_handler_register_with(esp_event_base_t event_base, int32_t event_id, esp_event_handler_t event_handler, void *event_handler_arg) { - if (arduino_usb_event_loop_handle == NULL) { + if (arduino_usb_event_loop_handle == nullptr) { return ESP_FAIL; } return esp_event_handler_register_with(arduino_usb_event_loop_handle, event_base, event_id, event_handler, event_handler_arg); } +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) static bool tinyusb_device_mounted = false; static bool tinyusb_device_suspended = false; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) // Invoked when device is mounted (configured) -void tud_mount_cb(void) { +void tud_mount_cb() { tinyusb_device_mounted = true; arduino_usb_event_data_t p; arduino_usb_event_post(ARDUINO_USB_EVENTS, ARDUINO_USB_STARTED_EVENT, &p, sizeof(arduino_usb_event_data_t), @@ -111,7 +116,7 @@ void tud_mount_cb(void) { } // Invoked when device is unmounted -void tud_umount_cb(void) { +void tud_umount_cb() { tinyusb_device_mounted = false; arduino_usb_event_data_t p; arduino_usb_event_post(ARDUINO_USB_EVENTS, ARDUINO_USB_STOPPED_EVENT, &p, sizeof(arduino_usb_event_data_t), @@ -129,7 +134,7 @@ void tud_suspend_cb(bool remote_wakeup_en) { } // Invoked when usb bus is resumed -void tud_resume_cb(void) { +void tud_resume_cb() { tinyusb_device_suspended = false; arduino_usb_event_data_t p; arduino_usb_event_post(ARDUINO_USB_EVENTS, ARDUINO_USB_RESUME_EVENT, &p, sizeof(arduino_usb_event_data_t), @@ -155,12 +160,12 @@ ESPUSB::ESPUSB(size_t task_stack_size, uint8_t event_task_priority) _started(false), _task_stack_size(task_stack_size), _event_task_priority(event_task_priority) { - if (!arduino_usb_event_loop_handle) { - esp_event_loop_args_t event_task_args = {.queue_size = 5, - .task_name = "arduino_usb_events", - .task_priority = _event_task_priority, - .task_stack_size = _task_stack_size, - .task_core_id = tskNO_AFFINITY}; + if (arduino_usb_event_loop_handle == nullptr) { + const esp_event_loop_args_t event_task_args = {.queue_size = 5, + .task_name = "arduino_usb_events", + .task_priority = _event_task_priority, + .task_stack_size = _task_stack_size, + .task_core_id = tskNO_AFFINITY}; if (esp_event_loop_create(&event_task_args, &arduino_usb_event_loop_handle) != ESP_OK) { log_e("esp_event_loop_create failed"); } @@ -168,9 +173,9 @@ ESPUSB::ESPUSB(size_t task_stack_size, uint8_t event_task_priority) } ESPUSB::~ESPUSB() { - if (arduino_usb_event_loop_handle) { + if (arduino_usb_event_loop_handle != nullptr) { esp_event_loop_delete(arduino_usb_event_loop_handle); - arduino_usb_event_loop_handle = NULL; + arduino_usb_event_loop_handle = nullptr; } } @@ -202,6 +207,7 @@ void ESPUSB::onEvent(arduino_usb_event_t event, esp_event_handler_t callback) { ESPUSB::operator bool() const { return _started && tinyusb_device_mounted; } +// NOLINTBEGIN(readability-convert-member-functions-to-static,readability-make-member-function-const) bool ESPUSB::enableDFU() { #if CFG_TUD_DFU_RUNTIME return tinyusb_enable_interface(USB_INTERFACE_DFU, TUD_DFU_RT_DESC_LEN, load_dfu_descriptor) == ESP_OK; @@ -215,7 +221,7 @@ bool ESPUSB::VID(uint16_t v) { } return !_started; } -uint16_t ESPUSB::VID(void) { return vid; } +uint16_t ESPUSB::VID() { return vid; } bool ESPUSB::PID(uint16_t p) { if (!_started) { @@ -223,7 +229,7 @@ bool ESPUSB::PID(uint16_t p) { } return !_started; } -uint16_t ESPUSB::PID(void) { return pid; } +uint16_t ESPUSB::PID() { return pid; } bool ESPUSB::firmwareVersion(uint16_t version) { if (!_started) { @@ -231,7 +237,7 @@ bool ESPUSB::firmwareVersion(uint16_t version) { } return !_started; } -uint16_t ESPUSB::firmwareVersion(void) { return fw_version; } +uint16_t ESPUSB::firmwareVersion() { return fw_version; } bool ESPUSB::usbVersion(uint16_t version) { if (!_started) { @@ -239,7 +245,7 @@ bool ESPUSB::usbVersion(uint16_t version) { } return !_started; } -uint16_t ESPUSB::usbVersion(void) { return usb_version; } +uint16_t ESPUSB::usbVersion() { return usb_version; } bool ESPUSB::usbPower(uint16_t mA) { if (!_started) { @@ -247,7 +253,7 @@ bool ESPUSB::usbPower(uint16_t mA) { } return !_started; } -uint16_t ESPUSB::usbPower(void) { return usb_power_ma; } +uint16_t ESPUSB::usbPower() { return usb_power_ma; } bool ESPUSB::usbClass(uint8_t _class) { if (!_started) { @@ -255,7 +261,7 @@ bool ESPUSB::usbClass(uint8_t _class) { } return !_started; } -uint8_t ESPUSB::usbClass(void) { return usb_class; } +uint8_t ESPUSB::usbClass() { return usb_class; } bool ESPUSB::usbSubClass(uint8_t subClass) { if (!_started) { @@ -263,7 +269,7 @@ bool ESPUSB::usbSubClass(uint8_t subClass) { } return !_started; } -uint8_t ESPUSB::usbSubClass(void) { return usb_subclass; } +uint8_t ESPUSB::usbSubClass() { return usb_subclass; } bool ESPUSB::usbProtocol(uint8_t protocol) { if (!_started) { @@ -271,7 +277,7 @@ bool ESPUSB::usbProtocol(uint8_t protocol) { } return !_started; } -uint8_t ESPUSB::usbProtocol(void) { return usb_protocol; } +uint8_t ESPUSB::usbProtocol() { return usb_protocol; } bool ESPUSB::usbAttributes(uint8_t attr) { if (!_started) { @@ -279,7 +285,7 @@ bool ESPUSB::usbAttributes(uint8_t attr) { } return !_started; } -uint8_t ESPUSB::usbAttributes(void) { return usb_attributes; } +uint8_t ESPUSB::usbAttributes() { return usb_attributes; } bool ESPUSB::webUSB(bool enabled) { if (!_started) { @@ -290,7 +296,7 @@ bool ESPUSB::webUSB(bool enabled) { } return !_started; } -bool ESPUSB::webUSB(void) { return webusb_enabled; } +bool ESPUSB::webUSB() { return webusb_enabled; } bool ESPUSB::productName(const char *name) { if (!_started) { @@ -298,7 +304,7 @@ bool ESPUSB::productName(const char *name) { } return !_started; } -const char *ESPUSB::productName(void) { return product_name.c_str(); } +const char *ESPUSB::productName() { return product_name.c_str(); } bool ESPUSB::manufacturerName(const char *name) { if (!_started) { @@ -306,7 +312,7 @@ bool ESPUSB::manufacturerName(const char *name) { } return !_started; } -const char *ESPUSB::manufacturerName(void) { return manufacturer_name.c_str(); } +const char *ESPUSB::manufacturerName() { return manufacturer_name.c_str(); } bool ESPUSB::serialNumber(const char *name) { if (!_started) { @@ -314,7 +320,7 @@ bool ESPUSB::serialNumber(const char *name) { } return !_started; } -const char *ESPUSB::serialNumber(void) { return serial_number.c_str(); } +const char *ESPUSB::serialNumber() { return serial_number.c_str(); } bool ESPUSB::webUSBURL(const char *name) { if (!_started) { @@ -322,8 +328,11 @@ bool ESPUSB::webUSBURL(const char *name) { } return !_started; } -const char *ESPUSB::webUSBURL(void) { return webusb_url.c_str(); } +const char *ESPUSB::webUSBURL() { return webusb_url.c_str(); } + +// NOLINTEND(readability-convert-member-functions-to-static,readability-make-member-function-const) +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) ESPUSB USB; #endif /* CONFIG_TINYUSB_ENABLED */ diff --git a/ground_station/src/USBCDC.cpp b/ground_station/src/USBCDC.cpp index e1421d0e..3b0fdb89 100644 --- a/ground_station/src/USBCDC.cpp +++ b/ground_station/src/USBCDC.cpp @@ -28,19 +28,22 @@ #include "USBCDC.h" #include "esp32-hal-tinyusb.h" +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) ESP_EVENT_DEFINE_BASE(ARDUINO_USB_CDC_EVENTS); esp_err_t arduino_usb_event_post(esp_event_base_t event_base, int32_t event_id, void *event_data, size_t event_data_size, TickType_t ticks_to_wait); esp_err_t arduino_usb_event_handler_register_with(esp_event_base_t event_base, int32_t event_id, esp_event_handler_t event_handler, void *event_handler_arg); -#define MAX_USB_CDC_DEVICES 2 -USBCDC *devices[MAX_USB_CDC_DEVICES] = {NULL, NULL}; +constexpr uint8_t kMaxUsbCdcDevices = 2; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) +USBCDC *devices[kMaxUsbCdcDevices] = {nullptr, nullptr}; static uint16_t load_cdc_descriptor(uint8_t *dst, uint8_t *itf) { - uint8_t str_index = tinyusb_add_string_descriptor("TinyUSB CDC"); + const uint8_t str_index = tinyusb_add_string_descriptor("TinyUSB CDC"); uint8_t descriptor[TUD_CDC_DESC_LEN] = { // Interface number, string index, EP notification address and size, EP data address (out, in) and size. + // NOLINTNEXTLINE(hicpp-signed-bitwise) TUD_CDC_DESCRIPTOR(*itf, str_index, 0x85, 64, 0x03, 0x84, 64)}; *itf += 2; memcpy(dst, descriptor, TUD_CDC_DESC_LEN); @@ -49,14 +52,14 @@ static uint16_t load_cdc_descriptor(uint8_t *dst, uint8_t *itf) { // Invoked when line state DTR & RTS are changed via SET_CONTROL_LINE_STATE void tud_cdc_line_state_cb(uint8_t itf, bool dtr, bool rts) { - if (itf < MAX_USB_CDC_DEVICES && devices[itf] != NULL) { + if (itf < kMaxUsbCdcDevices && devices[itf] != nullptr) { devices[itf]->_onLineState(dtr, rts); } } // Invoked when line coding is change via SET_LINE_CODING void tud_cdc_line_coding_cb(uint8_t itf, cdc_line_coding_t const *p_line_coding) { - if (itf < MAX_USB_CDC_DEVICES && devices[itf] != NULL) { + if (itf < kMaxUsbCdcDevices && devices[itf] != nullptr) { devices[itf]->_onLineCoding(p_line_coding->bit_rate, p_line_coding->stop_bits, p_line_coding->parity, p_line_coding->data_bits); } @@ -64,7 +67,7 @@ void tud_cdc_line_coding_cb(uint8_t itf, cdc_line_coding_t const *p_line_coding) // Invoked when received new data void tud_cdc_rx_cb(uint8_t itf) { - if (itf < MAX_USB_CDC_DEVICES && devices[itf] != NULL) { + if (itf < kMaxUsbCdcDevices && devices[itf] != nullptr) { devices[itf]->_onRX(); } } @@ -76,19 +79,20 @@ void tud_cdc_send_break_cb(uint8_t itf, uint16_t duration_ms) { // Invoked when space becomes available in TX buffer void tud_cdc_tx_complete_cb(uint8_t itf) { - if (itf < MAX_USB_CDC_DEVICES && devices[itf] != NULL) { + if (itf < kMaxUsbCdcDevices && devices[itf] != nullptr) { devices[itf]->_onTX(); } } static void ARDUINO_ISR_ATTR cdc0_write_char(char c) { - if (devices[0] != NULL) { + if (devices[0] != nullptr) { devices[0]->write(c); } } -static void usb_unplugged_cb(void *arg, esp_event_base_t event_base, int32_t event_id, void *event_data) { - ((USBCDC *)arg)->_onUnplugged(); +static void usb_unplugged_cb(void *arg, esp_event_base_t event_base [[maybe_unused]], int32_t event_id [[maybe_unused]], + void *event_data [[maybe_unused]]) { + static_cast(arg)->_onUnplugged(); } USBCDC::USBCDC(uint8_t itfn) @@ -101,11 +105,11 @@ USBCDC::USBCDC(uint8_t itfn) rts(false), connected(false), reboot_enable(true), - rx_queue(NULL), - tx_lock(NULL), + rx_queue(nullptr), + tx_lock(nullptr), tx_timeout_ms(250) { tinyusb_enable_interface(USB_INTERFACE_CDC, TUD_CDC_DESC_LEN, load_cdc_descriptor); - if (itf < MAX_USB_CDC_DEVICES) { + if (itf < kMaxUsbCdcDevices) { arduino_usb_event_handler_register_with(ARDUINO_USB_EVENTS, ARDUINO_USB_STOPPED_EVENT, usb_unplugged_cb, this); } } @@ -117,19 +121,20 @@ void USBCDC::onEvent(arduino_usb_cdc_event_t event, esp_event_handler_t callback arduino_usb_event_handler_register_with(ARDUINO_USB_CDC_EVENTS, event, callback, this); } -size_t USBCDC::setRxBufferSize(size_t rx_queue_len) { - size_t currentQueueSize = rx_queue ? uxQueueSpacesAvailable(rx_queue) + uxQueueMessagesWaiting(rx_queue) : 0; +size_t USBCDC::setRxBufferSize(size_t size) { + const size_t currentQueueSize = + rx_queue != nullptr ? uxQueueSpacesAvailable(rx_queue) + uxQueueMessagesWaiting(rx_queue) : 0; - if (rx_queue_len != currentQueueSize) { - xQueueHandle new_rx_queue = NULL; - if (rx_queue_len) { - new_rx_queue = xQueueCreate(rx_queue_len, sizeof(uint8_t)); - if (!new_rx_queue) { + if (size != currentQueueSize) { + xQueueHandle new_rx_queue = nullptr; + if (size > 0) { + new_rx_queue = xQueueCreate(size, sizeof(uint8_t)); + if (new_rx_queue == nullptr) { log_e("CDC Queue creation failed."); return 0; } - if (rx_queue) { - size_t copySize = uxQueueMessagesWaiting(rx_queue); + if (rx_queue != nullptr) { + const size_t copySize = uxQueueMessagesWaiting(rx_queue); if (copySize > 0) { for (size_t i = 0; i < copySize; i++) { uint8_t ch = 0; @@ -147,39 +152,42 @@ size_t USBCDC::setRxBufferSize(size_t rx_queue_len) { vQueueDelete(rx_queue); } rx_queue = new_rx_queue; - return rx_queue_len; + return size; + // NOLINTNEXTLINE(readability-else-after-return) more understandable like this } else { - if (rx_queue) { + if (rx_queue != nullptr) { vQueueDelete(rx_queue); - rx_queue = NULL; + rx_queue = nullptr; } } } - return rx_queue_len; + return size; } -void USBCDC::begin(unsigned long baud) { - if (tx_lock == NULL) { +void USBCDC::begin(uint32_t baud [[maybe_unused]]) { + if (tx_lock == nullptr) { tx_lock = xSemaphoreCreateMutex(); } // if rx_queue was set before begin(), keep it - if (!rx_queue) setRxBufferSize(256); // default if not preset + if (rx_queue == nullptr) { + setRxBufferSize(256); // default if not preset + } devices[itf] = this; } void USBCDC::end() { connected = false; - devices[itf] = NULL; + devices[itf] = nullptr; setRxBufferSize(0); - if (tx_lock != NULL) { + if (tx_lock != nullptr) { vSemaphoreDelete(tx_lock); - tx_lock = NULL; + tx_lock = nullptr; } } void USBCDC::setTxTimeoutMs(uint32_t timeout) { tx_timeout_ms = timeout; } -void USBCDC::_onUnplugged(void) { +void USBCDC::_onUnplugged() { if (connected) { connected = false; dtr = false; @@ -285,7 +293,7 @@ void USBCDC::_onRX() { uint8_t buf[CONFIG_TINYUSB_CDC_RX_BUFSIZE + 1]; uint32_t count = tud_cdc_n_read(itf, buf, CONFIG_TINYUSB_CDC_RX_BUFSIZE); for (uint32_t i = 0; i < count; i++) { - if (rx_queue == NULL || !xQueueSend(rx_queue, buf + i, 10)) { + if (rx_queue == nullptr || !xQueueSend(rx_queue, buf + i, 10)) { p.rx_overflow.dropped_bytes = count - i; arduino_usb_event_post(ARDUINO_USB_CDC_EVENTS, ARDUINO_USB_CDC_RX_OVERFLOW_EVENT, &p, sizeof(arduino_usb_cdc_event_data_t), portMAX_DELAY); @@ -294,13 +302,14 @@ void USBCDC::_onRX() { break; } } - if (count) { + if (count != 0) { p.rx.len = count; arduino_usb_event_post(ARDUINO_USB_CDC_EVENTS, ARDUINO_USB_CDC_RX_EVENT, &p, sizeof(arduino_usb_cdc_event_data_t), portMAX_DELAY); } } +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) void USBCDC::_onTX() { arduino_usb_cdc_event_data_t p; arduino_usb_event_post(ARDUINO_USB_CDC_EVENTS, ARDUINO_USB_CDC_TX_EVENT, &p, sizeof(arduino_usb_cdc_event_data_t), @@ -308,51 +317,53 @@ void USBCDC::_onTX() { } void USBCDC::enableReboot(bool enable) { reboot_enable = enable; } -bool USBCDC::rebootEnabled(void) { return reboot_enable; } -int USBCDC::available(void) { - if (itf >= MAX_USB_CDC_DEVICES || rx_queue == NULL) { +// NOLINTNEXTLINE(readability-make-member-function-const) +bool USBCDC::rebootEnabled() { return reboot_enable; } + +int USBCDC::available() { + if (itf >= kMaxUsbCdcDevices || rx_queue == nullptr) { return -1; } - return uxQueueMessagesWaiting(rx_queue); + return static_cast(uxQueueMessagesWaiting(rx_queue)); } -int USBCDC::peek(void) { - if (itf >= MAX_USB_CDC_DEVICES || rx_queue == NULL) { +int USBCDC::peek() { + if (itf >= kMaxUsbCdcDevices || rx_queue == nullptr) { return -1; } - uint8_t c; - if (xQueuePeek(rx_queue, &c, 0)) { + uint8_t c = 0; + if (xQueuePeek(rx_queue, &c, 0) != 0) { return c; } return -1; } -int USBCDC::read(void) { - if (itf >= MAX_USB_CDC_DEVICES || rx_queue == NULL) { +int USBCDC::read() { + if (itf >= kMaxUsbCdcDevices || rx_queue == nullptr) { return -1; } uint8_t c = 0; - if (xQueueReceive(rx_queue, &c, 0)) { + if (xQueueReceive(rx_queue, &c, 0) != 0) { return c; } return -1; } size_t USBCDC::read(uint8_t *buffer, size_t size) { - if (itf >= MAX_USB_CDC_DEVICES || rx_queue == NULL) { + if (itf >= kMaxUsbCdcDevices || rx_queue == nullptr) { return -1; } uint8_t c = 0; size_t count = 0; - while (count < size && xQueueReceive(rx_queue, &c, 0)) { + while ((count < size) && (xQueueReceive(rx_queue, &c, 0) != 0)) { buffer[count++] = c; } return count; } -void USBCDC::flush(void) { - if (itf >= MAX_USB_CDC_DEVICES || tx_lock == NULL || !tud_cdc_n_connected(itf)) { +void USBCDC::flush() { + if (itf >= kMaxUsbCdcDevices || tx_lock == nullptr || !tud_cdc_n_connected(itf)) { return; } if (xSemaphoreTake(tx_lock, tx_timeout_ms / portTICK_PERIOD_MS) != pdPASS) { @@ -362,46 +373,47 @@ void USBCDC::flush(void) { xSemaphoreGive(tx_lock); } -int USBCDC::availableForWrite(void) { - if (itf >= MAX_USB_CDC_DEVICES || tx_lock == NULL || !tud_cdc_n_connected(itf)) { +int USBCDC::availableForWrite() { + if (itf >= kMaxUsbCdcDevices || tx_lock == nullptr || !tud_cdc_n_connected(itf)) { return 0; } if (xSemaphoreTake(tx_lock, tx_timeout_ms / portTICK_PERIOD_MS) != pdPASS) { return 0; } - size_t a = tud_cdc_n_write_available(itf); + const size_t a = tud_cdc_n_write_available(itf); xSemaphoreGive(tx_lock); - return a; + return static_cast(a); } size_t USBCDC::write(const uint8_t *buffer, size_t size) { - if (itf >= MAX_USB_CDC_DEVICES || tx_lock == NULL || buffer == NULL || size == 0 || !tud_cdc_n_connected(itf)) { + if (itf >= kMaxUsbCdcDevices || tx_lock == nullptr || buffer == nullptr || size == 0 || !tud_cdc_n_connected(itf)) { return 0; } - if (xPortInIsrContext()) { - BaseType_t taskWoken = false; + if (xPortInIsrContext() != 0) { + BaseType_t taskWoken = 0; if (xSemaphoreTakeFromISR(tx_lock, &taskWoken) != pdPASS) { return 0; } } else if (xSemaphoreTake(tx_lock, tx_timeout_ms / portTICK_PERIOD_MS) != pdPASS) { return 0; } - size_t to_send = size, so_far = 0; - while (to_send) { + size_t to_send = size; + size_t so_far = 0; + while (to_send > 0) { if (!tud_cdc_n_connected(itf)) { size = so_far; break; } size_t space = tud_cdc_n_write_available(itf); - if (!space) { + if (space == 0) { tud_cdc_n_write_flush(itf); continue; } if (space > to_send) { space = to_send; } - size_t sent = tud_cdc_n_write(itf, buffer + so_far, space); - if (sent) { + const size_t sent = tud_cdc_n_write(itf, buffer + so_far, space); + if (sent > 0) { so_far += sent; to_send -= sent; tud_cdc_n_write_flush(itf); @@ -410,8 +422,8 @@ size_t USBCDC::write(const uint8_t *buffer, size_t size) { break; } } - if (xPortInIsrContext()) { - BaseType_t taskWoken = false; + if (xPortInIsrContext() != 0) { + BaseType_t taskWoken = 0; xSemaphoreGiveFromISR(tx_lock, &taskWoken); } else { xSemaphoreGive(tx_lock); @@ -421,19 +433,22 @@ size_t USBCDC::write(const uint8_t *buffer, size_t size) { size_t USBCDC::write(uint8_t c) { return write(&c, 1); } +// NOLINTNEXTLINE(readability-make-member-function-const) uint32_t USBCDC::baudRate() { return bit_rate; } +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) void USBCDC::setDebugOutput(bool en) { if (en) { - uartSetDebug(NULL); + uartSetDebug(nullptr); + // NOLINTNEXTLINE(google-readability-casting) no idea what this does ets_install_putc1((void (*)(char)) & cdc0_write_char); } else { - ets_install_putc1(NULL); + ets_install_putc1(nullptr); } } USBCDC::operator bool() const { - if (itf >= MAX_USB_CDC_DEVICES) { + if (itf >= kMaxUsbCdcDevices) { return false; } return connected; diff --git a/ground_station/src/config.cpp b/ground_station/src/config.cpp index a497a7b7..0870006e 100644 --- a/ground_station/src/config.cpp +++ b/ground_station/src/config.cpp @@ -4,8 +4,10 @@ #include "console.hpp" #include "systemParser.hpp" -SystemParser systemParser; -Config systemConfig; +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) +SystemParser systemParser{}; +Config systemConfig{}; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) /* if(systemParser.loadFile(configFileName)) @@ -35,7 +37,7 @@ void Config::save() { systemParser.setTestingPhrase(config.testingPhrase); systemParser.setLinkPhrase1(config.linkPhrase1); systemParser.setLinkPhrase2(config.linkPhrase2); - systemParser.setTelemetryMode(config.receiverMode); + systemParser.setTelemetryMode(static_cast(config.receiverMode)); systemParser.setNeverStopLoggingFlag(config.neverStopLogging); systemParser.setTimeZone(config.timeZoneOffset); systemParser.setMagCalib(config.mag_calib); @@ -45,8 +47,8 @@ void Config::save() { void Config::load() { systemParser.loadFile("/config.json"); console.log.println("Load config file"); - bool mode; - bool stop; + bool mode{false}; + bool stop{false}; if (!systemParser.getTestingPhrase(config.testingPhrase)) { strncpy(config.testingPhrase, "", 1); console.error.println("Failed"); @@ -68,12 +70,12 @@ void Config::load() { if (!systemParser.getTelemetryMode(mode)) { mode = false; } else { - console.log.println(mode); + console.log.println(static_cast(mode)); } if (!systemParser.getNeverStopLoggingFlag(stop)) { config.neverStopLogging = false; } else { - console.log.println(config.neverStopLogging); + console.log.println(static_cast(config.neverStopLogging)); } if (!systemParser.getTimeZone(config.timeZoneOffset)) { config.timeZoneOffset = 0; @@ -92,6 +94,6 @@ void Config::load() { console.log.println(config.timeZoneOffset); } - config.neverStopLogging = static_cast(stop); + config.neverStopLogging = stop; config.receiverMode = static_cast(mode); } diff --git a/ground_station/src/config.hpp b/ground_station/src/config.hpp index 60dce5c1..36323179 100644 --- a/ground_station/src/config.hpp +++ b/ground_station/src/config.hpp @@ -1,16 +1,17 @@ #pragma once -#include #include "systemParser.hpp" -typedef enum : bool { SINGLE = 0, DUAL = 1 } ReceiverTelemetryMode_e; +#include + +enum ReceiverTelemetryMode_e : bool { SINGLE = false, DUAL = true }; // Maximum number of characters for link & test phrases inline constexpr uint32_t kMaxPhraseLen = 16; struct systemConfig_t { int16_t timeZoneOffset; - uint8_t neverStopLogging; + bool neverStopLogging; ReceiverTelemetryMode_e receiverMode; char linkPhrase1[kMaxPhraseLen + 1]; char linkPhrase2[kMaxPhraseLen + 1]; @@ -20,7 +21,7 @@ struct systemConfig_t { class Config { public: - Config() {} + Config() = default; void save(); void load(); @@ -30,4 +31,5 @@ class Config { private: }; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern Config systemConfig; diff --git a/ground_station/src/console.cpp b/ground_station/src/console.cpp index cdc9a049..16dea8ed 100644 --- a/ground_station/src/console.cpp +++ b/ground_station/src/console.cpp @@ -32,38 +32,43 @@ #include "console.hpp" -bool Console::begin(void) { +bool Console::begin() { if (type == USBCDC_t) { - (*(USBCDC*)&stream).enableReboot(true); // Enables entering bootloader when changing to baudrate of 1200 bit/s - // (normaly not used, due to dedicated DFU USB-Endpoint) - (*(USBCDC*)&stream).onEvent(usbEventCallback); - (*(USBCDC*)&stream).begin(); - } else + // NOLINTBEGIN(cppcoreguidelines-pro-type-static-cast-downcast) dynamic cast is not allowed with -fno-rtti + static_cast(&stream)->enableReboot(true); // Enables entering bootloader when changing to baudrate of 1200 + // bit/s (normaly not used, due to dedicated DFU USB-Endpoint) + static_cast(&stream)->onEvent(usbEventCallback); + static_cast(&stream)->begin(); + // NOLINTEND(cppcoreguidelines-pro-type-static-cast-downcast) dynamic cast is not allowed with -fno-rtti + } else { return false; + } return initialize(); } -bool Console::begin(unsigned long baud, uint32_t config, int8_t rxPin, int8_t txPin, bool invert, - unsigned long timeout_ms, uint8_t rxfifo_full_thrhd) { +bool Console::begin(uint32_t baud, uint32_t config, int8_t rxPin, int8_t txPin, bool invert, uint32_t timeout_ms, + uint8_t rxfifo_full_thrhd) { if (type == HardwareSerial_t) { - (*(HardwareSerial*)&stream).begin(baud, config, rxPin, txPin, invert, timeout_ms, rxfifo_full_thrhd); - } else + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-static-cast-downcast) dynamic cast is not allowed with -fno-rtti + static_cast(&stream)->begin(baud, config, rxPin, txPin, invert, timeout_ms, rxfifo_full_thrhd); + } else { return false; + } return initialize(); } -bool Console::initialize(void) { +bool Console::initialize() { initialized = true; bufferAccessSemaphore = xSemaphoreCreateMutex(); xTaskCreate(writeTask, "task_consoleWrite", 4096, this, 1, &writeTaskHandle); - xTaskCreate(interfaceTask, "task_consoleIface", 4096, this, 1, NULL); // TODO: Stack size must be that large?! + xTaskCreate(interfaceTask, "task_consoleIface", 4096, this, 1, nullptr); // TODO: Stack size must be that large?! return true; } -void Console::end(void) { initialized = false; } +void Console::end() { initialized = false; } void Console::writeTask(void* pvParameter) { - Console* ref = (Console*)pvParameter; + auto* ref = static_cast(pvParameter); while (ref->initialized) { ulTaskNotifyTake(pdTRUE, portMAX_DELAY); // Wait on notification for data in buffer or console opened @@ -71,10 +76,13 @@ void Console::writeTask(void* pvParameter) { if (xSemaphoreTake(ref->bufferAccessSemaphore, portMAX_DELAY)) { if (ref->readIdx < ref->writeIdx) // Regular case, no wrap around needed { + // NOLINTNEXTLINE(google-readability-casting) ref->stream.write((const uint8_t*)ref->ringBuffer + ref->readIdx, ref->writeIdx - ref->readIdx); } else if (ref->readIdx > ref->writeIdx) // Need to send buffer in two parts (ReadIdx to End | 0 to WriteIdx) { + // NOLINTNEXTLINE(google-readability-casting) ref->stream.write((const uint8_t*)ref->ringBuffer + ref->readIdx, QUEUE_BUFFER_LENGTH - ref->readIdx); + // NOLINTNEXTLINE(google-readability-casting) ref->stream.write((const uint8_t*)ref->ringBuffer, ref->writeIdx); } ref->readIdx = ref->writeIdx; @@ -82,16 +90,18 @@ void Console::writeTask(void* pvParameter) { } } } - vTaskDelete(NULL); + vTaskDelete(nullptr); } void Console::interfaceTask(void* pvParameter) { - Console* ref = (Console*)pvParameter; - - TickType_t interfaceTimer = 0; - TickType_t enabledTimer = 0; - bool enabledOld = false, enabledDelayed = false; - bool interfaceOld = false, interfaceDelayed = false; + auto* ref = static_cast(pvParameter); + + TickType_t interfaceTimer{0}; + TickType_t enabledTimer{0}; + bool enabledOld = false; + bool enabledDelayed = false; + bool interfaceOld = false; + bool interfaceDelayed = false; bool streamActiveOld = false; while (ref->initialized) { TickType_t task_last_tick = xTaskGetTickCount(); @@ -111,8 +121,8 @@ void Console::interfaceTask(void* pvParameter) { ref->streamActive = enabledDelayed && interfaceDelayed; if (ref->streamActive && !streamActiveOld) { ref->printStartupMessage(); - vTaskDelay((const TickType_t)10); // Make sure that startup message is printed befor everything else - xTaskNotifyGive(ref->writeTaskHandle); // Send signal to update task (for sending out data in queue buffer) + vTaskDelay(static_cast(10)); // Make sure that startup message is printed befor everything else + xTaskNotifyGive(ref->writeTaskHandle); // Send signal to update task (for sending out data in queue buffer) } if (!ref->streamActive && streamActiveOld) // Detect if console has been closed { @@ -121,22 +131,27 @@ void Console::interfaceTask(void* pvParameter) { } streamActiveOld = ref->streamActive; - vTaskDelayUntil(&task_last_tick, (const TickType_t)1000 / INTERFACE_UPDATE_RATE); + vTaskDelayUntil(&task_last_tick, static_cast(1000) / INTERFACE_UPDATE_RATE); } - vTaskDelete(NULL); + vTaskDelete(nullptr); } size_t Console::write(const uint8_t* buffer, size_t size) { - if (size == 0) return 0; + if (size == 0) { + return 0; + } if (xSemaphoreTake(bufferAccessSemaphore, portMAX_DELAY)) { - int free; - size = min(size, (size_t)QUEUE_BUFFER_LENGTH - 1); + uint32_t free{0}; + size = min(size, static_cast(QUEUE_BUFFER_LENGTH) - 1); if (writeIdx + size <= QUEUE_BUFFER_LENGTH) { + // NOLINTNEXTLINE(google-readability-casting) memcpy((uint8_t*)ringBuffer + writeIdx, buffer, size); free = QUEUE_BUFFER_LENGTH - (writeIdx - readIdx); } else { - int firstPartSize = QUEUE_BUFFER_LENGTH - writeIdx; + const uint32_t firstPartSize = QUEUE_BUFFER_LENGTH - writeIdx; + // NOLINTNEXTLINE(google-readability-casting) memcpy((uint8_t*)ringBuffer + writeIdx, buffer, firstPartSize); + // NOLINTNEXTLINE(google-readability-casting) memcpy((uint8_t*)ringBuffer, buffer + firstPartSize, size - firstPartSize); free = readIdx - writeIdx; } @@ -152,15 +167,15 @@ size_t Console::write(const uint8_t* buffer, size_t size) { return 0; } -void Console::printTimestamp(void) { - int h = _min(millis() / 3600000, 99); - int m = (millis() / 60000) % 60; - int s = (millis() / 1000) % 60; - int ms = millis() % 1000; - printf("[%02d:%02d:%02d.%03d] ", h, m, s, ms); +void Console::printTimestamp() { + const uint32_t h = std::min(millis() / 3600000, 99UL); + const auto m = static_cast((millis() / 60000) % 60); + const auto s = static_cast((millis() / 1000) % 60); + const auto ms = static_cast(millis() % 1000); + printf("[%02lu:%02lu:%02lu.%03lu] ", h, m, s, ms); } -void Console::printStartupMessage(void) { +void Console::printStartupMessage() { stream.print(CONSOLE_CLEAR); stream.print(CONSOLE_COLOR_BOLD_CYAN CONSOLE_BACKGROUND_DEFAULT); stream.println("****************************************************"); @@ -169,17 +184,14 @@ void Console::printStartupMessage(void) { stream.println(CONSOLE_LOG); } -void Console::usbEventCallback(void* arg, esp_event_base_t event_base, int32_t event_id, void* event_data) { +void Console::usbEventCallback(void* arg [[maybe_unused]], esp_event_base_t event_base, int32_t event_id, + void* event_data [[maybe_unused]]) { if (event_base == ARDUINO_USB_CDC_EVENTS) { switch (event_id) { case ARDUINO_USB_CDC_CONNECTED_EVENT: - break; case ARDUINO_USB_CDC_DISCONNECTED_EVENT: - break; case ARDUINO_USB_CDC_LINE_STATE_EVENT: - break; case ARDUINO_USB_CDC_LINE_CODING_EVENT: - break; default: break; } @@ -187,6 +199,8 @@ void Console::usbEventCallback(void* arg, esp_event_base_t event_base, int32_t e } #ifndef USE_CUSTOM_CONSOLE +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) USBCDC USBSerial; Console console(USBSerial); +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) #endif diff --git a/ground_station/src/console.hpp b/ground_station/src/console.hpp index 990b8fb8..d83d0c81 100644 --- a/ground_station/src/console.hpp +++ b/ground_station/src/console.hpp @@ -34,14 +34,21 @@ #define CONSOLE_H #include -#include "USB.h" +#include -#define INTERFACE_UPDATE_RATE 10 // [hz] -#define QUEUE_BUFFER_LENGTH (1 << 13) // [#] Buffer Size must be power of 2 -#define CONSOLE_ACTIVE_DELAY 3000 // [ms] Data transmission hold-back delay after console object has been enabled -#define INTERFACE_ACTIVE_DELAY \ - 1500 // [ms] Data transmission hold-back delay after physical connection has been established (Terminal opened) +// [hz] +inline constexpr uint8_t INTERFACE_UPDATE_RATE = 10; +// [#] Buffer Size must be power of 2 +inline constexpr uint32_t QUEUE_BUFFER_LENGTH = 1U << 13U; + +// [ms] Data transmission hold-back delay after console object has been enabled +inline constexpr uint32_t CONSOLE_ACTIVE_DELAY = 3000; + +// [ms] Data transmission hold-back delay after physical connection has been established (Terminal opened) +inline constexpr uint32_t INTERFACE_ACTIVE_DELAY = 1500; + +// NOLINTBEGIN(cppcoreguidelines-macro-usage) #define CONSOLE_CLEAR "\033[2J\033[1;1H" #define CONSOLE_COLOR_BLACK "\033[0;30" @@ -73,6 +80,7 @@ #define CONSOLE_BACKGROUND_CYAN ";46m" #define CONSOLE_BACKGROUND_WHITE ";47m" #define CONSOLE_BACKGROUND_DEFAULT ";49m" +// NOLINTEND(cppcoreguidelines-macro-usage) #define CONSOLE_OK (CONSOLE_COLOR_GREEN CONSOLE_BACKGROUND_DEFAULT) #define CONSOLE_LOG (CONSOLE_COLOR_DEFAULT CONSOLE_BACKGROUND_DEFAULT) @@ -103,14 +111,15 @@ class ConsoleStatus : public Stream { const char* textColor = CONSOLE_COLOR_DEFAULT; const char* backgroundColor = CONSOLE_BACKGROUND_DEFAULT; - ConsoleStatus(ConsoleType t) : type(t) {} + explicit ConsoleStatus(ConsoleType t) : type(t) {} inline void ref(Stream* c) { console = c; } inline void enable(bool s) { enabled = s; } - inline int available(void) { return console->available(); } - inline int read(void) { return console->read(); } - inline int peek(void) { return console->peek(); } - inline size_t write(uint8_t c) { return write((const uint8_t*)&c, 1); } - inline size_t write(const char* buffer, size_t size) { return write((uint8_t*)buffer, size); } + inline int available() override { return console->available(); } + inline int read() override { return console->read(); } + inline int peek() override { return console->peek(); } + inline size_t write(uint8_t c) override { return write(static_cast(&c), 1); } + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + inline size_t write(const char* buffer, size_t size) { return write(reinterpret_cast(buffer), size); } ConsoleStatus& operator[](ConsoleColor color) { switch (color) { case COLOR_DEFAULT: @@ -143,8 +152,10 @@ class ConsoleStatus : public Stream { } return *this; } - size_t write(const uint8_t* buffer, size_t size) { - if (!enabled || type == StatusDummy_t) return 0; + size_t write(const uint8_t* buffer, size_t size) override { + if (!enabled || type == StatusDummy_t) { + return 0; + } if (colorEnabled) { switch (type) { case StatusCustom_t: @@ -165,7 +176,7 @@ class ConsoleStatus : public Stream { break; } } - size = console->write((const uint8_t*)buffer, size); + size = console->write(buffer, size); if (colorEnabled) { console->print(CONSOLE_LOG); } @@ -182,35 +193,41 @@ class Console : public Stream { volatile bool initialized = false; volatile bool enabled = false; // Indicates if the stream is enabled (e.g. is set after USB MSC setup is done) volatile bool streamActive = false; // Indicates if the console is opened and data is tranmitted - volatile char ringBuffer[QUEUE_BUFFER_LENGTH]; + volatile char ringBuffer[QUEUE_BUFFER_LENGTH]{}; volatile uint32_t writeIdx = 0, readIdx = 0; SemaphoreHandle_t bufferAccessSemaphore = nullptr; TaskHandle_t writeTaskHandle = nullptr; ConsoleStatus custom = ConsoleStatus(ConsoleStatus::StatusCustom_t); - bool initialize(void); - void printStartupMessage(void); + bool initialize(); + void printStartupMessage(); static void writeTask(void* pvParameter); static void interfaceTask(void* pvParameter); static void usbEventCallback(void* arg, esp_event_base_t event_base, int32_t event_id, void* event_data); - bool getInterfaceState(void) { + bool getInterfaceState() { + // NOLINTBEGIN(cppcoreguidelines-pro-type-static-cast-downcast) dynamic cast is not allowed with -fno-rtti if (type == USBCDC_t) { - return *(USBCDC*)&stream; - } else if (type == HardwareSerial_t) { - return *(HardwareSerial*)&stream; + return *static_cast(&stream); + } + if (type == HardwareSerial_t) { + return *static_cast(&stream); } + // NOLINTEND(cppcoreguidelines-pro-type-static-cast-downcast) dynamic cast is not allowed with -fno-rtti + return true; } public: enum ConsoleLevel { LEVEL_LOG = 0, LEVEL_OK = 1, LEVEL_WARNING = 2, LEVEL_ERROR = 3, LEVEL_OFF = 4 }; + // NOLINTBEGIN(cppcoreguidelines-non-private-member-variables-in-classes) ConsoleStatus ok = ConsoleStatus(ConsoleStatus::StatusOk_t); ConsoleStatus log = ConsoleStatus(ConsoleStatus::StatusLog_t); ConsoleStatus error = ConsoleStatus(ConsoleStatus::StatusError_t); ConsoleStatus warning = ConsoleStatus(ConsoleStatus::StatusWarning_t); ConsoleStatus dummy = ConsoleStatus(ConsoleStatus::StatusDummy_t); + // NOLINTEND(cppcoreguidelines-non-private-member-variables-in-classes) - Console(USBCDC& stream) : stream(stream), type(USBCDC_t) { + explicit Console(USBCDC& stream) : stream(stream), type(USBCDC_t) { ok.ref(this); log.ref(this); error.ref(this); @@ -218,7 +235,7 @@ class Console : public Stream { custom.ref(this); dummy.ref(this); } - Console(HardwareSerial& stream) : stream(stream), type(HardwareSerial_t) { + explicit Console(HardwareSerial& stream) : stream(stream), type(HardwareSerial_t) { ok.ref(this); log.ref(this); error.ref(this); @@ -227,13 +244,13 @@ class Console : public Stream { dummy.ref(this); } bool begin(); // Used for USBSerial - bool begin(unsigned long baud, uint32_t config = SERIAL_8N1, int8_t rxPin = -1, int8_t txPin = -1, - bool invert = false, unsigned long timeout_ms = 20000UL, + bool begin(uint32_t baud, uint32_t config = SERIAL_8N1, int8_t rxPin = -1, int8_t txPin = -1, bool invert = false, + uint32_t timeout_ms = 20000UL, uint8_t rxfifo_full_thrhd = 112); // Used for HardwareSerial - void end(void); + void end(); void enable(bool state) { enabled = state; } - void flush(void) { readIdx = writeIdx; } - void printTimestamp(void); // TODO: Add possibillity to add string as parameter + void flush() override { readIdx = writeIdx; } + void printTimestamp(); // TODO: Add possibillity to add string as parameter void enableColors(bool state) { ok.colorEnabled = log.colorEnabled = error.colorEnabled = warning.colorEnabled = custom.colorEnabled = dummy.colorEnabled = state; @@ -277,21 +294,22 @@ class Console : public Stream { return custom; } - operator bool() const { return streamActive; } - inline int available(void) { return stream.available(); } - inline int read(void) { return stream.read(); } - inline int peek(void) { return stream.peek(); } - inline size_t write(uint8_t c) { return write(&c, 1); } - inline size_t write(const char* buffer, size_t size) { return write((const uint8_t*)buffer, size); } - inline size_t write(const char* s) { return write((const uint8_t*)s, strlen(s)); } - inline size_t write(unsigned long n) { return write((uint8_t)n); } - inline size_t write(long n) { return write((uint8_t)n); } - inline size_t write(unsigned int n) { return write((uint8_t)n); } - inline size_t write(int n) { return write((uint8_t)n); } - size_t write(const uint8_t* buffer, size_t size); + explicit operator bool() const { return streamActive; } + inline int available() override { return stream.available(); } + inline int read() override { return stream.read(); } + inline int peek() override { return stream.peek(); } + inline size_t write(uint8_t c) override { return write(&c, 1); } + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + inline size_t write(const char* buffer, size_t size) { return write(reinterpret_cast(buffer), size); } + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + inline size_t write(const char* s) { return write(reinterpret_cast(s), strlen(s)); } + inline size_t write(uint32_t n) { return write(static_cast(n)); } + inline size_t write(int32_t n) { return write(static_cast(n)); } + size_t write(const uint8_t* buffer, size_t size) override; }; #ifndef USE_CUSTOM_CONSOLE +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern Console console; #endif diff --git a/ground_station/src/hmi/hmi.cpp b/ground_station/src/hmi/hmi.cpp index 00d5264c..cfc10ffa 100644 --- a/ground_station/src/hmi/hmi.cpp +++ b/ground_station/src/hmi/hmi.cpp @@ -1,15 +1,20 @@ #include "hmi.hpp" -#include + #include "console.hpp" #include "navigation.hpp" #include "telemetry/telemetry.hpp" #include "utils.hpp" +#include +#include + +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) extern Telemetry link1; extern Telemetry link2; extern Navigation navigation; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) void Hmi::begin() { upButton.begin(); @@ -26,7 +31,7 @@ void Hmi::begin() { window.begin(); initialized = true; - xTaskCreate(update, "task_hmi", 8196, this, 1, NULL); + xTaskCreate(update, "task_hmi", 8196, this, 1, nullptr); } void Hmi::fsm() { @@ -69,7 +74,7 @@ void Hmi::fsm() { void Hmi::initMenu() { window.initMenu(menuIndex); } void Hmi::menu() { - uint32_t oldIndex = menuIndex; + const uint32_t oldIndex = menuIndex; if (rightButton.wasPressed() && (menuIndex % 3) < 2) { menuIndex++; } @@ -91,7 +96,7 @@ void Hmi::menu() { } if (okButton.wasPressed() || centerButton.wasPressed()) { - state = (State)(menuIndex + 1); + state = static_cast(menuIndex + 1); if (state == LIVE) { initLive(); } else if (state == RECOVERY) { @@ -119,7 +124,7 @@ void Hmi::live() { // We log after LIFTOFF and stop either never (if neverStopLogging == TRUE) or at TOUCHDOWN link1Log = (link1.data.state() > 2) && (systemConfig.config.neverStopLogging || link1.data.state() < 7); if (link1Log) { - recorder.record(&link1.data.rxData, 1); + recorder.record(&link1.data.getRxData(), 1); } window.updateLive(&link1.data, &link1.info, 0); updated = true; @@ -132,7 +137,7 @@ void Hmi::live() { // We log after LIFTOFF and stop either never (if neverStopLogging == TRUE) or at TOUCHDOWN link2Log = (link2.data.state() > 2) && (systemConfig.config.neverStopLogging || link2.data.state() < 7); if (link2Log) { - recorder.record(&link2.data.rxData, 2); + recorder.record(&link2.data.getRxData(), 2); } window.updateLive(&link2.data, &link2.info, 1); updated = true; @@ -164,13 +169,6 @@ void Hmi::recovery() { a = navigation.getPointA(); b = navigation.getPointB(); - if (a.lat && a.lon && b.lat && b.lon) { - // window.updateRecovery(a, b, navigation.getHorizontalDistance(), - // navigation.getBearing()); - - } else { - // window.updateRecovery(a, b); - } if (navigation.isUpdated()) { window.updateRecovery(&navigation); @@ -186,6 +184,7 @@ void Hmi::recovery() { void Hmi::initTesting() { window.initTesting(); } +// NOLINTNEXTLINE(readability-function-cognitive-complexity) void Hmi::testing() { if (boxWindow) { bool exit = false; @@ -268,14 +267,12 @@ void Hmi::testing() { } } break; - case CAN_NOT_START: { - } break; - - case FAILED: { - } break; + case CAN_NOT_START: + case FAILED: + break; case STARTED: { - uint32_t oldIndex = testingIndex; + const uint32_t oldIndex = testingIndex; if (upButton.wasPressed() && (testingIndex % 4) > 0) { testingIndex--; } else if (downButton.wasPressed() && (testingIndex % 4) < 3) { @@ -389,6 +386,7 @@ void Hmi::initSettings() { window.initSettings(settingSubMenu); } +// NOLINTNEXTLINE(readability-function-cognitive-complexity) void Hmi::settings() { static bool keyboardActive = false; static bool configChanged = false; @@ -433,15 +431,11 @@ void Hmi::settings() { } } if (okButton.wasPressed() || okButton.pressedFor(500)) { - if (i == Window::kShiftIdx) { // shift - window.updateKeyboard(keyboardString, i, true); - } else { - window.updateKeyboard(keyboardString, i, true); - } + window.updateKeyboard(keyboardString, i, true); } if (backButton.wasPressed()) { - memcpy((char *)settingsTable[settingSubMenu][settingIndex].dataPtr, keyboardString, kMaxPhraseLen); + memcpy(static_cast(settingsTable[settingSubMenu][settingIndex].dataPtr), keyboardString, kMaxPhraseLen); keyboardString[kMaxPhraseLen] = '\0'; window.initSettings(settingSubMenu); configChanged = true; @@ -461,32 +455,32 @@ void Hmi::settings() { window.initSettings(settingSubMenu); } } else { + void *data_ptr = settingsTable[settingSubMenu][settingIndex].dataPtr; + const settings_limits_u &cfg = settingsTable[settingSubMenu][settingIndex].config; switch (settingsTable[settingSubMenu][settingIndex].type) { case NUMBER: { if ((rightButton.wasPressed() || rightButton.pressedFor(500)) && - *(int16_t *)settingsTable[settingSubMenu][settingIndex].dataPtr < - settingsTable[settingSubMenu][settingIndex].config.minmax.max) { - (*(int16_t *)settingsTable[settingSubMenu][settingIndex].dataPtr)++; + *static_cast(data_ptr) < cfg.minmax.max) { + (*static_cast(data_ptr))++; configChanged = true; window.updateSettings(settingIndex); } if ((leftButton.wasPressed() || leftButton.pressedFor(500)) && - *(int16_t *)settingsTable[settingSubMenu][settingIndex].dataPtr > - settingsTable[settingSubMenu][settingIndex].config.minmax.min) { - (*(int16_t *)settingsTable[settingSubMenu][settingIndex].dataPtr)--; + *static_cast(data_ptr) > cfg.minmax.min) { + (*static_cast(data_ptr))--; configChanged = true; window.updateSettings(settingIndex); } break; } case TOGGLE: { - if (rightButton.wasPressed() && *(bool *)settingsTable[settingSubMenu][settingIndex].dataPtr == false) { - (*(bool *)settingsTable[settingSubMenu][settingIndex].dataPtr) = true; + if (rightButton.wasPressed() && !*static_cast(data_ptr)) { + (*static_cast(data_ptr)) = true; configChanged = true; window.updateSettings(settingIndex); } - if (leftButton.wasPressed() && *(bool *)settingsTable[settingSubMenu][settingIndex].dataPtr == true) { - (*(bool *)settingsTable[settingSubMenu][settingIndex].dataPtr) = false; + if (leftButton.wasPressed() && *static_cast(data_ptr)) { + (*static_cast(data_ptr)) = false; configChanged = true; window.updateSettings(settingIndex); } @@ -494,10 +488,10 @@ void Hmi::settings() { } case STRING: { if (okButton.wasPressed()) { - memcpy(keyboardString, (char *)settingsTable[settingSubMenu][settingIndex].dataPtr, kMaxPhraseLen); + memcpy(keyboardString, static_cast(data_ptr), kMaxPhraseLen); keyboardString[kMaxPhraseLen] = '\0'; - window.initKeyboard(keyboardString, settingsTable[settingSubMenu][settingIndex].config.stringLength); + window.initKeyboard(keyboardString, cfg.stringLength); keyboardActive = true; } break; @@ -506,11 +500,11 @@ void Hmi::settings() { if (okButton.wasPressed()) { // If the setting is pointing to the bootloader function, we need to display the bootloader screen // first - if (settingsTable[settingSubMenu][settingIndex].config.fun_ptr == Utils::startBootloader) { + if (cfg.fun_ptr == Utils::startBootloader) { window.Bootloader(); } - if (settingsTable[settingSubMenu][settingIndex].config.fun_ptr != nullptr) { - settingsTable[settingSubMenu][settingIndex].config.fun_ptr(); + if (cfg.fun_ptr != nullptr) { + cfg.fun_ptr(); } } break; @@ -555,9 +549,7 @@ void Hmi::settings() { } void Hmi::update(void *pvParameter) { - Hmi *ref = (Hmi *)pvParameter; - - Utils utils; + auto *ref = static_cast(pvParameter); ref->window.logo(); @@ -580,17 +572,17 @@ void Hmi::update(void *pvParameter) { if (millis() - barUpdate >= 1000) { barUpdate = millis(); - float voltage = analogRead(18) * 0.00059154929; + float voltage = static_cast(analogRead(18)) * 0.00059154929F; if (!ref->isLogging) { - ref->flashFreeMemory = utils.getFlashMemoryUsage(); + ref->flashFreeMemory = Utils::getFlashMemoryUsage(); } if (link2.time.isUpdated()) { setTime(link2.time.hour(), link2.time.minute(), link2.time.second(), 0, 0, 0); - adjustTime(systemConfig.config.timeZoneOffset * 3600); + adjustTime(systemConfig.config.timeZoneOffset * 3600L); timeValid = true; } - ref->window.updateBar(voltage, digitalRead(21), ref->isLogging, link2.location.isValid(), timeValid, - ref->flashFreeMemory); + ref->window.updateBar(voltage, static_cast(digitalRead(21)), ref->isLogging, link2.location.isValid(), + timeValid, ref->flashFreeMemory); } ref->upButton.read(); @@ -601,6 +593,6 @@ void Hmi::update(void *pvParameter) { ref->okButton.read(); ref->backButton.read(); - vTaskDelayUntil(&task_last_tick, (const TickType_t)1000 / 50); + vTaskDelayUntil(&task_last_tick, static_cast(1000) / 50); } } diff --git a/ground_station/src/hmi/hmi.hpp b/ground_station/src/hmi/hmi.hpp index 623433bb..3f60eeb4 100644 --- a/ground_station/src/hmi/hmi.hpp +++ b/ground_station/src/hmi/hmi.hpp @@ -7,7 +7,7 @@ class Hmi { public: - Hmi(const char* dir) + explicit Hmi(const char* dir) : recorder(dir), upButton(3), downButton(4), @@ -50,7 +50,7 @@ class Hmi { TestingState testingState = DISCLAIMER; uint32_t startTestingTime = 0; - uint32_t testingIndex = 0; + int16_t testingIndex = 0; CalibrationState calibrationState = IDLE; @@ -58,8 +58,8 @@ class Hmi { uint16_t oldTimeStamp = 0; - uint32_t settingSubMenu = 0; - int32_t settingIndex = -1; + int16_t settingSubMenu = 0; + int16_t settingIndex = -1; char keyboardString[kMaxPhraseLen + 1] = {}; static void update(void* pvParameter); @@ -98,7 +98,7 @@ class Hmi { Window window; - uint32_t menuIndex = 0; + int16_t menuIndex = 0; uint32_t flashFreeMemory = 100; diff --git a/ground_station/src/hmi/settings.hpp b/ground_station/src/hmi/settings.hpp index b7c039de..6dad9a28 100644 --- a/ground_station/src/hmi/settings.hpp +++ b/ground_station/src/hmi/settings.hpp @@ -3,28 +3,29 @@ #include "config.hpp" #include "utils.hpp" +// NOLINTNEXTLINE(cppcoreguidelines-macro-usage) #define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0])) -typedef enum { +enum settings_type_e { STRING = 0, TOGGLE = 1, NUMBER = 2, BUTTON = 3, -} settings_type_e; +}; -typedef struct { +struct settings_min_max_t { int16_t min; int16_t max; -} settings_min_max_t; +}; -typedef union { +union settings_limits_u { uint32_t stringLength; uint32_t lookup; settings_min_max_t minmax; - void (*fun_ptr)(void); -} settings_limits_u; + void (*fun_ptr)(); +}; -typedef struct { +struct device_settings_t { const char* name; const char* description1; const char* description2; @@ -32,14 +33,13 @@ typedef struct { settings_limits_u config; void* dataPtr; +}; -} device_settings_t; - -typedef enum { +enum lookup_table_index_e { TABLE_MODE = 0, TABLE_UNIT, TABLE_LOGGING, -} lookup_table_index_e; +}; const char* const mode_map[2] = { "SINGLE", @@ -56,11 +56,12 @@ const char* const logging_map[2] = { "NEVER", }; -typedef struct { +struct lookup_table_entry_t { const char* const* values; const uint8_t value_count; -} lookup_table_entry_t; +}; +// NOLINTNEXTLINE(cppcoreguidelines-macro-usage) #define LOOKUP_TABLE_ENTRY(name) \ { name, ARRAYLEN(name) } @@ -76,6 +77,7 @@ enum { const char* const settingPageName[kSettingPages] = {"General", "Telemetry"}; +// NOLINTNEXTLINE(cppcoreguidelines-interfaces-global-init) const device_settings_t settingsTable[][4] = { { {"Time Zone", diff --git a/ground_station/src/hmi/window.cpp b/ground_station/src/hmi/window.cpp index 48d3b778..af9e531b 100644 --- a/ground_station/src/hmi/window.cpp +++ b/ground_station/src/hmi/window.cpp @@ -1,11 +1,19 @@ #include "window.hpp" +#include "bmp.hpp" + #include #include #include #include #include #include -#include "bmp.hpp" + +uint16_t GetNegativeColor(uint16_t color) { + if (color == BLACK) { + return WHITE; + } + return BLACK; +} void Window::begin() { display.begin(); @@ -24,27 +32,31 @@ void Window::Bootloader() { display.refresh(); } -void Window::drawCentreString(const char *buf, int x, int y) { - int16_t x1, y1; - uint16_t w, h; +void Window::drawCentreString(const char *buf, int16_t x, int16_t y) { + int16_t x1 = 0; + int16_t y1 = 0; + uint16_t w = 0; + uint16_t h = 0; display.getTextBounds(buf, 0, y, &x1, &y1, &w, &h); // calc width of new // string - display.setCursor(x - w / 2, y); + display.setCursor(static_cast(x - w / 2), static_cast(y)); display.print(buf); } -void Window::drawCentreString(String &buf, int x, int y) { - int16_t x1, y1; - uint16_t w, h; +void Window::drawCentreString(String &buf, int16_t x, int16_t y) { + int16_t x1 = 0; + int16_t y1 = 0; + uint16_t w = 0; + uint16_t h = 0; display.getTextBounds(buf, 0, y, &x1, &y1, &w, &h); // calc width of new // string - display.setCursor(x - w / 2, y); + display.setCursor(static_cast(x - w / 2), static_cast(y)); display.print(buf); } void Window::initBar() { // Memory - display.setFont(NULL); + display.setFont(nullptr); display.drawBitmap(5, 1, bar_memory, 16, 16, BLACK); display.setTextColor(BLACK); display.setTextSize(2); @@ -62,8 +74,7 @@ void Window::updateBar(float batteryVoltage, bool usb, bool logging, bool locati static bool oldUsbStatus = false; static bool oldLoggingStatus = false; static int32_t oldFreeMemory = 0; - - static uint32_t blinkStatus = 0; + static bool blinkStatus = false; // Logging if (logging != oldLoggingStatus) { @@ -81,7 +92,7 @@ void Window::updateBar(float batteryVoltage, bool usb, bool logging, bool locati // Memory Usage if (free_memory != oldFreeMemory) { - display.setFont(NULL); + display.setFont(nullptr); display.setTextSize(2); display.setTextColor(WHITE); @@ -97,13 +108,15 @@ void Window::updateBar(float batteryVoltage, bool usb, bool logging, bool locati } if ((minute() != oldMinute || hour() != oldHour) && time) { - display.setFont(NULL); + display.setFont(nullptr); display.setTextSize(2); display.setTextColor(WHITE); String t = String(oldHour) + ":"; - if (oldMinute < 10) t += '0'; + if (oldMinute < 10) { + t += '0'; + } t += String(oldMinute); drawCentreString(t, 200, 2); @@ -113,7 +126,9 @@ void Window::updateBar(float batteryVoltage, bool usb, bool logging, bool locati display.setTextColor(BLACK); t = String(oldHour) + ":"; - if (oldMinute < 10) t += '0'; + if (oldMinute < 10) { + t += '0'; + } t += String(oldMinute); drawCentreString(t, 200, 2); @@ -127,26 +142,26 @@ void Window::updateBar(float batteryVoltage, bool usb, bool logging, bool locati display.fillRect(380, 5, 6, 8, WHITE); display.fillRect(387, 5, 6, 8, WHITE); - display.drawBitmap(376, 1, bar_flash, 16, 16, !usb); + display.drawBitmap(376, 1, bar_flash, 16, 16, static_cast(!usb)); } // Battery - if (batteryVoltage && !usb) { - if (batteryVoltage > 3.3f) { + if (batteryVoltage != 0.0F && !usb) { + if (batteryVoltage > 3.3F) { display.fillRect(373, 5, 6, 8, BLACK); display.drawRoundRect(371, 3, 24, 12, 2, BLACK); display.fillRect(395, 5, 3, 8, BLACK); } else { display.fillRect(373, 5, 6, 8, WHITE); - display.drawRoundRect(371, 3, 24, 12, 2, blinkStatus); - display.fillRect(395, 5, 3, 8, blinkStatus); + display.drawRoundRect(371, 3, 24, 12, 2, static_cast(blinkStatus)); + display.fillRect(395, 5, 3, 8, static_cast(blinkStatus)); } - if (batteryVoltage > 3.6f) { + if (batteryVoltage > 3.6F) { display.fillRect(380, 5, 6, 8, BLACK); } else { display.fillRect(380, 5, 6, 8, WHITE); } - if (batteryVoltage > 3.9f) { + if (batteryVoltage > 3.9F) { display.fillRect(387, 5, 6, 8, BLACK); } else { display.fillRect(387, 5, 6, 8, WHITE); @@ -158,7 +173,7 @@ void Window::updateBar(float batteryVoltage, bool usb, bool logging, bool locati display.refresh(); } -void Window::initMenu(uint32_t index) { +void Window::initMenu(int16_t index) { clearMainScreen(); display.setFont(&FreeSans9pt7b); @@ -195,18 +210,18 @@ void Window::initMenu(uint32_t index) { display.refresh(); } -void Window::updateMenu(uint32_t index) { - static int oldHighlight = 0; +void Window::updateMenu(int16_t index) { + static int16_t oldHighlight = 0; - /* Pait over last selcted with white */ + /* Paint over last selcted with white */ - int xPos = (oldHighlight % 3) * 125 + 36; - int yPos = (oldHighlight / 3) * 105 + 31; + auto xPos = static_cast((oldHighlight % 3) * 125 + 36); + auto yPos = static_cast((oldHighlight / 3) * 105 + 31); display.drawRoundRect(xPos, yPos, 78, 78, 9, WHITE); - xPos = (index % 3) * 125 + 36; - yPos = (index / 3) * 105 + 31; + xPos = static_cast((index % 3) * 125 + 36); + yPos = static_cast((index / 3) * 105 + 31); display.drawRoundRect(xPos, yPos, 78, 78, 9, BLACK); display.refresh(); @@ -255,12 +270,14 @@ void Window::initLive() { display.print("Disconnected"); display.setTextColor(BLACK); - display.setFont(NULL); + display.setFont(nullptr); display.refresh(); } -void Window::updateLive(TelemetryInfo *info, uint32_t index) { - if (index > 1) return; +void Window::updateLive(TelemetryInfo *info, int16_t index) { + if (index > 1) { + return; + } // clear update flag info->clear(); @@ -272,8 +289,10 @@ void Window::updateLive(TelemetryInfo *info, uint32_t index) { updateLiveInfo(&infoData[index], index, WHITE); } -void Window::updateLive(TelemetryData *data, TelemetryInfo *info, uint32_t index) { - if (index > 1) return; +void Window::updateLive(TelemetryData *data, TelemetryInfo *info, int16_t index) { + if (index > 1) { + return; + } lastTeleData[index] = millis(); @@ -295,8 +314,10 @@ void Window::updateLive(TelemetryData *data, TelemetryInfo *info, uint32_t index updateLiveInfo(&infoData[index], index, WHITE); } -void Window::updateLive(TelemetryData *data, uint32_t index) { - if (index > 1) return; +void Window::updateLive(TelemetryData *data, int16_t index) { + if (index > 1) { + return; + } lastTeleData[index] = millis(); @@ -319,79 +340,79 @@ const char *const stateName[] = {"INVALID", "CALIB", "READY", "THRUST", "COAST", const char *const errorName[] = {"No Config", "Log Full", "Filter Error", "Overheating", "Continuity Error", "Calibration Error"}; -void Window::updateLiveData(TelemetryData *data, uint32_t index, uint32_t color) { - int xOffset = index * 200; +void Window::updateLiveData(TelemetryData *data, int16_t index, uint16_t color) { + const auto xOffset = static_cast(index * 200); display.setFont(&FreeSans12pt7b); display.setTextSize(1); display.setTextColor(color); if (data->testingMode()) { - drawCentreString("TESTING", xOffset + 100, 42); - display.fillRect(xOffset + 1, 50, 198, 151, WHITE); - display.setCursor(xOffset + 20, 80); + drawCentreString("TESTING", static_cast(xOffset + 100), 42); + display.fillRect(static_cast(xOffset + 1), 50, 198, 151, WHITE); + display.setCursor(static_cast(xOffset + 20), 80); display.print("DO NOT FLY!"); return; - } else { - drawCentreString(stateName[data->state()], xOffset + 100, 42); } - display.setCursor(xOffset + 35, 70); + drawCentreString(stateName[data->state()], static_cast(xOffset + 100), 42); + + display.setCursor(static_cast(xOffset + 35), 70); display.print(data->altitude()); display.print(" m"); - display.setCursor(xOffset + 35, 95); + display.setCursor(static_cast(xOffset + 35), 95); display.print(data->velocity()); display.print(" m/s"); - display.setCursor(xOffset + 35, 120); + display.setCursor(static_cast(xOffset + 35), 120); display.print(data->lat(), 4); display.print(" N"); - display.setCursor(xOffset + 35, 145); + display.setCursor(static_cast(xOffset + 35), 145); display.print(data->lon(), 4); display.print(" E"); - display.setCursor(xOffset + 35, 170); + display.setCursor(static_cast(xOffset + 35), 170); display.print(data->voltage()); display.print(" V"); - if (data->pyroContinuity() & 0x01) { - display.drawBitmap(xOffset + 142, 156, live_checkmark, 16, 16, color); + if (static_cast(data->pyroContinuity() & 0x01U)) { + display.drawBitmap(static_cast(xOffset + 142), 156, live_checkmark, 16, 16, color); } else { - display.drawBitmap(xOffset + 142, 156, live_cross, 16, 16, color); + display.drawBitmap(static_cast(xOffset + 142), 156, live_cross, 16, 16, color); } - if (data->pyroContinuity() & 0x02) { - display.drawBitmap(xOffset + 180, 156, live_checkmark, 16, 16, color); + if (static_cast(data->pyroContinuity() & 0x02U)) { + display.drawBitmap(static_cast(xOffset + 180), 156, live_checkmark, 16, 16, color); } else { - display.drawBitmap(xOffset + 180, 156, live_cross, 16, 16, color); + display.drawBitmap(static_cast(xOffset + 180), 156, live_cross, 16, 16, color); } display.setFont(&FreeSans9pt7b); - display.setCursor(xOffset + 35, 192); + display.setCursor(static_cast(xOffset + 35), 192); - if (data->errors() & 0x04) { + if (static_cast(data->errors() & 0x04U)) { display.print(errorName[2]); - } else if (data->errors() & 0x20) { + } else if (static_cast(data->errors() & 0x20U)) { display.print(errorName[5]); - } else if (data->errors() & 0x10) { + } else if (static_cast(data->errors() & 0x10U)) { display.print(errorName[4]); - } else if (data->errors() & 0x02) { + } else if (static_cast(data->errors() & 0x02U)) { display.print(errorName[1]); - } else if (data->errors() & 0x01) { + } else if (static_cast(data->errors() & 0x01U)) { display.print(errorName[0]); - } else if (data->errors() & 0x08) { + } else if (static_cast(data->errors() & 0x08U)) { display.print(errorName[3]); } display.setFont(&FreeSans9pt7b); display.setTextSize(1); - display.setTextColor(!color); + display.setTextColor(GetNegativeColor(color)); } -void Window::updateLiveInfo(TelemetryInfo *info, uint32_t index, uint32_t color) { - int xOffset = index * 200; +void Window::updateLiveInfo(TelemetryInfo *info, int16_t index, uint16_t color) { + const auto xOffset = static_cast(index * 200); display.setFont(&FreeSans9pt7b); display.setTextSize(1); @@ -400,33 +421,33 @@ void Window::updateLiveInfo(TelemetryInfo *info, uint32_t index, uint32_t color) if (dataAge[index] > 4900) { if (color == WHITE) { connected[index] = false; - display.fillRect(xOffset + 0, 202, 199, 240, BLACK); - display.setCursor(xOffset + 45, 227); + display.fillRect(xOffset, 202, 199, 240, BLACK); + display.setCursor(static_cast(xOffset + 45), 227); display.print("Disconnected"); info->lq(); } } else { - if (connected[index] == false) { + if (!connected[index]) { if (color == WHITE) { - display.fillRect(xOffset + 0, 202, 199, 240, BLACK); + display.fillRect(xOffset, 202, 199, 240, BLACK); connected[index] = true; - display.setCursor(xOffset + 5, 217); + display.setCursor(static_cast(xOffset + 5), 217); display.print("AGE"); - display.setCursor(xOffset + 100, 217); + display.setCursor(static_cast(xOffset + 100), 217); display.print("SNR"); - display.setCursor(xOffset + 5, 237); + display.setCursor(static_cast(xOffset + 5), 237); display.print("LQ"); - display.setCursor(xOffset + 100, 237); + display.setCursor(static_cast(xOffset + 100), 237); display.print("RSSI"); } } - display.setCursor(xOffset + 50, 217); - display.print((float)dataAge[index] / 1000.0f, 1); - display.setCursor(xOffset + 145, 217); + display.setCursor(static_cast(xOffset + 50), 217); + display.print(static_cast(dataAge[index]) / 1000.0F, 1); + display.setCursor(static_cast(xOffset + 145), 217); display.print(info->snr()); - display.setCursor(xOffset + 50, 237); + display.setCursor(static_cast(xOffset + 50), 237); display.print(info->lq()); - display.setCursor(xOffset + 145, 237); + display.setCursor(static_cast(xOffset + 145), 237); display.print(info->rssi()); } } @@ -495,33 +516,37 @@ void Window::updateRecovery(Navigation *navigation) { display.setFont(&FreeSans9pt7b); - float radius = 90; - float correctionFactor = 0.06; + const float radius = 90; + const float correctionFactor = 0.06; - int x = radius * cos(angle - PI_F / 2); - int y = radius * sin(angle - PI_F / 2) + 125; - drawCentreString("N", x + 300, y + correctionFactor * y); + auto x = static_cast(radius * cos(angle - PI_F / 2)); + auto y = static_cast(radius * sin(angle - PI_F / 2) + 125); + drawCentreString("N", static_cast(x + 300), + static_cast(static_cast(y) + correctionFactor * static_cast(y))); - x = radius * cos(angle); - y = radius * sin(angle) + 125; - drawCentreString("E", x + 300, y + correctionFactor * y); + x = static_cast(radius * cos(angle)); + y = static_cast(radius * sin(angle) + 125); + drawCentreString("E", static_cast(x + 300), + static_cast(static_cast(y) + correctionFactor * static_cast(y))); - x = radius * cos(angle + PI_F / 2); - y = radius * sin(angle + PI_F / 2) + 125; - drawCentreString("S", x + 300, y + correctionFactor * y); + x = static_cast(radius * cos(angle + PI_F / 2)); + y = static_cast(radius * sin(angle + PI_F / 2) + 125); + drawCentreString("S", static_cast(x + 300), + static_cast(static_cast(y) + correctionFactor * static_cast(y))); - x = radius * cos(angle + PI_F); - y = radius * sin(angle + PI_F) + 125; - drawCentreString("W", x + 300, y + correctionFactor * y); + x = static_cast(radius * cos(angle + PI_F)); + y = static_cast(radius * sin(angle + PI_F) + 125); + drawCentreString("W", static_cast(x + 300), + static_cast(static_cast(y) + correctionFactor * static_cast(y))); angle = navigation->getAzimuth() + angle - PI_F / 2; - x = 70 * cos(angle) + 300; - y = 70 * sin(angle) + 125; - int x1 = 30 * cos(angle + 0.2F) + 300; - int y1 = 30 * sin(angle + 0.2F) + 125; - int x2 = 30 * cos(angle - 0.2F) + 300; - int y2 = 30 * sin(angle - 0.2F) + 125; + x = static_cast(70 * cos(angle) + 300); + y = static_cast(70 * sin(angle) + 125); + const auto x1 = static_cast(30 * cos(angle + 0.2F) + 300); + const auto y1 = static_cast(30 * sin(angle + 0.2F) + 125); + const auto x2 = static_cast(30 * cos(angle - 0.2F) + 300); + const auto y2 = static_cast(30 * sin(angle - 0.2F) + 125); display.drawCircle(300, 125, 80, BLACK); @@ -555,7 +580,7 @@ void Window::initBox(const char *text) { display.refresh(); } -void Window::initTestingBox(uint32_t index) { +void Window::initTestingBox(int16_t index [[maybe_unused]]) { display.fillRect(60, 60, 280, 120, WHITE); display.drawRect(60, 60, 280, 120, BLACK); @@ -745,10 +770,10 @@ void Window::initTestingReady() { drawCentreString(eventName[7], 300, 201); } -void Window::updateTesting(uint32_t index) { - static uint32_t oldIndex = 0; - uint32_t xOffset = 201 * (oldIndex / 4); - uint32_t yOffset = 50 * (oldIndex % 4) + 20; +void Window::updateTesting(int16_t index) { + static int16_t oldIndex = 0; + auto xOffset = static_cast(201 * (oldIndex / 4)); + auto yOffset = static_cast(50 * (oldIndex % 4) + 20); display.fillRect(xOffset, yOffset, 199, 48, WHITE); @@ -756,19 +781,19 @@ void Window::updateTesting(uint32_t index) { display.setFont(&FreeSans12pt7b); display.setTextColor(BLACK); - xOffset = 200 * (oldIndex / 4) + 100; - yOffset = 50 * (oldIndex % 4) + 51; + xOffset = static_cast(200 * (oldIndex / 4) + 100); + yOffset = static_cast(50 * (oldIndex % 4) + 51); drawCentreString(eventName[oldIndex], xOffset, yOffset); - xOffset = 201 * (index / 4); - yOffset = 50 * (index % 4) + 20; + xOffset = static_cast(201 * (index / 4)); + yOffset = static_cast(50 * (index % 4) + 20); display.fillRect(xOffset, yOffset, 199, 48, BLACK); display.setTextColor(WHITE); - xOffset = 200 * (index / 4) + 100; - yOffset = 50 * (index % 4) + 51; + xOffset = static_cast(200 * (index / 4) + 100); + yOffset = static_cast(50 * (index % 4) + 51); drawCentreString(eventName[index], xOffset, yOffset); oldIndex = index; @@ -820,10 +845,10 @@ void Window::initSensors() { } void Window::updateSensors(Navigation *navigation) { - int xinitOffset = 10; - int xOffset = 30; - int yinitOffset = 90; - int yOffset = 30; + int16_t xinitOffset = 10; + int16_t xOffset = 30; + int16_t yinitOffset = 90; + const int16_t yOffset = 30; display.setFont(&FreeSans9pt7b); display.setTextSize(1); @@ -831,27 +856,27 @@ void Window::updateSensors(Navigation *navigation) { display.fillRect(20, 75, 75, 80, WHITE); - /* Ax, Ay, Az*/ + /* Ax, Ay, Az */ display.setCursor(xinitOffset, yinitOffset); display.print("Ax: "); - display.setCursor(xinitOffset + xOffset, yinitOffset); - display.print((float)navigation->getAX(), 2); + display.setCursor(static_cast(xinitOffset + xOffset), yinitOffset); + display.print(navigation->getAX(), 2); - display.setCursor(xinitOffset, yinitOffset + yOffset); + display.setCursor(xinitOffset, static_cast(yinitOffset + yOffset)); display.print("Ay: "); - display.setCursor(xinitOffset + xOffset, yinitOffset + yOffset); - display.print((float)navigation->getAY(), 2); + display.setCursor(static_cast(xinitOffset + xOffset), static_cast(yinitOffset + yOffset)); + display.print(navigation->getAY(), 2); - display.setCursor(xinitOffset, yinitOffset + 2 * yOffset); + display.setCursor(xinitOffset, static_cast(yinitOffset + 2 * yOffset)); display.print("Az: "); - display.setCursor(xinitOffset + xOffset, yinitOffset + 2 * yOffset); - display.print((float)navigation->getAZ(), 2); + display.setCursor(static_cast(xinitOffset + xOffset), static_cast(yinitOffset + 2 * yOffset)); + display.print(navigation->getAZ(), 2); - /* Gx, Gy, Gz*/ + /* Gx, Gy, Gz */ xinitOffset = 110; @@ -860,20 +885,20 @@ void Window::updateSensors(Navigation *navigation) { display.setCursor(xinitOffset, yinitOffset); display.print("Gx: "); - display.setCursor(xinitOffset + xOffset, yinitOffset); - display.print((float)navigation->getGX(), 2); + display.setCursor(static_cast(xinitOffset + xOffset), yinitOffset); + display.print(navigation->getGX(), 2); - display.setCursor(xinitOffset, yinitOffset + yOffset); + display.setCursor(xinitOffset, static_cast(yinitOffset + yOffset)); display.print("Gy: "); - display.setCursor(xinitOffset + xOffset, yinitOffset + yOffset); - display.print((float)navigation->getGY(), 2); + display.setCursor(static_cast(xinitOffset + xOffset), static_cast(yinitOffset + yOffset)); + display.print(navigation->getGY(), 2); - display.setCursor(xinitOffset, yinitOffset + 2 * yOffset); + display.setCursor(xinitOffset, static_cast(yinitOffset + 2 * yOffset)); display.print("Gz: "); - display.setCursor(xinitOffset + xOffset, yinitOffset + 2 * yOffset); - display.print((float)navigation->getGZ(), 2); + display.setCursor(static_cast(xinitOffset + xOffset), static_cast(yinitOffset + 2 * yOffset)); + display.print(navigation->getGZ(), 2); /* GNSS */ @@ -887,19 +912,19 @@ void Window::updateSensors(Navigation *navigation) { display.setCursor(xinitOffset, yinitOffset); display.print("Lon: "); - display.setCursor(xinitOffset + xOffset, yinitOffset); - float lon = (float)navigation->getPointA().lon; + display.setCursor(static_cast(xinitOffset + xOffset), yinitOffset); + const float lon = navigation->getPointA().lon; if (lon == 0) { display.print("-"); } else { display.print(lon, 5); } - display.setCursor(xinitOffset, yinitOffset + yOffset); + display.setCursor(xinitOffset, static_cast(yinitOffset + yOffset)); display.print("Lat: "); - display.setCursor(xinitOffset + xOffset, yinitOffset + yOffset); - float lat = (float)navigation->getPointA().lat; + display.setCursor(static_cast(xinitOffset + xOffset), static_cast(yinitOffset + yOffset)); + const float lat = navigation->getPointA().lat; if (lat == 0) { display.print("-"); } else { @@ -918,22 +943,22 @@ void Window::updateSensors(Navigation *navigation) { display.setCursor(xinitOffset, yinitOffset); display.print("Mx: "); - display.setCursor(xinitOffset + xOffset, yinitOffset); - display.print((float)navigation->getMX() / 1000, 2); + display.setCursor(static_cast(xinitOffset + xOffset), yinitOffset); + display.print(navigation->getMX() / 1000, 2); xinitOffset = 110; display.setCursor(xinitOffset, yinitOffset); display.print("My: "); - display.setCursor(xinitOffset + xOffset, yinitOffset); - display.print((float)navigation->getMY() / 1000, 2); + display.setCursor(static_cast(xinitOffset + xOffset), yinitOffset); + display.print(navigation->getMY() / 1000, 2); - display.setCursor(70, yinitOffset + yOffset); + display.setCursor(70, static_cast(yinitOffset + yOffset)); display.print("Mz: "); - display.setCursor(70 + xOffset, yinitOffset + yOffset); - display.print((float)navigation->getMZ() / 1000, 2); + display.setCursor(static_cast(70 + xOffset), static_cast(yinitOffset + yOffset)); + display.print(navigation->getMZ() / 1000, 2); } void Window::initSensorPrepareCalibrate() { @@ -997,7 +1022,7 @@ void Window::initSensorCalibrateDone() { display.refresh(); } -void Window::initSettings(uint32_t submenu) { +void Window::initSettings(int16_t submenu) { clearMainScreen(); display.drawLine(0, 49, 400, 49, BLACK); @@ -1027,8 +1052,8 @@ void Window::initSettings(uint32_t submenu) { display.refresh(); } -void Window::addSettingEntry(uint32_t settingIndex, const device_settings_t *setting, bool color) { - uint32_t y = 75 + 30 * settingIndex; +void Window::addSettingEntry(uint32_t settingIndex, const device_settings_t *setting, uint16_t color) { + auto y = static_cast(75 + 30 * settingIndex); display.setTextColor(color); @@ -1036,40 +1061,46 @@ void Window::addSettingEntry(uint32_t settingIndex, const device_settings_t *set display.print(setting->name); if (setting->type == TOGGLE) { - bool data = *(bool *)setting->dataPtr; + const auto data = *static_cast(setting->dataPtr); drawCentreString(lookup_tables[setting->config.lookup].values[static_cast(data)], 305, y); y -= 23; - if (data == false) { - display.fillTriangle(386, y + 14, 378, y + 6, 378, y + 22, color); + if (!data) { + display.fillTriangle(386, static_cast(y + 14), 378, static_cast(y + 6), 378, + static_cast(y + 22), color); } else { - display.fillTriangle(224, y + 14, 232, y + 6, 232, y + 22, color); + display.fillTriangle(224, static_cast(y + 14), 232, static_cast(y + 6), 232, + static_cast(y + 22), color); } } else if (setting->type == STRING) { display.setFont(&FreeMonoBold12pt7b); - drawCentreString((const char *)setting->dataPtr, 285, y); + drawCentreString(static_cast(setting->dataPtr), 285, y); display.setFont(&FreeSans12pt7b); } else if (setting->type == NUMBER) { char buffer[8]; - snprintf(buffer, 8, "%+d", *(int16_t *)setting->dataPtr); + snprintf(buffer, 8, "%+d", *static_cast(setting->dataPtr)); drawCentreString(buffer, 305, y); y -= 23; - if (setting->config.minmax.max == *(int16_t *)setting->dataPtr) { - display.fillTriangle(386, y + 14, 378, y + 6, 378, y + 22, !color); + if (setting->config.minmax.max == *static_cast(setting->dataPtr)) { + display.fillTriangle(386, static_cast(y + 14), 378, static_cast(y + 6), 378, + static_cast(y + 22), GetNegativeColor(color)); } else { - display.fillTriangle(386, y + 14, 378, y + 6, 378, y + 22, color); + display.fillTriangle(386, static_cast(y + 14), 378, static_cast(y + 6), 378, + static_cast(y + 22), color); } - if (setting->config.minmax.min == *(int16_t *)setting->dataPtr) { - display.fillTriangle(224, y + 14, 232, y + 6, 232, y + 22, !color); + if (setting->config.minmax.min == *static_cast(setting->dataPtr)) { + display.fillTriangle(224, static_cast(y + 14), 232, static_cast(y + 6), 232, + static_cast(y + 22), GetNegativeColor(color)); } else { - display.fillTriangle(224, y + 14, 232, y + 6, 232, y + 22, color); + display.fillTriangle(224, static_cast(y + 14), 232, static_cast(y + 6), 232, + static_cast(y + 22), color); } } } -void Window::updateSettings(int32_t index) { +void Window::updateSettings(int16_t index) { display.setTextSize(1); if (oldSettingsIndex >= 0) { @@ -1077,19 +1108,21 @@ void Window::updateSettings(int32_t index) { highlightSetting(oldSettingsIndex, BLACK); } } else { - if (subMenuSettingIndex == 0) + if (subMenuSettingIndex == 0) { display.fillTriangle(386, 33, 378, 25, 378, 41, BLACK); - else + } else { display.fillTriangle(13, 33, 21, 25, 21, 41, BLACK); + } } if (index >= 0) { highlightSetting(index, WHITE); } else { - if (subMenuSettingIndex == 0) + if (subMenuSettingIndex == 0) { display.fillTriangle(386, 33, 378, 25, 378, 41, WHITE); - else + } else { display.fillTriangle(13, 33, 21, 25, 21, 41, WHITE); + } display.fillRect(0, 178, 400, 62, WHITE); } @@ -1097,14 +1130,11 @@ void Window::updateSettings(int32_t index) { display.refresh(); } -void Window::highlightSetting(uint32_t index, bool color) { +void Window::highlightSetting(int16_t index, uint16_t color) { display.setFont(&FreeSans12pt7b); - uint32_t yPos = 52 + 30 * index; - display.fillRect(0, yPos, 400, 30, !color); - if (subMenuSettingIndex == 0) - addSettingEntry(index, &settingsTable[subMenuSettingIndex][index], color); - else - addSettingEntry(index, &settingsTable[subMenuSettingIndex][index], color); + const auto yPos = static_cast(52 + 30 * index); + display.fillRect(0, yPos, 400, 30, GetNegativeColor(color)); + addSettingEntry(index, &settingsTable[subMenuSettingIndex][index], color); display.fillRect(0, 178, 400, 62, WHITE); display.setFont(&FreeSans9pt7b); @@ -1119,7 +1149,7 @@ const uint8_t kNumKeyboardChars = 38; const uint32_t kBackspaceCoordX = 330; const uint32_t kBackspaceCoordY = 62; -const int keybXY[kNumKeyboardChars][2] = { +const int16_t keybXY[kNumKeyboardChars][2] = { {20, 125}, //'1' {60, 125}, //'2' {100, 125}, //'3' @@ -1191,7 +1221,8 @@ void Window::initKeyboard(char *text, uint32_t maxLength) { } if (oldKey != kShiftIdx) { - display.drawBitmap(keybXY[kShiftIdx][0] - 4, keybXY[kShiftIdx][1] - 1, shift_keyboard, 16, 16, BLACK); + display.drawBitmap(static_cast(keybXY[kShiftIdx][0] - 4), static_cast(keybXY[kShiftIdx][1] - 1), + shift_keyboard, 16, 16, BLACK); } if (oldKey != -1) { display.drawBitmap(kBackspaceCoordX, kBackspaceCoordY, backspace_keyboard, 24, 24, BLACK); @@ -1223,7 +1254,7 @@ void Window::updateKeyboard(char *text, int32_t keyHighlight, bool keyPressed) { if (strlen(text) < keyboardTextMaxLength) { updateKeyboardText(text, WHITE); if (keyHighlight > 9 && keyHighlight != kUnderscoreIdx) { - text[strlen(text)] = keybChar[keyHighlight] + !upperCase * 32; + text[strlen(text)] = static_cast(keybChar[keyHighlight] + static_cast(!upperCase) * 32); } else { text[strlen(text)] = keybChar[keyHighlight]; } @@ -1243,26 +1274,27 @@ void Window::updateKeyboard(char *text, int32_t keyHighlight, bool keyPressed) { display.refresh(); } -void Window::highlightKeyboardKey(int32_t key, bool color) { +void Window::highlightKeyboardKey(int32_t key, uint16_t color) { if (key == -1) { display.fillCircle(kBackspaceCoordX + 12, kBackspaceCoordY + 11, 16, color); - display.drawBitmap(kBackspaceCoordX, kBackspaceCoordY, backspace_keyboard, 24, 24, !color); + display.drawBitmap(kBackspaceCoordX, kBackspaceCoordY, backspace_keyboard, 24, 24, GetNegativeColor(color)); } else { - display.fillCircle(keybXY[key][0] + 4, keybXY[key][1] + 7, 16, color); + display.fillCircle(static_cast(keybXY[key][0] + 4), static_cast(keybXY[key][1] + 7), 16, color); } if (key == kShiftIdx) { - display.drawBitmap(keybXY[kShiftIdx][0] - 4, keybXY[kShiftIdx][1] - 1, shift_keyboard, 16, 16, !color); + display.drawBitmap(static_cast(keybXY[kShiftIdx][0] - 4), static_cast(keybXY[kShiftIdx][1] - 1), + shift_keyboard, 16, 16, GetNegativeColor(color)); } else { if (!upperCase && key > 9 && key != kUnderscoreIdx) { - display.drawChar(keybXY[key][0], keybXY[key][1], keybChar[key] + 32, !color, color, 2); + display.drawChar(keybXY[key][0], keybXY[key][1], keybChar[key] + 32, GetNegativeColor(color), color, 2); } else { - display.drawChar(keybXY[key][0], keybXY[key][1], keybChar[key], !color, color, 2); + display.drawChar(keybXY[key][0], keybXY[key][1], keybChar[key], GetNegativeColor(color), color, 2); } } } -void Window::updateKeyboardText(char *text, bool color) { +void Window::updateKeyboardText(char *text, uint16_t color) { display.setFont(&FreeMonoBold12pt7b); display.setTextColor(color); display.setCursor(90, 80); diff --git a/ground_station/src/hmi/window.hpp b/ground_station/src/hmi/window.hpp index 6b29d38e..16ff1cc7 100644 --- a/ground_station/src/hmi/window.hpp +++ b/ground_station/src/hmi/window.hpp @@ -7,20 +7,20 @@ #include "settings.hpp" #include "telemetry/telemetryData.hpp" -#define BLACK 0 -#define WHITE 1 +inline constexpr uint16_t BLACK = 0; +inline constexpr uint16_t WHITE = 1; -#define SHARP_SCK 36 -#define SHARP_MOSI 35 -#define SHARP_SS 34 +inline constexpr uint8_t SHARP_SCK = 36; +inline constexpr uint8_t SHARP_MOSI = 35; +inline constexpr uint8_t SHARP_SS = 34; -typedef struct { +struct topBarData { time_t time; uint32_t storage; bool saving; bool locationLock; bool usbDetection; -} topBarData; +}; class Window { public: @@ -33,13 +33,13 @@ class Window { void updateBar(float batteryVoltage, bool usb = false, bool logging = false, bool location = false, bool time = false, int32_t free_memory = 100); - void initMenu(uint32_t index); - void updateMenu(uint32_t index); + void initMenu(int16_t index); + void updateMenu(int16_t index); void initLive(); - void updateLive(TelemetryInfo *info, uint32_t index); - void updateLive(TelemetryData *data, TelemetryInfo *info, uint32_t index); - void updateLive(TelemetryData *data, uint32_t index); + void updateLive(TelemetryInfo *info, int16_t index); + void updateLive(TelemetryData *data, TelemetryInfo *info, int16_t index); + void updateLive(TelemetryData *data, int16_t index); void initRecovery(); void updateRecovery(Navigation *navigation); @@ -50,8 +50,8 @@ class Window { void initTestingWait(); void initTestingReady(); void initTestingLost(); - void updateTesting(uint32_t index); - void initTestingBox(uint32_t index); + void updateTesting(int16_t index); + void initTestingBox(int16_t index); void initData(); @@ -62,8 +62,8 @@ class Window { void initSensorCalibrateDone(); void updateSensors(Navigation *navigation); - void initSettings(uint32_t submenu); - void updateSettings(int32_t index); + void initSettings(int16_t submenu); + void updateSettings(int16_t index); void initBox(const char *text); @@ -76,34 +76,34 @@ class Window { static constexpr uint8_t kUnderscoreIdx = 37; private: - void updateLiveData(TelemetryData *data, uint32_t index, uint32_t color); - void updateLiveInfo(TelemetryInfo *info, uint32_t index, uint32_t color); - void drawCentreString(const char *buf, int x, int y); - void drawCentreString(String &buf, int x, int y); + void updateLiveData(TelemetryData *data, int16_t index, uint16_t color); + void updateLiveInfo(TelemetryInfo *info, int16_t index, uint16_t color); + void drawCentreString(const char *buf, int16_t x, int16_t y); + void drawCentreString(String &buf, int16_t x, int16_t y); - void addSettingEntry(uint32_t settingIndex, const device_settings_t *setting, bool color = BLACK); - void highlightSetting(uint32_t index, bool color); + void addSettingEntry(uint32_t settingIndex, const device_settings_t *setting, uint16_t color = BLACK); + void highlightSetting(int16_t index, uint16_t color); - void highlightKeyboardKey(int32_t key, bool color); - void updateKeyboardText(char *text, bool color); + void highlightKeyboardKey(int32_t key, uint16_t color); + void updateKeyboardText(char *text, uint16_t color); void clearMainScreen(); Adafruit_SharpMem display; - bool connected[2]; - uint32_t lastTeleData[2]; - uint32_t dataAge[2]; - topBarData barData; - TelemetryData teleData[2]; - TelemetryInfo infoData[2]; + bool connected[2]{}; + uint32_t lastTeleData[2]{}; + uint32_t dataAge[2]{}; + topBarData barData{}; + TelemetryData teleData[2]{}; + TelemetryInfo infoData[2]{}; - int32_t oldSettingsIndex; - uint32_t subMenuSettingIndex; + int16_t oldSettingsIndex{0}; + int16_t subMenuSettingIndex{0}; - bool upperCase = false; - int32_t oldKey = 0; - uint32_t keyboardTextMaxLength = 0; + bool upperCase{false}; + int32_t oldKey{0}; + uint32_t keyboardTextMaxLength{0}; const char *eventName[9] = {"Ready", "Liftoff", "Burnout", "Apogee", "Main", "Touchdown", "Custom 1", "Custom 2"}; }; diff --git a/ground_station/src/logging/recorder.cpp b/ground_station/src/logging/recorder.cpp index 7c54b5f4..2c1130eb 100644 --- a/ground_station/src/logging/recorder.cpp +++ b/ground_station/src/logging/recorder.cpp @@ -21,7 +21,7 @@ bool Recorder::begin() { } while (fatfs.exists(fileName)); queue = xQueueCreate(64, sizeof(RecorderElement)); - xTaskCreate(recordTask, "task_recorder", 4096, this, 1, NULL); + xTaskCreate(recordTask, "task_recorder", 4096, this, 1, nullptr); initialized = true; return initialized; } @@ -40,10 +40,10 @@ void Recorder::createFile() { } void Recorder::recordTask(void *pvParameter) { - Recorder *ref = (Recorder *)pvParameter; + auto *ref = static_cast(pvParameter); char line[128]; uint32_t count = 0; - RecorderElement element; + RecorderElement element{}; while (ref->initialized) { if (xQueueReceive(ref->queue, &element, portMAX_DELAY) == pdPASS) { if (!ref->fileCreated) { @@ -51,8 +51,8 @@ void Recorder::recordTask(void *pvParameter) { } const auto &data = element.data; snprintf(line, 128, "%hu,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d", element.source, data.timestamp, data.state, data.errors, - data.lat, data.lon, data.altitude, data.velocity, data.voltage, (bool)(data.pyro_continuity & 0x01), - (bool)(data.pyro_continuity & 0x02)); + data.lat, data.lon, data.altitude, data.velocity, data.voltage, + static_cast(data.pyro_continuity & 0x01), static_cast(data.pyro_continuity & 0x02)); ref->file.println(line); count++; @@ -62,5 +62,5 @@ void Recorder::recordTask(void *pvParameter) { } } } - vTaskDelete(NULL); + vTaskDelete(nullptr); } diff --git a/ground_station/src/logging/recorder.hpp b/ground_station/src/logging/recorder.hpp index 7b6b324f..7c46b809 100644 --- a/ground_station/src/logging/recorder.hpp +++ b/ground_station/src/logging/recorder.hpp @@ -10,7 +10,7 @@ struct RecorderElement { class Recorder { public: - Recorder(const char* directory) : directory(directory) {} + explicit Recorder(const char* directory) : directory(directory) {} bool begin(); void enable() { enabled = true; } @@ -33,8 +33,8 @@ class Recorder { char fileName[30] = {}; - QueueHandle_t queue; - File file; + QueueHandle_t queue{nullptr}; + File file{}; void createFile(); diff --git a/ground_station/src/main.cpp b/ground_station/src/main.cpp index 8ad79031..24f8955a 100644 --- a/ground_station/src/main.cpp +++ b/ground_station/src/main.cpp @@ -30,7 +30,6 @@ * SOFTWARE. ******************************************************************************/ -#include #include "console.hpp" #include "hmi/hmi.hpp" #include "logging/recorder.hpp" @@ -38,6 +37,9 @@ #include "telemetry/telemetry.hpp" #include "utils.hpp" +#include + +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables,cppcoreguidelines-interfaces-global-init) Utils utils; Hmi hmi("/logs"); @@ -45,6 +47,7 @@ Telemetry link1(Serial, 8, 9); Telemetry link2(Serial1, 11, 12); Navigation navigation; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables,cppcoreguidelines-interfaces-global-init) void setup() { pinMode(21, INPUT); @@ -66,8 +69,8 @@ void setup() { hmi.begin(); } -bool ini = false; void loop() { + static bool ini{false}; if (millis() > 5000 && !ini) { ini = true; if (systemConfig.config.receiverMode == SINGLE) { @@ -92,8 +95,8 @@ void loop() { // In single mode, both antennas track the same rocket if (systemConfig.config.receiverMode == SINGLE) { - bool link1DataValid = (link1.data.lat() != 0) && (link1.data.lon() != 0); - bool link2DataValid = (link2.data.lat() != 0) && (link2.data.lon() != 0); + const bool link1DataValid = (link1.data.lat() != 0) && (link1.data.lon() != 0); + const bool link2DataValid = (link2.data.lat() != 0) && (link2.data.lon() != 0); // Check if data from link 1 is newer than link 2 if (link1.data.getLastUpdateTime() > link2.data.getLastUpdateTime()) { // Take data from link 1 with higher priority diff --git a/ground_station/src/navigation.cpp b/ground_station/src/navigation.cpp index 24d736d6..7324bce7 100644 --- a/ground_station/src/navigation.cpp +++ b/ground_station/src/navigation.cpp @@ -3,29 +3,31 @@ #include "console.hpp" #include "utils.hpp" -#define NAVIGATION_TASK_FREQUENCY 50 +constexpr uint8_t NAVIGATION_TASK_FREQUENCY = 50; bool Navigation::begin() { initialized = true; compass.init(); - if (imu.begin(Wire, 0x6A) != 1) console.error.println("IMU init failed!"); + if (imu.begin(Wire, 0x6A) != 1) { + console.error.println("IMU init failed!"); + } filter.begin(NAVIGATION_TASK_FREQUENCY); calibration = CALIB_CONCLUDED; - xTaskCreate(navigationTask, "task_navigation", 1024, this, 1, NULL); + xTaskCreate(navigationTask, "task_navigation", 1024, this, 1, nullptr); return true; } void Navigation::initFibonacciSphere() { - float golden_angle = PI_F * (3.0F - sqrtf(5.0F)); + const float golden_angle = PI_F * (3.0F - sqrtf(5.0F)); for (uint32_t i = 0; i < n_points; i++) { - float theta = static_cast(i) * golden_angle; - float z = (1.0F - 1.0F / n_points) * (1.0F - 2.0F / (n_points - 1.0F) * static_cast(i)); - float radius = sqrt(1.0F - z * z); + const float theta = static_cast(i) * golden_angle; + const float z = (1.0F - 1.0F / n_points) * (1.0F - 2.0F / (n_points - 1.0F) * static_cast(i)); + const float radius = sqrt(1.0F - z * z); sphere_points[i][0] = radius * cos(theta); sphere_points[i][1] = radius * sin(theta); @@ -33,7 +35,7 @@ void Navigation::initFibonacciSphere() { } } -void Navigation::calibrate(float *val) { +void Navigation::calibrate(const float *val) { /* Dumb Calibration Approach */ /* Hard Iron */ @@ -69,7 +71,7 @@ void Navigation::calibrate(float *val) { avg_scale[i] = (mag_calib_temp.max_vals_scal[i] - mag_calib_temp.min_vals_scal[i]) / 2.0F; } - float avg = (avg_scale[0] + avg_scale[1] + avg_scale[2]) / 3.0F; + const float avg = (avg_scale[0] + avg_scale[1] + avg_scale[2]) / 3.0F; for (uint32_t i = 0; i < 3; i++) { mag_calib_temp.scaling[i] = avg / avg_scale[i]; @@ -96,6 +98,7 @@ void Navigation::check_rotation() { void Navigation::compute_calibration_status() { float counter = 0; + // NOLINTNEXTLINE(modernize-loop-convert) for (uint32_t i = 0; i < n_points; i++) { if (sphere_checked[i]) { ++counter; @@ -125,7 +128,7 @@ void Navigation::get_saved_calib() { mag_calib.scaling[2] = static_cast(systemConfig.config.mag_calib.mag_scale_z) / 1000.0F; } -void Navigation::transform(float *val, float *output) { +void Navigation::transform(const float *val, float *output) { for (uint32_t i = 0; i < 3; i++) { output[i] = (val[i] - mag_calib.offset[i]) * mag_calib.scaling[i]; } @@ -137,13 +140,14 @@ void Navigation::resetCalib() { mag_calib_temp.min_vals[i] = 100; } + // NOLINTNEXTLINE(modernize-loop-convert) for (uint32_t i = 0; i < n_points; i++) { sphere_checked[i] = false; } } void Navigation::navigationTask(void *pvParameter) { - Navigation *ref = (Navigation *)pvParameter; + auto *ref = static_cast(pvParameter); TickType_t task_last_tick = xTaskGetTickCount(); @@ -197,18 +201,18 @@ void Navigation::navigationTask(void *pvParameter) { } count++; - vTaskDelayUntil(&task_last_tick, (const TickType_t)1000 / NAVIGATION_TASK_FREQUENCY); + vTaskDelayUntil(&task_last_tick, static_cast(1000) / NAVIGATION_TASK_FREQUENCY); } - vTaskDelete(NULL); + vTaskDelete(nullptr); } void Navigation::calculateDistanceDirection() { - float dy_dphi = (2 * R * PI_F) / (2 * PI_F); - float dx_dtheta = cos(pointA.lat * (PI_F / 180)) * (2 * R * PI_F) / (2 * PI_F); + const float dy_dphi = (2 * R * PI_F) / (2 * PI_F); + const float dx_dtheta = cos(pointA.lat * (PI_F / 180)) * (2 * R * PI_F) / (2 * PI_F); - float dy = (pointB.lat - pointA.lat) * (PI_F / 180) * dy_dphi; - float dx = (pointB.lon - pointA.lon) * (PI_F / 180) * dx_dtheta; - float dz = pointB.alt - pointA.alt; + const float dy = (pointB.lat - pointA.lat) * (PI_F / 180) * dy_dphi; + const float dx = (pointB.lon - pointA.lon) * (PI_F / 180) * dx_dtheta; + const float dz = pointB.alt - pointA.alt; dist = sqrt(dx * dx + dy * dy + dz * dz); azimuth = atan2(dx, dy); diff --git a/ground_station/src/navigation.hpp b/ground_station/src/navigation.hpp index 229726e8..4976ad33 100644 --- a/ground_station/src/navigation.hpp +++ b/ground_station/src/navigation.hpp @@ -1,41 +1,32 @@ #pragma once +#include "console.hpp" +#include "utils.hpp" + #include #include #include #include -#include -#include "console.hpp" -#include "utils.hpp" -const float R = 6378100.0F; // Earth radius in m (zero tide radius IAU) -const float C = 40075017.0F; // Earth circumference in m +#include + +constexpr float R = 6378100.0F; // Earth radius in m (zero tide radius IAU) +constexpr float C = 40075017.0F; // Earth circumference in m class EarthPoint3D { public: - // Point3D() : x(0), y(0), z(0) { } - // Point3D(float x, float y) : x(x), y(y), z(0) { } - EarthPoint3D(float lat = 0, float lon = 0, float alt = 0) : lat(lat), lon(lon), alt(alt) {} - - EarthPoint3D operator=(EarthPoint3D const &other) { - // Guard self assignment - if (this == &other) return *this; - lat = other.lat; - lon = other.lon; - alt = other.alt; - return *this; - } + explicit EarthPoint3D(float lat = 0, float lon = 0, float alt = 0) : lat(lat), lon(lon), alt(alt) {} EarthPoint3D deg() { return *this; } - EarthPoint3D rad() { + EarthPoint3D rad() const { EarthPoint3D res; res.lat = lat * (PI_F / 180); res.lon = lon * (PI_F / 180); return res; } - void print() { + void print() const { console.log.print("Lat:"); console.log.println(lat); console.log.print("Lon:"); @@ -47,8 +38,6 @@ class EarthPoint3D { float lat; float lon; float alt; - - private: }; class Navigation { @@ -128,7 +117,7 @@ class Navigation { enum calibration_state_e { INV_CALIB = 0, CALIB_ONGOING, CALIB_CANCELLED, CALIB_CONCLUDED }; - void set_saved_calib(mag_calibration_t mag_calib); + static void set_saved_calib(mag_calibration_t mag_calib); void get_saved_calib(); @@ -171,14 +160,14 @@ class Navigation { float elevation = 0; mag_calibration_t mag_calib_temp = {.offset = {0, 0, 0}, - .scaling = {1.0f, 1.0f, 1.0f}, + .scaling = {1.0F, 1.0F, 1.0F}, .max_vals = {-100, -100, -100}, .min_vals = {100, 100, 100}, .max_vals_scal = {-100, -100, -100}, .min_vals_scal = {100, 100, 100}}; mag_calibration_t mag_calib = {.offset = {0, 0, 0}, - .scaling = {1.0f, 1.0f, 1.0f}, + .scaling = {1.0F, 1.0F, 1.0F}, .max_vals = {-100, -100, -100}, .min_vals = {100, 100, 100}, .max_vals_scal = {-100, -100, -100}, @@ -187,8 +176,8 @@ class Navigation { static void navigationTask(void *pvParameter); void calculateDistanceDirection(); void initFibonacciSphere(); - void calibrate(float *val); - void transform(float *val, float *output); + void calibrate(const float *val); + void transform(const float *val, float *output); void check_rotation(); void compute_calibration_status(); diff --git a/ground_station/src/systemParser.cpp b/ground_station/src/systemParser.cpp index bea1f860..2731f6b1 100644 --- a/ground_station/src/systemParser.cpp +++ b/ground_station/src/systemParser.cpp @@ -31,12 +31,15 @@ ******************************************************************************/ #include "systemParser.hpp" + #include "USB.h" #include "config.hpp" #include "console.hpp" #include "utils.hpp" -SystemParser::SystemParser(void) {} +#include + +SystemParser::SystemParser() = default; /** * @brief Load a system configuration file @@ -47,6 +50,7 @@ SystemParser::SystemParser(void) {} */ bool SystemParser::loadFile(const char* path) { filePath = path; + // NOLINTNEXTLINE(cppcoreguidelines-init-variables) something is wrong with this 'File' type File file = fatfs.open(filePath); if (!file) { @@ -65,6 +69,8 @@ bool SystemParser::loadFile(const char* path) { return true; } +// NOLINTBEGIN(readability-convert-member-functions-to-static,readability-simplify-boolean-expr) + bool SystemParser::setNeverStopLoggingFlag(bool flag) { doc["never_stop_logging"] = flag; return true; @@ -81,7 +87,7 @@ bool SystemParser::setTelemetryMode(bool mode) { } bool SystemParser::setLinkPhrase1(const char* phrase) { - if (phrase == NULL) { + if (phrase == nullptr) { return false; } doc["link_phrase_1"] = phrase; @@ -89,7 +95,7 @@ bool SystemParser::setLinkPhrase1(const char* phrase) { } bool SystemParser::setLinkPhrase2(const char* phrase) { - if (phrase == NULL) { + if (phrase == nullptr) { return false; } doc["link_phrase_2"] = phrase; @@ -97,7 +103,7 @@ bool SystemParser::setLinkPhrase2(const char* phrase) { } bool SystemParser::setTestingPhrase(const char* phrase) { - if (phrase == NULL) { + if (phrase == nullptr) { return false; } doc["testing_phrase"] = phrase; @@ -178,6 +184,8 @@ bool SystemParser::getMagCalib(mag_calib_t& calib) { return false; } +// NOLINTEND(readability-convert-member-functions-to-static,readability-simplify-boolean-expr) + /** * @brief Save the current loaded system config as a file * @@ -187,7 +195,7 @@ bool SystemParser::getMagCalib(mag_calib_t& calib) { */ bool SystemParser::saveFile(const char* path) { console.log.println("[PARSER] Store file"); - if (path != NULL) { + if (path != nullptr) { filePath = path; } if (fatfs.exists(filePath)) { @@ -196,6 +204,7 @@ bool SystemParser::saveFile(const char* path) { return false; } } + // NOLINTNEXTLINE(cppcoreguidelines-init-variables) something is wrong with this 'File' type File file = fatfs.open(filePath, FILE_WRITE); if (!file) { console.error.println("[PARSER] Open file failed"); diff --git a/ground_station/src/systemParser.hpp b/ground_station/src/systemParser.hpp index d4d7a168..d0453b84 100644 --- a/ground_station/src/systemParser.hpp +++ b/ground_station/src/systemParser.hpp @@ -34,20 +34,20 @@ #include -#define MAX_SYSTEM_FILE_SIZE 1 * 1024 +constexpr uint32_t MAX_SYSTEM_FILE_SIZE = 1 * 1024UL; -typedef struct { +struct mag_calib_t { int32_t mag_offset_x; int32_t mag_offset_y; int32_t mag_offset_z; int32_t mag_scale_x; int32_t mag_scale_y; int32_t mag_scale_z; -} mag_calib_t; +}; class SystemParser { public: - SystemParser(void); + SystemParser(); bool loadFile(const char* path); bool setLinkPhrase1(const char* phrase); @@ -66,9 +66,9 @@ class SystemParser { bool getTelemetryMode(bool& mode); bool getMagCalib(mag_calib_t& calib); - bool saveFile(const char* path = NULL); + bool saveFile(const char* path = nullptr); private: StaticJsonDocument doc; - const char* filePath; + const char* filePath{nullptr}; }; diff --git a/ground_station/src/telemetry/crc.cpp b/ground_station/src/telemetry/crc.cpp index 96e77f08..2afc1c0a 100644 --- a/ground_station/src/telemetry/crc.cpp +++ b/ground_station/src/telemetry/crc.cpp @@ -52,16 +52,18 @@ static const uint8_t crc8_tab[] = { uint32_t crc32(const uint8_t *buf, size_t size) { const uint8_t *p = buf; - uint32_t crc; - - crc = ~0U; - while (size--) crc = crc32_tab[(crc ^ *p++) & 0xFF] ^ (crc >> 8); + uint32_t crc{~0U}; + while (size-- > 0) { + crc = crc32_tab[(crc ^ *p++) & 0xFFU] ^ (crc >> 8U); + } return crc ^ ~0U; } uint8_t crc8(const uint8_t *buf, size_t size) { uint8_t crc = 0; - for (int i = 0; i < size; i++) crc = crc8_tab[crc ^ *buf++]; + for (int i = 0; i < size; i++) { + crc = crc8_tab[crc ^ *buf++]; + } return crc; } diff --git a/ground_station/src/telemetry/parser.cpp b/ground_station/src/telemetry/parser.cpp index fbec57e9..e11c2669 100644 --- a/ground_station/src/telemetry/parser.cpp +++ b/ground_station/src/telemetry/parser.cpp @@ -13,7 +13,9 @@ void Parser::parse() { int32_t Parser::getOpCodeIndex(uint8_t opCode) { for (int32_t i = 0; i < CMD_NUMBER; i++) { - if (opCode == cmdIndex[i]) return i; + if (opCode == cmdIndex[i]) { + return i; + } } return -1; } @@ -47,7 +49,7 @@ void Parser::process(uint8_t ch) { } break; case STATE_CRC: { - uint8_t crc = crc8(buffer, dataIndex + 2); + const uint8_t crc = crc8(buffer, dataIndex + 2); if (crc == ch) { parse(); } else { @@ -65,15 +67,18 @@ void Parser::cmdRX(uint8_t *args, uint32_t length) { data->commit(args, length); void Parser::cmdInfo(uint8_t *args, uint32_t length) { info->commit(args, length); } void Parser::cmdGNSSLoc(uint8_t *args, uint32_t length) { - if (location != NULL) { + if (location != nullptr) { location->commit(args, length); } } void Parser::cmdGNSSTime(uint8_t *args, uint32_t length) { - if (time != NULL) { + if (time != nullptr) { time->commit(args, length); } } -void Parser::cmdGNSSInfo(uint8_t *args, uint32_t length) { console.log.println("GNSS Info Received"); } +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) function ptr doesn't work if it's static +void Parser::cmdGNSSInfo(uint8_t *args [[maybe_unused]], uint32_t length [[maybe_unused]]) { + console.log.println("GNSS Info Received"); +} diff --git a/ground_station/src/telemetry/parser.hpp b/ground_station/src/telemetry/parser.hpp index dd2df1f0..fbcd3700 100644 --- a/ground_station/src/telemetry/parser.hpp +++ b/ground_station/src/telemetry/parser.hpp @@ -18,21 +18,20 @@ #pragma once -#include -#include #include "telemetryData.hpp" #include "telemetry_reg.hpp" -typedef struct { +#include +#include +#include + +struct link_info_t { uint8_t rssi; uint8_t lq; int8_t snr; -} link_info_t; - -#define MAX_CMD_BUFFER 20 +}; -#define CMD_DEF(identifier, cmd) \ - { identifier, cmd } +inline constexpr uint8_t MAX_CMD_BUFFER = 20; /* The parser is not interrupt safe! */ @@ -42,7 +41,7 @@ class Parser { void parse(); - void init(TelemetryData* d, TelemetryInfo* i, TelemetryLocation* l = NULL, TelemetryTime* t = NULL) { + void init(TelemetryData* d, TelemetryInfo* i, TelemetryLocation* l = nullptr, TelemetryTime* t = nullptr) { data = d; info = i; location = l; @@ -63,26 +62,26 @@ class Parser { void cmdGNSSInfo(uint8_t* args, uint32_t length); private: - int32_t getOpCodeIndex(uint8_t opCode); + static int32_t getOpCodeIndex(uint8_t opCode); - TelemetryData* data; - TelemetryInfo* info; - TelemetryLocation* location; - TelemetryTime* time; + TelemetryData* data{nullptr}; + TelemetryInfo* info{nullptr}; + TelemetryLocation* location{nullptr}; + TelemetryTime* time{nullptr}; - uint8_t buffer[MAX_CMD_BUFFER]; + uint8_t buffer[MAX_CMD_BUFFER]{}; uint32_t dataIndex = 0; int32_t opCodeIndex = -1; - link_info_t linkInfo; + link_info_t linkInfo{}; - typedef enum { + enum state_e { STATE_OP, STATE_LEN, STATE_DATA, STATE_CRC, - } state_e; + }; enum { INDEX_OP = 0, @@ -96,7 +95,7 @@ enum { CMD_NUMBER = 5, }; -typedef void (Parser::*cmd_fn)(uint8_t* args, uint32_t length); +using cmd_fn = void (Parser::*)(uint8_t* args, uint32_t length); const cmd_fn commandFunction[] = {&Parser::cmdRX, &Parser::cmdInfo, &Parser::cmdGNSSLoc, &Parser::cmdGNSSTime, &Parser::cmdGNSSInfo}; diff --git a/ground_station/src/telemetry/telemetry.cpp b/ground_station/src/telemetry/telemetry.cpp index 05dbeeff..b7638f2c 100644 --- a/ground_station/src/telemetry/telemetry.cpp +++ b/ground_station/src/telemetry/telemetry.cpp @@ -3,14 +3,14 @@ #include "console.hpp" #include "crc.hpp" -#define TASK_TELE_FREQ 100 +constexpr uint8_t TASK_TELE_FREQ = 100; void Telemetry::begin() { serial.begin(115200, SERIAL_8N1, rxPin, txPin); parser.init(&data, &info, &location, &time); initialized = true; - xTaskCreate(update, "task_telemetry", 2048, this, 1, NULL); + xTaskCreate(update, "task_telemetry", 2048, this, 1, nullptr); } void Telemetry::setLinkPhrase(const char* phrase, uint32_t length) { @@ -19,7 +19,7 @@ void Telemetry::setLinkPhrase(const char* phrase, uint32_t length) { newSetting = true; } -void Telemetry::setLinkPhrase(String phrase) { setLinkPhrase(phrase.c_str(), phrase.length()); } +void Telemetry::setLinkPhrase(const String& phrase) { setLinkPhrase(phrase.c_str(), phrase.length()); } void Telemetry::setTestingPhrase(const char* phrase, uint32_t length) { memset(testingPhrase, 0, kMaxPhraseLen + 1); @@ -27,7 +27,7 @@ void Telemetry::setTestingPhrase(const char* phrase, uint32_t length) { newSetting = true; } -void Telemetry::setTestingPhrase(String phrase) { setTestingPhrase(phrase.c_str(), phrase.length()); } +void Telemetry::setTestingPhrase(const String& phrase) { setTestingPhrase(phrase.c_str(), phrase.length()); } void Telemetry::setDirection(transmission_direction_e dir) { if (dir != transmissionDirection) { @@ -59,7 +59,8 @@ void Telemetry::initLink() { vTaskDelay(100); if (linkPhrase[0] != 0) { - uint32_t phraseCrc = crc32(linkPhrase, strlen((const char*)linkPhrase)); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) uint8 to char is OK + const uint32_t phraseCrc = crc32(linkPhrase, strlen(reinterpret_cast(linkPhrase))); console.error.printf("[TELEMETRY] Sending link phrase: %s (CRC: %lu)\n", linkPhrase, phraseCrc); sendLinkPhraseCrc(phraseCrc, 4); vTaskDelay(100); @@ -68,7 +69,7 @@ void Telemetry::initLink() { } if (testingPhrase[0] != 0) { - testingCrc = crc32(testingPhrase, strlen((const char*)testingPhrase)); + testingCrc = crc32(testingPhrase, strlen(reinterpret_cast(testingPhrase))); } } @@ -77,7 +78,8 @@ void Telemetry::exitTesting() { testingMsg.passcode = testingCrc; testingMsg.enable_pyros = 0; testingMsg.event = 0; - sendTXPayload((uint8_t*)&testingMsg, 15); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + sendTXPayload(reinterpret_cast(&testingMsg), 15); vTaskDelay(50); setMode(BIDIRECTIONAL); requestExitTesting = true; @@ -88,7 +90,8 @@ void Telemetry::enterTesting() { testingMsg.passcode = testingCrc; testingMsg.enable_pyros = 1; testingMsg.event = 0; - sendTXPayload((uint8_t*)&testingMsg, 15); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + sendTXPayload(reinterpret_cast(&testingMsg), 15); vTaskDelay(50); setMode(BIDIRECTIONAL); } @@ -98,13 +101,14 @@ void Telemetry::triggerEvent(uint8_t event) { testingMsg.passcode = testingCrc; testingMsg.enable_pyros = 1; testingMsg.event = event; - sendTXPayload((uint8_t*)&testingMsg, 15); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + sendTXPayload(reinterpret_cast(&testingMsg), 15); triggerAction = true; triggerActionStart = xTaskGetTickCount(); } void Telemetry::update(void* pvParameter) { - Telemetry* ref = (Telemetry*)pvParameter; + auto* ref = static_cast(pvParameter); while (ref->initialized) { TickType_t task_last_tick = xTaskGetTickCount(); @@ -126,29 +130,32 @@ void Telemetry::update(void* pvParameter) { ref->testingMsg.passcode = ref->testingCrc; ref->testingMsg.enable_pyros = 1; ref->testingMsg.event = 0; - ref->sendTXPayload((uint8_t*)&ref->testingMsg, 15); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + ref->sendTXPayload(reinterpret_cast(&ref->testingMsg), 15); } while (ref->serial.available()) { ref->parser.process(ref->serial.read()); } - vTaskDelayUntil(&task_last_tick, (const TickType_t)1000 / TASK_TELE_FREQ); + vTaskDelayUntil(&task_last_tick, static_cast(1000) / TASK_TELE_FREQ); } } +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) uses serial void Telemetry::sendLinkPhraseCrc(uint32_t crc, uint32_t length) { console.log.println(crc); console.log.println(length); uint8_t out[7]; // 1 OP + 1 LEN + 4 DATA + 1 CRC out[0] = CMD_LINK_PHRASE; - out[1] = (uint8_t)length; + out[1] = static_cast(length); memcpy(&out[2], &crc, length); out[length + 2] = crc8(out, length + 2); serial.write(out, length + 3); } +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) uses serial void Telemetry::sendSetting(uint8_t command, uint8_t value) { uint8_t out[4]; // 1 OP + 1 LEN + 1 DATA + 1 CRC out[0] = command; @@ -159,6 +166,7 @@ void Telemetry::sendSetting(uint8_t command, uint8_t value) { serial.write(out, 4); } +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) uses serial void Telemetry::sendEnable() { uint8_t out[3]; // 1 OP + 1 LEN + 1 DATA + 1 CRC out[0] = CMD_ENABLE; @@ -168,6 +176,7 @@ void Telemetry::sendEnable() { serial.write(out, 3); } +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) uses serial void Telemetry::sendDisable() { uint8_t out[3]; // 1 OP + 1 LEN + 1 DATA + 1 CRC out[0] = CMD_DISBALE; @@ -177,10 +186,11 @@ void Telemetry::sendDisable() { serial.write(out, 3); } +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) uses serial void Telemetry::sendTXPayload(uint8_t* payload, uint32_t length) { uint8_t out[19]; // 1 OP + 1 LEN + 16 DATA + 1 CRC out[0] = CMD_TX; - out[1] = (uint8_t)length; + out[1] = static_cast(length); memcpy(&out[2], payload, length); out[length + 2] = crc8(out, length + 2); diff --git a/ground_station/src/telemetry/telemetry.hpp b/ground_station/src/telemetry/telemetry.hpp index df1c3de2..56965ab2 100644 --- a/ground_station/src/telemetry/telemetry.hpp +++ b/ground_station/src/telemetry/telemetry.hpp @@ -11,16 +11,14 @@ class Telemetry { void begin(); void setLinkPhrase(const char* phrase, uint32_t length); - void setLinkPhrase(String phrase); + void setLinkPhrase(const String& phrase); void setTestingPhrase(const char* phrase, uint32_t length); - void setTestingPhrase(String phrase); + void setTestingPhrase(const String& phrase); void setDirection(transmission_direction_e dir); void setMode(transmission_mode_e mode); - void sendTXPayload(uint8_t* payload, uint32_t length); - void exitTesting(); void enterTesting(); void triggerEvent(uint8_t event); @@ -39,26 +37,29 @@ class Telemetry { } } - TelemetryData data; - TelemetryInfo info; - TelemetryLocation location; - TelemetryTime time; + // NOLINTBEGIN(cppcoreguidelines-non-private-member-variables-in-classes) + TelemetryData data{}; + TelemetryInfo info{}; + TelemetryLocation location{}; + TelemetryTime time{}; + // NOLINTEND(cppcoreguidelines-non-private-member-variables-in-classes) private: + HardwareSerial serial; + void initLink(); + static void update(void* pvParameter); + void sendLinkPhraseCrc(uint32_t crc, uint32_t length); void sendSetting(uint8_t command, uint8_t value); void sendEnable(); void sendDisable(); - - static void update(void* pvParameter); + void sendTXPayload(uint8_t* payload, uint32_t length); volatile bool initialized = false; volatile bool linkInitialized = false; - HardwareSerial serial; - Parser parser; int rxPin; int txPin; @@ -74,12 +75,14 @@ class Telemetry { transmission_direction_e transmissionDirection = RX_DIR; transmission_mode_e transmissionMode = UNIDIRECTIONAL; - struct packed_testing_msg_t { + struct [[gnu::packed]] { uint8_t header; uint32_t passcode; uint8_t event; uint8_t enable_pyros; uint32_t dummy1; uint32_t dummy2; - } __attribute__((packed)) testingMsg; + } testingMsg{}; + + static_assert(sizeof(testingMsg) == 15); }; diff --git a/ground_station/src/telemetry/telemetryData.hpp b/ground_station/src/telemetry/telemetryData.hpp index 49eb0b54..6cc2e50c 100644 --- a/ground_station/src/telemetry/telemetryData.hpp +++ b/ground_station/src/telemetry/telemetryData.hpp @@ -1,9 +1,10 @@ #pragma once -#include #include "console.hpp" -typedef struct { +#include + +struct [[gnu::packed]] packedRXMessage { uint8_t state : 3; uint16_t timestamp : 15; uint8_t errors : 6; @@ -17,7 +18,7 @@ typedef struct { // fill up to 16 bytes uint8_t : 0; // sent uint8_t d1; // dummy -} __attribute__((packed)) packedRXMessage; +}; static_assert(sizeof(packedRXMessage) == 15); @@ -33,7 +34,7 @@ class TelemetryData { void clear() { updated = false; } /// Returns true if the data has been updated since the last call to clear() - bool isUpdated() const { return updated; } + [[nodiscard]] bool isUpdated() const { return updated; } int16_t velocity() { updated = false; @@ -52,15 +53,15 @@ class TelemetryData { float lat() { updated = false; - return (float)rxData.lat / 10000.0f; + return static_cast(rxData.lat) / 10000.0F; } float lon() { updated = false; - return (float)rxData.lon / 10000.0f; + return static_cast(rxData.lon) / 10000.0F; } - int8_t d1() { return rxData.d1; } + [[nodiscard]] uint8_t d1() const { return rxData.d1; } uint16_t state() { updated = false; @@ -74,7 +75,7 @@ class TelemetryData { float voltage() { updated = false; - return static_cast(rxData.voltage / 10.0F); + return static_cast(rxData.voltage) / 10.0F; } uint8_t pyroContinuity() { @@ -87,24 +88,27 @@ class TelemetryData { return rxData.testing_mode; } - uint32_t getLastUpdateTime() const { return lastCommitTime; } + [[nodiscard]] uint32_t getLastUpdateTime() const { return lastCommitTime; } - packedRXMessage rxData; + packedRXMessage &getRxData() { return rxData; } private: - bool updated; - uint32_t lastCommitTime; + packedRXMessage rxData{}; + bool updated{false}; + uint32_t lastCommitTime{0}; }; -typedef struct { +struct [[gnu::packed]] TelemetryInfoData { uint8_t lq; int8_t rssi; int8_t snr; -} __attribute__((packed)) TelemetryInfoData; +}; + +static_assert(sizeof(TelemetryInfoData) == 3); class TelemetryInfo { public: - void commit(uint8_t *data, uint32_t length) { + void commit(uint8_t *data, uint32_t length [[maybe_unused]]) { memcpy(&infoData, data, sizeof(infoData)); lastCommitTime = millis(); updated = true; @@ -112,21 +116,21 @@ class TelemetryInfo { void clear() { updated = false; } - bool isUpdated() const { return updated; } + [[nodiscard]] bool isUpdated() const { return updated; } int16_t snr() { updated = false; - return (int16_t)infoData.snr; + return static_cast(infoData.snr); } int16_t rssi() { updated = false; - return (int16_t)infoData.rssi; + return static_cast(infoData.rssi); } uint16_t lq() { updated = false; - return (uint16_t)infoData.lq; + return static_cast(infoData.lq); } private: @@ -135,22 +139,24 @@ class TelemetryInfo { bool updated; }; -typedef struct { +struct [[gnu::packed]] TelemetryTimeData { uint8_t second; uint8_t minute; uint8_t hour; -} __attribute__((packed)) TelemetryTimeData; +}; + +static_assert(sizeof(TelemetryTimeData) == 3); class TelemetryTime { public: - void commit(uint8_t *data, uint32_t length) { + void commit(uint8_t *data, uint32_t length [[maybe_unused]]) { memcpy(&timeData, data, sizeof(TelemetryTimeData)); lastCommitTime = millis(); updated = true; wasUpdated = true; } - bool isUpdated() const { return updated; } + [[nodiscard]] bool isUpdated() const { return updated; } uint8_t second() { updated = false; @@ -168,35 +174,32 @@ class TelemetryTime { } private: - TelemetryTimeData timeData; - uint32_t lastCommitTime; - bool updated; - bool wasUpdated = false; + TelemetryTimeData timeData{}; + uint32_t lastCommitTime{0}; + bool updated{false}; + bool wasUpdated{false}; }; -typedef struct { +struct [[gnu::packed]] TelemetryLocationData { float lat; float lon; int32_t alt; -} __attribute__((packed)) TelemetryLocationData; +}; + +static_assert(sizeof(TelemetryLocationData) == 12); class TelemetryLocation { public: - void commit(uint8_t *data, uint32_t length) { + void commit(uint8_t *data, uint32_t length [[maybe_unused]]) { memcpy(&locationData, data, sizeof(TelemetryLocationData)); lastCommitTime = millis(); updated = true; wasUpdated = true; } - bool isUpdated() const { return updated; } + [[nodiscard]] bool isUpdated() const { return updated; } - bool isValid() const { - if (locationData.lat && locationData.lon && wasUpdated) { - return true; - } - return false; - } + [[nodiscard]] bool isValid() const { return locationData.lat != 0 && locationData.lon != 0 && wasUpdated; } float lat() { updated = false; @@ -210,12 +213,12 @@ class TelemetryLocation { int16_t alt() { updated = false; - return (uint16_t)locationData.alt; + return static_cast(locationData.alt); } private: - TelemetryLocationData locationData; - uint32_t lastCommitTime; - bool updated; - bool wasUpdated = false; + TelemetryLocationData locationData{}; + uint32_t lastCommitTime{0}; + bool updated{false}; + bool wasUpdated{false}; }; diff --git a/ground_station/src/telemetry/telemetry_reg.hpp b/ground_station/src/telemetry/telemetry_reg.hpp index 939ce470..f34bb531 100644 --- a/ground_station/src/telemetry/telemetry_reg.hpp +++ b/ground_station/src/telemetry/telemetry_reg.hpp @@ -18,16 +18,17 @@ #pragma once -typedef enum { +enum transmission_direction_e { TX_DIR = 0, RX_DIR = 1, -} transmission_direction_e; +}; -typedef enum { +enum transmission_mode_e { UNIDIRECTIONAL = 0, BIDIRECTIONAL = 1, -} transmission_mode_e; +}; +// NOLINTBEGIN(cppcoreguidelines-macro-usage) #define CMD_DIRECTION 0x10 #define CMD_PA_GAIN 0x11 #define CMD_POWER_LEVEL 0x12 @@ -46,3 +47,4 @@ typedef enum { #define CMD_GNSS_LOC 0x40 #define CMD_GNSS_TIME 0x41 #define CMD_GNSS_INFO 0x42 +// NOLINTEND(cppcoreguidelines-macro-usage) diff --git a/ground_station/src/utils.cpp b/ground_station/src/utils.cpp index ec2a4f57..0411e5e6 100644 --- a/ground_station/src/utils.cpp +++ b/ground_station/src/utils.cpp @@ -40,22 +40,28 @@ #include "diskio.h" #include "ff.h" -#include "esp_private/system_internal.h" -#include "esp_task_wdt.h" -#include "freertos/FreeRTOS.h" -#include "freertos/task.h" +#include +#include +#include +#include -static void msc_flush_cb(void); +constexpr uint8_t BOOT_BUTTON = 0; +constexpr uint8_t TASK_UTILS_FREQ = 5; // [Hz] +constexpr uint16_t MSC_STARTUP_DELAY = 2000; // [ms] + +static void msc_flush_cb(); static int32_t msc_read_cb(uint32_t lba, void *buffer, uint32_t bufsize); static int32_t msc_write_cb(uint32_t lba, uint8_t *buffer, uint32_t bufsize); static void usbEventCallback(void *arg, esp_event_base_t event_base, int32_t event_id, void *event_data); + +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) static volatile bool updated = false; static volatile bool connected = false; - Adafruit_USBD_MSC usb_msc; Adafruit_FlashTransport_ESP32 flashTransport; Adafruit_SPIFlash flash(&flashTransport); FatFileSystem fatfs; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) bool Utils::begin(uint32_t watchdogTimeout, const char *labelName, bool forceFormat) { bool status = true; @@ -79,8 +85,8 @@ bool Utils::begin(uint32_t watchdogTimeout, const char *labelName, bool forceFor } delay(200); - uint16_t vid = USB_VID; - uint16_t pid = USB_PID; + const uint16_t vid = USB_VID; + const uint16_t pid = USB_PID; USB.VID(vid); USB.PID(pid); @@ -99,29 +105,29 @@ bool Utils::begin(uint32_t watchdogTimeout, const char *labelName, bool forceFor // regardless of spi flash page size usb_msc.begin(); - xTaskCreate(update, "task_utils", 2048, this, 1, NULL); + xTaskCreate(update, "task_utils", 2048, this, 1, nullptr); delay(200); // TODO: Check if delay helps return status; } -void Utils::startBootloader(void) { +void Utils::startBootloader() { const uint16_t APP_REQUEST_UF2_RESET_HINT = 0x11F2; esp_reset_reason(); - esp_reset_reason_set_hint((esp_reset_reason_t)APP_REQUEST_UF2_RESET_HINT); + esp_reset_reason_set_hint(static_cast(APP_REQUEST_UF2_RESET_HINT)); esp_restart(); } void Utils::startWatchdog(uint32_t seconds) { esp_task_wdt_init(seconds, true); // Enable panic so ESP32 restarts - esp_task_wdt_add(NULL); // Add current thread to WDT watch + esp_task_wdt_add(nullptr); // Add current thread to WDT watch esp_task_wdt_reset(); console.log.printf("[SYSTEM] Watchdog started with timeout of %lu s\n", seconds); } -void Utils::feedWatchdog(void) { esp_task_wdt_reset(); } +void Utils::feedWatchdog() { esp_task_wdt_reset(); } void Utils::update(void *pvParameter) { - Utils *ref = (Utils *)pvParameter; + auto *ref = static_cast(pvParameter); TickType_t mscTimer = 0; bool connectedOld = false; @@ -145,18 +151,20 @@ void Utils::update(void *pvParameter) { } connectedOld = connected; - vTaskDelayUntil(&task_last_tick, (const TickType_t)1000 / TASK_UTILS_FREQ); + vTaskDelayUntil(&task_last_tick, static_cast(1000) / TASK_UTILS_FREQ); } - vTaskDelete(NULL); + vTaskDelete(nullptr); } bool Utils::isUpdated(bool clearFlag) { - bool status = updated; - if (clearFlag) updated = false; + const bool status = updated; + if (clearFlag) { + updated = false; + } return status; } -bool Utils::isConnected(void) { return connected; } +bool Utils::isConnected() { return connected; } bool Utils::format(const char *labelName) { static FATFS elmchanFatfs; @@ -169,29 +177,30 @@ bool Utils::format(const char *labelName) { buf); // Partition the flash with 1 partition that takes the entire space. if (r != FR_OK) { console.error.printf("[UTILS] Error, f_fdisk failed with error code: %d\n", r); - return 0; + return false; } console.println("[UTILS] Partitioned flash!"); console.println( "[UTILS] Creating and formatting FAT filesystem (this takes " "~60 seconds)..."); + // NOLINTNEXTLINE(hicpp-signed-bitwise) r = f_mkfs("", FM_FAT | FM_SFD, 0, workbuf, sizeof(workbuf)); // Make filesystem. if (r != FR_OK) { console.error.printf("[UTILS] Error, f_mkfs failed with error code: %d\n", r); - return 0; + return false; } r = f_mount(&elmchanFatfs, "0:", 1); // mount to set disk label if (r != FR_OK) { console.error.printf("[UTILS] Error, f_mount failed with error code: %d\n", r); - return 0; + return false; } console.log.printf("[UTILS] Setting disk label to: %s\n", labelName); r = f_setlabel(labelName); // Setting label if (r != FR_OK) { console.error.printf("[UTILS] Error, f_setlabel failed with error code: %d\n", r); - return 0; + return false; } f_unmount("0:"); // unmount flash.syncBlocks(); // sync to make sure all data is written to flash @@ -199,23 +208,24 @@ bool Utils::format(const char *labelName) { if (!fatfs.begin(&flash)) // Check new filesystem { console.error.println("[UTILS] Error, failed to mount newly formatted filesystem!"); - return 0; + return false; } console.ok.println("[UTILS] Flash chip successfully formatted with new empty filesystem!"); yield(); - return 1; + return true; } int32_t Utils::getFlashMemoryUsage() { - uint32_t num_clusters = fatfs.clusterCount() - 2; - uint32_t available_clusters = fatfs.freeClusterCount(); + const uint32_t num_clusters = fatfs.clusterCount() - 2; + const uint32_t available_clusters = fatfs.freeClusterCount(); - double percentage = (static_cast(available_clusters) / num_clusters) * 100; + const double percentage = (static_cast(available_clusters) / static_cast(num_clusters)) * 100.0; return static_cast(std::ceil(percentage)); } -void usbEventCallback(void *arg, esp_event_base_t event_base, int32_t event_id, void *event_data) { +void usbEventCallback(void *arg [[maybe_unused]], esp_event_base_t event_base, int32_t event_id, + void *event_data [[maybe_unused]]) { if (event_base == ARDUINO_USB_EVENTS) { // arduino_usb_event_data_t *data = (arduino_usb_event_data_t *)event_data; if (event_id == ARDUINO_USB_STARTED_EVENT || event_id == ARDUINO_USB_RESUME_EVENT) { @@ -231,19 +241,19 @@ void usbEventCallback(void *arg, esp_event_base_t event_base, int32_t event_id, // Copy disk's data to buffer (up to bufsize) and // return number of copied bytes (must be multiple of block size) static int32_t msc_read_cb(uint32_t lba, void *buffer, uint32_t bufsize) { - return flash.readBlocks(lba, (uint8_t *)buffer, bufsize / 512) ? bufsize : -1; + return flash.readBlocks(lba, static_cast(buffer), bufsize / 512) ? static_cast(bufsize) : -1; } // Callback invoked when received WRITE10 command. // Process data in buffer to disk's storage and // return number of written bytes (must be multiple of block size) static int32_t msc_write_cb(uint32_t lba, uint8_t *buffer, uint32_t bufsize) { - return flash.writeBlocks(lba, buffer, bufsize / 512) ? bufsize : -1; + return flash.writeBlocks(lba, buffer, bufsize / 512) ? static_cast(bufsize) : -1; } // Callback invoked when WRITE10 command is completed (status received and // accepted by host). Used to flush any pending cache. -static void msc_flush_cb(void) { +static void msc_flush_cb() { flash.syncBlocks(); // sync with flash fatfs.cacheClear(); // clear file system's cache to force refresh updated = true; diff --git a/ground_station/src/utils.hpp b/ground_station/src/utils.hpp index f9352b21..c98ec31b 100644 --- a/ground_station/src/utils.hpp +++ b/ground_station/src/utils.hpp @@ -32,31 +32,29 @@ #pragma once #include -#include "SdFat.h" +#include -#define BOOT_BUTTON 0 -#define TASK_UTILS_FREQ 5 // [Hz] -#define MSC_STARTUP_DELAY 2000 // [ms] -#define DEFAULT_CONFIG_FILE_NAME "system.json" +inline constexpr const char *DEFAULT_CONFIG_FILE_NAME = "system.json"; constexpr float PI_F = static_cast(PI); +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern FatFileSystem fatfs; class Utils { public: - Utils(const char *systemConfigFilename = DEFAULT_CONFIG_FILE_NAME) : configFileName(systemConfigFilename) {} + explicit Utils(const char *systemConfigFilename = DEFAULT_CONFIG_FILE_NAME) : configFileName(systemConfigFilename) {} bool begin(uint32_t watchdogTimeout = 0, const char *labelName = "DRIVE", bool forceFormat = false); - static void startBootloader(void); - void startWatchdog(uint32_t seconds); - void feedWatchdog(void); - bool isUpdated(bool clearFlag = true); - bool isConnected(void); - int32_t getFlashMemoryUsage(); - bool format(const char *labelName); - inline const char *getSerialNumber(void) { return serial; } + static void startBootloader(); + static void startWatchdog(uint32_t seconds); + static void feedWatchdog(); + static bool isUpdated(bool clearFlag = true); + static bool isConnected(); + static int32_t getFlashMemoryUsage(); + static bool format(const char *labelName); + inline const char *getSerialNumber() { return serial; } - operator bool() const { return mscReady; } + explicit operator bool() const { return mscReady; } private: const char *configFileName; diff --git a/telemetry/lib/LqCalculator/LqCalculator.hpp b/telemetry/lib/LqCalculator/LqCalculator.hpp index c80018ee..de190b8a 100644 --- a/telemetry/lib/LqCalculator/LqCalculator.hpp +++ b/telemetry/lib/LqCalculator/LqCalculator.hpp @@ -21,16 +21,11 @@ template class LqCalculator { public: - LqCalculator() { - reset(); - // count is reset here only once on construction to start LQ counting - // at 100% on first connect, but 0 out of N after a failsafe - count = 1; - } - /* Set the bit for the current period to true and update the running LQ */ void add() { - if (currentIsSet()) return; + if (currentIsSet()) { + return; + } LQArray[index] |= LQmask; LQ += 1; } @@ -39,16 +34,16 @@ class LqCalculator { void inc() { // Increment the counter by shifting one bit higher // If we've shifted out all the bits, move to next idx - LQmask = LQmask << 1; + LQmask = LQmask << 1U; if (LQmask == 0) { - LQmask = (1 << 0); + LQmask = (1U << 0U); index += 1; } // At idx N / 32 and bit N % 32, wrap back to idx=0, bit=0 - if ((index == (N / 32)) && (LQmask & (1 << (N % 32)))) { + if ((index == (N / 32)) && static_cast(LQmask & (1U << (N % 32U)))) { index = 0; - LQmask = (1 << 0); + LQmask = (1U << 0U); } if ((LQArray[index] & LQmask) != 0) { @@ -56,11 +51,13 @@ class LqCalculator { LQ -= 1; } - if (count < N) ++count; + if (count < N) { + ++count; + } } /* Return the current running total of bits set, in percent */ - uint8_t getLQ() const { return (uint32_t)LQ * 100U / count; } + uint8_t getLQ() const { return static_cast(LQ) * 100U / count; } /* Return the current running total of bits set, up to N */ uint8_t getLQRaw() const { return LQ; } @@ -77,8 +74,8 @@ class LqCalculator { // after a failsafe, instead of down from 100 LQ = 0; index = 0; - LQmask = (1 << 0); - for (uint8_t i = 0; i < (sizeof(LQArray) / sizeof(LQArray[0])); i++) { + LQmask = (1U << 0U); + for (uint32_t i = 0; i < (sizeof(LQArray) / sizeof(LQArray[0])); i++) { LQArray[i] = 0; } } @@ -87,9 +84,11 @@ class LqCalculator { bool currentIsSet() const { return LQArray[index] & LQmask; } private: - uint8_t LQ; - uint8_t index; // current position in LQArray - uint8_t count; - uint32_t LQmask; - uint32_t LQArray[(N + 31) / 32]; + uint8_t LQ{0}; + uint8_t index{0}; // current position in LQArray + // count is reset here only once on construction to start LQ counting + // at 100% on first connect, but 0 out of N after a failsafe + uint8_t count{1}; + uint32_t LQmask{1U << 0U}; + uint32_t LQArray[(N + 31) / 32]{}; }; diff --git a/telemetry/lib/Thermistor/Thermistor.hpp b/telemetry/lib/Thermistor/Thermistor.hpp index a4307c03..8a0332f5 100644 --- a/telemetry/lib/Thermistor/Thermistor.hpp +++ b/telemetry/lib/Thermistor/Thermistor.hpp @@ -27,7 +27,7 @@ class Thermistor { explicit Thermistor(ADC_HandleTypeDef *adc) : adcHandle(adc) { HAL_ADC_Start_DMA(adc, &rawAdcValue, 1); } float getTemperature() { - float resistance = 10000.0F / ((65535.0F / static_cast((uint16_t)rawAdcValue)) - 1.0F); + float resistance = 10000.0F / ((65535.0F / static_cast(static_cast(rawAdcValue))) - 1.0F); float steinhart = logf(resistance / 10000.0F); // ln(R/R0) @@ -41,5 +41,5 @@ class Thermistor { private: ADC_HandleTypeDef *adcHandle; - uint32_t rawAdcValue; + uint32_t rawAdcValue{0}; }; diff --git a/telemetry/src/SerialComm/Serial.hpp b/telemetry/src/SerialComm/Serial.hpp index 69811327..92b93785 100644 --- a/telemetry/src/SerialComm/Serial.hpp +++ b/telemetry/src/SerialComm/Serial.hpp @@ -23,9 +23,7 @@ void start_serial(); template class Serial { public: - explicit Serial(UART_HandleTypeDef *handle) : tail(0U), uart(handle), buffer{} { - HAL_UART_Receive_DMA(uart, buffer, N); - } + explicit Serial(UART_HandleTypeDef *handle) : uart(handle) { HAL_UART_Receive_DMA(uart, buffer, N); } uint32_t available() { volatile uint32_t head = N - uart->hdmarx->Instance->CNDTR; @@ -43,7 +41,7 @@ class Serial { } private: - volatile uint32_t tail; + volatile uint32_t tail{0}; UART_HandleTypeDef *uart; - uint8_t buffer[N]; + uint8_t buffer[N]{}; }; From 646efc982f78a977e99b99484cc42143ee6def0e Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Mon, 28 Aug 2023 21:04:21 +0200 Subject: [PATCH 03/11] [FC] Fix clang-tidy issues --- flight_computer/src/cli/cli.cpp | 119 ++++++---- flight_computer/src/cli/cli.hpp | 4 +- flight_computer/src/cli/cli_commands.cpp | 216 ++++++++++-------- flight_computer/src/cli/cli_commands.hpp | 1 + flight_computer/src/cli/settings.cpp | 2 + flight_computer/src/cli/settings.hpp | 37 +-- flight_computer/src/comm/fifo.cpp | 31 +-- flight_computer/src/comm/stream.cpp | 16 +- flight_computer/src/comm/stream_group.cpp | 8 +- flight_computer/src/config/cats_config.cpp | 25 +- flight_computer/src/config/cats_config.hpp | 32 +-- flight_computer/src/config/control_config.hpp | 14 +- flight_computer/src/config/globals.cpp | 6 +- flight_computer/src/config/globals.hpp | 16 +- flight_computer/src/control/calibration.cpp | 37 +-- flight_computer/src/control/calibration.hpp | 4 +- .../src/control/data_processing.cpp | 156 +++++++------ .../src/control/data_processing.hpp | 3 +- flight_computer/src/control/flight_phases.cpp | 17 +- flight_computer/src/control/flight_phases.hpp | 22 +- flight_computer/src/control/kalman_filter.cpp | 39 ++-- flight_computer/src/control/kalman_filter.hpp | 8 +- .../src/control/orientation_filter.cpp | 22 +- .../src/control/orientation_filter.hpp | 2 +- flight_computer/src/drivers/adc.cpp | 7 +- flight_computer/src/drivers/adc.hpp | 2 +- flight_computer/src/drivers/buzzer.cpp | 1 + flight_computer/src/drivers/buzzer.hpp | 2 +- flight_computer/src/drivers/gpio.hpp | 2 +- flight_computer/src/drivers/pwm.cpp | 8 +- flight_computer/src/drivers/pwm.hpp | 17 +- flight_computer/src/drivers/servo.hpp | 2 +- flight_computer/src/drivers/spi.hpp | 2 +- flight_computer/src/drivers/uart.cpp | 16 +- flight_computer/src/drivers/uart.hpp | 7 +- flight_computer/src/drivers/w25q.cpp | 143 +++++++----- flight_computer/src/drivers/w25q.hpp | 33 +-- flight_computer/src/flash/lfs_custom.cpp | 46 ++-- flight_computer/src/flash/lfs_custom.hpp | 8 +- flight_computer/src/flash/reader.cpp | 87 +++---- flight_computer/src/flash/recorder.cpp | 52 +++-- flight_computer/src/flash/recorder.hpp | 52 +++-- flight_computer/src/init/config.cpp | 19 +- flight_computer/src/init/system.cpp | 2 +- flight_computer/src/main.cpp | 16 +- flight_computer/src/{main.h => main.hpp} | 6 +- flight_computer/src/sensors/lsm6dso32.hpp | 10 +- flight_computer/src/sensors/ms5607.hpp | 25 +- .../src/target/VEGA/stm32f4xx_hal_msp.cpp | 2 +- .../src/target/VEGA/stm32f4xx_it.cpp | 2 +- flight_computer/src/target/VEGA/target.cpp | 38 +-- .../src/target/VEGA/{target.h => target.hpp} | 16 +- flight_computer/src/tasks/task.hpp | 12 +- flight_computer/src/tasks/task_buzzer.cpp | 2 +- flight_computer/src/tasks/task_cdc.cpp | 7 +- flight_computer/src/tasks/task_cli.cpp | 1 + .../src/tasks/task_health_monitor.cpp | 19 +- .../src/tasks/task_peripherals.cpp | 9 +- .../src/tasks/task_preprocessing.cpp | 129 +++++------ flight_computer/src/tasks/task_recorder.cpp | 37 +-- .../src/tasks/task_sensor_read.cpp | 4 +- flight_computer/src/tasks/task_simulator.cpp | 10 +- flight_computer/src/tasks/task_state_est.cpp | 8 +- flight_computer/src/tasks/task_state_est.hpp | 8 +- flight_computer/src/tasks/task_telemetry.cpp | 47 ++-- flight_computer/src/tasks/task_telemetry.hpp | 2 +- flight_computer/src/tasks/task_usb_device.cpp | 1 + flight_computer/src/usb/msc_disk.c | 18 +- flight_computer/src/usb/tusb_config.h | 5 +- flight_computer/src/usb/usb_descriptors.c | 13 +- flight_computer/src/util/actions.cpp | 44 ++-- flight_computer/src/util/actions.hpp | 2 +- flight_computer/src/util/battery.cpp | 12 +- flight_computer/src/util/crc.cpp | 2 +- flight_computer/src/util/debug.cpp | 8 +- flight_computer/src/util/enum_str_maps.cpp | 5 +- flight_computer/src/util/error_handler.cpp | 30 +-- flight_computer/src/util/error_handler.hpp | 36 +-- flight_computer/src/util/log.cpp | 20 +- flight_computer/src/util/math_util.cpp | 4 +- flight_computer/src/util/task_util.cpp | 3 +- flight_computer/src/util/task_util.hpp | 1 + flight_computer/src/util/telemetry_reg.hpp | 32 +-- flight_computer/src/util/types.cpp | 25 -- flight_computer/src/util/types.hpp | 29 +-- 85 files changed, 1130 insertions(+), 915 deletions(-) rename flight_computer/src/{main.h => main.hpp} (88%) rename flight_computer/src/target/VEGA/{target.h => target.hpp} (86%) delete mode 100644 flight_computer/src/util/types.cpp diff --git a/flight_computer/src/cli/cli.cpp b/flight_computer/src/cli/cli.cpp index 79b9cff0..626a0a0a 100644 --- a/flight_computer/src/cli/cli.cpp +++ b/flight_computer/src/cli/cli.cpp @@ -19,24 +19,27 @@ #include "cli/cli.hpp" +#include "cli/cli_commands.hpp" +#include "comm/stream_group.hpp" +#include "flash/lfs_custom.hpp" +#include "util/log.h" + #include + #include #include #include #include -#include "cli/cli_commands.hpp" -#include "comm/stream_group.hpp" -#include "flash/lfs_custom.hpp" -#include "util/log.h" - -#define CLI_IN_BUFFER_SIZE 128 -#define CLI_OUT_BUFFER_SIZE 256 +constexpr uint16_t CLI_IN_BUFFER_SIZE = 128; +constexpr uint16_t CLI_OUT_BUFFER_SIZE = 256; +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) static uint32_t buffer_index = 0; static char cli_buffer[CLI_IN_BUFFER_SIZE]; static char old_cli_buffer[CLI_IN_BUFFER_SIZE]; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) static void cli_print_error_va(const char *cmdName, const char *format, va_list va); static void cli_print_error(const char *cmdName, const char *format, ...) __attribute__((format(printf, 2, 3))); @@ -59,7 +62,8 @@ void get_min_max(const cli_value_t *var, int *min, int *max) { } } -void cli_print(const char *str) { stream_write(USB_SG.out, (uint8_t *)str, strlen(str)); } +// NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) +void cli_print(const char *str) { stream_write(USB_SG.out, reinterpret_cast(str), strlen(str)); } static void cli_prompt() { cli_printf("\r\n^._.^:%s> ", cwd); } @@ -126,17 +130,18 @@ char *skip_space(char *buffer) { return buffer; } +// NOLINTBEGIN(readability-implicit-bool-conversion,bugprone-narrowing-conversions) static char *check_command(char *cmdline, const char *command) { - if (!strncasecmp(cmdline, command, strlen(command)) // command names match - && (isspace((unsigned)cmdline[strlen(command)]) || cmdline[strlen(command)] == 0)) { + if ((strncasecmp(cmdline, command, strlen(command)) == 0) // command names match + && (isspace(static_cast(cmdline[strlen(command)])) || cmdline[strlen(command)] == 0)) { return skip_space(cmdline + strlen(command) + 1); - } else { - return nullptr; } + return nullptr; } +// NOLINTEND(readability-implicit-bool-conversion,bugprone-narrowing-conversions) static void process_character(const char c) { - if (buffer_index && (c == '\n' || c == '\r')) { + if ((buffer_index > 0) && (c == '\n' || c == '\r')) { // enter pressed cli_print_linefeed(); @@ -144,7 +149,7 @@ static void process_character(const char c) { char *p = cli_buffer; p = strchr(p, '#'); if (nullptr != p) { - buffer_index = (uint32_t)(p - cli_buffer); + buffer_index = static_cast(p - cli_buffer); } // Strip trailing whitespace while (buffer_index > 0 && cli_buffer[buffer_index - 1] == ' ') { @@ -155,11 +160,13 @@ static void process_character(const char c) { if (buffer_index > 0) { cli_buffer[buffer_index] = 0; // null terminate - const clicmd_t *cmd; + const clicmd_t *cmd{nullptr}; char *options = nullptr; for (cmd = cmd_table; cmd < cmd_table + NUM_CLI_COMMANDS; cmd++) { options = check_command(cli_buffer, cmd->name); - if (options) break; + if (options != nullptr) { + break; + } } if (cmd < cmd_table + NUM_CLI_COMMANDS) { cmd->cli_command(cmd->name, options); @@ -175,36 +182,43 @@ static void process_character(const char c) { // 'exit' will reset this flag, so we don't need to print prompt again } else if (buffer_index < sizeof(cli_buffer) && c >= 32 && c <= 126) { - if (!buffer_index && c == ' ') return; // Ignore leading spaces + if ((buffer_index == 0) && (c == ' ')) { + return; // Ignore leading spaces + } cli_buffer[buffer_index++] = c; cli_write(c); } } +// NOLINTNEXTLINE(readability-function-cognitive-complexity) static void process_character_interactive(const char c) { // We ignore a few characters, this is only used for the up arrow static uint16_t ignore = 0; - if (ignore) { + if (ignore > 0) { ignore--; return; } if (c == '\t' || c == '?') { // do tab completion - const clicmd_t *cmd, *pstart = nullptr, *pend = nullptr; + const clicmd_t *cmd{nullptr}; + const clicmd_t *pstart{nullptr}; + const clicmd_t *pend{nullptr}; uint32_t i = buffer_index; for (cmd = cmd_table; cmd < cmd_table + NUM_CLI_COMMANDS; cmd++) { - if (buffer_index && (strncasecmp(cli_buffer, cmd->name, buffer_index) != 0)) { + if ((buffer_index != 0) && (strncasecmp(cli_buffer, cmd->name, buffer_index) != 0)) { continue; } - if (!pstart) { + if (pstart == nullptr) { pstart = cmd; } pend = cmd; } - if (pstart) { /* Buffer matches one or more commands */ + if (pstart != nullptr) { /* Buffer matches one or more commands */ for (;; buffer_index++) { - if (pstart->name[buffer_index] != pend->name[buffer_index]) break; - if (!pstart->name[buffer_index] && buffer_index < sizeof(cli_buffer) - 2) { + if (pstart->name[buffer_index] != pend->name[buffer_index]) { + break; + } + if ((pstart->name[buffer_index] == '\0') && (buffer_index < sizeof(cli_buffer) - 2)) { /* Unambiguous -- append a space */ cli_buffer[buffer_index++] = ' '; cli_buffer[buffer_index] = '\0'; @@ -213,7 +227,7 @@ static void process_character_interactive(const char c) { cli_buffer[buffer_index] = pstart->name[buffer_index]; } } - if (!buffer_index || pstart != pend) { + if ((buffer_index == 0) || (pstart != pend)) { /* Print list of ambiguous matches */ cli_print("\r\n\033[K"); for (cmd = pstart; cmd <= pend && cmd != nullptr; cmd++) { @@ -223,7 +237,9 @@ static void process_character_interactive(const char c) { cli_prompt(); i = 0; /* Redraw prompt */ } - for (; i < buffer_index; i++) cli_write(cli_buffer[i]); + for (; i < buffer_index; i++) { + cli_write(cli_buffer[i]); + } } else if (c == 4) { // CTRL-D - clear screen cli_print("\033[2J\033[1;1H"); @@ -237,18 +253,21 @@ static void process_character_interactive(const char c) { } } else if (c == '\b') { // backspace - if (buffer_index) { + if (buffer_index > 0) { cli_buffer[--buffer_index] = 0; cli_print("\010 \010"); } } else if (c == 27) { // ESC character is called from the up arrow, we only look at the first of 3 characters // up arrow - while (buffer_index) { + while (buffer_index > 0) { cli_buffer[--buffer_index] = 0; cli_print("\010 \010"); } + // NOLINTNEXTLINE(modernize-loop-convert) for (uint32_t i = 0; i < sizeof(old_cli_buffer); i++) { - if (old_cli_buffer[i] == 0) break; + if (old_cli_buffer[i] == 0) { + break; + } process_character(old_cli_buffer[i]); } // Ignore the following characters @@ -258,11 +277,11 @@ static void process_character_interactive(const char c) { } } -void cli_process(void) { +void cli_process() { while (stream_length(USB_SG.in) > 0) { uint8_t ch = 0; if (stream_read_byte(USB_SG.in, &ch)) { - process_character_interactive(ch); + process_character_interactive(static_cast(ch)); } } } @@ -276,27 +295,27 @@ static void print_value_pointer(const char *cmdName, const cli_value_t *var, con default: case VAR_UINT8: // uint8_t array - cli_printf("%d", ((uint8_t *)valuePointer)[i]); + cli_printf("%d", static_cast(valuePointer)[i]); break; case VAR_INT8: // int8_t array - cli_printf("%d", ((int8_t *)valuePointer)[i]); + cli_printf("%d", static_cast(valuePointer)[i]); break; case VAR_UINT16: // uin16_t array - cli_printf("%d", ((uint16_t *)valuePointer)[i]); + cli_printf("%d", static_cast(valuePointer)[i]); break; case VAR_INT16: // int16_t array - cli_printf("%d", ((int16_t *)valuePointer)[i]); + cli_printf("%d", static_cast(valuePointer)[i]); break; case VAR_UINT32: // uin32_t array - cli_printf("%lu", ((uint32_t *)valuePointer)[i]); + cli_printf("%lu", static_cast(valuePointer)[i]); break; } @@ -309,23 +328,25 @@ static void print_value_pointer(const char *cmdName, const cli_value_t *var, con switch (var->type & VALUE_TYPE_MASK) { case VAR_UINT8: - value = *(uint8_t *)valuePointer; + value = *static_cast(valuePointer); break; case VAR_INT8: - value = *(int8_t *)valuePointer; + // NOLINTNEXTLINE(bugprone-signed-char-misuse) + value = *static_cast(valuePointer); break; case VAR_UINT16: - value = *(uint16_t *)valuePointer; + value = *static_cast(valuePointer); break; case VAR_INT16: - value = *(int16_t *)valuePointer; + value = *static_cast(valuePointer); break; case VAR_UINT32: - value = *(uint32_t *)valuePointer; + // NOLINTNEXTLINE(bugprone-narrowing-conversions) + value = *static_cast(valuePointer); break; } @@ -334,15 +355,15 @@ static void print_value_pointer(const char *cmdName, const cli_value_t *var, con switch (var->type & VALUE_MODE_MASK) { case MODE_DIRECT: if ((var->type & VALUE_TYPE_MASK) == VAR_UINT32) { - cli_printf("%lu", (uint32_t)value); - if ((uint32_t)value > var->config.u32_max) { + cli_printf("%lu", static_cast(value)); + if (static_cast(value) > var->config.u32_max) { value_is_corrupted = true; } else if (full) { cli_printf(" 0 %lu", var->config.u32_max); } } else { - int min; - int max; + int min{0}; + int max{0}; get_min_max(var, &min, &max); cli_printf("%d", value); @@ -361,14 +382,16 @@ static void print_value_pointer(const char *cmdName, const cli_value_t *var, con } break; case MODE_BITSET: - if (value & 1 << var->config.bitpos) { + if (static_cast((static_cast(value) & 1U) << var->config.bitpos)) { cli_printf("ON"); } else { cli_printf("OFF"); } break; case MODE_STRING: - cli_printf("%s", (strlen((char *)valuePointer) == 0) ? "-" : (char *)valuePointer); + cli_printf("%s", (strlen(static_cast(valuePointer)) == 0) + ? "-" + : static_cast(valuePointer)); break; } @@ -407,7 +430,7 @@ uint16_t cli_get_setting_index(char *name, uint8_t length) { const char *next_arg(const char *current_arg) { const char *ptr = strchr(current_arg, ' '); - while (ptr && *ptr == ' ') { + while (ptr != nullptr && *ptr == ' ') { ptr++; } return ptr; diff --git a/flight_computer/src/cli/cli.hpp b/flight_computer/src/cli/cli.hpp index 55d88bc1..cc70bcb2 100644 --- a/flight_computer/src/cli/cli.hpp +++ b/flight_computer/src/cli/cli.hpp @@ -23,13 +23,13 @@ #include "cli/settings.hpp" #include "comm/fifo.hpp" -void cli_process(void); +void cli_process(); void cli_enter(); void cli_print(const char *str); void cli_printf(const char *format, ...) __attribute__((format(printf, 1, 2))); -void cli_print_linefeed(void); +void cli_print_linefeed(); void cli_print_line(const char *str); void cli_print_linef(const char *format, ...) __attribute__((format(printf, 1, 2))); diff --git a/flight_computer/src/cli/cli_commands.cpp b/flight_computer/src/cli/cli_commands.cpp index f56d1f74..94ecc93a 100644 --- a/flight_computer/src/cli/cli_commands.cpp +++ b/flight_computer/src/cli/cli_commands.cpp @@ -19,13 +19,17 @@ #include "cli/cli_commands.hpp" +#ifdef CATS_DEBUG +#include "tasks/task_simulator.hpp" +#endif + #include "cli/cli.hpp" #include "config/cats_config.hpp" #include "config/globals.hpp" #include "drivers/w25q.hpp" #include "flash/lfs_custom.hpp" #include "flash/reader.hpp" -#include "main.h" +#include "main.hpp" #include "tasks/task_state_est.hpp" #include "util/actions.hpp" #include "util/battery.hpp" @@ -33,11 +37,9 @@ #include "util/log.h" #include + #include #include -#ifdef CATS_DEBUG -#include "tasks/task_simulator.hpp" -#endif /** CLI command function declarations **/ static void cli_cmd_help(const char *cmd_name, char *args); @@ -129,12 +131,13 @@ static void fill_buf(uint8_t *buf, size_t buf_sz); static void cli_cmd_help(const char *cmd_name, char *args) { bool any_matches = false; + // NOLINTNEXTLINE(modernize-loop-convert) for (uint32_t i = 0; i < ARRAYLEN(cmd_table); i++) { bool print_entry = false; if (is_empty(args)) { print_entry = true; } else { - if (strstr(cmd_table[i].name, args) || strstr(cmd_table[i].description, args)) { + if ((strstr(cmd_table[i].name, args) != nullptr) || (strstr(cmd_table[i].description, args) != nullptr)) { print_entry = true; } } @@ -142,10 +145,10 @@ static void cli_cmd_help(const char *cmd_name, char *args) { if (print_entry) { any_matches = true; cli_print(cmd_table[i].name); - if (cmd_table[i].description) { + if (cmd_table[i].description != nullptr) { cli_printf(" - %s", cmd_table[i].description); } - if (cmd_table[i].args) { + if (cmd_table[i].args != nullptr) { cli_printf("\r\n\t%s", cmd_table[i].args); } cli_print_linefeed(); @@ -156,15 +159,15 @@ static void cli_cmd_help(const char *cmd_name, char *args) { } } -static void cli_cmd_reboot(const char *cmd_name, char *args) { NVIC_SystemReset(); } +static void cli_cmd_reboot(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { NVIC_SystemReset(); } -static void cli_cmd_bl(const char *cmd_name, char *args) { +static void cli_cmd_bl(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { HAL_RTCEx_BKUPWrite(&hrtc, RTC_BKP_DR0, BOOTLOADER_MAGIC_PATTERN); __disable_irq(); NVIC_SystemReset(); } -static void cli_cmd_save(const char *cmd_name, char *args) { +static void cli_cmd_save(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { if (!cc_save()) { cli_print_line("Saving unsuccessful, trying force save..."); if (!cc_format_save()) { @@ -176,11 +179,11 @@ static void cli_cmd_save(const char *cmd_name, char *args) { } static void cli_cmd_get(const char *cmd_name, char *args) { - const cli_value_t *val; + const cli_value_t *val{nullptr}; int matched_commands = 0; for (uint32_t i = 0; i < value_table_entry_count; i++) { - if (strstr(value_table[i].name, args)) { + if (strstr(value_table[i].name, args) != nullptr) { val = &value_table[i]; if (matched_commands > 0) { cli_print_linefeed(); @@ -195,11 +198,12 @@ static void cli_cmd_get(const char *cmd_name, char *args) { } } - if (!matched_commands) { + if (matched_commands == 0) { cli_print_error_linef(cmd_name, "INVALID NAME"); } } +// NOLINTNEXTLINE(readability-function-cognitive-complexity) static void cli_cmd_set(const char *cmd_name, char *args) { const uint32_t arg_len = strlen(args); char *eqptr = nullptr; @@ -208,9 +212,9 @@ static void cli_cmd_set(const char *cmd_name, char *args) { cli_print_line("Current settings: "); // when arg_len is 1 (when * is passed as argument), it will print min/max values as well, for gui - print_cats_config(cmd_name, &global_cats_config, arg_len); + print_cats_config(cmd_name, &global_cats_config, arg_len > 0); - } else if ((eqptr = strstr(args, "=")) != nullptr) { + } else if ((eqptr = strstr(args, "=")) != nullptr) { // NOLINT(bugprone-assignment-in-if-condition) // has equals const uint8_t variable_name_length = get_word_length(args, eqptr); @@ -238,7 +242,7 @@ static void cli_cmd_set(const char *cmd_name, char *args) { value_changed = true; } } else { - int value = atoi(eqptr); + const int value = atoi(eqptr); int min = 0; int max = 0; @@ -285,13 +289,14 @@ static void cli_cmd_set(const char *cmd_name, char *args) { // process substring starting at valPtr // note: no need to copy substrings for atoi() // it stops at the first character that cannot be converted... + // NOLINTBEGIN(google-readability-casting) switch (val->type & VALUE_TYPE_MASK) { default: case VAR_UINT8: { // fetch data pointer uint8_t *data = (uint8_t *)var_ptr + i; // store value - *data = (uint8_t)atoi((const char *)valPtr); + *data = static_cast(atoi(static_cast(valPtr))); } break; @@ -299,7 +304,7 @@ static void cli_cmd_set(const char *cmd_name, char *args) { // fetch data pointer int8_t *data = (int8_t *)var_ptr + i; // store value - *data = (int8_t)atoi((const char *)valPtr); + *data = static_cast(atoi(static_cast(valPtr))); } break; @@ -307,7 +312,7 @@ static void cli_cmd_set(const char *cmd_name, char *args) { // fetch data pointer uint16_t *data = (uint16_t *)var_ptr + i; // store value - *data = (uint16_t)atoi((const char *)valPtr); + *data = static_cast(atoi(static_cast(valPtr))); } break; @@ -315,7 +320,7 @@ static void cli_cmd_set(const char *cmd_name, char *args) { // fetch data pointer int16_t *data = (int16_t *)var_ptr + i; // store value - *data = (int16_t)atoi((const char *)valPtr); + *data = static_cast(atoi(static_cast(valPtr))); } break; @@ -323,11 +328,12 @@ static void cli_cmd_set(const char *cmd_name, char *args) { // fetch data pointer uint32_t *data = (uint32_t *)var_ptr + i; // store value - *data = (uint32_t)strtoul((const char *)valPtr, nullptr, 10); + *data = static_cast(strtoul(static_cast(valPtr), nullptr, 10)); } break; } + // NOLINTEND(google-readability-casting) // find next comma (or end of string) valPtr = strchr(valPtr, ',') + 1; @@ -342,7 +348,7 @@ static void cli_cmd_set(const char *cmd_name, char *args) { case MODE_STRING: { char *val_ptr = eqptr; val_ptr = skip_space(val_ptr); - char *var_ptr = (char *)get_cats_config_member_ptr(&global_cats_config, val); + char *var_ptr = static_cast(get_cats_config_member_ptr(&global_cats_config, val)); const unsigned int len = strlen(val_ptr); const uint8_t min = val->config.string.min_length; const uint8_t max = val->config.string.max_length; @@ -351,7 +357,7 @@ static void cli_cmd_set(const char *cmd_name, char *args) { if (updatable && len > 0 && len <= max) { memset(var_ptr, 0, max); - if (len >= min && strncmp(val_ptr, emptyName, len)) { + if ((len >= min) && (strncmp(val_ptr, emptyName, len) != 0)) { strncpy(var_ptr, val_ptr, len); } value_changed = true; @@ -380,15 +386,15 @@ static void cli_cmd_set(const char *cmd_name, char *args) { } } -static void cli_cmd_config(const char *cmd_name, char *args) { +static void cli_cmd_config(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { print_control_config(); print_action_config(); print_timer_config(); } -static void cli_cmd_defaults(const char *cmd_name, char *args) { +static void cli_cmd_defaults(const char *cmd_name [[maybe_unused]], char *args) { bool use_default_outputs = true; - if (!strcmp(args, "--no-outputs")) { + if (strcmp(args, "--no-outputs") == 0) { use_default_outputs = false; } cc_defaults(use_default_outputs, true); @@ -399,25 +405,26 @@ static void cli_cmd_dump(const char *cmd_name, char *args) { const uint32_t len = strlen(args); cli_print_linef("#Configuration dump"); - print_cats_config(cmd_name, &global_cats_config, len); + print_cats_config(cmd_name, &global_cats_config, len > 0); cli_printf("#End of configuration dump"); } -static void cli_cmd_status(const char *cmd_name, char *args) { +static void cli_cmd_status(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { cli_printf("System time: %lu ticks\n", osKernelGetTickCount()); auto new_enum = static_cast(osEventFlagsWait(fsm_flag_id, 0xFF, osFlagsNoClear, 0)); if (new_enum > TOUCHDOWN || new_enum < CALIBRATING) { new_enum = INVALID; } cli_printf("State: %s\n", GetStr(new_enum, fsm_map)); - cli_printf("Voltage: %.2fV\n", (double)battery_voltage()); - cli_printf("h: %.2fm, v: %.2fm/s, a: %.2fm/s^2", (double)task::global_state_estimation->GetEstimationOutput().height, - (double)task::global_state_estimation->GetEstimationOutput().velocity, - (double)task::global_state_estimation->GetEstimationOutput().acceleration); + cli_printf("Voltage: %.2fV\n", static_cast(battery_voltage())); + cli_printf("h: %.2fm, v: %.2fm/s, a: %.2fm/s^2", + static_cast(task::global_state_estimation->GetEstimationOutput().height), + static_cast(task::global_state_estimation->GetEstimationOutput().velocity), + static_cast(task::global_state_estimation->GetEstimationOutput().acceleration)); #ifdef CATS_DEBUG - if (!strcmp(args, "--heap")) { + if (strcmp(args, "--heap") == 0) { HeapStats_t heap_stats = {}; vPortGetHeapStats(&heap_stats); cli_print_linef("\nHeap stats"); @@ -433,24 +440,24 @@ static void cli_cmd_status(const char *cmd_name, char *args) { #endif } -static void cli_cmd_version(const char *cmd_name, char *args) { +static void cli_cmd_version(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { cli_printf("Board: %s\n", board_name); cli_printf("Code version: %s\n", code_version); cli_printf("Telemetry Code version: %s\n", telemetry_code_version); } -static void cli_cmd_log_enable(const char *cmd_name, char *args) { log_enable(); } +static void cli_cmd_log_enable(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { log_enable(); } -static void cli_cmd_ls(const char *cmd_name, char *args) { +static void cli_cmd_ls(const char *cmd_name [[maybe_unused]], char *args) { if (args == nullptr) { lfs_ls(cwd); } else { - uint32_t full_path_len = strlen(cwd) + 1 + strlen(args); + const uint32_t full_path_len = strlen(cwd) + 1 + strlen(args); if (full_path_len > LFS_NAME_MAX) { cli_print_line("File path too long!"); return; } - char *full_path = (char *)(pvPortMalloc(full_path_len + 1)); + char *full_path = static_cast(pvPortMalloc(full_path_len + 1)); strcpy(full_path, cwd); strcat(full_path, "/"); strcat(full_path, args); @@ -459,7 +466,7 @@ static void cli_cmd_ls(const char *cmd_name, char *args) { } } -static void cli_cmd_cd(const char *cmd_name, char *args) { +static void cli_cmd_cd(const char *cmd_name [[maybe_unused]], char *args) { /* TODO - check if a directory actually exists */ if (args == nullptr || strcmp(args, "/") == 0) { strncpy(cwd, "/", sizeof(cwd)); @@ -467,18 +474,18 @@ static void cli_cmd_cd(const char *cmd_name, char *args) { /* Return one lvl back by clearing everything after the last path separator. */ const char *last_path_sep = strrchr(cwd, '/'); if (last_path_sep != nullptr) { - uint32_t last_path_sep_loc = last_path_sep - cwd; + const uint32_t last_path_sep_loc = last_path_sep - cwd; cwd[last_path_sep_loc + 1] = '\0'; } } else if (strcmp(args, ".") != 0) { if (args[0] == '/') { /* absolute path */ - uint32_t full_path_len = strlen(args); + const uint32_t full_path_len = strlen(args); if (full_path_len > LFS_NAME_MAX) { cli_print_line("Path too long!"); return; } - char *tmp_path = (char *)(pvPortMalloc(full_path_len + 1)); + char *tmp_path = static_cast(pvPortMalloc(full_path_len + 1)); strcpy(tmp_path, args); if (lfs_obj_type(tmp_path) != LFS_TYPE_DIR) { cli_print_linef("Cannot go to '%s': not a directory!", tmp_path); @@ -489,12 +496,12 @@ static void cli_cmd_cd(const char *cmd_name, char *args) { vPortFree(tmp_path); } else { /* relative path */ - uint32_t full_path_len = strlen(cwd) + 1 + strlen(args); + const uint32_t full_path_len = strlen(cwd) + 1 + strlen(args); if (full_path_len > LFS_NAME_MAX) { cli_print_line("Path too long!"); return; } - char *tmp_path = (char *)(pvPortMalloc(full_path_len + 1)); + char *tmp_path = static_cast(pvPortMalloc(full_path_len + 1)); strcpy(tmp_path, args); if (lfs_obj_type(tmp_path) != LFS_TYPE_DIR) { cli_print_linef("Cannot go to '%s': not a directory!", tmp_path); @@ -507,16 +514,16 @@ static void cli_cmd_cd(const char *cmd_name, char *args) { } } -static void cli_cmd_rm(const char *cmd_name, char *args) { +static void cli_cmd_rm(const char *cmd_name [[maybe_unused]], char *args) { if (args != nullptr) { /* +1 for the path separator (/) */ - uint32_t full_path_len = strlen(cwd) + 1 + strlen(args); + const uint32_t full_path_len = strlen(cwd) + 1 + strlen(args); if (full_path_len > LFS_NAME_MAX) { cli_print_line("File path too long!"); return; } /* +1 for the null terminator */ - char *full_path = (char *)(pvPortMalloc(full_path_len + 1)); + char *full_path = static_cast(pvPortMalloc(full_path_len + 1)); strcpy(full_path, cwd); strcat(full_path, "/"); strcat(full_path, args); @@ -527,7 +534,7 @@ static void cli_cmd_rm(const char *cmd_name, char *args) { return; } - int32_t rm_err = lfs_remove(&lfs, full_path); + const int32_t rm_err = lfs_remove(&lfs, full_path); if (rm_err < 0) { cli_print_linef("Removal of file '%s' failed with %ld", full_path, rm_err); } @@ -538,7 +545,7 @@ static void cli_cmd_rm(const char *cmd_name, char *args) { } } -static void cli_cmd_rec_info(const char *cmd_name, char *args) { +static void cli_cmd_rec_info(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { const lfs_ssize_t curr_sz_blocks = lfs_fs_size(&lfs); const int32_t num_flights = lfs_cnt("/flights", LFS_TYPE_REG); const int32_t num_stats = lfs_cnt("/stats", LFS_TYPE_REG); @@ -551,7 +558,8 @@ static void cli_cmd_rec_info(const char *cmd_name, char *args) { const lfs_size_t block_size_kb = get_lfs_cfg()->block_size / 1024; const lfs_size_t curr_sz_kb = curr_sz_blocks * block_size_kb; const lfs_size_t total_sz_kb = block_size_kb * get_lfs_cfg()->block_count; - const double percentage_used = (double)curr_sz_kb / total_sz_kb * 100; + const double percentage_used = + static_cast(curr_sz_kb) / static_cast(static_cast(total_sz_kb) * 100); cli_print_linef("Space:\n Total: %lu KB\n Used: %lu KB (%.2f%%)\n Free: %lu KB (%.2f%%)", total_sz_kb, curr_sz_kb, percentage_used, total_sz_kb - curr_sz_kb, 100 - percentage_used); @@ -599,11 +607,11 @@ static int32_t get_flight_idx(const char *log_idx_arg) { return -1; } - return flight_idx; + return static_cast(flight_idx); } -static void cli_cmd_dump_flight(const char *cmd_name, char *args) { - int32_t flight_idx_or_err = get_flight_idx(args); +static void cli_cmd_dump_flight(const char *cmd_name [[maybe_unused]], char *args) { + const int32_t flight_idx_or_err = get_flight_idx(args); if (flight_idx_or_err > 0) { cli_print_linefeed(); @@ -612,10 +620,10 @@ static void cli_cmd_dump_flight(const char *cmd_name, char *args) { } /* flight_parse [--filter ...] */ -static void cli_cmd_parse_flight(const char *cmd_name, char *args) { +static void cli_cmd_parse_flight(const char *cmd_name [[maybe_unused]], char *args) { char *ptr = strtok(args, " "); - int32_t flight_idx_or_err = get_flight_idx(ptr); + const int32_t flight_idx_or_err = get_flight_idx(ptr); auto filter_mask = static_cast(0); if (flight_idx_or_err < 0) { @@ -625,33 +633,53 @@ static void cli_cmd_parse_flight(const char *cmd_name, char *args) { /* Read filter command */ ptr = strtok(nullptr, " "); if (ptr != nullptr) { - if (!strcmp(ptr, "--filter")) { + if (strcmp(ptr, "--filter") == 0) { /*Read filter types */ while (ptr != nullptr) { - if (!strcmp(ptr, "IMU")) filter_mask = (rec_entry_type_e)(filter_mask | IMU); - if (!strcmp(ptr, "BARO")) filter_mask = (rec_entry_type_e)(filter_mask | BARO); - if (!strcmp(ptr, "FLIGHT_INFO")) filter_mask = (rec_entry_type_e)(filter_mask | FLIGHT_INFO); - if (!strcmp(ptr, "ORIENTATION_INFO")) filter_mask = (rec_entry_type_e)(filter_mask | ORIENTATION_INFO); - if (!strcmp(ptr, "FILTERED_DATA_INFO")) filter_mask = (rec_entry_type_e)(filter_mask | FILTERED_DATA_INFO); - if (!strcmp(ptr, "FLIGHT_STATE")) filter_mask = (rec_entry_type_e)(filter_mask | FLIGHT_STATE); - if (!strcmp(ptr, "EVENT_INFO")) filter_mask = (rec_entry_type_e)(filter_mask | EVENT_INFO); - if (!strcmp(ptr, "ERROR_INFO")) filter_mask = (rec_entry_type_e)(filter_mask | ERROR_INFO); - if (!strcmp(ptr, "GNSS_INFO")) filter_mask = (rec_entry_type_e)(filter_mask | GNSS_INFO); - if (!strcmp(ptr, "VOLTAGE_INFO")) filter_mask = (rec_entry_type_e)(filter_mask | VOLTAGE_INFO); + if (strcmp(ptr, "IMU") == 0) { + filter_mask = static_cast(filter_mask | IMU); + } + if (strcmp(ptr, "BARO") == 0) { + filter_mask = static_cast(filter_mask | BARO); + } + if (strcmp(ptr, "FLIGHT_INFO") == 0) { + filter_mask = static_cast(filter_mask | FLIGHT_INFO); + } + if (strcmp(ptr, "ORIENTATION_INFO") == 0) { + filter_mask = static_cast(filter_mask | ORIENTATION_INFO); + } + if (strcmp(ptr, "FILTERED_DATA_INFO") == 0) { + filter_mask = static_cast(filter_mask | FILTERED_DATA_INFO); + } + if (strcmp(ptr, "FLIGHT_STATE") == 0) { + filter_mask = static_cast(filter_mask | FLIGHT_STATE); + } + if (strcmp(ptr, "EVENT_INFO") == 0) { + filter_mask = static_cast(filter_mask | EVENT_INFO); + } + if (strcmp(ptr, "ERROR_INFO") == 0) { + filter_mask = static_cast(filter_mask | ERROR_INFO); + } + if (strcmp(ptr, "GNSS_INFO") == 0) { + filter_mask = static_cast(filter_mask | GNSS_INFO); + } + if (strcmp(ptr, "VOLTAGE_INFO") == 0) { + filter_mask = static_cast(filter_mask | VOLTAGE_INFO); + } ptr = strtok(nullptr, " "); } } else { cli_print_linef("\nBad option: %s!", ptr); } } else { - filter_mask = (rec_entry_type_e)(UINT32_MAX); + filter_mask = static_cast(UINT32_MAX); } reader::parse_recording(flight_idx_or_err, filter_mask); } -static void cli_cmd_print_stats(const char *cmd_name, char *args) { - int32_t flight_idx_or_err = get_flight_idx(args); +static void cli_cmd_print_stats(const char *cmd_name [[maybe_unused]], char *args) { + const int32_t flight_idx_or_err = get_flight_idx(args); if (flight_idx_or_err > 0) { cli_print_linefeed(); @@ -659,7 +687,7 @@ static void cli_cmd_print_stats(const char *cmd_name, char *args) { } } -static void cli_cmd_lfs_format(const char *cmd_name, char *args) { +static void cli_cmd_lfs_format(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { cli_print_line("\nTrying LFS format"); lfs_format(&lfs, get_lfs_cfg()); const int err = lfs_mount(&lfs, get_lfs_cfg()); @@ -677,7 +705,7 @@ static void cli_cmd_lfs_format(const char *cmd_name, char *args) { } } -static void cli_cmd_erase_flash(const char *cmd_name, char *args) { +static void cli_cmd_erase_flash(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { cli_print_line("\nErasing the flash, this might take a while..."); w25q_chip_erase(); cli_print_line("Flash erased!"); @@ -706,28 +734,29 @@ static void cli_cmd_erase_flash(const char *cmd_name, char *args) { strncpy(cwd, "/", sizeof(cwd)); } -static void cli_cmd_flash_write(const char *cmd_name, char *args) { +static void cli_cmd_flash_write(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { cli_print_line("\nSetting recorder state to REC_WRITE_TO_FLASH"); set_recorder_state(REC_WRITE_TO_FLASH); } -static void cli_cmd_flash_stop(const char *cmd_name, char *args) { +static void cli_cmd_flash_stop(const char *cmd_name [[maybe_unused]], char *args [[maybe_unused]]) { cli_print_line("\nSetting recorder state to REC_FILL_QUEUE"); set_recorder_state(REC_FILL_QUEUE); } -static void cli_cmd_flash_test(const char *cmd_name, char *args) { +// NOLINTNEXTLINE(readability-function-cognitive-complexity) +static void cli_cmd_flash_test(const char *cmd_name [[maybe_unused]], char *args) { uint8_t write_buf[256] = {}; uint8_t read_buf[256] = {}; fill_buf(write_buf, 256); // w25q_chip_erase(); - if (!strcmp(args, "full")) { + if (strcmp(args, "full") == 0) { cli_print_line("\nStep 1: Erasing the chip sector by sector..."); for (uint32_t i = 0; i < w25q.sector_count; ++i) { if (i % 100 == 0) { cli_print_linef("%lu / %lu sectors erased...", i, w25q.sector_count); } - w25q_status_e sector_erase_status = w25q_sector_erase(i); + const w25q_status_e sector_erase_status = w25q_sector_erase(i); if (sector_erase_status != W25Q_OK) { cli_print_linef("Sector erase error encountered at sector %lu; status %d", i, sector_erase_status); osDelay(5000); @@ -739,7 +768,7 @@ static void cli_cmd_flash_test(const char *cmd_name, char *args) { if (i % 100 == 0) { cli_print_linef("%lu / %lu pages written...", i, w25q.page_count); } - w25q_status_e write_status = w25qxx_write_page(write_buf, i, 0, 256); + const w25q_status_e write_status = w25qxx_write_page(write_buf, i, 0, 256); if (write_status != W25Q_OK) { cli_print_linef("Write error encountered at page %lu; status %d", i, write_status); osDelay(5000); @@ -752,7 +781,7 @@ static void cli_cmd_flash_test(const char *cmd_name, char *args) { if (i % 100 == 0) { cli_print_linef("%lu / %lu pages read...", i, w25q.page_count); } - w25q_status_e read_status = w25qxx_read_page(read_buf, i, 0, 256); + const w25q_status_e read_status = w25qxx_read_page(read_buf, i, 0, 256); if (read_status != W25Q_OK) { cli_print_linef("Read error encountered at page %lu; status %d", i, read_status); osDelay(1); @@ -768,7 +797,7 @@ static void cli_cmd_flash_test(const char *cmd_name, char *args) { if (i % 100 == 0) { cli_print_linef("%lu / %lu sectors erased...", i, w25q.sector_count); } - w25q_status_e sector_erase_status = w25q_sector_erase(i); + const w25q_status_e sector_erase_status = w25q_sector_erase(i); if (sector_erase_status != W25Q_OK) { cli_print_linef("Sector erase error encountered at sector %lu; status %d", i, sector_erase_status); osDelay(5000); @@ -776,7 +805,7 @@ static void cli_cmd_flash_test(const char *cmd_name, char *args) { } } else { char *endptr = nullptr; - uint32_t sector_idx = strtoul(args, &endptr, 10); + const uint32_t sector_idx = strtoul(args, &endptr, 10); if (args != endptr) { if (sector_idx >= w25q.sector_count) { cli_print_linef("Sector %lu not found!", sector_idx); @@ -798,7 +827,7 @@ static void cli_cmd_flash_test(const char *cmd_name, char *args) { if (i % 4 == 0) { cli_print_linef("%lu / %lu pages written...", i - start_page_idx, pages_per_sector); } - w25q_status_e write_status = w25qxx_write_page(write_buf, i, 0, 256); + const w25q_status_e write_status = w25qxx_write_page(write_buf, i, 0, 256); if (write_status != W25Q_OK) { cli_print_linef("Write error encountered at page %lu; status %d", i, write_status); osDelay(5000); @@ -811,7 +840,7 @@ static void cli_cmd_flash_test(const char *cmd_name, char *args) { if (i % 4 == 0) { cli_print_linef("%lu / %lu pages read...", i - start_page_idx, pages_per_sector); } - w25q_status_e read_status = w25qxx_read_page(read_buf, i, 0, 256); + const w25q_status_e read_status = w25qxx_read_page(read_buf, i, 0, 256); if (read_status != W25Q_OK) { cli_print_linef("Read error encountered at page %lu; status %d", i, read_status); osDelay(1); @@ -834,7 +863,7 @@ static void cli_cmd_flash_test(const char *cmd_name, char *args) { } #ifdef CATS_DEBUG -static void cli_cmd_start_simulation(const char *cmd_name, char *args) { start_simulation(args); } +static void cli_cmd_start_simulation(const char *cmd_name [[maybe_unused]], char *args) { start_simulation(args); } #endif /** Helper function definitions **/ @@ -851,7 +880,7 @@ static void print_action_config() { const EnumToStrMap &p_action_table = lookup_tables[TABLE_ACTIONS]; cli_printf("\n * ACTION CONFIGURATION *\n"); - config_action_t action; + config_action_t action{}; for (int i = 0; i < NUM_EVENTS; i++) { const auto ev = static_cast(i); int nr_actions = cc_get_num_actions(ev); @@ -882,6 +911,10 @@ static void print_timer_config() { } } +// TODO: The casts in this function can be fixed with: +// *(reinterpret_cast(const_cast(ptr))) = static_cast(value); +// But it should be tested. +// NOLINTBEGIN(google-readability-casting) static void cli_set_var(const cli_value_t *var, const uint32_t value) { const void *ptr = get_cats_config_member_ptr(&global_cats_config, var); @@ -891,8 +924,8 @@ static void cli_set_var(const cli_value_t *var, const uint32_t value) { if ((var->type & VALUE_MODE_MASK) == MODE_BITSET) { switch (var->type & VALUE_TYPE_MASK) { case VAR_UINT8: - mask = (1 << var->config.bitpos) & 0xff; - if (value) { + mask = (1U << var->config.bitpos) & 0xffU; + if (value > 0) { work_value = *(uint8_t *)ptr | mask; } else { work_value = *(uint8_t *)ptr & ~mask; @@ -901,8 +934,8 @@ static void cli_set_var(const cli_value_t *var, const uint32_t value) { break; case VAR_UINT16: - mask = (1 << var->config.bitpos) & 0xffff; - if (value) { + mask = (1U << var->config.bitpos) & 0xffffU; + if (value > 0) { work_value = *(uint16_t *)ptr | mask; } else { work_value = *(uint16_t *)ptr & ~mask; @@ -911,8 +944,8 @@ static void cli_set_var(const cli_value_t *var, const uint32_t value) { break; case VAR_UINT32: - mask = 1 << var->config.bitpos; - if (value) { + mask = 1U << var->config.bitpos; + if (value > 0) { work_value = *(uint32_t *)ptr | mask; } else { work_value = *(uint32_t *)ptr & ~mask; @@ -927,6 +960,7 @@ static void cli_set_var(const cli_value_t *var, const uint32_t value) { break; case VAR_INT8: + // NOLINTNEXTLINE(bugprone-narrowing-conversions) *(int8_t *)ptr = value; break; @@ -935,6 +969,7 @@ static void cli_set_var(const cli_value_t *var, const uint32_t value) { break; case VAR_INT16: + // NOLINTNEXTLINE(bugprone-narrowing-conversions) *(int16_t *)ptr = value; break; @@ -944,6 +979,7 @@ static void cli_set_var(const cli_value_t *var, const uint32_t value) { } } } +// NOLINTEND(google-readability-casting) static void fill_buf(uint8_t *buf, size_t buf_sz) { for (uint32_t i = 0; i < buf_sz / 2; ++i) { diff --git a/flight_computer/src/cli/cli_commands.hpp b/flight_computer/src/cli/cli_commands.hpp index 5ef05a61..e1e98e91 100644 --- a/flight_computer/src/cli/cli_commands.hpp +++ b/flight_computer/src/cli/cli_commands.hpp @@ -30,6 +30,7 @@ struct clicmd_t { cli_command_fn *cli_command; }; +// NOLINTNEXTLINE(cppcoreguidelines-macro-usage) #define CLI_COMMAND_DEF(name, description, args, cli_command) \ { name, description, args, cli_command } diff --git a/flight_computer/src/cli/settings.cpp b/flight_computer/src/cli/settings.cpp index dfc14afb..2ada48ac 100644 --- a/flight_computer/src/cli/settings.cpp +++ b/flight_computer/src/cli/settings.cpp @@ -139,6 +139,7 @@ const cli_value_t value_table[] = { const uint16_t value_table_entry_count = ARRAYLEN(value_table); void *get_cats_config_member_ptr(const cats_config_t *cfg, const cli_value_t *var) { + // NOLINTNEXTLINE(google-readability-casting) return ((uint8_t *)cfg) + var->member_offset; } @@ -148,6 +149,7 @@ void print_cats_config(const char *cmd_name, const cats_config_t *cfg, bool prin prefix = "set "; } + // NOLINTNEXTLINE(modernize-loop-convert) for (uint32_t i = 0; i < value_table_entry_count; i++) { const cli_value_t *val = &value_table[i]; cli_printf("%s%s = ", prefix, value_table[i].name); diff --git a/flight_computer/src/cli/settings.hpp b/flight_computer/src/cli/settings.hpp index 22ee5e92..0bdd6d52 100644 --- a/flight_computer/src/cli/settings.hpp +++ b/flight_computer/src/cli/settings.hpp @@ -24,33 +24,34 @@ #include "config/cats_config.hpp" #include "util/enum_str_maps.hpp" +// NOLINTNEXTLINE(cppcoreguidelines-macro-usage) #define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0])) enum lookup_table_index_e { TABLE_EVENTS = 0, TABLE_ACTIONS, TABLE_POWER, TABLE_SPEEDS, TABLE_BATTERY }; -#define VALUE_TYPE_OFFSET 0 -#define VALUE_SECTION_OFFSET 3 -#define VALUE_MODE_OFFSET 5 +inline constexpr uint8_t VALUE_TYPE_OFFSET = 0; +inline constexpr uint8_t VALUE_SECTION_OFFSET = 3; +inline constexpr uint8_t VALUE_MODE_OFFSET = 5; enum cli_value_flag_e { // value type, bits 0-2 - VAR_UINT8 = (0 << VALUE_TYPE_OFFSET), - VAR_INT8 = (1 << VALUE_TYPE_OFFSET), - VAR_UINT16 = (2 << VALUE_TYPE_OFFSET), - VAR_INT16 = (3 << VALUE_TYPE_OFFSET), - VAR_UINT32 = (4 << VALUE_TYPE_OFFSET), + VAR_UINT8 = (0U << VALUE_TYPE_OFFSET), + VAR_INT8 = (1U << VALUE_TYPE_OFFSET), + VAR_UINT16 = (2U << VALUE_TYPE_OFFSET), + VAR_INT16 = (3U << VALUE_TYPE_OFFSET), + VAR_UINT32 = (4U << VALUE_TYPE_OFFSET), // value mode, bits 5-7 - MODE_DIRECT = (0 << VALUE_MODE_OFFSET), - MODE_LOOKUP = (1 << VALUE_MODE_OFFSET), - MODE_ARRAY = (2 << VALUE_MODE_OFFSET), - MODE_BITSET = (3 << VALUE_MODE_OFFSET), - MODE_STRING = (4 << VALUE_MODE_OFFSET), + MODE_DIRECT = (0U << VALUE_MODE_OFFSET), + MODE_LOOKUP = (1U << VALUE_MODE_OFFSET), + MODE_ARRAY = (2U << VALUE_MODE_OFFSET), + MODE_BITSET = (3U << VALUE_MODE_OFFSET), + MODE_STRING = (4U << VALUE_MODE_OFFSET), }; -#define VALUE_TYPE_MASK (0x07) -#define VALUE_SECTION_MASK (0x18) -#define VALUE_MODE_MASK (0xE0) +inline constexpr uint32_t VALUE_TYPE_MASK = 0x07; +inline constexpr uint32_t VALUE_SECTION_MASK = 0x18; +inline constexpr uint32_t VALUE_MODE_MASK = 0xE0; struct cli_minmax_config_t { const int16_t min; @@ -76,8 +77,8 @@ struct cli_string_length_config_t { const uint8_t flags; }; -#define STRING_FLAGS_NONE (0) -#define STRING_FLAGS_WRITEONCE (1 << 0) +inline constexpr uint32_t STRING_FLAGS_NONE = 0; +inline constexpr uint32_t STRING_FLAGS_WRITEONCE = 1U << 0U; union cli_value_config_u { cli_lookup_table_config_t lookup; // used for MODE_LOOKUP excl. VAR_UINT32 diff --git a/flight_computer/src/comm/fifo.cpp b/flight_computer/src/comm/fifo.cpp index e88239f1..adbbdc3e 100644 --- a/flight_computer/src/comm/fifo.cpp +++ b/flight_computer/src/comm/fifo.cpp @@ -28,7 +28,7 @@ void fifo_init(fifo_t *fifo, uint8_t *buf, uint32_t size) { } void fifo_reset(fifo_t *fifo) { - if (fifo->mutex == false) { + if (!fifo->mutex) { fifo->mutex = true; fifo->tail = 0; fifo->head = 0; @@ -40,13 +40,13 @@ void fifo_reset(fifo_t *fifo) { uint32_t fifo_get_length(const fifo_t *const fifo) { return fifo->used; } bool fifo_read_byte(fifo_t *const fifo, uint8_t *byte_ptr) { - if (fifo->mutex == false) { + if (!fifo->mutex) { fifo->mutex = true; if (fifo->used == 0) { fifo->mutex = false; return false; } - uint8_t data = fifo->buf[fifo->tail]; + const uint8_t data = fifo->buf[fifo->tail]; fifo->tail = (fifo->tail + 1) % fifo->size; fifo->used--; fifo->mutex = false; @@ -57,7 +57,7 @@ bool fifo_read_byte(fifo_t *const fifo, uint8_t *byte_ptr) { } bool fifo_write_byte(fifo_t *const fifo, uint8_t data) { - if (fifo->mutex == false) { + if (!fifo->mutex) { fifo->mutex = true; if (fifo->used >= fifo->size) { fifo->mutex = false; @@ -73,15 +73,15 @@ bool fifo_write_byte(fifo_t *const fifo, uint8_t data) { } bool fifo_read(fifo_t *const fifo, uint8_t *data, uint32_t count) { - if (fifo->mutex == false) { + if (!fifo->mutex) { fifo->mutex = true; if (fifo->used < count) { fifo->mutex = false; return false; } if (fifo->tail + count > fifo->size) { - uint32_t front = (fifo->tail + count) % fifo->size; - uint32_t back = count - front; + const uint32_t front = (fifo->tail + count) % fifo->size; + const uint32_t back = count - front; memcpy(&data[0], &fifo->buf[fifo->tail], back); memcpy(&data[back], &fifo->buf[0], front); } else { @@ -97,15 +97,15 @@ bool fifo_read(fifo_t *const fifo, uint8_t *data, uint32_t count) { bool fifo_write(fifo_t *const fifo, const uint8_t *data, uint32_t count) { // If there is not enough space return false - if (fifo->mutex == false) { + if (!fifo->mutex) { fifo->mutex = true; if ((fifo->size - fifo->used) < count) { fifo->mutex = false; return false; } if (count + fifo->head > fifo->size) { - uint32_t front = fifo->head + count - fifo->size; - uint32_t back = count - front; + const uint32_t front = fifo->head + count - fifo->size; + const uint32_t back = count - front; memcpy(&fifo->buf[fifo->head], data, back); memcpy(&fifo->buf[0], &data[back], front); } else { @@ -120,14 +120,15 @@ bool fifo_write(fifo_t *const fifo, const uint8_t *data, uint32_t count) { } uint32_t fifo_read_until(fifo_t *const fifo, uint8_t *data, uint8_t delimiter, uint32_t count) { - uint32_t max; + uint32_t max{0}; bool found = false; - if (count > fifo->used) + if (count > fifo->used) { max = fifo->used; - else + } else { max = count; + } - uint32_t i; + uint32_t i{0}; for (i = 0; i < max; i++) { if (fifo->buf[(fifo->tail + i) % fifo->size] == delimiter) { found = true; @@ -137,7 +138,7 @@ uint32_t fifo_read_until(fifo_t *const fifo, uint8_t *data, uint8_t delimiter, u if (found) { fifo_read(fifo, data, i); - uint8_t dummy; + uint8_t dummy{0}; fifo_read_byte(fifo, &dummy); return i; } diff --git a/flight_computer/src/comm/stream.cpp b/flight_computer/src/comm/stream.cpp index 025ae669..e8c2d0f7 100644 --- a/flight_computer/src/comm/stream.cpp +++ b/flight_computer/src/comm/stream.cpp @@ -37,7 +37,7 @@ bool stream_read_byte(const stream_t *stream, uint8_t *byte_ptr) { do { ret |= fifo_read_byte(stream->fifo, byte_ptr); - if (ret == true) { + if (ret) { break; } sysDelay(1); @@ -51,7 +51,7 @@ bool stream_write_byte(const stream_t *stream, uint8_t byte) { do { ret |= fifo_write_byte(stream->fifo, byte); - if (ret == true) { + if (ret) { break; } sysDelay(1); @@ -63,11 +63,13 @@ bool stream_read(const stream_t *stream, uint8_t *data, uint32_t len) { bool ret = false; uint32_t timeout = 0; - if (len == 0) return true; + if (len == 0) { + return true; + } do { ret |= fifo_read(stream->fifo, data, len); - if (ret == true) { + if (ret) { break; } sysDelay(1); @@ -79,11 +81,13 @@ bool stream_write(const stream_t *stream, const uint8_t *data, uint32_t len) { bool ret = false; uint32_t timeout = 0; - if (len == 0) return true; + if (len == 0) { + return true; + } do { ret |= fifo_write(stream->fifo, data, len); - if (ret == true) { + if (ret) { break; } sysDelay(1); diff --git a/flight_computer/src/comm/stream_group.cpp b/flight_computer/src/comm/stream_group.cpp index da744bba..fb39015f 100644 --- a/flight_computer/src/comm/stream_group.cpp +++ b/flight_computer/src/comm/stream_group.cpp @@ -22,11 +22,12 @@ #include "comm/stream.hpp" /** USB STREAM GROUP **/ -#define USB_OUT_BUF_SIZE 512 -#define USB_IN_BUF_SIZE 1024 +constexpr uint16_t USB_OUT_BUF_SIZE = 512; +constexpr uint16_t USB_IN_BUF_SIZE = 1024; -#define USB_TIMEOUT_MSEC 10 +constexpr uint8_t USB_TIMEOUT_MSEC = 10; +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) static uint8_t usb_fifo_out_buf[USB_OUT_BUF_SIZE]; static uint8_t usb_fifo_in_buf[USB_IN_BUF_SIZE]; @@ -39,3 +40,4 @@ static stream_t usb_stream_in = {.fifo = &usb_fifo_in, .timeout_msec = USB_TIMEO static stream_t usb_stream_out = {.fifo = &usb_fifo_out, .timeout_msec = USB_TIMEOUT_MSEC}; const stream_group_t USB_SG = {.in = &usb_stream_in, .out = &usb_stream_out}; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) diff --git a/flight_computer/src/config/cats_config.cpp b/flight_computer/src/config/cats_config.cpp index 9e263c84..d46d33d1 100644 --- a/flight_computer/src/config/cats_config.cpp +++ b/flight_computer/src/config/cats_config.cpp @@ -17,13 +17,15 @@ */ #include "config/cats_config.hpp" -#include + #include "flash/lfs_custom.hpp" #include "lfs.h" #include "util/actions.hpp" #include "util/enum_str_maps.hpp" #include "util/error_handler.hpp" +#include + const cats_config_t DEFAULT_CONFIG = { .config_version = CONFIG_VERSION, .rec_mask = UINT32_MAX, @@ -64,9 +66,11 @@ const cats_config_t DEFAULT_CONFIG = { /* Assume that when the user starts the board for the first time the default config will be considered theirs. */ .is_set_by_user = true}; +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) cats_config_t global_cats_config = {}; lfs_file_t config_file; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) /** cats config initialization **/ @@ -125,7 +129,7 @@ bool cc_save() { const bool ret = lfs_file_write(&lfs, &config_file, &global_cats_config, sizeof(global_cats_config)) == sizeof(global_cats_config); lfs_file_close(&lfs, &config_file); - if (ret == false) { + if (!ret) { log_error("Error while saving configuration file!"); } return ret; @@ -137,9 +141,11 @@ bool cc_save() { * @return number of actions mapped to event */ uint16_t cc_get_num_actions(cats_event_e event) { - uint16_t i = 0; - uint16_t nr_actions; - if (event > (NUM_EVENTS - 1)) return 0; + uint16_t i{0}; + uint16_t nr_actions{0}; + if (event > (NUM_EVENTS - 1)) { + return 0; + } // Count the number of entries while ((global_cats_config.action_array[event][i] != 0) && (i < 16)) { i += 2; @@ -156,10 +162,13 @@ uint16_t cc_get_num_actions(cats_event_e event) { * @return */ bool cc_get_action(cats_event_e event, uint16_t act_idx, config_action_t* action) { - if ((action == nullptr) || (cc_get_num_actions(event) < (act_idx + 1))) return false; + if ((action == nullptr) || (cc_get_num_actions(event) < (act_idx + 1))) { + return false; + } - int16_t idx = global_cats_config.action_array[event][act_idx * 2]; - int16_t arg = global_cats_config.action_array[event][act_idx * 2 + 1]; + // NOLINTNEXTLINE(bugprone-implicit-widening-of-multiplication-result) + const int16_t idx = global_cats_config.action_array[event][act_idx * 2]; + const int16_t arg = global_cats_config.action_array[event][act_idx * 2 + 1]; if (idx > 0 && idx <= NUM_ACTION_FUNCTIONS) { action->action_idx = idx; diff --git a/flight_computer/src/config/cats_config.hpp b/flight_computer/src/config/cats_config.hpp index 656b8c48..4ea2da88 100644 --- a/flight_computer/src/config/cats_config.hpp +++ b/flight_computer/src/config/cats_config.hpp @@ -19,38 +19,40 @@ #pragma once #include -#include "target.h" + +#include "target.hpp" #include "util/types.hpp" /* The system will reload the default config when the number changes */ -#define CONFIG_VERSION 212U +constexpr uint32_t CONFIG_VERSION = 212U; /* Number of supported recording speeds */ -#define NUM_REC_SPEEDS 10 +constexpr uint8_t NUM_REC_SPEEDS = 10; struct cats_config_t { /* Needs to be in first position */ - uint32_t config_version; + uint32_t config_version{0}; /* A bit mask that specifies which readings to log to the flash */ - uint32_t rec_mask; + uint32_t rec_mask{0}; // Timers - config_timer_t timers[NUM_TIMERS]; + config_timer_t timers[NUM_TIMERS]{}; // Event action map - int16_t action_array[NUM_EVENTS][16]; // 8 (16/2) actions for each event - int16_t initial_servo_position[2]; + int16_t action_array[NUM_EVENTS][16]{}; // 8 (16/2) actions for each event + int16_t initial_servo_position[2]{}; - config_telemetry_t telemetry_settings; - control_settings_t control_settings; - uint8_t buzzer_volume; - battery_type_e battery_type; - uint8_t rec_speed_idx; // == inverse recording rate - 1 + config_telemetry_t telemetry_settings{}; + control_settings_t control_settings{}; + uint8_t buzzer_volume{0}; + battery_type_e battery_type{LI_ION}; + uint8_t rec_speed_idx{0}; // == inverse recording rate - 1 /* Testing Mode */ - bool enable_testing_mode; - bool is_set_by_user; + bool enable_testing_mode{false}; + bool is_set_by_user{false}; }; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern cats_config_t global_cats_config; /** cats config initialization **/ diff --git a/flight_computer/src/config/control_config.hpp b/flight_computer/src/config/control_config.hpp index e31b8365..5101cfb6 100644 --- a/flight_computer/src/config/control_config.hpp +++ b/flight_computer/src/config/control_config.hpp @@ -18,11 +18,13 @@ #pragma once +#include + #define USE_MEDIAN_FILTER -#define MEDIAN_FILTER_SIZE 9 +inline constexpr uint8_t MEDIAN_FILTER_SIZE = 9; -static const float P_INITIAL = 101250.0f; // hPa -static const float GRAVITY = 9.81f; // m/s^2 -static const float TEMPERATURE_0 = 15.0f; // °C -static const float BARO_LIFTOFF_MOV_AVG_SIZE = 500.0f; // samples -> 5 seconds -static const float BARO_LIFTOFF_FAST_MOV_AVG_SIZE = 10.0f; // samples -> 5 seconds +inline constexpr float P_INITIAL = 101250.0F; // hPa +inline constexpr float GRAVITY = 9.81F; // m/s^2 +inline constexpr float TEMPERATURE_0 = 15.0F; // °C +inline constexpr float BARO_LIFTOFF_MOV_AVG_SIZE = 500.0F; // samples -> 5 seconds +inline constexpr float BARO_LIFTOFF_FAST_MOV_AVG_SIZE = 10.0F; // samples -> 5 seconds diff --git a/flight_computer/src/config/globals.cpp b/flight_computer/src/config/globals.cpp index 6e62cc40..564db0be 100644 --- a/flight_computer/src/config/globals.cpp +++ b/flight_computer/src/config/globals.cpp @@ -20,10 +20,9 @@ #include "comm/fifo.hpp" #include "drivers/spi.hpp" -#include "target.h" - -/** Protocol Handles **/ +#include "target.hpp" +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) /** Device Handles **/ // We need these for now, but will eventually get rid of them by replacing the actions with a class @@ -56,3 +55,4 @@ volatile recorder_status_e global_recorder_status = REC_OFF; event_action_map_elem_t* event_action_map = nullptr; char telemetry_code_version[20] = {}; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) \ No newline at end of file diff --git a/flight_computer/src/config/globals.hpp b/flight_computer/src/config/globals.hpp index 95730a65..ec37ab3b 100644 --- a/flight_computer/src/config/globals.hpp +++ b/flight_computer/src/config/globals.hpp @@ -23,14 +23,14 @@ #include "drivers/spi.hpp" #include "flash/recorder.hpp" -#include "target.h" +#include "target.hpp" #include "util/types.hpp" /** Sampling Frequencies **/ -#define CONTROL_SAMPLING_FREQ 100 // in Hz -#define TELEMETRY_SAMPLING_FREQ 10 // in Hz +inline constexpr uint16_t CONTROL_SAMPLING_FREQ = 100; // in Hz +inline constexpr uint16_t TELEMETRY_SAMPLING_FREQ = 10; // in Hz -/** Device Handles **/ +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) /** State Estimation **/ @@ -59,9 +59,11 @@ extern volatile recorder_status_e global_recorder_status; extern event_action_map_elem_t* event_action_map; #ifdef CATS_DEBUG -static constexpr const char* code_version = FIRMWARE_VERSION "-dev"; +inline constexpr const char* code_version = FIRMWARE_VERSION "-dev"; #else -static constexpr const char* code_version = FIRMWARE_VERSION; +inline constexpr const char* code_version = FIRMWARE_VERSION; #endif -static constexpr const char* board_name = "CATS Vega"; +inline constexpr const char* board_name = "CATS Vega"; extern char telemetry_code_version[20]; + +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) \ No newline at end of file diff --git a/flight_computer/src/control/calibration.cpp b/flight_computer/src/control/calibration.cpp index 9d40982e..9e4ef8b3 100644 --- a/flight_computer/src/control/calibration.cpp +++ b/flight_computer/src/control/calibration.cpp @@ -35,23 +35,31 @@ void calibrate_imu(const vf32_t *accel_data, calibration_data_t *calibration) { } } - /* Then get the angle (or here the cos(angle)) between vector and gravity for - * further use */ + /* Then get the angle (or here the cos(angle)) between vector and gravity for further use */ switch (calibration->axis) { case 0: calibration->angle = accel_data->x / GRAVITY; - if (fabsf(calibration->angle) < 0.3f) calibration->angle = 0.3f; - log_info("Calibration chose X Axis with invcos(alpha)*1000 = %ld", (int32_t)(1000 * calibration->angle)); + if (fabsf(calibration->angle) < 0.3F) { + calibration->angle = 0.3F; + } + log_info("Calibration chose X Axis with invcos(alpha)*1000 = %ld", + static_cast(1000 * calibration->angle)); break; case 1: calibration->angle = accel_data->y / GRAVITY; - if (fabsf(calibration->angle) < 0.3f) calibration->angle = 0.3f; - log_info("Calibration chose Y Axis with invcos(alpha)*1000 = %ld", (int32_t)(1000 * calibration->angle)); + if (fabsf(calibration->angle) < 0.3F) { + calibration->angle = 0.3F; + } + log_info("Calibration chose Y Axis with invcos(alpha)*1000 = %ld", + static_cast(1000 * calibration->angle)); break; case 2: calibration->angle = accel_data->z / GRAVITY; - if (fabsf(calibration->angle) < 0.3f) calibration->angle = 0.3f; - log_info("Calibration chose Z Axis with invcos(alpha)*1000 = %ld", (int32_t)(1000 * calibration->angle)); + if (fabsf(calibration->angle) < 0.3F) { + calibration->angle = 0.3F; + } + log_info("Calibration chose Z Axis with invcos(alpha)*1000 = %ld", + static_cast(1000 * calibration->angle)); break; default: break; @@ -64,10 +72,9 @@ bool compute_gyro_calibration(const vf32_t *gyro_data, calibration_data_t *calib static vf32_t averaged_gyro_data = {.x = 0, .y = 0, .z = 0}; /* compute gyro error */ - vf32_t vector_error; - vector_error.x = fabsf(first_gyro_data.x - gyro_data->x); - vector_error.y = fabsf(first_gyro_data.y - gyro_data->y); - vector_error.z = fabsf(first_gyro_data.z - gyro_data->z); + const vf32_t vector_error{.x = fabsf(first_gyro_data.x - gyro_data->x), + .y = fabsf(first_gyro_data.y - gyro_data->y), + .z = fabsf(first_gyro_data.z - gyro_data->z)}; /* check if the gyro error is inside the bounds * if yes, increase counter and compute averaged gyro data @@ -76,9 +83,9 @@ bool compute_gyro_calibration(const vf32_t *gyro_data, calibration_data_t *calib if ((vector_error.x < GYRO_ALLOWED_ERROR_SI) && (vector_error.y < GYRO_ALLOWED_ERROR_SI) && (vector_error.z < GYRO_ALLOWED_ERROR_SI)) { calibration_counter++; - averaged_gyro_data.x += gyro_data->x / (float)GYRO_NUM_SAME_VALUE; - averaged_gyro_data.y += gyro_data->y / (float)GYRO_NUM_SAME_VALUE; - averaged_gyro_data.z += gyro_data->z / (float)GYRO_NUM_SAME_VALUE; + averaged_gyro_data.x += gyro_data->x / static_cast(GYRO_NUM_SAME_VALUE); + averaged_gyro_data.y += gyro_data->y / static_cast(GYRO_NUM_SAME_VALUE); + averaged_gyro_data.z += gyro_data->z / static_cast(GYRO_NUM_SAME_VALUE); } else { calibration_counter = 0; averaged_gyro_data.x = 0; diff --git a/flight_computer/src/control/calibration.hpp b/flight_computer/src/control/calibration.hpp index 484961e6..255af1cf 100644 --- a/flight_computer/src/control/calibration.hpp +++ b/flight_computer/src/control/calibration.hpp @@ -20,8 +20,8 @@ #include "util/types.hpp" -#define GYRO_NUM_SAME_VALUE 200 -#define GYRO_ALLOWED_ERROR_SI 3.0f +inline constexpr uint16_t GYRO_NUM_SAME_VALUE = 200; +inline constexpr float GYRO_ALLOWED_ERROR_SI = 3.0F; void calibrate_imu(const vf32_t *accel_data, calibration_data_t *); bool compute_gyro_calibration(const vf32_t *gyro_data, calibration_data_t *calibration); diff --git a/flight_computer/src/control/data_processing.cpp b/flight_computer/src/control/data_processing.cpp index a4cfb97f..65bb31b0 100644 --- a/flight_computer/src/control/data_processing.cpp +++ b/flight_computer/src/control/data_processing.cpp @@ -17,17 +17,21 @@ */ #include "control/data_processing.hpp" -#include + #include "config/control_config.hpp" +#include + /* a temporary variable "tmp" must be defined beforehand to use these macros */ +// NOLINTNEXTLINE(cppcoreguidelines-macro-usage) #define SWAP(a, b, tmp) \ { \ - tmp = (a); \ + (tmp) = (a); \ (a) = (b); \ - (b) = tmp; \ + (b) = (tmp); \ } +// NOLINTNEXTLINE(cppcoreguidelines-macro-usage) #define SORT_TWO(a, b, tmp) \ { \ if ((a) > (b)) SWAP((a), (b), (tmp)) \ @@ -35,82 +39,100 @@ /* this function returns the median of an array of size MEDIAN_FILTER_SIZE * it assumes that the size of "input_array" is equal to MEDIAN_FILTER_SIZE */ +// NOLINTNEXTLINE(readability-function-cognitive-complexity) float32_t median(float32_t input_array[]) { float32_t array[MEDIAN_FILTER_SIZE]; memcpy(array, input_array, MEDIAN_FILTER_SIZE * sizeof(float32_t)); -#if MEDIAN_FILTER_SIZE == 9 - /* hardwired algorithm - see https://web.archive.org/web/20060613213236/https://www.xilinx.com/xcell/xl23/xl23_16.pdf - */ - float tmp; - SORT_TWO(array[1], array[2], tmp); - SORT_TWO(array[4], array[5], tmp); - SORT_TWO(array[7], array[8], tmp); - SORT_TWO(array[0], array[1], tmp); - SORT_TWO(array[3], array[4], tmp); - SORT_TWO(array[6], array[7], tmp); - SORT_TWO(array[1], array[2], tmp); - SORT_TWO(array[4], array[5], tmp); - SORT_TWO(array[7], array[8], tmp); - SORT_TWO(array[0], array[3], tmp); - SORT_TWO(array[5], array[8], tmp); - SORT_TWO(array[4], array[7], tmp); - SORT_TWO(array[3], array[6], tmp); - SORT_TWO(array[1], array[4], tmp); - SORT_TWO(array[2], array[5], tmp); - SORT_TWO(array[4], array[7], tmp); - SORT_TWO(array[4], array[2], tmp); - SORT_TWO(array[6], array[4], tmp); - SORT_TWO(array[4], array[2], tmp); - return array[4]; -#else - /* quickselect algorithm */ - float a, tmp; - int32_t i, j, m, k = (MEDIAN_FILTER_SIZE >> 1); - int32_t l = 0, r = MEDIAN_FILTER_SIZE - 1; - - while (r > l + 1) { /* keep iterating until our partition is of size less than two */ - m = (l + r) >> 1; - - /* we want the inequalities array[l] <= array[l + 1] <= array[r] to hold */ - SWAP(array[m], array[l + 1], tmp); - SORT_TWO(array[l], array[r], tmp); - SORT_TWO(array[l + 1], array[r], tmp); - SORT_TWO(array[l], array[l + 1], tmp); - - i = l + 1; - j = r; - a = array[l + 1]; - - while (true) { - i++; - j--; - while (array[i] < a) i++; - while (array[j] > a) j--; - if (j < i) break; - SWAP(array[i], array[j], tmp); - } + if constexpr (MEDIAN_FILTER_SIZE == 9) { + /* hardwired algorithm - see + * https://web.archive.org/web/20060613213236/https://www.xilinx.com/xcell/xl23/xl23_16.pdf + */ + float tmp{0.0F}; + SORT_TWO(array[1], array[2], tmp); + SORT_TWO(array[4], array[5], tmp); + SORT_TWO(array[7], array[8], tmp); + SORT_TWO(array[0], array[1], tmp); + SORT_TWO(array[3], array[4], tmp); + SORT_TWO(array[6], array[7], tmp); + SORT_TWO(array[1], array[2], tmp); + SORT_TWO(array[4], array[5], tmp); + SORT_TWO(array[7], array[8], tmp); + SORT_TWO(array[0], array[3], tmp); + SORT_TWO(array[5], array[8], tmp); + SORT_TWO(array[4], array[7], tmp); + SORT_TWO(array[3], array[6], tmp); + SORT_TWO(array[1], array[4], tmp); + SORT_TWO(array[2], array[5], tmp); + SORT_TWO(array[4], array[7], tmp); + SORT_TWO(array[4], array[2], tmp); + SORT_TWO(array[6], array[4], tmp); + SORT_TWO(array[4], array[2], tmp); + return array[4]; + } else { + /* quickselect algorithm */ + float a = 0.0F; + float tmp = 0.0F; + int32_t i = 0; + int32_t j = 0; + int32_t m = 0; + const int32_t k = MEDIAN_FILTER_SIZE >> 1U; + int32_t l = 0; + int32_t r = MEDIAN_FILTER_SIZE - 1; - array[l + 1] = array[j]; - array[j] = a; + while (r > l + 1) { /* keep iterating until our partition is of size less than two */ + // NOLINTNEXTLINE(hicpp-signed-bitwise) + m = (l + r) >> 1U; - /* the partition for the next iteration [l, r] must contain the median */ - if (j >= k) r = j - 1; - if (j <= k) l = i; - } + /* we want the inequalities array[l] <= array[l + 1] <= array[r] to hold */ + SWAP(array[m], array[l + 1], tmp); + SORT_TWO(array[l], array[r], tmp); + SORT_TWO(array[l + 1], array[r], tmp); + SORT_TWO(array[l], array[l + 1], tmp); - /* we have the final partition which is of size 1 or 2 */ - if (r == l + 1) { - SORT_TWO(array[l], array[r], tmp); - } + i = l + 1; + j = r; + a = array[l + 1]; - return array[k]; -#endif + while (true) { + i++; + j--; + while (array[i] < a) { + i++; + } + while (array[j] > a) { + j--; + } + if (j < i) { + break; + } + SWAP(array[i], array[j], tmp); + } + + array[l + 1] = array[j]; + array[j] = a; + + /* the partition for the next iteration [l, r] must contain the median */ + if (j >= k) { + r = j - 1; + } + if (j <= k) { + l = i; + } + } + + /* we have the final partition which is of size 1 or 2 */ + if (r == l + 1) { + SORT_TWO(array[l], array[r], tmp); + } + + return array[k]; + } } /* Todo: Huge Ass comment describing this formula */ float32_t calculate_height(float32_t pressure) { - return (-(powf(pressure / P_INITIAL, (1 / 5.257f)) - 1) * (TEMPERATURE_0 + 273.15f) / 0.0065f); + return (-(powf(pressure / P_INITIAL, (1 / 5.257F)) - 1) * (TEMPERATURE_0 + 273.15F) / 0.0065F); } /* Todo: Huge Ass comment describing Barometric Liftoff Detection */ diff --git a/flight_computer/src/control/data_processing.hpp b/flight_computer/src/control/data_processing.hpp index 0279c67b..c3559ce3 100644 --- a/flight_computer/src/control/data_processing.hpp +++ b/flight_computer/src/control/data_processing.hpp @@ -18,9 +18,10 @@ #pragma once -#include #include "arm_math.h" +#include + float32_t median(float32_t input_array[]); float32_t calculate_height(float32_t pressure); float32_t approx_moving_average(float32_t data, bool is_transparent); diff --git a/flight_computer/src/control/flight_phases.cpp b/flight_computer/src/control/flight_phases.cpp index c9561ca1..9bff7db5 100644 --- a/flight_computer/src/control/flight_phases.cpp +++ b/flight_computer/src/control/flight_phases.cpp @@ -33,7 +33,7 @@ static void change_state_to(flight_fsm_e new_state, cats_event_e event_to_trigge void check_flight_phase(flight_fsm_t *fsm_state, vf32_t acc_data, vf32_t gyro_data, estimation_output_t state_data, const control_settings_t *settings) { /* Save old FSM State */ - flight_fsm_t old_fsm_state = *fsm_state; + const flight_fsm_t old_fsm_state = *fsm_state; /* Check FSM State */ switch (fsm_state->flight_state) { @@ -56,16 +56,11 @@ void check_flight_phase(flight_fsm_t *fsm_state, vf32_t acc_data, vf32_t gyro_da check_main_phase(fsm_state, state_data); break; case TOUCHDOWN: - break; default: break; } - if (old_fsm_state.flight_state != fsm_state->flight_state) { - fsm_state->state_changed = true; - } else { - fsm_state->state_changed = false; - } + fsm_state->state_changed = old_fsm_state.flight_state != fsm_state->flight_state; } static void check_calibrating_phase(flight_fsm_t *fsm_state, vf32_t acc_data, vf32_t gyro_data) { @@ -95,10 +90,10 @@ static void check_calibrating_phase(flight_fsm_t *fsm_state, vf32_t acc_data, vf static void check_ready_phase(flight_fsm_t *fsm_state, vf32_t acc_data, const control_settings_t *settings) { /* Check if we move from READY To THRUSTING */ /* The absolute value of the acceleration is used here to make sure that we detect liftoff */ - float32_t accel_x = acc_data.x * acc_data.x; - float32_t accel_y = acc_data.y * acc_data.y; - float32_t accel_z = acc_data.z * acc_data.z; - float32_t acceleration = accel_x + accel_y + accel_z; + const float32_t accel_x = acc_data.x * acc_data.x; + const float32_t accel_y = acc_data.y * acc_data.y; + const float32_t accel_z = acc_data.z * acc_data.z; + const float32_t acceleration = accel_x + accel_y + accel_z; if (acceleration > (static_cast(settings->liftoff_acc_threshold) * static_cast(settings->liftoff_acc_threshold))) { diff --git a/flight_computer/src/control/flight_phases.hpp b/flight_computer/src/control/flight_phases.hpp index f42ec6b4..3db214c0 100644 --- a/flight_computer/src/control/flight_phases.hpp +++ b/flight_computer/src/control/flight_phases.hpp @@ -20,43 +20,45 @@ #include "util/types.hpp" +#include + /* CALIBRATING */ // num iterations, imu action needs to be 0 for at least 10 seconds -#define TIME_THRESHOLD_CALIB_TO_READY 1000 +inline constexpr uint16_t TIME_THRESHOLD_CALIB_TO_READY = 1000; // m/s^2, if the IMU measurement is smaller than 0.6 m/s^2 it is not considered as movement for the transition // CALIBRATING -> READY -#define ALLOWED_ACC_ERROR 0.6F +inline constexpr float ALLOWED_ACC_ERROR = 0.6F; // dps, if the GYRO measurement is smaller than 10 dps it is not considered as movement for the transition CALIBRATING // -> READY -#define ALLOWED_GYRO_ERROR 10.0F +inline constexpr float ALLOWED_GYRO_ERROR = 10.0F; /* READY */ // num iterations, if the acceleration is bigger than the threshold for 0.1 s we detect liftoff -#define LIFTOFF_SAFETY_COUNTER 10 +inline constexpr uint16_t LIFTOFF_SAFETY_COUNTER = 10; /* THRUSTING */ // num iterations, acceleration needs to be smaller than 0 for at least 0.1 s for the transition THRUSTING -> COASTING -#define COASTING_SAFETY_COUNTER 10 +inline constexpr uint16_t COASTING_SAFETY_COUNTER = 10; /* COASTING */ // num iterations, velocity needs to be smaller than 0 for at least 0.3 s for the transition COASTING -> DROGUE -#define APOGEE_SAFETY_COUNTER 30 +inline constexpr uint16_t APOGEE_SAFETY_COUNTER = 30; /* DROGUE */ // num iterations, height needs to be smaller than user-defined for at least 0.3 s for the transition DROGUE -> MAIN -#define MAIN_SAFETY_COUNTER 30 +inline constexpr uint16_t MAIN_SAFETY_COUNTER = 30; // tick counts [ms] -#define MIN_TICK_COUNTS_BETWEEN_THRUSTING_APOGEE 1500 +inline constexpr uint16_t MIN_TICK_COUNTS_BETWEEN_THRUSTING_APOGEE = 1500; /* MAIN */ // m/s, velocity needs to be smaller than this to detect touchdown -#define VELOCITY_BOUND_TOUCHDOWN 3.0F +inline constexpr float VELOCITY_BOUND_TOUCHDOWN = 3.0F; // num iterations, for at least 1s it needs to be smaller -#define TOUCHDOWN_SAFETY_COUNTER 100 +inline constexpr uint16_t TOUCHDOWN_SAFETY_COUNTER = 100; /* Function which implements the FSM */ void check_flight_phase(flight_fsm_t *fsm_state, vf32_t acc_data, vf32_t gyro_data, estimation_output_t state_data, diff --git a/flight_computer/src/control/kalman_filter.cpp b/flight_computer/src/control/kalman_filter.cpp index 5b933809..26d4555e 100644 --- a/flight_computer/src/control/kalman_filter.cpp +++ b/flight_computer/src/control/kalman_filter.cpp @@ -17,11 +17,14 @@ */ #include "control/kalman_filter.hpp" + +#include "util/error_handler.hpp" + +#include "cmsis_os.h" + #include #include #include -#include "cmsis_os.h" -#include "util/error_handler.hpp" void init_filter_struct(kalman_filter_t *const filter) { arm_mat_init_f32(&filter->Ad, 3, 3, filter->Ad_data); @@ -99,11 +102,11 @@ void initialize_matrices(kalman_filter_t *const filter) { arm_matrix_instance_f32 K_mat; arm_mat_init_f32(&K_mat, 3, 1, K); - float32_t P_hat[9] = {0.1f, 0, 0, 0, 0.1f, 0, 0, 0, 0.1f}; + float32_t P_hat[9] = {0.1F, 0, 0, 0, 0.1F, 0, 0, 0, 0.1F}; arm_matrix_instance_f32 P_hat_mat; arm_mat_init_f32(&P_hat_mat, 3, 3, P_hat); - float32_t P_bar[9] = {0.1f, 0, 0, 0, 0.1f, 0, 0, 0, 0.1f}; + float32_t P_bar[9] = {0.1F, 0, 0, 0, 0.1F, 0, 0, 0, 0.1F}; arm_matrix_instance_f32 P_bar_mat; arm_mat_init_f32(&P_bar_mat, 3, 3, P_bar); @@ -123,8 +126,8 @@ void initialize_matrices(kalman_filter_t *const filter) { void reset_kalman(kalman_filter_t *filter) { log_debug("Resetting Kalman Filter..."); - float32_t x_dash[3] = {0.0f, 10.0f, 0.0f}; - float32_t P_dash[9] = {0.1f, 0.0f, 0.0f, 0.0f, 0.1f, 0.0f, 0.0f, 0.0f, 0.1f}; + float32_t x_dash[3] = {0.0F, 10.0F, 0.0F}; + float32_t P_dash[9] = {0.1F, 0.0F, 0.0F, 0.0F, 0.1F, 0.0F, 0.0F, 0.0F, 0.1F}; memcpy(filter->x_bar_data, x_dash, sizeof(x_dash)); memcpy(filter->x_bar_data, x_dash, sizeof(x_dash)); @@ -134,7 +137,7 @@ void reset_kalman(kalman_filter_t *filter) { void soft_reset_kalman(kalman_filter_t *filter) { log_debug("Resetting Kalman Filter..."); - float32_t P_dash[9] = {0.1f, 0.0f, 0.0f, 0.0f, 0.1f, 0.0f, 0.0f, 0.0f, 0.1f}; + float32_t P_dash[9] = {0.1F, 0.0F, 0.0F, 0.0F, 0.1F, 0.0F, 0.0F, 0.0F, 0.1F}; memcpy(filter->P_hat_data, P_dash, sizeof(P_dash)); memcpy(filter->P_bar_data, P_dash, sizeof(P_dash)); @@ -196,7 +199,7 @@ void kalman_update(kalman_filter_t *filter) { holder_single[0] += filter->R; arm_mat_mult_f32(&filter->P_hat, &filter->H_T, &holder2_vec); - arm_mat_scale_f32(&holder2_vec, 1.0f / holder_single[0], &filter->K); + arm_mat_scale_f32(&holder2_vec, 1.0F / holder_single[0], &filter->K); /* Calculate x_bar = x_hat+K*(y-Hx_hat); */ @@ -224,28 +227,26 @@ void kalman_update(kalman_filter_t *filter) { float32_t R_interpolation(float32_t velocity) { /* Todo: Can be optimized */ - float32_t lower_bound = 20.0F; - float32_t upper_bound = 100.0F; - float32_t f_lower_bound = 0.3981F; - float32_t f_upper_bound = 1.0F; + const float32_t lower_bound = 20.0F; + const float32_t upper_bound = 100.0F; + const float32_t f_lower_bound = 0.3981F; + const float32_t f_upper_bound = 1.0F; - float32_t m = (f_lower_bound - f_upper_bound) / (lower_bound - upper_bound); - float32_t b = f_upper_bound - m * upper_bound; + const float32_t m = (f_lower_bound - f_upper_bound) / (lower_bound - upper_bound); + const float32_t b = f_upper_bound - m * upper_bound; if (velocity < lower_bound) { return powf(f_lower_bound, 5.0F); - } else if (velocity < upper_bound) { + } + if (velocity < upper_bound) { return powf(m * velocity + b, 5.0F); - } else { - return f_upper_bound; } + return f_upper_bound; } void kalman_step(kalman_filter_t *filter, flight_fsm_e flight_state) { /* Update IMU trust value based on flight phase */ switch (flight_state) { case READY: - filter->R = STD_NOISE_BARO_INITIAL; - break; case CALIBRATING: filter->R = STD_NOISE_BARO_INITIAL; break; diff --git a/flight_computer/src/control/kalman_filter.hpp b/flight_computer/src/control/kalman_filter.hpp index f4cbcc49..33c289d4 100644 --- a/flight_computer/src/control/kalman_filter.hpp +++ b/flight_computer/src/control/kalman_filter.hpp @@ -26,15 +26,15 @@ * Hence, the noise matrices are changed over time. At liftoff, the offset is large and close to apogee * it is close to zero. The noise matrices here are therefore not agreeing to the data analysis. */ // Tuned by simulations -#define STD_NOISE_BARO 900.0f +inline constexpr float STD_NOISE_BARO = 900.0F; // From data analysis: 2.6f m - but in practice this value makes the barometer too trustworthy -#define STD_NOISE_BARO_INITIAL 9.0f +inline constexpr float STD_NOISE_BARO_INITIAL = 9.0F; // From data analysis: 0.004f m/s^2 -#define STD_NOISE_IMU 0.004f +inline constexpr float STD_NOISE_IMU = 0.004F; -#define STD_NOISE_OFFSET 0.000001f +inline constexpr float STD_NOISE_OFFSET = 0.000001F; void init_filter_struct(kalman_filter_t *filter); diff --git a/flight_computer/src/control/orientation_filter.cpp b/flight_computer/src/control/orientation_filter.cpp index 4ddf0694..e48c4705 100644 --- a/flight_computer/src/control/orientation_filter.cpp +++ b/flight_computer/src/control/orientation_filter.cpp @@ -24,21 +24,21 @@ void init_orientation_filter(orientation_filter_t* filter) { arm_mat_init_f32(&filter->gyro, 4, 1, filter->gyro_data); arm_mat_init_f32(&filter->estimate, 4, 1, filter->estimate_data); - filter->t_sampl = (float32_t)(1.0f / CONTROL_SAMPLING_FREQ); + filter->t_sampl = static_cast(1.0F / CONTROL_SAMPLING_FREQ); } void reset_orientation_filter(orientation_filter_t* filter) { - filter->estimate_data[0] = 1.0f; - filter->estimate_data[1] = 0.0f; - filter->estimate_data[2] = 0.0f; - filter->estimate_data[3] = 0.0f; + filter->estimate_data[0] = 1.0F; + filter->estimate_data[1] = 0.0F; + filter->estimate_data[2] = 0.0F; + filter->estimate_data[3] = 0.0F; } -void quaternion_kinematics(orientation_filter_t* filter, const vf32_t angular_vel) { - filter->gyro_data[0] = 0.0f; - filter->gyro_data[1] = angular_vel.x / 180.0f * PI; // Convert to rad/s - filter->gyro_data[2] = angular_vel.y / 180.0f * PI; // Convert to rad/s - filter->gyro_data[3] = angular_vel.z / 180.0f * PI; // Convert to rad/s +void quaternion_kinematics(orientation_filter_t* filter, vf32_t angular_vel) { + filter->gyro_data[0] = 0.0F; + filter->gyro_data[1] = angular_vel.x / 180.0F * PI; // Convert to rad/s + filter->gyro_data[2] = angular_vel.y / 180.0F * PI; // Convert to rad/s + filter->gyro_data[3] = angular_vel.z / 180.0F * PI; // Convert to rad/s /* x_hat = x_bar + 1/2*Ts(quat_mult(velocity, x_bar)) */ float32_t holder_data[4] = {}; @@ -50,7 +50,7 @@ void quaternion_kinematics(orientation_filter_t* filter, const vf32_t angular_ve arm_mat_init_f32(&holder2_mat, 4, 1, holder2_data); quaternion_mat(&filter->estimate, &filter->gyro, &holder_mat); - arm_mat_scale_f32(&holder_mat, (float32_t)(0.5f * filter->t_sampl), &holder2_mat); + arm_mat_scale_f32(&holder_mat, static_cast(0.5F * filter->t_sampl), &holder2_mat); arm_mat_add_f32(&holder2_mat, &filter->estimate, &filter->estimate); diff --git a/flight_computer/src/control/orientation_filter.hpp b/flight_computer/src/control/orientation_filter.hpp index 411c5a68..308c5f44 100644 --- a/flight_computer/src/control/orientation_filter.hpp +++ b/flight_computer/src/control/orientation_filter.hpp @@ -31,4 +31,4 @@ struct orientation_filter_t { /* Filter Functions */ void init_orientation_filter(orientation_filter_t* filter); void reset_orientation_filter(orientation_filter_t* filter); -void quaternion_kinematics(orientation_filter_t* filter, const vf32_t angular_vel); +void quaternion_kinematics(orientation_filter_t* filter, vf32_t angular_vel); diff --git a/flight_computer/src/drivers/adc.cpp b/flight_computer/src/drivers/adc.cpp index a81179c2..123adeac 100644 --- a/flight_computer/src/drivers/adc.cpp +++ b/flight_computer/src/drivers/adc.cpp @@ -17,8 +17,9 @@ */ #include "drivers/adc.hpp" -#include "target.h" +#include "target.hpp" +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static uint32_t adc_value[ADC_NUM_CHANNELS]; void adc_init() { HAL_ADC_Start_DMA(&ADC_HANDLE, adc_value, ADC_NUM_CHANNELS); } @@ -30,7 +31,9 @@ uint32_t adc_get(adc_channels_e channel) { HAL_ADC_Start_DMA(&ADC_HANDLE, adc_value, ADC_NUM_CHANNELS); } - if ((channel < 0) || (channel > (ADC_NUM_CHANNELS - 1))) return 0; + if ((channel < 0) || (channel > (ADC_NUM_CHANNELS - 1))) { + return 0; + } return adc_value[channel]; } diff --git a/flight_computer/src/drivers/adc.hpp b/flight_computer/src/drivers/adc.hpp index de433512..7ec90527 100644 --- a/flight_computer/src/drivers/adc.hpp +++ b/flight_computer/src/drivers/adc.hpp @@ -18,7 +18,7 @@ #pragma once -#include "target.h" +#include "target.hpp" enum adc_channels_e { ADC_BATTERY = 0, ADC_PYRO2, ADC_PYRO1 }; diff --git a/flight_computer/src/drivers/buzzer.cpp b/flight_computer/src/drivers/buzzer.cpp index 8f338b55..0c492c37 100644 --- a/flight_computer/src/drivers/buzzer.cpp +++ b/flight_computer/src/drivers/buzzer.cpp @@ -23,6 +23,7 @@ namespace driver { void Buzzer::SetVolume(uint16_t volume) { const uint16_t pwm_depth = m_pwm_channel.GetPwmDepth(); // 100% volume = 50% pwm + // NOLINTNEXTLINE(bugprone-implicit-widening-of-multiplication-result) const uint32_t pwm_ticks = (pwm_depth / 200U) * volume; m_pwm_channel.SetDutyCycleTicks(pwm_ticks); } diff --git a/flight_computer/src/drivers/buzzer.hpp b/flight_computer/src/drivers/buzzer.hpp index 37cf00db..10bc2cee 100644 --- a/flight_computer/src/drivers/buzzer.hpp +++ b/flight_computer/src/drivers/buzzer.hpp @@ -20,7 +20,7 @@ #include "cmsis_os.h" #include "drivers/pwm.hpp" -#include "target.h" +#include "target.hpp" namespace driver { diff --git a/flight_computer/src/drivers/gpio.hpp b/flight_computer/src/drivers/gpio.hpp index 20024ad6..381ac425 100644 --- a/flight_computer/src/drivers/gpio.hpp +++ b/flight_computer/src/drivers/gpio.hpp @@ -18,7 +18,7 @@ #pragma once -#include "target.h" +#include "target.hpp" namespace driver { diff --git a/flight_computer/src/drivers/pwm.cpp b/flight_computer/src/drivers/pwm.cpp index d8f92b67..957717cd 100644 --- a/flight_computer/src/drivers/pwm.cpp +++ b/flight_computer/src/drivers/pwm.cpp @@ -22,7 +22,7 @@ namespace driver { bool Pwm::SetFrequency(uint32_t frequency) { // Calculate the prescaler to get as close to the pwm depth as possible - uint32_t psc = SystemCoreClock / (m_depth * frequency); + const uint32_t psc = SystemCoreClock / (m_depth * frequency); // If the frequency requested is too high we can not set the pwm, reduce the PWM depth if (psc < 1U) { @@ -60,9 +60,9 @@ bool Pwm::SetDutyCycleTicks(const uint32_t dutyCycleTicks) { void Pwm::UpdateDutyCycleTicks() { // calculate pulse duration - uint32_t pulse = static_cast((static_cast(m_period) / static_cast(m_depth)) * - (static_cast(m_duty_cycle_ticks))) - - 1U; + const uint32_t pulse = static_cast((static_cast(m_period) / static_cast(m_depth)) * + (static_cast(m_duty_cycle_ticks))) - + 1U; // Setup pwm channel TIM_OC_InitTypeDef sConfigOC; diff --git a/flight_computer/src/drivers/pwm.hpp b/flight_computer/src/drivers/pwm.hpp index ae9dfcea..07439b50 100644 --- a/flight_computer/src/drivers/pwm.hpp +++ b/flight_computer/src/drivers/pwm.hpp @@ -18,7 +18,7 @@ #pragma once -#include "target.h" +#include "target.hpp" namespace driver { @@ -29,8 +29,7 @@ class Pwm { * @param timer Reference to the HAL timer @injected * @param channel Channel number */ - Pwm(TIM_HandleTypeDef& timer, uint32_t channel) - : m_timer(timer), m_channel(channel), m_period(0U), m_duty_cycle_ticks(0U), m_started(false), m_depth(10000U) {} + Pwm(TIM_HandleTypeDef& timer, uint32_t channel) : m_timer(timer), m_channel(channel) {} /** Set the frequency of the pwm generator * @@ -44,7 +43,7 @@ class Pwm { * * @param depth pwm depth in ticks */ - void SetPwmDepth(const uint16_t depth); + void SetPwmDepth(uint16_t depth); /** Get the pwm depth, the number of possible positions * @@ -57,7 +56,7 @@ class Pwm { * @param dutyCycleTicks duty cycle in pwm ticks * @return true on success */ - bool SetDutyCycleTicks(const uint32_t dutyCycleTicks); + bool SetDutyCycleTicks(uint32_t dutyCycleTicks); /** Start the pwm generation */ @@ -83,13 +82,13 @@ class Pwm { /// Timer channel number uint32_t m_channel; /// Timer period - uint32_t m_period; + uint32_t m_period{0U}; /// Timer duty cycle in ticks - uint32_t m_duty_cycle_ticks; + uint32_t m_duty_cycle_ticks{0U}; /// Started flag - bool m_started; + bool m_started{false}; /// Duty cycle depth - uint16_t m_depth; + uint16_t m_depth{10000U}; }; } // namespace driver diff --git a/flight_computer/src/drivers/servo.hpp b/flight_computer/src/drivers/servo.hpp index ee987040..f799b1a6 100644 --- a/flight_computer/src/drivers/servo.hpp +++ b/flight_computer/src/drivers/servo.hpp @@ -19,7 +19,7 @@ #pragma once #include "drivers/pwm.hpp" -#include "target.h" +#include "target.hpp" namespace driver { diff --git a/flight_computer/src/drivers/spi.hpp b/flight_computer/src/drivers/spi.hpp index 355206d7..3bad1d8a 100644 --- a/flight_computer/src/drivers/spi.hpp +++ b/flight_computer/src/drivers/spi.hpp @@ -18,7 +18,7 @@ #pragma once -#include "target.h" +#include "target.hpp" namespace driver { diff --git a/flight_computer/src/drivers/uart.cpp b/flight_computer/src/drivers/uart.cpp index a808fd4d..aa8383e4 100644 --- a/flight_computer/src/drivers/uart.cpp +++ b/flight_computer/src/drivers/uart.cpp @@ -17,11 +17,13 @@ */ #include "uart.hpp" -#include "target.h" +#include "target.hpp" +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) static uint16_t instance_count = 0; static UART_BUS *buses[MAX_INSTANCES]; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) void uart_init(UART_BUS *bus) { buses[instance_count] = bus; @@ -29,18 +31,24 @@ void uart_init(UART_BUS *bus) { } uint8_t uart_transmit_receive(UART_BUS *bus, uint8_t *tx_buf, uint16_t tx_size, uint8_t *rx_buf, uint16_t rx_size) { - if (bus->busy) return 0; + if (bus->busy) { + return 0; + } HAL_UART_Transmit(bus->uart_handle, tx_buf, tx_size, UART_TIMEOUT); HAL_UART_Receive(bus->uart_handle, rx_buf, rx_size, UART_TIMEOUT); return 1; } uint8_t uart_transmit(UART_BUS *bus, uint8_t *tx_buf, uint16_t tx_size) { - if (bus->busy) return 0; + if (bus->busy) { + return 0; + } return HAL_UART_Transmit(&huart2, tx_buf, tx_size, UART_TIMEOUT); } uint8_t uart_receive(UART_BUS *bus, uint8_t *rx_buf, uint16_t rx_size) { - if (bus->busy) return 0; + if (bus->busy) { + return 0; + } return HAL_UART_Receive(&huart2, rx_buf, rx_size, UART_TIMEOUT); } diff --git a/flight_computer/src/drivers/uart.hpp b/flight_computer/src/drivers/uart.hpp index 2781580a..ed8e809d 100644 --- a/flight_computer/src/drivers/uart.hpp +++ b/flight_computer/src/drivers/uart.hpp @@ -18,9 +18,10 @@ #pragma once -#include #include "stm32f4xx.h" +#include + struct UART_BUS { UART_HandleTypeDef* const uart_handle; uint8_t initialized; @@ -32,5 +33,5 @@ uint8_t uart_transmit(UART_BUS* bus, uint8_t* tx_buf, uint16_t tx_size); uint8_t uart_receive(UART_BUS* bus, uint8_t* rx_buf, uint16_t rx_size); void uart_init(UART_BUS* bus); -#define MAX_INSTANCES 10 -#define UART_TIMEOUT 5 +inline constexpr uint8_t MAX_INSTANCES = 10; +inline constexpr uint8_t UART_TIMEOUT = 5; diff --git a/flight_computer/src/drivers/w25q.cpp b/flight_computer/src/drivers/w25q.cpp index 353fcd06..02da7547 100644 --- a/flight_computer/src/drivers/w25q.cpp +++ b/flight_computer/src/drivers/w25q.cpp @@ -17,12 +17,14 @@ */ #include "drivers/w25q.hpp" -#include "target.h" +#include "target.hpp" #include "util/log.h" #include "util/task_util.hpp" -w25q_t w25q = {.id = W25QINVALID}; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) +w25q_t w25q{}; +// NOLINTBEGIN(cppcoreguidelines-macro-usage) /* Settings */ #define W25Q_CMD_ENABLE_RESET 0x66 #define W25Q_CMD_RESET_DEVICE 0x99 @@ -55,6 +57,7 @@ w25q_t w25q = {.id = W25QINVALID}; #define W25Q_STATUS_REG1_BUSY 0x01 /* Status register 1 write enabled bit */ #define W25Q_STATUS_REG1_WEL 0x02 +// NOLINTEND(cppcoreguidelines-macro-usage) static inline void w25qxx_spi_transmit(uint8_t data) { HAL_SPI_Transmit(&FLASH_SPI_HANDLE, &data, 1, 100); } @@ -64,7 +67,7 @@ static inline uint8_t w25qxx_spi_receive() { return ret; } -static inline void w25qxx_wait_for_write_end(void) { +static inline void w25qxx_wait_for_write_end() { // sysDelay(1); HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_RESET); w25qxx_spi_transmit(W25Q_CMD_READ_STATUS_REG1); @@ -72,13 +75,14 @@ static inline void w25qxx_wait_for_write_end(void) { do { status_reg_val = w25qxx_spi_receive(); sysDelay(1); - } while ((status_reg_val & W25Q_STATUS_REG1_BUSY) == 1); + } while ((status_reg_val & static_cast(W25Q_STATUS_REG1_BUSY)) == 1); HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_SET); } static inline void w25q_send_4_byte_addr(uint32_t address) { uint8_t buf[4]; - uint8_t *addr_ptr = (uint8_t *)&address; + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + auto *addr_ptr = reinterpret_cast(&address); // buf[0] = (address & 0xFF000000) >> 24; // buf[1] = (address & 0xFF0000) >> 16; // buf[2] = (address & 0xFF00) >> 8; @@ -92,9 +96,9 @@ static inline void w25q_send_4_byte_addr(uint32_t address) { static inline void w25q_send_3_byte_addr(uint32_t address) { uint8_t buf[3]; - buf[0] = (address & 0xFF0000) >> 16; - buf[1] = (address & 0xFF00) >> 8; - buf[2] = address & 0xFF; + buf[0] = (address & 0xFF0000U) >> 16U; + buf[1] = (address & 0xFF00U) >> 8U; + buf[2] = address & 0xFFU; // uint8_t *addr_ptr = (uint8_t *)&address; // buf[0] = addr_ptr[3]; // buf[1] = addr_ptr[2]; @@ -103,7 +107,7 @@ static inline void w25q_send_3_byte_addr(uint32_t address) { } // Write enable -int8_t w25q_write_enable(void) { +int8_t w25q_write_enable() { HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_RESET); w25qxx_spi_transmit(W25Q_CMD_WRITE_ENABLE); HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_SET); @@ -125,7 +129,7 @@ static inline void w25qxx_write_status_register(uint8_t status_register, uint8_t HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_SET); } -w25q_status_e w25q_init(void) { +w25q_status_e w25q_init() { w25q.lock = 1; // while (osKernelGetTickCount() < 100) sysDelay(1); HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_SET); @@ -138,7 +142,7 @@ w25q_status_e w25q_init(void) { // log_debug("W25Q ID:0x%lX", device_id); - switch (device_id & 0x0000FFFF) { + switch (device_id & 0x0000FFFFU) { case 0x4020: w25q.id = W25Q512; w25q.block_count = 1024; @@ -230,15 +234,17 @@ w25q_status_e w25q_init(void) { return W25Q_OK; } -w25q_status_e w25q_read_id(uint32_t *w25q_id) { - uint32_t temp0 = 0, temp1 = 0, temp2 = 0; +w25q_status_e w25q_read_id(uint32_t *device_id) { + uint32_t temp0 = 0; + uint32_t temp1 = 0; + uint32_t temp2 = 0; HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_RESET); w25qxx_spi_transmit(W25Q_CMD_JEDEC_ID); temp0 = w25qxx_spi_receive(); temp1 = w25qxx_spi_receive(); temp2 = w25qxx_spi_receive(); HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_SET); - *w25q_id = (temp0 << 16) | (temp1 << 8) | temp2; + *device_id = (temp0 << 16U) | (temp1 << 8U) | temp2; return W25Q_OK; } @@ -260,7 +266,9 @@ w25q_status_e w25q_read_status_reg(uint8_t status_reg_num, uint8_t *status_reg_v } w25q_status_e w25q_sector_erase(uint32_t sector_idx) { - while (w25q.lock == 1) sysDelay(1); + while (w25q.lock == 1) { + sysDelay(1); + } w25q.lock = 1; w25qxx_wait_for_write_end(); @@ -285,11 +293,12 @@ w25q_status_e w25q_sector_erase(uint32_t sector_idx) { bool w25q_is_sector_empty(uint32_t sector_idx) { uint8_t buf[32] = {}; - uint32_t i; + uint32_t i{0}; bool sector_empty = true; uint32_t curr_address = sector_idx * w25q.sector_size; for (i = 0; (i < w25q.sector_size) && sector_empty; i += 32) { w25q_read_buffer(buf, curr_address, 32); + // NOLINTNEXTLINE(modernize-loop-convert) for (uint32_t x = 0; x < 32; x++) { if (buf[x] != 0xFF) { sector_empty = false; @@ -302,7 +311,9 @@ bool w25q_is_sector_empty(uint32_t sector_idx) { } w25q_status_e w25q_block_erase_32k(uint32_t block_idx) { - while (w25q.lock == 1) sysDelay(1); + while (w25q.lock == 1) { + sysDelay(1); + } w25q.lock = 1; w25qxx_wait_for_write_end(); @@ -319,7 +330,9 @@ w25q_status_e w25q_block_erase_32k(uint32_t block_idx) { } w25q_status_e w25q_block_erase_64k(uint32_t block_idx) { - while (w25q.lock == 1) sysDelay(1); + while (w25q.lock == 1) { + sysDelay(1); + } w25q.lock = 1; w25qxx_wait_for_write_end(); @@ -340,8 +353,10 @@ w25q_status_e w25q_block_erase_64k(uint32_t block_idx) { return W25Q_OK; } -w25q_status_e w25q_chip_erase(void) { - while (w25q.lock == 1) sysDelay(1); +w25q_status_e w25q_chip_erase() { + while (w25q.lock == 1) { + sysDelay(1); + } w25q.lock = 1; w25q_write_enable(); HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_RESET); @@ -355,12 +370,16 @@ w25q_status_e w25q_chip_erase(void) { w25q_status_e w25qxx_write_page(uint8_t *buf, uint32_t page_num, uint32_t offset_in_bytes, uint32_t bytes_to_write_up_to_page_size) { - while (w25q.lock == 1) sysDelay(1); + while (w25q.lock == 1) { + sysDelay(1); + } w25q.lock = 1; - if (((bytes_to_write_up_to_page_size + offset_in_bytes) > w25q.page_size) || (bytes_to_write_up_to_page_size == 0)) + if (((bytes_to_write_up_to_page_size + offset_in_bytes) > w25q.page_size) || (bytes_to_write_up_to_page_size == 0)) { bytes_to_write_up_to_page_size = w25q.page_size - offset_in_bytes; - if ((offset_in_bytes + bytes_to_write_up_to_page_size) > w25q.page_size) + } + if ((offset_in_bytes + bytes_to_write_up_to_page_size) > w25q.page_size) { bytes_to_write_up_to_page_size = w25q.page_size - offset_in_bytes; + } page_num = (page_num * w25q.page_size) + offset_in_bytes; w25qxx_wait_for_write_end(); @@ -382,25 +401,27 @@ w25q_status_e w25qxx_write_page(uint8_t *buf, uint32_t page_num, uint32_t offset w25q_status_e w25q_write_sector(uint8_t *buf, uint32_t sector_num, uint32_t offset_in_bytes, uint32_t bytes_to_write_up_to_sector_size) { - if ((bytes_to_write_up_to_sector_size > w25q.sector_size) || (bytes_to_write_up_to_sector_size == 0)) + if ((bytes_to_write_up_to_sector_size > w25q.sector_size) || (bytes_to_write_up_to_sector_size == 0)) { bytes_to_write_up_to_sector_size = w25q.sector_size; + } if (offset_in_bytes >= w25q.sector_size) { return W25Q_ERR_TRANSMIT; } uint32_t start_page = w25q_sector_to_page(sector_num) + (offset_in_bytes / w25q.page_size); uint32_t local_offset = offset_in_bytes % w25q.page_size; - int32_t bytes_to_write; - if ((offset_in_bytes + bytes_to_write_up_to_sector_size) > w25q.sector_size) - bytes_to_write = w25q.sector_size - offset_in_bytes; - else - bytes_to_write = bytes_to_write_up_to_sector_size; + int32_t bytes_to_write{0}; + if ((offset_in_bytes + bytes_to_write_up_to_sector_size) > w25q.sector_size) { + bytes_to_write = static_cast(w25q.sector_size - offset_in_bytes); + } else { + bytes_to_write = static_cast(bytes_to_write_up_to_sector_size); + } do { w25qxx_write_page(buf, start_page, local_offset, bytes_to_write); // log_debug("Page %lu written", start_page); start_page++; - bytes_to_write -= w25q.page_size - local_offset; + bytes_to_write -= static_cast(w25q.page_size - local_offset); buf += w25q.page_size - local_offset; local_offset = 0; } while (bytes_to_write > 0); @@ -409,11 +430,12 @@ w25q_status_e w25q_write_sector(uint8_t *buf, uint32_t sector_num, uint32_t offs w25q_status_e w25q_write_buffer(uint8_t *buf, uint32_t write_addr, uint32_t num_bytes_to_write) { uint32_t bytes_to_write_up_to_sector_size = num_bytes_to_write; - uint32_t offset_in_bytes = write_addr; - uint32_t sector_num = num_bytes_to_write; + const uint32_t offset_in_bytes = write_addr; + const uint32_t sector_num = num_bytes_to_write; - if ((bytes_to_write_up_to_sector_size > w25q.sector_size) || (bytes_to_write_up_to_sector_size == 0)) + if ((bytes_to_write_up_to_sector_size > w25q.sector_size) || (bytes_to_write_up_to_sector_size == 0)) { bytes_to_write_up_to_sector_size = w25q.sector_size; + } if (offset_in_bytes >= w25q.sector_size) { return W25Q_ERR_TRANSMIT; @@ -421,16 +443,16 @@ w25q_status_e w25q_write_buffer(uint8_t *buf, uint32_t write_addr, uint32_t num_ uint32_t start_page = w25q_sector_to_page(sector_num) + (offset_in_bytes / w25q.page_size); uint32_t local_offset = offset_in_bytes % w25q.page_size; - int32_t bytes_to_write; - if ((offset_in_bytes + bytes_to_write_up_to_sector_size) > w25q.sector_size) - bytes_to_write = w25q.sector_size - offset_in_bytes; - else - bytes_to_write = bytes_to_write_up_to_sector_size; - + int32_t bytes_to_write{0}; + if ((offset_in_bytes + bytes_to_write_up_to_sector_size) > w25q.sector_size) { + bytes_to_write = static_cast(w25q.sector_size - offset_in_bytes); + } else { + bytes_to_write = static_cast(bytes_to_write_up_to_sector_size); + } do { w25qxx_write_page(buf, start_page, local_offset, bytes_to_write); start_page++; - bytes_to_write -= w25q.page_size - local_offset; + bytes_to_write -= static_cast(w25q.page_size - local_offset); buf += w25q.page_size - local_offset; local_offset = 0; } while (bytes_to_write > 0); @@ -439,12 +461,16 @@ w25q_status_e w25q_write_buffer(uint8_t *buf, uint32_t write_addr, uint32_t num_ w25q_status_e w25qxx_read_page(uint8_t *buf, uint32_t page_num, uint32_t offset_in_bytes, uint32_t NumByteToRead_up_to_PageSize) { - while (w25q.lock == 1) sysDelay(1); + while (w25q.lock == 1) { + sysDelay(1); + } w25q.lock = 1; - if ((NumByteToRead_up_to_PageSize > w25q.page_size) || (NumByteToRead_up_to_PageSize == 0)) + if ((NumByteToRead_up_to_PageSize > w25q.page_size) || (NumByteToRead_up_to_PageSize == 0)) { NumByteToRead_up_to_PageSize = w25q.page_size; - if ((offset_in_bytes + NumByteToRead_up_to_PageSize) > w25q.page_size) + } + if ((offset_in_bytes + NumByteToRead_up_to_PageSize) > w25q.page_size) { NumByteToRead_up_to_PageSize = w25q.page_size - offset_in_bytes; + } page_num = page_num * w25q.page_size + offset_in_bytes; HAL_GPIO_WritePin(FLASH_CS_GPIO_Port, FLASH_CS_Pin, GPIO_PIN_RESET); if (w25q.needs_4_byte_addressing) { @@ -465,8 +491,9 @@ w25q_status_e w25qxx_read_page(uint8_t *buf, uint32_t page_num, uint32_t offset_ w25q_status_e w25q_read_sector(uint8_t *buf, uint32_t sector_num, uint32_t offset_in_bytes, uint32_t bytes_to_read_up_to_sector_size) { - if ((bytes_to_read_up_to_sector_size > w25q.sector_size) || (bytes_to_read_up_to_sector_size == 0)) + if ((bytes_to_read_up_to_sector_size > w25q.sector_size) || (bytes_to_read_up_to_sector_size == 0)) { bytes_to_read_up_to_sector_size = w25q.sector_size; + } if (offset_in_bytes >= w25q.sector_size) { return W25Q_ERR_TRANSMIT; @@ -474,16 +501,17 @@ w25q_status_e w25q_read_sector(uint8_t *buf, uint32_t sector_num, uint32_t offse uint32_t start_page = w25q_sector_to_page(sector_num) + (offset_in_bytes / w25q.page_size); uint32_t local_offset = offset_in_bytes % w25q.page_size; - int32_t bytes_to_read; - if ((offset_in_bytes + bytes_to_read_up_to_sector_size) > w25q.sector_size) - bytes_to_read = w25q.sector_size - offset_in_bytes; - else - bytes_to_read = bytes_to_read_up_to_sector_size; + int32_t bytes_to_read{0}; + if ((offset_in_bytes + bytes_to_read_up_to_sector_size) > w25q.sector_size) { + bytes_to_read = static_cast(w25q.sector_size - offset_in_bytes); + } else { + bytes_to_read = static_cast(bytes_to_read_up_to_sector_size); + } do { w25qxx_read_page(buf, start_page, local_offset, bytes_to_read); start_page++; - bytes_to_read -= w25q.page_size - local_offset; + bytes_to_read -= static_cast(w25q.page_size - local_offset); buf += w25q.page_size - local_offset; local_offset = 0; } while (bytes_to_read > 0); @@ -492,27 +520,28 @@ w25q_status_e w25q_read_sector(uint8_t *buf, uint32_t sector_num, uint32_t offse w25q_status_e w25q_read_buffer(uint8_t *buf, uint32_t read_addr, uint32_t num_bytes_to_read) { uint32_t bytes_to_read_up_to_sector_size = num_bytes_to_read; - uint32_t offset_in_bytes = read_addr; - uint32_t sector_num = read_addr; + const uint32_t offset_in_bytes = read_addr; + const uint32_t sector_num = read_addr; - if ((bytes_to_read_up_to_sector_size > w25q.sector_size) || (bytes_to_read_up_to_sector_size == 0)) + if ((bytes_to_read_up_to_sector_size > w25q.sector_size) || (bytes_to_read_up_to_sector_size == 0)) { bytes_to_read_up_to_sector_size = w25q.sector_size; + } if (offset_in_bytes >= w25q.sector_size) { return W25Q_ERR_TRANSMIT; } uint32_t start_page = w25q_sector_to_page(sector_num) + (offset_in_bytes / w25q.page_size); uint32_t local_offset = offset_in_bytes % w25q.page_size; - int32_t bytes_to_read; + int32_t bytes_to_read{0}; if ((offset_in_bytes + bytes_to_read_up_to_sector_size) > w25q.sector_size) { - bytes_to_read = w25q.sector_size - offset_in_bytes; + bytes_to_read = static_cast(w25q.sector_size - offset_in_bytes); } else { - bytes_to_read = bytes_to_read_up_to_sector_size; + bytes_to_read = static_cast(bytes_to_read_up_to_sector_size); } do { w25qxx_read_page(buf, start_page, local_offset, bytes_to_read); start_page++; - bytes_to_read -= w25q.page_size - local_offset; + bytes_to_read -= static_cast(w25q.page_size - local_offset); buf += w25q.page_size - local_offset; local_offset = 0; } while (bytes_to_read > 0); diff --git a/flight_computer/src/drivers/w25q.hpp b/flight_computer/src/drivers/w25q.hpp index 6b4065fa..00641731 100644 --- a/flight_computer/src/drivers/w25q.hpp +++ b/flight_computer/src/drivers/w25q.hpp @@ -26,7 +26,7 @@ #pragma once -#include "target.h" +#include "target.hpp" enum w25q_id_e { W25QINVALID = 0, @@ -42,20 +42,20 @@ enum w25q_id_e { W25Q512, }; -#define W25Q_PAGE_SIZE_BYTES 256 -#define W25Q_SECTOR_SIZE_BYTES 4096 // 4kB +inline constexpr uint16_t W25Q_PAGE_SIZE_BYTES = 256; +inline constexpr uint16_t W25Q_SECTOR_SIZE_BYTES = 4096; // 4kB struct w25q_t { const uint16_t page_size{W25Q_PAGE_SIZE_BYTES}; const uint32_t sector_size{W25Q_SECTOR_SIZE_BYTES}; - w25q_id_e id; - uint32_t page_count; - uint32_t sector_count; - uint32_t block_size; - uint32_t block_count; - uint32_t capacity_in_kilobytes; - bool needs_4_byte_addressing; - uint8_t lock; + w25q_id_e id{W25QINVALID}; + uint32_t page_count{0}; + uint32_t sector_count{0}; + uint32_t block_size{0}; + uint32_t block_count{0}; + uint32_t capacity_in_kilobytes{0}; + bool needs_4_byte_addressing{false}; + uint8_t lock{0}; bool initialized{false}; }; @@ -75,14 +75,14 @@ enum w25q_status_e { * * @return W25Q_OK if successful, W25Q_ERR_* otherwise */ -w25q_status_e w25q_init(void); +w25q_status_e w25q_init(); /** * Sends the reset command. * * @return W25Q_OK if successful, W25Q_ERR_* otherwise */ -w25q_status_e w25q_reset(void); +w25q_status_e w25q_reset(); /** * Reads the JEDEC ID of the flash chip. @@ -121,7 +121,7 @@ w25q_status_e w25q_block_erase_64k(uint32_t block_idx); * * @return W25Q_OK if successful, W25Q_ERR_* otherwise */ -w25q_status_e w25q_chip_erase(void); +w25q_status_e w25q_chip_erase(); /** * Write up to one page to the flash. @@ -162,9 +162,9 @@ w25q_status_e w25q_read_buffer(uint8_t *buf, uint32_t read_addr, uint32_t num_by */ w25q_status_e w25q_read_status_reg(uint8_t status_reg_num, uint8_t *status_reg_val); -uint32_t w25q_sector_to_page(uint32_t sector_num); +uint32_t w25q_sector_to_page(uint32_t sector_idx); -uint32_t w25q_block_to_page(uint32_t block_num); +uint32_t w25q_block_to_page(uint32_t block_idx); /** * Check whether a given sector is empty. @@ -186,4 +186,5 @@ w25q_status_e w25qxx_write_page(uint8_t *buf, uint32_t page_num, uint32_t offset w25q_status_e w25qxx_read_page(uint8_t *buf, uint32_t page_num, uint32_t offset_in_bytes, uint32_t NumByteToRead_up_to_PageSize); +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern w25q_t w25q; diff --git a/flight_computer/src/flash/lfs_custom.cpp b/flight_computer/src/flash/lfs_custom.cpp index c9643488..7a93103e 100644 --- a/flight_computer/src/flash/lfs_custom.cpp +++ b/flight_computer/src/flash/lfs_custom.cpp @@ -28,9 +28,10 @@ static int w25q_lfs_prog(const struct lfs_config *c, lfs_block_t block, lfs_off_ static int w25q_lfs_erase(const struct lfs_config *c, lfs_block_t block); static int w25q_lfs_sync(const struct lfs_config *c); -#define LFS_CACHE_SIZE 512 -#define LFS_LOOKAHEAD_SIZE 512 +constexpr uint16_t LFS_CACHE_SIZE = 512; +constexpr uint16_t LFS_LOOKAHEAD_SIZE = 512; +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) /* LFS Static Buffers */ static uint8_t read_buffer[LFS_CACHE_SIZE] = {}; static uint8_t prog_buffer[LFS_CACHE_SIZE] = {}; @@ -77,28 +78,29 @@ uint32_t flight_counter = 0; // static uint8_t fc_file_cfg_buffer[LFS_CACHE_SIZE] = {}; // struct lfs_file_config fc_file_cfg = {.buffer = fc_file_cfg_buffer, .attr_count = 1}; lfs_file_t fc_file /* = {.cfg = &fc_file_cfg} */; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) int8_t lfs_obj_type(const char *path) { - struct lfs_info info; - int32_t stat_err = lfs_stat(&lfs, path, &info); + struct lfs_info info {}; + const int32_t stat_err = lfs_stat(&lfs, path, &info); if (stat_err < 0) { // cli_print_linef("lfs_stat failed with error: %ld", stat_err); return -1; } /* casting here is fine because info.type should be 0x1 (LFS_TYPE_REG) or 0x2 (LFS_TYPE_FILE) */ - return (int8_t)info.type; + return static_cast(info.type); } int lfs_ls(const char *path) { lfs_dir_t dir; int err = lfs_dir_open(&lfs, &dir, path); - if (err) { + if (err != 0) { return err; } - struct lfs_info info; + struct lfs_info info {}; while (true) { - int res = lfs_dir_read(&lfs, &dir, &info); + const int res = lfs_dir_read(&lfs, &dir, &info); if (res < 0) { return res; } @@ -122,8 +124,8 @@ int lfs_ls(const char *path) { static const char *prefixes[] = {"", "K", "M", "G"}; if (info.type == LFS_TYPE_REG) { for (int i = sizeof(prefixes) / sizeof(prefixes[0]) - 1; i >= 0; i--) { - if (info.size >= (1U << 10 * i) - 1) { - cli_printf("%*lu%sB ", 4 - (i != 0), info.size >> 10 * i, prefixes[i]); + if (info.size >= (1U << 10U * i) - 1) { + cli_printf("%*lu%sB ", 4 - static_cast(i != 0), info.size >> 10U * i, prefixes[i]); break; } } @@ -135,7 +137,7 @@ int lfs_ls(const char *path) { } err = lfs_dir_close(&lfs, &dir); - if (err) { + if (err != 0) { return err; } @@ -151,14 +153,14 @@ extern "C" int32_t lfs_cnt(const char *path, enum lfs_type type) { lfs_dir_t dir; int err = lfs_dir_open(&lfs, &dir, path); - if (err) { + if (err != 0) { return err; } - struct lfs_info info; + struct lfs_info info {}; /* Iterate over all the files in the current directory */ while (true) { - int32_t res = lfs_dir_read(&lfs, &dir, &info); + const int32_t res = lfs_dir_read(&lfs, &dir, &info); if (res < 0) { return res; } @@ -174,23 +176,25 @@ extern "C" int32_t lfs_cnt(const char *path, enum lfs_type type) { } err = lfs_dir_close(&lfs, &dir); - if (err) { + if (err != 0) { return err; } return cnt; } -static int w25q_lfs_read(const struct lfs_config *c, lfs_block_t block, lfs_off_t off, void *buffer, lfs_size_t size) { - if (w25q_read_sector((uint8_t *)buffer, block, off, size) == W25Q_OK) { +static int w25q_lfs_read(const struct lfs_config *c [[maybe_unused]], lfs_block_t block, lfs_off_t off, void *buffer, + lfs_size_t size) { + if (w25q_read_sector(static_cast(buffer), block, off, size) == W25Q_OK) { return 0; } return LFS_ERR_CORRUPT; } -static int w25q_lfs_prog(const struct lfs_config *c, lfs_block_t block, lfs_off_t off, const void *buffer, - lfs_size_t size) { +static int w25q_lfs_prog(const struct lfs_config *c [[maybe_unused]], lfs_block_t block, lfs_off_t off, + const void *buffer, lfs_size_t size) { static uint32_t sync_counter = 0; static uint32_t sync_counter_err = 0; + // NOLINTNEXTLINE(google-readability-casting) if (w25q_write_sector((uint8_t *)buffer, block, off, size) == W25Q_OK) { if (sync_counter % 32 == 0) { /* Flash the LED at certain intervals */ @@ -206,10 +210,10 @@ static int w25q_lfs_prog(const struct lfs_config *c, lfs_block_t block, lfs_off_ ++sync_counter_err; return LFS_ERR_CORRUPT; } -static int w25q_lfs_erase(const struct lfs_config *c, lfs_block_t block) { +static int w25q_lfs_erase(const struct lfs_config *c [[maybe_unused]], lfs_block_t block) { if (w25q_sector_erase(block) == W25Q_OK) { return 0; } return LFS_ERR_CORRUPT; } -static int w25q_lfs_sync(const struct lfs_config *c) { return 0; } +static int w25q_lfs_sync(const struct lfs_config *c [[maybe_unused]]) { return 0; } diff --git a/flight_computer/src/flash/lfs_custom.hpp b/flight_computer/src/flash/lfs_custom.hpp index c25ae317..f73d9a28 100644 --- a/flight_computer/src/flash/lfs_custom.hpp +++ b/flight_computer/src/flash/lfs_custom.hpp @@ -20,9 +20,6 @@ #include "lfs.h" -/* TODO: Wrap lfs functions where you always pass this lfs variable instead of making it visible globally */ -extern lfs_t lfs; - #ifdef __cplusplus extern "C" { #endif @@ -31,11 +28,16 @@ const struct lfs_config *get_lfs_cfg(); } #endif +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) +/* TODO: Wrap lfs functions where you always pass this lfs variable instead of making it visible globally */ +extern lfs_t lfs; + extern lfs_file_t fc_file; extern char cwd[LFS_NAME_MAX]; extern uint32_t flight_counter; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) /** * List the contents of the directory. diff --git a/flight_computer/src/flash/reader.cpp b/flight_computer/src/flash/reader.cpp index 2820d3e7..af385656 100644 --- a/flight_computer/src/flash/reader.cpp +++ b/flight_computer/src/flash/reader.cpp @@ -28,8 +28,8 @@ #include "util/enum_str_maps.hpp" #include "util/log.h" -#define STRING_BUF_SZ 400 -#define READ_BUF_SZ 256 +constexpr uint16_t STRING_BUF_SZ = 400; +constexpr uint16_t READ_BUF_SZ = 256; namespace { @@ -53,14 +53,14 @@ void print_stats(uint16_t flight_num) { if (lfs_file_open(&lfs, &curr_file, filename, LFS_O_RDONLY) == LFS_ERR_OK) { const auto file_size = lfs_file_size(&lfs, &curr_file); if (file_size > 0) { - uint8_t *read_buf = (uint8_t *)(pvPortMalloc(READ_BUF_SZ * sizeof(uint8_t))); + auto *read_buf = static_cast(pvPortMalloc(READ_BUF_SZ * sizeof(uint8_t))); for (lfs_size_t i = 0; i < static_cast(file_size); i += READ_BUF_SZ) { memset(read_buf, 0, READ_BUF_SZ); - lfs_size_t bytes_read = lfs_min(READ_BUF_SZ, file_size - i); + const lfs_size_t bytes_read = lfs_min(READ_BUF_SZ, file_size - i); lfs_file_read(&lfs, &curr_file, read_buf, bytes_read); - + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) log_rawr("%.*s", static_cast(bytes_read), reinterpret_cast(read_buf)); } @@ -101,8 +101,9 @@ void print_cfg(uint16_t flight_num) { if (local_config->config_version == CONFIG_VERSION) { print_cats_config("cli", local_config, false); } else { - log_raw("Config versions do not match, cannot print -- version in config file: %lu, current config version: %u", - local_config->config_version, CONFIG_VERSION); + log_raw( + "Config versions do not match, cannot print -- version in config file: %lu, current config version: %lu", + local_config->config_version, CONFIG_VERSION); } } else { @@ -126,9 +127,9 @@ void dump_recording(uint16_t flight_num) { return; } - char *string_buffer1 = (char *)(pvPortMalloc(STRING_BUF_SZ * sizeof(char))); - char *string_buffer2 = (char *)(pvPortMalloc(STRING_BUF_SZ * sizeof(char))); - uint8_t *read_buf = (uint8_t *)(pvPortMalloc(READ_BUF_SZ * sizeof(uint8_t))); + char *string_buffer1 = static_cast(pvPortMalloc(STRING_BUF_SZ * sizeof(char))); + char *string_buffer2 = static_cast(pvPortMalloc(STRING_BUF_SZ * sizeof(char))); + auto *read_buf = static_cast(pvPortMalloc(READ_BUF_SZ * sizeof(uint8_t))); if (string_buffer1 == nullptr || string_buffer2 == nullptr || read_buf == nullptr) { log_raw("Cannot allocate enough memory for flight dumping!"); @@ -149,7 +150,7 @@ void dump_recording(uint16_t flight_num) { const auto file_size = lfs_file_size(&lfs, &curr_file); if (file_size > 0) { for (lfs_size_t i = 0; i < static_cast(file_size); i += READ_BUF_SZ) { - lfs_size_t chunk = lfs_min(READ_BUF_SZ, file_size - i); + const lfs_size_t chunk = lfs_min(READ_BUF_SZ, file_size - i); lfs_file_read(&lfs, &curr_file, read_buf, chunk); @@ -179,6 +180,8 @@ void dump_recording(uint16_t flight_num) { vPortFree(read_buf); } +// NOLINTBEGIN(cppcoreguidelines-pro-type-reinterpret-cast) +// NOLINTNEXTLINE(readability-function-cognitive-complexity) void parse_recording(uint16_t flight_num, rec_entry_type_e filter_mask) { if (global_recorder_status == REC_WRITE_TO_FLASH) { log_raw("The recorder is currently active, stop it first!"); @@ -192,8 +195,8 @@ void parse_recording(uint16_t flight_num, rec_entry_type_e filter_mask) { lfs_file_t curr_file; if (lfs_file_open(&lfs, &curr_file, filename, LFS_O_RDONLY) == LFS_ERR_OK) { - rec_elem_t rec_elem; - lfs_ssize_t file_size = lfs_file_size(&lfs, &curr_file); + rec_elem_t rec_elem{}; + const lfs_ssize_t file_size = lfs_file_size(&lfs, &curr_file); if (file_size < 0) { log_raw("Invalid file size %ld!", file_size); return; @@ -209,13 +212,13 @@ void parse_recording(uint16_t flight_num, rec_entry_type_e filter_mask) { } } - while (lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem, 8) > 0) { + while (lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem), 8) > 0) { const rec_entry_type_e rec_type = rec_elem.rec_type; const rec_entry_type_e rec_type_without_id = get_record_type_without_id(rec_type); switch (rec_type_without_id) { case IMU: { - size_t elem_sz = sizeof(rec_elem.u.imu); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.imu); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { log_raw("%lu|IMU%hu|%d|%d|%d|%d|%d|%d", rec_elem.ts, get_id_from_record_type(rec_type), rec_elem.u.imu.acc.x, rec_elem.u.imu.acc.y, rec_elem.u.imu.acc.z, rec_elem.u.imu.gyro.x, @@ -223,24 +226,25 @@ void parse_recording(uint16_t flight_num, rec_entry_type_e filter_mask) { } } break; case BARO: { - size_t elem_sz = sizeof(rec_elem.u.baro); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.baro); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { log_raw("%lu|BARO%hu|%ld|%ld", rec_elem.ts, get_id_from_record_type(rec_type), rec_elem.u.baro.pressure, rec_elem.u.baro.temperature); } } break; case FLIGHT_INFO: { - size_t elem_sz = sizeof(rec_elem.u.flight_info); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.flight_info); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { - log_raw("%lu|FLIGHT_INFO|%f|%f|%f", rec_elem.ts, (double)rec_elem.u.flight_info.acceleration, - (double)rec_elem.u.flight_info.height, (double)rec_elem.u.flight_info.velocity); + log_raw("%lu|FLIGHT_INFO|%f|%f|%f", rec_elem.ts, static_cast(rec_elem.u.flight_info.acceleration), + static_cast(rec_elem.u.flight_info.height), + static_cast(rec_elem.u.flight_info.velocity)); } } break; case ORIENTATION_INFO: { - size_t elem_sz = sizeof(rec_elem.u.orientation_info); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.orientation_info); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { log_raw("%lu|ORIENTATION_INFO|%d|%d|%d|%d", rec_elem.ts, rec_elem.u.orientation_info.estimated_orientation[0], @@ -250,48 +254,48 @@ void parse_recording(uint16_t flight_num, rec_entry_type_e filter_mask) { } } break; case FILTERED_DATA_INFO: { - size_t elem_sz = sizeof(rec_elem.u.filtered_data_info); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.filtered_data_info); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { log_raw("%lu|FILTERED_DATA_INFO|%f|%f", rec_elem.ts, - (double)rec_elem.u.filtered_data_info.filtered_altitude_AGL, - (double)rec_elem.u.filtered_data_info.filtered_acceleration); + static_cast(rec_elem.u.filtered_data_info.filtered_altitude_AGL), + static_cast(rec_elem.u.filtered_data_info.filtered_acceleration)); } } break; case FLIGHT_STATE: { - size_t elem_sz = sizeof(rec_elem.u.flight_state); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.flight_state); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { log_raw("%lu|FLIGHT_STATE|%s", rec_elem.ts, GetStr(rec_elem.u.flight_state, fsm_map)); } } break; case EVENT_INFO: { - size_t elem_sz = sizeof(rec_elem.u.event_info); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.event_info); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { - peripheral_act_t action = rec_elem.u.event_info.action; + const peripheral_act_t action = rec_elem.u.event_info.action; log_raw("%lu|EVENT_INFO|%s|%s|%d", rec_elem.ts, GetStr(rec_elem.u.event_info.event, event_map), GetStr(rec_elem.u.event_info.action.action, action_map), action.action_arg); } } break; case ERROR_INFO: { - size_t elem_sz = sizeof(rec_elem.u.error_info); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.error_info); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { log_raw("%lu|ERROR_INFO|%lu", rec_elem.ts, rec_elem.u.error_info.error); } } break; case GNSS_INFO: { - size_t elem_sz = sizeof(rec_elem.u.gnss_info); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.gnss_info); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { - log_raw("%lu|GNSS_INFO|%f|%f|%hu", rec_elem.ts, (double)rec_elem.u.gnss_info.lat, - (double)rec_elem.u.gnss_info.lon, rec_elem.u.gnss_info.sats); + log_raw("%lu|GNSS_INFO|%f|%f|%hu", rec_elem.ts, static_cast(rec_elem.u.gnss_info.lat), + static_cast(rec_elem.u.gnss_info.lon), rec_elem.u.gnss_info.sats); } } break; case VOLTAGE_INFO: { - size_t elem_sz = sizeof(rec_elem.u.voltage_info); - lfs_file_read(&lfs, &curr_file, (uint8_t *)&rec_elem.u.imu, elem_sz); + const size_t elem_sz = sizeof(rec_elem.u.voltage_info); + lfs_file_read(&lfs, &curr_file, reinterpret_cast(&rec_elem.u.imu), elem_sz); if ((rec_type_without_id & filter_mask) > 0) { /* Convert mV to V by dividing with 1000. */ log_raw("%lu|VOLTAGE_INFO|%.3f", rec_elem.ts, static_cast(rec_elem.u.voltage_info) / 1000); @@ -307,6 +311,7 @@ void parse_recording(uint16_t flight_num, rec_entry_type_e filter_mask) { log_raw("Flight %d not found!", flight_num); } } +// NOLINTEND(cppcoreguidelines-pro-type-reinterpret-cast) void print_stats_and_cfg(uint16_t flight_num) { print_stats(flight_num); diff --git a/flight_computer/src/flash/recorder.cpp b/flight_computer/src/flash/recorder.cpp index 4b8edb18..869ee41b 100644 --- a/flight_computer/src/flash/recorder.cpp +++ b/flight_computer/src/flash/recorder.cpp @@ -24,6 +24,7 @@ #include +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) flight_stats_t global_flight_stats = { .max_height = {.val = -INFINITY}, .max_velocity = {.val = -INFINITY}, .max_acceleration = {.val = -INFINITY}}; @@ -64,6 +65,7 @@ struct skip_counter_t { uint8_t filtered_data; }; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static skip_counter_t skip_counter = {}; /** @@ -105,54 +107,66 @@ static skip_counter_t skip_counter = {}; */ inline static bool should_skip(uint8_t *cnt, uint8_t num_reps_per_iter) { /* Return right away if everything should be recorded */ - if (global_cats_config.rec_speed_idx == 0) return false; - uint8_t inv_rec_rate = global_cats_config.rec_speed_idx + 1; + if (global_cats_config.rec_speed_idx == 0) { + return false; + } + const uint8_t inv_rec_rate = global_cats_config.rec_speed_idx + 1; /* Skip the entry if we already recorded all entries from the iteration that should be recorded */ - bool skip = (*cnt % (inv_rec_rate * num_reps_per_iter)) >= num_reps_per_iter; + const bool skip = (*cnt % (inv_rec_rate * num_reps_per_iter)) >= num_reps_per_iter; /* Increment the counter and reset it to 0 if the max value is reached */ *cnt = (*cnt + 1) % (inv_rec_rate * num_reps_per_iter); return skip; } void record(timestamp_t ts, rec_entry_type_e rec_type_with_id, const void *const rec_value) { - rec_entry_type_e pure_rec_type = get_record_type_without_id(rec_type_with_id); + const rec_entry_type_e pure_rec_type = get_record_type_without_id(rec_type_with_id); if (global_recorder_status >= REC_FILL_QUEUE && should_record(pure_rec_type)) { rec_elem_t e = {.ts = ts, .rec_type = rec_type_with_id}; switch (pure_rec_type) { case IMU: - if (should_skip(&skip_counter.imu, NUM_IMU)) return; - e.u.imu = *((imu_data_t *)rec_value); + if (should_skip(&skip_counter.imu, NUM_IMU)) { + return; + } + e.u.imu = *(static_cast(rec_value)); break; case BARO: - if (should_skip(&skip_counter.baro, NUM_BARO)) return; - e.u.baro = *((baro_data_t *)rec_value); + if (should_skip(&skip_counter.baro, NUM_BARO)) { + return; + } + e.u.baro = *(static_cast(rec_value)); break; case FLIGHT_INFO: - e.u.flight_info = *((flight_info_t *)rec_value); + e.u.flight_info = *(static_cast(rec_value)); /* Record the flight info stats before deciding whether to record this entry or not. */ collect_flight_info_stats(ts, e.u.flight_info); - if (should_skip(&skip_counter.flight_info, 1)) return; + if (should_skip(&skip_counter.flight_info, 1)) { + return; + } break; case ORIENTATION_INFO: - if (should_skip(&skip_counter.orientation, 1)) return; - e.u.orientation_info = *((orientation_info_t *)rec_value); + if (should_skip(&skip_counter.orientation, 1)) { + return; + } + e.u.orientation_info = *(static_cast(rec_value)); break; case FILTERED_DATA_INFO: - if (should_skip(&skip_counter.filtered_data, 1)) return; - e.u.filtered_data_info = *((filtered_data_info_t *)rec_value); + if (should_skip(&skip_counter.filtered_data, 1)) { + return; + } + e.u.filtered_data_info = *(static_cast(rec_value)); break; case FLIGHT_STATE: - e.u.flight_state = *((flight_fsm_e *)rec_value); + e.u.flight_state = *(static_cast(rec_value)); break; case EVENT_INFO: - e.u.event_info = *((event_info_t *)rec_value); + e.u.event_info = *(static_cast(rec_value)); break; case ERROR_INFO: - e.u.error_info = *((error_info_t *)rec_value); + e.u.error_info = *(static_cast(rec_value)); break; case GNSS_INFO: - e.u.gnss_info = *((gnss_position_t *)rec_value); + e.u.gnss_info = *(static_cast(rec_value)); break; case VOLTAGE_INFO: e.u.voltage_info = *(static_cast(rec_value)); @@ -162,7 +176,7 @@ void record(timestamp_t ts, rec_entry_type_e rec_type_with_id, const void *const break; } - osStatus_t ret = osMessageQueuePut(rec_queue, &e, 0U, 0U); + const osStatus_t ret = osMessageQueuePut(rec_queue, &e, 0U, 0U); if (ret != osOK) { log_error("Inserting an element to the recorder queue failed! Error: %d", ret); } diff --git a/flight_computer/src/flash/recorder.hpp b/flight_computer/src/flash/recorder.hpp index 963aa1e5..711c0a26 100644 --- a/flight_computer/src/flash/recorder.hpp +++ b/flight_computer/src/flash/recorder.hpp @@ -28,36 +28,37 @@ /** Exported Defines **/ -#define REC_QUEUE_SIZE 512 +inline constexpr uint16_t REC_QUEUE_SIZE = 512; -#define REC_CMD_QUEUE_SIZE 16 +inline constexpr uint8_t REC_CMD_QUEUE_SIZE = 16; -#define MAX_FILENAME_SIZE 32 +inline constexpr uint16_t MAX_FILENAME_SIZE = 32; -#define REC_QUEUE_PRE_THRUSTING_FILL_RATIO 0.75f -#define REC_QUEUE_PRE_THRUSTING_LIMIT (uint32_t)(REC_QUEUE_PRE_THRUSTING_FILL_RATIO * REC_QUEUE_SIZE) +inline constexpr float REC_QUEUE_PRE_THRUSTING_FILL_RATIO = 0.75F; +inline constexpr auto REC_QUEUE_PRE_THRUSTING_LIMIT = + static_cast(REC_QUEUE_PRE_THRUSTING_FILL_RATIO * REC_QUEUE_SIZE); /** * A bit mask that specifies where the IDs are located. The IDs occupy the first four bits of the rec_entry_type_e enum. */ -#define REC_ID_MASK 0x0000000F +inline constexpr uint32_t REC_ID_MASK = 0x0000000F; /** Exported Types **/ // clang-format off enum rec_entry_type_e: uint32_t { // Periodic recorder types, their recording speed is affected by global_cats_config.rec_speed_idx - IMU = 1 << 4, // 0x20 - BARO = 1 << 5, // 0x40 - FLIGHT_INFO = 1 << 6, // 0x80 - ORIENTATION_INFO = 1 << 7, // 0x100 - FILTERED_DATA_INFO = 1 << 8, // 0x200 + IMU = 1U << 4U, // 0x20 + BARO = 1U << 5U, // 0x40 + FLIGHT_INFO = 1U << 6U, // 0x80 + ORIENTATION_INFO = 1U << 7U, // 0x100 + FILTERED_DATA_INFO = 1U << 8U, // 0x200 // Sporadic recorder types, they will always be logged - FLIGHT_STATE = 1 << 9, // 0x400 - EVENT_INFO = 1 << 10, // 0x800 - ERROR_INFO = 1 << 11, // 0x1000 - GNSS_INFO = 1 << 12, // 0x2000 - VOLTAGE_INFO = 1 << 13, // 0x4000 + FLIGHT_STATE = 1U << 9U, // 0x400 + EVENT_INFO = 1U << 10U, // 0x800 + ERROR_INFO = 1U << 11U, // 0x1000 + GNSS_INFO = 1U << 12U, // 0x2000 + VOLTAGE_INFO = 1U << 13U, // 0x4000 }; // clang-format on @@ -113,29 +114,30 @@ struct rec_elem_t { /* Flight Statistics */ struct flight_stats_t { - cats_config_t config; + cats_config_t config{}; struct { timestamp_t ts; float32_t val; - } max_height; + } max_height{}; struct { timestamp_t ts; float32_t val; - } max_velocity; + } max_velocity{}; struct { timestamp_t ts; float32_t val; - } max_acceleration; + } max_acceleration{}; - calibration_data_t calibration_data; - float32_t height_0; + calibration_data_t calibration_data{}; + float32_t height_0{}; - gnss_time_t liftoff_time; + gnss_time_t liftoff_time{}; }; /** Exported Variables **/ +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern flight_stats_t global_flight_stats; /** Exported Functions **/ @@ -158,7 +160,7 @@ inline void init_global_flight_stats() { * @return record type without ID */ constexpr rec_entry_type_e get_record_type_without_id(rec_entry_type_e rec_type) { - return (rec_entry_type_e)(rec_type & ~REC_ID_MASK); + return static_cast(rec_type & ~REC_ID_MASK); } /** @@ -169,7 +171,7 @@ constexpr rec_entry_type_e get_record_type_without_id(rec_entry_type_e rec_type) * @return record type with ID */ constexpr rec_entry_type_e add_id_to_record_type(rec_entry_type_e rec_type, uint8_t id) { - return (rec_entry_type_e)(rec_type | (id & REC_ID_MASK)); + return static_cast(rec_type | (id & REC_ID_MASK)); } /** diff --git a/flight_computer/src/init/config.cpp b/flight_computer/src/init/config.cpp index b452912b..6ad9cd29 100644 --- a/flight_computer/src/init/config.cpp +++ b/flight_computer/src/init/config.cpp @@ -42,7 +42,7 @@ void load_and_set_config() { static void create_event_map() { /* number of event types + 0th element */ - event_action_map = (event_action_map_elem_t *)(pvPortMalloc(NUM_EVENTS * sizeof(event_action_map_elem_t))); + event_action_map = static_cast(pvPortMalloc(NUM_EVENTS * sizeof(event_action_map_elem_t))); if (event_action_map == nullptr) { // TODO: set some error, beep!! log_raw("Could not allocate memory for event_action_map!"); @@ -50,15 +50,16 @@ static void create_event_map() { } memset(event_action_map, 0, NUM_EVENTS * sizeof(event_action_map_elem_t)); - uint16_t nr_actions; - config_action_t action; + uint16_t nr_actions{0}; + config_action_t action{}; // Loop over all events for (int ev_idx = 0; ev_idx < NUM_EVENTS; ev_idx++) { - nr_actions = cc_get_num_actions((cats_event_e)(ev_idx)); + nr_actions = cc_get_num_actions(static_cast(ev_idx)); // If an action is mapped to the event if (nr_actions > 0) { event_action_map[ev_idx].num_actions = nr_actions; - event_action_map[ev_idx].action_list = (peripheral_act_t *)(pvPortMalloc(nr_actions * sizeof(peripheral_act_t))); + event_action_map[ev_idx].action_list = + static_cast(pvPortMalloc(nr_actions * sizeof(peripheral_act_t))); if (event_action_map[ev_idx].action_list == nullptr) { // TODO: set some error, beep!! log_raw("Could not allocate memory for actions in event_action_map[%d].action_list!", ev_idx); @@ -68,7 +69,7 @@ static void create_event_map() { // Loop over all actions for (uint16_t act_idx = 0; act_idx < nr_actions; act_idx++) { - if (cc_get_action((cats_event_e)(ev_idx), act_idx, &action)) { + if (cc_get_action(static_cast(ev_idx), act_idx, &action)) { event_action_map[ev_idx].action_list[act_idx].action = static_cast(action.action_idx); event_action_map[ev_idx].action_list[act_idx].action_arg = action.arg; } else { @@ -94,8 +95,10 @@ static void init_timers() { /* Create Timers */ for (uint32_t i = 0; i < NUM_TIMERS; i++) { if (global_cats_config.timers[i].duration > 0) { - ev_timers[i].timer_id = - osTimerNew((osTimerFunc_t)trigger_event, osTimerOnce, (void *)ev_timers[i].execute_event, nullptr); + // NOLINTBEGIN(cppcoreguidelines-pro-type-reinterpret-cast) + ev_timers[i].timer_id = osTimerNew(reinterpret_cast(trigger_event), osTimerOnce, + reinterpret_cast(ev_timers[i].execute_event), nullptr); + // NOLINTEND(cppcoreguidelines-pro-type-reinterpret-cast) } } } diff --git a/flight_computer/src/init/system.cpp b/flight_computer/src/init/system.cpp index db50afd3..30921e90 100644 --- a/flight_computer/src/init/system.cpp +++ b/flight_computer/src/init/system.cpp @@ -40,7 +40,7 @@ void init_lfs() { log_error("LFS mounting failed with error %d!", err); log_error("Trying LFS format"); lfs_format(&lfs, get_lfs_cfg()); - int err2 = lfs_mount(&lfs, get_lfs_cfg()); + const int err2 = lfs_mount(&lfs, get_lfs_cfg()); if (err2 != 0) { log_error("LFS mounting failed again with error %d!", err2); } diff --git a/flight_computer/src/main.cpp b/flight_computer/src/main.cpp index ae8be47b..b2247f15 100644 --- a/flight_computer/src/main.cpp +++ b/flight_computer/src/main.cpp @@ -16,9 +16,9 @@ * along with this program. If not, see . */ -#include "main.h" +#include "main.hpp" #include "cmsis_os.h" -#include "target.h" +#include "target.hpp" #include "drivers/adc.hpp" @@ -45,8 +45,10 @@ #include "tasks/task_state_est.hpp" #include "tasks/task_telemetry.hpp" +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) extern driver::Servo* global_servo1; extern driver::Servo* global_servo2; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) static void init_logging() { log_set_level(LOG_TRACE); @@ -57,7 +59,7 @@ static void init_logging() { * @brief The application entry point. * @retval int */ -int main(void) { +int main() { /* MCU Configuration--------------------------------------------------------*/ target_pre_init(); @@ -76,8 +78,8 @@ int main(void) { // Build digital io static driver::OutputPin imu_cs(GPIOB, 0U); static driver::OutputPin barometer_cs(GPIOB, 1U); - static driver::OutputPin status_led(GPIOC, 14U); - static driver::InputPin test_button(GPIOB, 13U); + const static driver::OutputPin status_led(GPIOC, 14U); + const static driver::InputPin test_button(GPIOB, 13U); // Build the SPI driver static driver::Spi spi1(&hspi1); @@ -96,8 +98,10 @@ int main(void) { static driver::Buzzer buzzer(pwm_buzzer); // Build the sensors + // NOLINTBEGIN(misc-const-correctness) linter is confused static sensor::Lsm6dso32 imu(spi1, imu_cs); static sensor::Ms5607 barometer(spi1, barometer_cs); + // NOLINTEND(misc-const-correctness) global_servo1 = &servo1; global_servo2 = &servo2; @@ -155,6 +159,7 @@ int main(void) { task::Peripherals::Start(); + // NOLINTNEXTLINE(cppcoreguidelines-init-variables) linter is confused task::HealthMonitor::Start(task_buzzer); static const task::StateEstimation* task_state_estimation_ptr = nullptr; @@ -167,6 +172,7 @@ int main(void) { static const task::Preprocessing& task_preprocessing = task::Preprocessing::Start(task_sensor_read); + // NOLINTNEXTLINE(cppcoreguidelines-init-variables,cppcoreguidelines-avoid-non-const-global-variables) static task::StateEstimation& task_state_estimation = task::StateEstimation::Start(task_preprocessing); task::FlightFsm::Start(task_preprocessing, task_state_estimation); diff --git a/flight_computer/src/main.h b/flight_computer/src/main.hpp similarity index 88% rename from flight_computer/src/main.h rename to flight_computer/src/main.hpp index 0720f920..eb8d8af0 100644 --- a/flight_computer/src/main.h +++ b/flight_computer/src/main.hpp @@ -18,7 +18,9 @@ #pragma once -#include "target.h" +#include "target.hpp" + +#include /* Random pattern to tell system to jump to bootloader */ -#define BOOTLOADER_MAGIC_PATTERN 0xAA88BB77 +constexpr uint32_t BOOTLOADER_MAGIC_PATTERN = 0xAA88BB77; diff --git a/flight_computer/src/sensors/lsm6dso32.hpp b/flight_computer/src/sensors/lsm6dso32.hpp index 704d49b0..09780133 100644 --- a/flight_computer/src/sensors/lsm6dso32.hpp +++ b/flight_computer/src/sensors/lsm6dso32.hpp @@ -18,13 +18,14 @@ #pragma once -#include -#include -#include #include "drivers/gpio.hpp" #include "drivers/spi.hpp" #include "util/log.h" +#include +#include +#include + namespace sensor { class Lsm6dso32 { @@ -106,7 +107,8 @@ class Lsm6dso32 { */ void WriteRegister(const uint8_t reg, const uint8_t* data, const size_t length) { // Concatenate the register and the data - std::vector concatenated; + // NOLINTNEXTLINE(cppcoreguidelines-init-variables) linter is confused + std::vector concatenated{}; concatenated.push_back(reg); concatenated.insert(concatenated.end(), data, data + length); // Transfer the data diff --git a/flight_computer/src/sensors/ms5607.hpp b/flight_computer/src/sensors/ms5607.hpp index 47fe9b0a..b613a926 100644 --- a/flight_computer/src/sensors/ms5607.hpp +++ b/flight_computer/src/sensors/ms5607.hpp @@ -18,11 +18,12 @@ #pragma once -#include -#include #include "drivers/gpio.hpp" #include "drivers/spi.hpp" +#include +#include + namespace sensor { class Ms5607 { @@ -38,10 +39,7 @@ class Ms5607 { * @param spi reference the the SPI interface @injected * @param cs reference the the chip select output pin @injected */ - Ms5607(driver::Spi &spi, driver::OutputPin &cs) - : m_spi{spi}, m_cs{cs}, m_last_request{Request::kPressure}, m_pressure{}, m_temperature{}, m_coefficients{} { - m_cs.SetHigh(); - } + Ms5607(driver::Spi &spi, driver::OutputPin &cs) : m_spi{spi}, m_cs{cs} { m_cs.SetHigh(); } /** Initialize the sensor * @@ -59,6 +57,7 @@ class Ms5607 { } // Check if we received invalid data if ((m_coefficients[0] == 0U) || (m_coefficients[0] == UINT16_MAX)) { + // NOLINTNEXTLINE(readability-simplify-boolean-expr) return false; } return true; @@ -93,10 +92,11 @@ class Ms5607 { void GetMeasurement(int32_t &pressure, int32_t &temperature) { const uint32_t d1 = (static_cast(m_pressure[0]) << 16U) + (static_cast(m_pressure[1]) << 8U) + static_cast(m_pressure[2]); - const int32_t d2 = + const auto d2 = static_cast((static_cast(m_temperature[0]) << 16U) + (static_cast(m_temperature[1]) << 8U) + static_cast(m_temperature[2])); + // NOLINTBEGIN(hicpp-signed-bitwise) // Calculate compensated temperature const int64_t dT = d2 - static_cast(static_cast(m_coefficients[4]) << 8U); temperature = static_cast(2000) + ((dT * static_cast(m_coefficients[5])) >> 23U); @@ -106,8 +106,9 @@ class Ms5607 { (static_cast(m_coefficients[3] * static_cast(dT)) >> 6U); const int64_t sens = (static_cast(m_coefficients[0]) << 16U) + (static_cast(m_coefficients[2] * static_cast(dT)) >> 7U); + // NOLINTEND(hicpp-signed-bitwise) - pressure = ((((d1 * sens) >> 21U) - off) >> 15U); + pressure = static_cast((((d1 * sens) >> 21U) - off) >> 15U); } private: @@ -159,13 +160,13 @@ class Ms5607 { /// Reference to the chip select pin driver::OutputPin &m_cs; /// The last measurement request - Request m_last_request; + Request m_last_request{Request::kPressure}; /// The raw pressure data - uint8_t m_pressure[3]; + uint8_t m_pressure[3]{}; /// The raw temperature data - uint8_t m_temperature[3]; + uint8_t m_temperature[3]{}; /// The barometer calibration coefficients - uint16_t m_coefficients[6]; + uint16_t m_coefficients[6]{}; }; } // namespace sensor diff --git a/flight_computer/src/target/VEGA/stm32f4xx_hal_msp.cpp b/flight_computer/src/target/VEGA/stm32f4xx_hal_msp.cpp index c8114298..3f82a7a7 100644 --- a/flight_computer/src/target/VEGA/stm32f4xx_hal_msp.cpp +++ b/flight_computer/src/target/VEGA/stm32f4xx_hal_msp.cpp @@ -20,7 +20,7 @@ /* USER CODE END Header */ /* Includes ------------------------------------------------------------------*/ -#include "main.h" +#include "main.hpp" /* USER CODE BEGIN Includes */ /* USER CODE END Includes */ diff --git a/flight_computer/src/target/VEGA/stm32f4xx_it.cpp b/flight_computer/src/target/VEGA/stm32f4xx_it.cpp index c6c2da95..08a6801e 100644 --- a/flight_computer/src/target/VEGA/stm32f4xx_it.cpp +++ b/flight_computer/src/target/VEGA/stm32f4xx_it.cpp @@ -20,7 +20,7 @@ /* Includes ------------------------------------------------------------------*/ #include "stm32f4xx_it.h" -#include "main.h" +#include "main.hpp" #include "tusb.h" /* Private includes ----------------------------------------------------------*/ /* USER CODE BEGIN Includes */ diff --git a/flight_computer/src/target/VEGA/target.cpp b/flight_computer/src/target/VEGA/target.cpp index e1db67c9..a58fdba5 100644 --- a/flight_computer/src/target/VEGA/target.cpp +++ b/flight_computer/src/target/VEGA/target.cpp @@ -16,8 +16,9 @@ * along with this program. If not, see . */ -#include "target.h" +#include "target.hpp" +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) RTC_HandleTypeDef hrtc; ADC_HandleTypeDef hadc1; @@ -50,13 +51,14 @@ sens_info_t baro_info[NUM_BARO] = {{.sens_type = SensorType::kBaro, .resolution = 1.0F}}; PCD_HandleTypeDef hpcd_USB_OTG_FS; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) /** * @brief RTC Initialization Function * @param None * @retval None */ -static void RTC_Init(void) { +static void RTC_Init() { hrtc.Instance = RTC; hrtc.Init.HourFormat = RTC_HOURFORMAT_24; hrtc.Init.AsynchPrediv = 127; @@ -73,7 +75,7 @@ static void RTC_Init(void) { * @brief System Clock Configuration * @retval None */ -void SystemClock_Config(void) { +void SystemClock_Config() { RCC_OscInitTypeDef RCC_OscInitStruct = {0}; RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; @@ -120,7 +122,7 @@ void SystemClock_Config(void) { * @param None * @retval None */ -static void MX_ADC1_Init(void) { +static void MX_ADC1_Init() { ADC_ChannelConfTypeDef sConfig = {0}; /** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion) @@ -169,7 +171,7 @@ static void MX_ADC1_Init(void) { * @param None * @retval None */ -static void MX_SPI1_Init(void) { +static void MX_SPI1_Init() { /* SPI1 parameter configuration*/ hspi1.Instance = SPI1; hspi1.Init.Mode = SPI_MODE_MASTER; @@ -193,7 +195,7 @@ static void MX_SPI1_Init(void) { * @param None * @retval None */ -static void MX_SPI2_Init(void) { +static void MX_SPI2_Init() { /* SPI2 parameter configuration*/ hspi2.Instance = SPI2; hspi2.Init.Mode = SPI_MODE_MASTER; @@ -217,7 +219,7 @@ static void MX_SPI2_Init(void) { * @param None * @retval None */ -static void MX_TIM3_Init(void) { +static void MX_TIM3_Init() { TIM_MasterConfigTypeDef sMasterConfig = {0}; TIM_OC_InitTypeDef sConfigOC = {0}; @@ -254,7 +256,7 @@ static void MX_TIM3_Init(void) { * @param None * @retval None */ -static void MX_TIM4_Init(void) { +static void MX_TIM4_Init() { TIM_MasterConfigTypeDef sMasterConfig = {0}; TIM_OC_InitTypeDef sConfigOC = {0}; @@ -288,7 +290,7 @@ static void MX_TIM4_Init(void) { * @param None * @retval None */ -static void MX_USART1_UART_Init(void) { +static void MX_USART1_UART_Init() { huart1.Instance = USART1; huart1.Init.BaudRate = 115200; huart1.Init.WordLength = UART_WORDLENGTH_8B; @@ -307,7 +309,7 @@ static void MX_USART1_UART_Init(void) { * @param None * @retval None */ -static void MX_USART2_UART_Init(void) { +static void MX_USART2_UART_Init() { huart2.Instance = USART2; huart2.Init.BaudRate = 115200; huart2.Init.WordLength = UART_WORDLENGTH_8B; @@ -327,7 +329,7 @@ static void MX_USART2_UART_Init(void) { * @retval None */ -void MX_USB_OTG_FS_PCD_Init(void) { +void MX_USB_OTG_FS_PCD_Init() { hpcd_USB_OTG_FS.Instance = USB_OTG_FS; hpcd_USB_OTG_FS.Init.dev_endpoints = 4; hpcd_USB_OTG_FS.Init.speed = PCD_SPEED_FULL; @@ -346,7 +348,7 @@ void MX_USB_OTG_FS_PCD_Init(void) { /** * Enable DMA controller clock */ -static void MX_DMA_Init(void) { +static void MX_DMA_Init() { /* DMA controller clock enable */ __HAL_RCC_DMA2_CLK_ENABLE(); @@ -361,7 +363,7 @@ static void MX_DMA_Init(void) { * @param None * @retval None */ -static void MX_GPIO_Init(void) { +static void MX_GPIO_Init() { GPIO_InitTypeDef GPIO_InitStruct = {0}; /* GPIO Ports Clock Enable */ @@ -371,9 +373,11 @@ static void MX_GPIO_Init(void) { __HAL_RCC_GPIOB_CLK_ENABLE(); /*Configure GPIO pin Output Level */ + // NOLINTNEXTLINE(hicpp-signed-bitwise) HAL_GPIO_WritePin(GPIOC, LED1_Pin | LED2_Pin, GPIO_PIN_RESET); /*Configure GPIO pin Output Level */ + // NOLINTNEXTLINE(hicpp-signed-bitwise) HAL_GPIO_WritePin(GPIOB, CS_BARO1_Pin | CS_IMU1_Pin | PYRO_EN_Pin | FLASH_CS_Pin | IO1_Pin | PYRO1_Pin | PYRO2_Pin, GPIO_PIN_RESET); @@ -386,6 +390,7 @@ static void MX_GPIO_Init(void) { /*Configure GPIO pins : CS_BARO1_Pin CS_IMU1_Pin PYRO_EN_Pin FLASH_CS_Pin IO1_Pin PYRO1_Pin PYRO2_Pin */ + // NOLINTNEXTLINE(hicpp-signed-bitwise) GPIO_InitStruct.Pin = CS_BARO1_Pin | CS_IMU1_Pin | PYRO_EN_Pin | FLASH_CS_Pin | IO1_Pin | PYRO1_Pin | PYRO2_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; @@ -409,7 +414,7 @@ static void MX_GPIO_Init(void) { * @brief This function is executed in case of error occurrence. * @retval None */ -void Error_Handler(void) { +void Error_Handler() { __disable_irq(); while (true) { } @@ -438,8 +443,5 @@ bool target_init() { MX_TIM4_Init(); MX_USART1_UART_Init(); MX_USART2_UART_Init(); - if (HAL_GPIO_ReadPin(USB_DET_GPIO_Port, USB_DET_Pin)) { - return true; - } - return false; + return static_cast(HAL_GPIO_ReadPin(USB_DET_GPIO_Port, USB_DET_Pin)); } diff --git a/flight_computer/src/target/VEGA/target.h b/flight_computer/src/target/VEGA/target.hpp similarity index 86% rename from flight_computer/src/target/VEGA/target.h rename to flight_computer/src/target/VEGA/target.hpp index 0453d0da..617bc587 100644 --- a/flight_computer/src/target/VEGA/target.h +++ b/flight_computer/src/target/VEGA/target.hpp @@ -51,11 +51,12 @@ /***** Peripherals config *****/ // #define USE_CAN +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) /* ADC config */ extern ADC_HandleTypeDef hadc1; extern DMA_HandleTypeDef hdma_adc1; -#define ADC_HANDLE hadc1 -#define ADC_NUM_CHANNELS 3 +#define ADC_HANDLE hadc1 +inline constexpr uint8_t ADC_NUM_CHANNELS = 3; /* RTC config */ extern RTC_HandleTypeDef hrtc; @@ -77,6 +78,7 @@ extern CAN_HandleTypeDef hcan1; /* UART config */ extern UART_HandleTypeDef huart1; extern UART_HandleTypeDef huart2; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) /***** Device config *****/ @@ -95,11 +97,11 @@ extern UART_HandleTypeDef huart2; #define BUZZER_TIMER_CHANNEL TIM_CHANNEL_1 /* Sensor config */ -#define NUM_IMU 1 -#define NUM_BARO 1 +inline constexpr uint8_t NUM_IMU = 1; +inline constexpr uint8_t NUM_BARO = 1; -#define NUM_PYRO 2 -#define NUM_LOW_LEVEL_IO 1 +inline constexpr uint8_t NUM_PYRO = 2; +inline constexpr uint8_t NUM_LOW_LEVEL_IO = 1; enum class SensorType : uint32_t { kInvalid = 0, @@ -116,9 +118,11 @@ struct sens_info_t { float32_t resolution; }; +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) extern sens_info_t acc_info[NUM_IMU]; extern sens_info_t gyro_info[NUM_IMU]; extern sens_info_t baro_info[NUM_BARO]; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) #ifdef __cplusplus extern "C" { diff --git a/flight_computer/src/tasks/task.hpp b/flight_computer/src/tasks/task.hpp index 3fc068b5..b5b161e0 100644 --- a/flight_computer/src/tasks/task.hpp +++ b/flight_computer/src/tasks/task.hpp @@ -17,18 +17,20 @@ */ #pragma once -#include -#include -#include -#include #include "config/globals.hpp" #include "util/types.hpp" #include "cmsis_os.h" +#include +#include +#include +#include + namespace task { template +// NOLINTNEXTLINE(cppcoreguidelines-special-member-functions) not sure about the destructor class Task { public: /* Deleted move constructor & move assignment operator */ @@ -63,6 +65,7 @@ class Task { /* Protected constructor */ Task() = default; + // NOLINTNEXTLINE(cppcoreguidelines-non-private-member-variables-in-classes) flight_fsm_e m_fsm_enum = INVALID; /* Update FSM enum */ @@ -82,6 +85,7 @@ class Task { return true; } + // NOLINTNEXTLINE(misc-misplaced-const) void SetThreadId(const osThreadId_t thread_id) { m_thread_id = thread_id; } private: diff --git a/flight_computer/src/tasks/task_buzzer.cpp b/flight_computer/src/tasks/task_buzzer.cpp index eb076002..cc8436b9 100644 --- a/flight_computer/src/tasks/task_buzzer.cpp +++ b/flight_computer/src/tasks/task_buzzer.cpp @@ -34,7 +34,7 @@ void Buzzer::Beep(BeepCode code) const { osEventFlagsClear(m_buzzer_event_id, id); uint32_t duration = 0; for (int i = 0; i < s_status_code_length[id]; i++) { - char pitch = s_status_codes[id][i]; + const char pitch = s_status_codes[id][i]; if (pitch >= 'A' && pitch <= 'H') { m_buzzer.SetFrequency(s_frequency_lookup[pitch - 'A']); duration = static_cast(Duration::kLongBeep); diff --git a/flight_computer/src/tasks/task_cdc.cpp b/flight_computer/src/tasks/task_cdc.cpp index dc997532..d206c574 100644 --- a/flight_computer/src/tasks/task_cdc.cpp +++ b/flight_computer/src/tasks/task_cdc.cpp @@ -27,16 +27,17 @@ namespace task { +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) [[noreturn]] void Cdc::Run() noexcept { uint8_t buf[512]{}; while (true) { - while (tud_cdc_available()) { + while (tud_cdc_available() > 0) { global_usb_detection = true; - uint32_t count = tud_cdc_read(buf, sizeof(buf)); + const uint32_t count = tud_cdc_read(buf, sizeof(buf)); stream_write(USB_SG.in, buf, count); } - uint32_t len = stream_length(USB_SG.out); + const uint32_t len = stream_length(USB_SG.out); if (len > 0 && stream_read(USB_SG.out, buf, len)) { tud_cdc_write(buf, len); tud_cdc_write_flush(); diff --git a/flight_computer/src/tasks/task_cli.cpp b/flight_computer/src/tasks/task_cli.cpp index 089b98a5..e6513ec5 100644 --- a/flight_computer/src/tasks/task_cli.cpp +++ b/flight_computer/src/tasks/task_cli.cpp @@ -25,6 +25,7 @@ namespace task { +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) [[noreturn]] void Cli::Run() noexcept { log_raw("USB config started"); log_raw("CATS is now ready to receive commands..."); diff --git a/flight_computer/src/tasks/task_health_monitor.cpp b/flight_computer/src/tasks/task_health_monitor.cpp index 0a6d4a9a..ecbf1420 100644 --- a/flight_computer/src/tasks/task_health_monitor.cpp +++ b/flight_computer/src/tasks/task_health_monitor.cpp @@ -31,7 +31,7 @@ #include "tasks/task_simulator.hpp" #include "tasks/task_usb_device.hpp" -#include "target.h" +#include "target.hpp" /** Private Constants **/ @@ -41,6 +41,7 @@ namespace task { static void init_usb(); +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static bool cli_task_started = false; /** Exported Function Definitions **/ @@ -69,23 +70,23 @@ static bool cli_task_started = false; /* Get new FSM enum */ bool fsm_updated = GetNewFsmEnum(); - if (global_usb_detection == true && cli_task_started == false) { + if (global_usb_detection && !cli_task_started) { cli_task_started = true; Cli::Start(); } - if (HAL_GPIO_ReadPin(USB_DET_GPIO_Port, USB_DET_Pin) && usb_communication_complete == false) { + if ((HAL_GPIO_ReadPin(USB_DET_GPIO_Port, USB_DET_Pin) > 0) && !usb_communication_complete) { init_usb(); } - if (usb_device_initialized == false) { - if (HAL_GPIO_ReadPin(USB_DET_GPIO_Port, USB_DET_Pin)) { + if (!usb_device_initialized) { + if (HAL_GPIO_ReadPin(USB_DET_GPIO_Port, USB_DET_Pin) > 0) { usb_device_initialized = true; } } // Check battery level - battery_level_e level = battery_level(); - bool level_changed = (old_level != level); + const battery_level_e level = battery_level(); + const bool level_changed = (old_level != level); if ((level == BATTERY_CRIT) && level_changed) { clear_error(CATS_ERR_BAT_LOW); @@ -149,13 +150,13 @@ static bool cli_task_started = false; void HealthMonitor::DeterminePyroCheck() { // Loop over all events for (int ev_idx = 0; ev_idx < NUM_EVENTS; ev_idx++) { - uint16_t nr_actions = cc_get_num_actions((cats_event_e)ev_idx); + const uint16_t nr_actions = cc_get_num_actions(static_cast(ev_idx)); // If an action is mapped to the event if (nr_actions > 0) { // Loop over all actions for (uint16_t act_idx = 0; act_idx < nr_actions; act_idx++) { config_action_t action{}; - if (cc_get_action((cats_event_e)ev_idx, act_idx, &action) == true) { + if (cc_get_action(static_cast(ev_idx), act_idx, &action)) { switch (action.action_idx) { case ACT_HIGH_CURRENT_ONE: m_check_pyro_1 = true; diff --git a/flight_computer/src/tasks/task_peripherals.cpp b/flight_computer/src/tasks/task_peripherals.cpp index dc532bd6..10942d6b 100644 --- a/flight_computer/src/tasks/task_peripherals.cpp +++ b/flight_computer/src/tasks/task_peripherals.cpp @@ -35,8 +35,9 @@ namespace task { * @param argument: Not used * @retval None */ +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) [[noreturn]] void Peripherals::Run() noexcept { - cats_event_e curr_event; + cats_event_e curr_event{EV_CALIBRATE}; while (true) { if (osMessageQueueGet(event_queue, &curr_event, nullptr, osWaitForever) == osOK) { /* Start Timer if the Config says so */ @@ -58,9 +59,9 @@ namespace task { } peripheral_act_t* action_list = event_action_map[curr_event].action_list; - uint8_t num_actions = event_action_map[curr_event].num_actions; + const uint8_t num_actions = event_action_map[curr_event].num_actions; for (uint32_t i = 0; i < num_actions; ++i) { - timestamp_t curr_ts = osKernelGetTickCount(); + const timestamp_t curr_ts = osKernelGetTickCount(); /* get the actuator function */ peripheral_act_fp curr_fp = action_table[action_list[i].action]; if (curr_fp != nullptr) { @@ -75,7 +76,7 @@ namespace task { if (num_actions == 0) { log_error("EXECUTING EVENT: %s, ACTION: %s", GetStr(curr_event, event_map), GetStr(action_list[0].action, action_map)); - timestamp_t curr_ts = osKernelGetTickCount(); + const timestamp_t curr_ts = osKernelGetTickCount(); event_info_t event_info = {.event = curr_event, .action = {ACT_NO_OP}}; record(curr_ts, EVENT_INFO, &event_info); } diff --git a/flight_computer/src/tasks/task_preprocessing.cpp b/flight_computer/src/tasks/task_preprocessing.cpp index 12ff638c..4f4da6e1 100644 --- a/flight_computer/src/tasks/task_preprocessing.cpp +++ b/flight_computer/src/tasks/task_preprocessing.cpp @@ -16,7 +16,7 @@ * along with this program. If not, see . */ -#include "target.h" +#include "target.hpp" #include "config/globals.hpp" #include "control/calibration.hpp" @@ -25,7 +25,7 @@ #include "util/task_util.hpp" -#define MAX_NUM_SAME_VALUE 7 +constexpr uint8_t MAX_NUM_SAME_VALUE = 7; namespace task { @@ -114,62 +114,61 @@ SI_data_t Preprocessing::GetSIData() const noexcept { return m_si_data; } void Preprocessing::AvgToSi() noexcept { float32_t counter = 0; -#if NUM_IMU > 0 - /* Reset SI data */ - m_si_data.acc.x = 0; - m_si_data.acc.y = 0; - m_si_data.acc.z = 0; - m_si_data.gyro.x = 0; - m_si_data.gyro.y = 0; - m_si_data.gyro.z = 0; - - /* Sum up all non-eliminated IMUs and transform to SI */ - for (int i = 0; i < NUM_IMU; i++) { - if (m_sensor_elimination.faulty_imu[i] == 0) { - counter++; - m_si_data.acc.x += (float32_t)m_imu_data[i].acc.x * acc_info[i].conversion_to_SI; - m_si_data.acc.y += (float32_t)m_imu_data[i].acc.y * acc_info[i].conversion_to_SI; - m_si_data.acc.z += (float32_t)m_imu_data[i].acc.z * acc_info[i].conversion_to_SI; - m_si_data.gyro.x += (float32_t)m_imu_data[i].gyro.x * gyro_info[i].conversion_to_SI; - m_si_data.gyro.y += (float32_t)m_imu_data[i].gyro.y * gyro_info[i].conversion_to_SI; - m_si_data.gyro.z += (float32_t)m_imu_data[i].gyro.z * gyro_info[i].conversion_to_SI; + if constexpr (NUM_IMU > 0) { + /* Reset SI data */ + m_si_data.acc.x = 0; + m_si_data.acc.y = 0; + m_si_data.acc.z = 0; + m_si_data.gyro.x = 0; + m_si_data.gyro.y = 0; + m_si_data.gyro.z = 0; + + /* Sum up all non-eliminated IMUs and transform to SI */ + for (int i = 0; i < NUM_IMU; i++) { + if (m_sensor_elimination.faulty_imu[i] == 0) { + counter++; + m_si_data.acc.x += static_cast(m_imu_data[i].acc.x) * acc_info[i].conversion_to_SI; + m_si_data.acc.y += static_cast(m_imu_data[i].acc.y) * acc_info[i].conversion_to_SI; + m_si_data.acc.z += static_cast(m_imu_data[i].acc.z) * acc_info[i].conversion_to_SI; + m_si_data.gyro.x += static_cast(m_imu_data[i].gyro.x) * gyro_info[i].conversion_to_SI; + m_si_data.gyro.y += static_cast(m_imu_data[i].gyro.y) * gyro_info[i].conversion_to_SI; + m_si_data.gyro.z += static_cast(m_imu_data[i].gyro.z) * gyro_info[i].conversion_to_SI; + } } - } - /* average for SI data */ - if (counter > 0) { - m_si_data.acc.x /= counter; - m_si_data.acc.y /= counter; - m_si_data.acc.z /= counter; - m_si_data.gyro.x /= counter; - m_si_data.gyro.y /= counter; - m_si_data.gyro.z /= counter; - clear_error(CATS_ERR_FILTER_ACC); - } else { - m_si_data.acc = m_si_data_old.acc; - m_si_data.gyro = m_si_data_old.gyro; - add_error(CATS_ERR_FILTER_ACC); + /* average for SI data */ + if (counter > 0) { + m_si_data.acc.x /= counter; + m_si_data.acc.y /= counter; + m_si_data.acc.z /= counter; + m_si_data.gyro.x /= counter; + m_si_data.gyro.y /= counter; + m_si_data.gyro.z /= counter; + clear_error(CATS_ERR_FILTER_ACC); + } else { + m_si_data.acc = m_si_data_old.acc; + m_si_data.gyro = m_si_data_old.gyro; + add_error(CATS_ERR_FILTER_ACC); + } } -#endif - -#if NUM_BARO > 0 - counter = 0; - m_si_data.pressure = 0; - for (int i = 0; i < NUM_BARO; i++) { - if (m_sensor_elimination.faulty_baro[i] == 0) { - counter++; - m_si_data.pressure += (float32_t)m_baro_data[i].pressure * baro_info[i].conversion_to_SI; + if constexpr (NUM_BARO > 0) { + counter = 0; + m_si_data.pressure = 0; + for (int i = 0; i < NUM_BARO; i++) { + if (m_sensor_elimination.faulty_baro[i] == 0) { + counter++; + m_si_data.pressure += static_cast(m_baro_data[i].pressure) * baro_info[i].conversion_to_SI; + } + } + if (counter > 0) { + m_si_data.pressure /= counter; + clear_error(CATS_ERR_FILTER_HEIGHT); + } else { + m_si_data.pressure = m_si_data_old.pressure; + add_error(CATS_ERR_FILTER_HEIGHT); } } - if (counter > 0) { - m_si_data.pressure /= counter; - clear_error(CATS_ERR_FILTER_HEIGHT); - } else { - m_si_data.pressure = m_si_data_old.pressure; - add_error(CATS_ERR_FILTER_HEIGHT); - } -#endif } void Preprocessing::MedianFilter() noexcept { @@ -213,11 +212,11 @@ void Preprocessing::CheckSensors() noexcept { /* IMU */ for (uint8_t i = 0; i < NUM_IMU; i++) { - status = (cats_error_e)(CheckSensorBounds(i, &acc_info[i]) | CheckSensorFreezing(i, &acc_info[i])); + status = static_cast(CheckSensorBounds(i, &acc_info[i]) | CheckSensorFreezing(i, &acc_info[i])); /* Check if accel is not faulty anymore */ if (status == CATS_ERR_OK) { m_sensor_elimination.faulty_imu[i] = 0; - clear_error((cats_error_e)(CATS_ERR_IMU_0 << i)); + clear_error(static_cast(CATS_ERR_IMU_0 << i)); } else { add_error(status); } @@ -225,11 +224,11 @@ void Preprocessing::CheckSensors() noexcept { /* Barometer */ for (uint8_t i = 0; i < NUM_BARO; i++) { - status = (cats_error_e)(CheckSensorBounds(i, &baro_info[i]) | CheckSensorFreezing(i, &baro_info[i])); + status = static_cast(CheckSensorBounds(i, &baro_info[i]) | CheckSensorFreezing(i, &baro_info[i])); /* Check if accel is not faulty anymore */ if (status == CATS_ERR_OK) { m_sensor_elimination.faulty_baro[i] = 0; - clear_error((cats_error_e)(CATS_ERR_BARO_0 << i)); + clear_error(static_cast(CATS_ERR_BARO_0 << i)); } else { add_error(status); } @@ -241,17 +240,19 @@ cats_error_e Preprocessing::CheckSensorBounds(uint8_t index, const sens_info_t * switch (sens_info->sens_type) { case SensorType::kBaro: - if ((((float32_t)m_baro_data[index].pressure * sens_info->conversion_to_SI) > sens_info->upper_limit) || - (((float32_t)m_baro_data[index].pressure * sens_info->conversion_to_SI) < sens_info->lower_limit)) { + if (((static_cast(m_baro_data[index].pressure) * sens_info->conversion_to_SI) > + sens_info->upper_limit) || + ((static_cast(m_baro_data[index].pressure) * sens_info->conversion_to_SI) < + sens_info->lower_limit)) { m_sensor_elimination.faulty_baro[index] = 1; - status = (cats_error_e)(CATS_ERR_BARO_0 << index); + status = static_cast(CATS_ERR_BARO_0 << index); } break; case SensorType::kAcc: - if ((((float32_t)m_imu_data[index].acc.x * sens_info->conversion_to_SI) > sens_info->upper_limit) || - (((float32_t)m_imu_data[index].acc.x * sens_info->conversion_to_SI) < sens_info->lower_limit)) { + if (((static_cast(m_imu_data[index].acc.x) * sens_info->conversion_to_SI) > sens_info->upper_limit) || + ((static_cast(m_imu_data[index].acc.x) * sens_info->conversion_to_SI) < sens_info->lower_limit)) { m_sensor_elimination.faulty_imu[index] = 1; - status = (cats_error_e)(CATS_ERR_IMU_0 << index); + status = static_cast(CATS_ERR_IMU_0 << index); } break; default: @@ -270,7 +271,7 @@ cats_error_e Preprocessing::CheckSensorFreezing(uint8_t index, const sens_info_t m_sensor_elimination.freeze_counter_baro[index]++; if (m_sensor_elimination.freeze_counter_baro[index] > MAX_NUM_SAME_VALUE) { m_sensor_elimination.faulty_baro[index] = 1; - status = (cats_error_e)(CATS_ERR_BARO_0 << index); + status = static_cast(CATS_ERR_BARO_0 << index); } } else { m_sensor_elimination.last_value_baro[index] = m_baro_data[index].pressure; @@ -282,7 +283,7 @@ cats_error_e Preprocessing::CheckSensorFreezing(uint8_t index, const sens_info_t m_sensor_elimination.freeze_counter_imu[index]++; if (m_sensor_elimination.freeze_counter_imu[index] > MAX_NUM_SAME_VALUE) { m_sensor_elimination.faulty_imu[index] = 1; - status = (cats_error_e)(CATS_ERR_IMU_0 << index); + status = static_cast(CATS_ERR_IMU_0 << index); } } else { m_sensor_elimination.last_value_imu[index] = m_imu_data[index].acc.x; diff --git a/flight_computer/src/tasks/task_recorder.cpp b/flight_computer/src/tasks/task_recorder.cpp index dbd303fd..51d3b6e2 100644 --- a/flight_computer/src/tasks/task_recorder.cpp +++ b/flight_computer/src/tasks/task_recorder.cpp @@ -28,7 +28,7 @@ /** Private Constants **/ -#define REC_BUFFER_LEN 256 +constexpr uint16_t REC_BUFFER_LEN = 256; /** Private Function Declarations **/ @@ -46,6 +46,7 @@ void create_stats_and_cfg_log(); namespace task { +// NOLINTNEXTLINE(readability-convert-member-functions-to-static,readability-function-cognitive-complexity) [[noreturn]] void Recorder::Run() noexcept { uint8_t rec_buffer[REC_BUFFER_LEN] = {}; @@ -71,11 +72,11 @@ namespace task { log_error("Invalid command value!"); break; case REC_CMD_FILL_Q: { - rec_elem_t dummy_log_elem; + rec_elem_t dummy_log_elem{}; uint32_t cmd_check_counter = 0; log_info("Started filling pre recording queue"); while (true) { - uint32_t curr_elem_count = osMessageQueueGetCount(rec_queue); + const uint32_t curr_elem_count = osMessageQueueGetCount(rec_queue); if (curr_elem_count > REC_QUEUE_PRE_THRUSTING_LIMIT) { /* If the number of elements goes over REC_QUEUE_PRE_THRUSTING_LIMIT we start to empty it. When thrusting is * detected we will have around REC_QUEUE_PRE_THRUSTING_LIMIT elements in the queue and in the next loop @@ -119,7 +120,7 @@ namespace task { log_info("Creating log file %lu...", flight_counter); lfs_file_open(&lfs, ¤t_flight_file, current_flight_filename, LFS_O_WRONLY | LFS_O_CREAT); lfs_file_write(&lfs, ¤t_flight_file, code_version, strlen(code_version) + 1); // including '\0' - rec_elem_t curr_log_elem; + rec_elem_t curr_log_elem{}; uint32_t sync_counter = 0; log_info("Started writing to flash"); while (true) { @@ -144,7 +145,8 @@ namespace task { } } - const int32_t sz = lfs_file_write(&lfs, ¤t_flight_file, rec_buffer, (lfs_size_t)REC_BUFFER_LEN); + const int32_t sz = + lfs_file_write(&lfs, ¤t_flight_file, rec_buffer, static_cast(REC_BUFFER_LEN)); /* Writing less than REC_BUFFER_LEN bytes indicates that there is not enough space left on the flash chip. */ if ((sz > 0) && (static_cast(sz) < static_cast(REC_BUFFER_LEN))) { @@ -168,7 +170,9 @@ namespace task { } if (rec_buffer_idx > 0) { - memcpy(rec_buffer, (uint8_t *)(&curr_log_elem) + curr_log_elem_size - bytes_remaining, bytes_remaining); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + memcpy(rec_buffer, reinterpret_cast(&curr_log_elem) + curr_log_elem_size - bytes_remaining, + bytes_remaining); } /* Check for a new command */ if (osMessageQueueGetCount(rec_cmd_queue) > 0) { @@ -264,10 +268,10 @@ void create_cfg_file() { snprintf(current_stats_filename, MAX_FILENAME_SIZE, "configs/flight_%05lu.cfg", flight_counter); log_info("Creating flights_%05lu.cfg...", flight_counter); - int err = lfs_file_open(&lfs, ¤t_stats_file, current_stats_filename, LFS_O_WRONLY | LFS_O_CREAT); + int32_t err = lfs_file_open(&lfs, ¤t_stats_file, current_stats_filename, LFS_O_WRONLY | LFS_O_CREAT); if (err != LFS_ERR_OK) { - log_error("Creating config file %lu failed with %d", flight_counter, err); + log_error("Creating config file %lu failed with %ld", flight_counter, err); } else { log_info("Created config file %lu.", flight_counter); } @@ -275,7 +279,7 @@ void create_cfg_file() { err = lfs_file_write(&lfs, ¤t_stats_file, &global_flight_stats.config, sizeof(global_flight_stats.config)); if (err < 0) { - log_error("Writing to config file failed with %d", err); + log_error("Writing to config file failed with %ld", err); } else if (auto err_u = static_cast(err); err_u < sizeof(global_flight_stats.config)) { log_error("Written less bytes to config file than expected: %lu vs %u", err_u, sizeof(global_flight_stats.config)); } @@ -283,7 +287,7 @@ void create_cfg_file() { err = lfs_file_close(&lfs, ¤t_stats_file); if (err != LFS_ERR_OK) { - log_error("Closing config file failed with %d", err); + log_error("Closing config file failed with %ld", err); } } @@ -297,21 +301,22 @@ void create_stats_file() { auto *string_buf = static_cast(pvPortMalloc(kStringBufSz * sizeof(char))); log_info("Creating stats file %lu...", flight_counter); - int err = lfs_file_open(&lfs, ¤t_stats_file, current_stats_filename, LFS_O_WRONLY | LFS_O_CREAT); + int32_t err = lfs_file_open(&lfs, ¤t_stats_file, current_stats_filename, LFS_O_WRONLY | LFS_O_CREAT); if (err != LFS_ERR_OK) { - log_error("Creating stats file %lu failed with %d", flight_counter, err); + log_error("Creating stats file %lu failed with %ld", flight_counter, err); vPortFree(string_buf); return; - } else { - log_info("Created stats file %lu.", flight_counter); } + log_info("Created stats file %lu.", flight_counter); + auto write_line = [&](const char *fmt, ...) __attribute__((format(printf, 2, 3))) { va_list va; va_start(va, fmt); vsnprintf(string_buf, kStringBufSz, fmt, va); va_end(va); + // NOLINTNEXTLINE(hicpp-signed-bitwise) err |= lfs_file_write(&lfs, ¤t_stats_file, string_buf, strlen(string_buf)); }; @@ -344,13 +349,13 @@ void create_stats_file() { write_line("========================\r\n"); if (err < 0) { - log_error("Writing to stats file failed with %d", err); + log_error("Writing to stats file failed with %ld", err); } err = lfs_file_close(&lfs, ¤t_stats_file); if (err != LFS_ERR_OK) { - log_error("Closing stats file failed with %d", err); + log_error("Closing stats file failed with %ld", err); } vPortFree(string_buf); diff --git a/flight_computer/src/tasks/task_sensor_read.cpp b/flight_computer/src/tasks/task_sensor_read.cpp index 8b91506a..bd517bc4 100644 --- a/flight_computer/src/tasks/task_sensor_read.cpp +++ b/flight_computer/src/tasks/task_sensor_read.cpp @@ -49,7 +49,7 @@ imu_data_t SensorRead::GetImu(uint8_t index) const noexcept { return m_imu_data[ /* This task is sampled with 2 times the control sampling frequency to maximize speed of the barometer. In one * timestep the Baro pressure is read out and then the Baro Temperature. The other sensors are only read out one in * two times. */ - constexpr uint32_t tick_update = sysGetTickFreq() / (2 * CONTROL_SAMPLING_FREQ); + constexpr uint32_t tick_update = sysGetTickFreq() / static_cast(2 * CONTROL_SAMPLING_FREQ); while (true) { // Readout the baro register m_barometer->Read(); @@ -81,8 +81,10 @@ imu_data_t SensorRead::GetImu(uint8_t index) const noexcept { return m_imu_data[ m_imu_data[i].acc = global_imu_sim[i].acc; } else { if (imu_initialized[i]) { + // NOLINTBEGIN(cppcoreguidelines-pro-type-reinterpret-cast) m_imu->ReadGyroRaw(reinterpret_cast(&m_imu_data[i].gyro)); m_imu->ReadAccelRaw(reinterpret_cast(&m_imu_data[i].acc)); + // NOLINTEND(cppcoreguidelines-pro-type-reinterpret-cast) } } record(tick_count, add_id_to_record_type(IMU, i), &(m_imu_data[i])); diff --git a/flight_computer/src/tasks/task_simulator.cpp b/flight_computer/src/tasks/task_simulator.cpp index 5a580720..3affb482 100644 --- a/flight_computer/src/tasks/task_simulator.cpp +++ b/flight_computer/src/tasks/task_simulator.cpp @@ -19,7 +19,7 @@ #include "tasks/task_simulator.hpp" #include "cli/cli.hpp" #include "config/globals.hpp" -#include "target.h" +#include "target.hpp" #include "util/log.h" #include "util/task_util.hpp" @@ -132,7 +132,7 @@ void Simulator::ComputeSimValues(float32_t time) { [[noreturn]] void Simulator::Run() noexcept { imu_data_t sim_imu_data[NUM_IMU] = {}; - log_mode_e prev_log_mode = log_get_mode(); + const log_mode_e prev_log_mode = log_get_mode(); log_set_mode(LOG_MODE_SIM); /* RNG Init with known seed */ @@ -144,7 +144,7 @@ void Simulator::ComputeSimValues(float32_t time) { constexpr uint32_t tick_update = sysGetTickFreq() / CONTROL_SAMPLING_FREQ; /* initialise time */ - timestamp_t sim_start = osKernelGetTickCount(); + const timestamp_t sim_start = osKernelGetTickCount(); float32_t time_to_liftoff = 0.0F; // This is in seconds while (true) { @@ -191,6 +191,7 @@ void Simulator::ComputeSimValues(float32_t time) { } /* Write into global pressure sim variable */ + // NOLINTNEXTLINE(modernize-loop-convert) for (int i = 0; i < NUM_BARO; i++) { global_baro_sim[i].pressure = static_cast(static_cast(m_current_press) + rand_bounds(-m_press_noise, m_press_noise)); @@ -213,7 +214,7 @@ void Simulator::ComputeSimValues(float32_t time) { /** Private Function Definitions **/ float32_t rand_bounds(float32_t lower_b, float32_t upper_b) { - float32_t var = (static_cast(rand() % 1000)) / 1000; + const float32_t var = (static_cast(rand() % 1000)) / 1000; return var * (upper_b - lower_b) - lower_b; } @@ -261,5 +262,6 @@ void start_simulation(char *args) { simulation_started = true; log_info("Starting Simulation"); + // NOLINTNEXTLINE(cppcoreguidelines-init-variables) linter is confused task::Simulator::Start(sim_config); } diff --git a/flight_computer/src/tasks/task_state_est.cpp b/flight_computer/src/tasks/task_state_est.cpp index e1e351b4..847c5149 100644 --- a/flight_computer/src/tasks/task_state_est.cpp +++ b/flight_computer/src/tasks/task_state_est.cpp @@ -22,13 +22,14 @@ namespace task { +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) StateEstimation* global_state_estimation = nullptr; void StateEstimation::GetEstimationInputData() { /* After apogee we assume that the linear acceleration is zero. This assumption is true if the parachute has been * ejected. If this assumption is not done, the linear acceleration will be bad because of movement of the rocket * due to parachute forces. */ - state_estimation_input_t input = m_task_preprocessing.GetEstimationInput(); + const state_estimation_input_t input = m_task_preprocessing.GetEstimationInput(); if (m_fsm_enum < DROGUE) { m_filter.measured_acceleration = input.acceleration_z; @@ -91,14 +92,15 @@ estimation_output_t StateEstimation::GetEstimationOutput() const noexcept { /* Do a Kalman Step */ kalman_step(&m_filter, m_fsm_enum); - orientation_info_t orientation_info; + orientation_info_t orientation_info{}; /* log_raw("[%lu] KF: q0: %ld; q1: %ld; q2: %ld; q3: %ld", tick_count, (int32_t)(orientation_filter.estimate_data[0] * 1000), (int32_t)(orientation_filter.estimate_data[1] * 1000), (int32_t)(orientation_filter.estimate_data[2] * 1000), (int32_t)(orientation_filter.estimate_data[3] * 1000)); */ for (uint8_t i = 0; i < 4; i++) { - orientation_info.estimated_orientation[i] = (int16_t)(m_orientation_filter.estimate_data[i] * 10000.0f); + orientation_info.estimated_orientation[i] = + static_cast(m_orientation_filter.estimate_data[i] * 10000.0F); } record(tick_count, ORIENTATION_INFO, &orientation_info); diff --git a/flight_computer/src/tasks/task_state_est.hpp b/flight_computer/src/tasks/task_state_est.hpp index 4aae3114..68e9216b 100644 --- a/flight_computer/src/tasks/task_state_est.hpp +++ b/flight_computer/src/tasks/task_state_est.hpp @@ -18,21 +18,21 @@ #pragma once -#include -#include "task.hpp" - #include "control/kalman_filter.hpp" #include "control/orientation_filter.hpp" +#include "task.hpp" +#include "task_preprocessing.hpp" #include "tasks/task_preprocessing.hpp" #include "util/error_handler.hpp" #include "util/log.h" #include "util/types.hpp" -#include "task_preprocessing.hpp" +#include namespace task { class StateEstimation; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern StateEstimation* global_state_estimation; class StateEstimation final : public Task { diff --git a/flight_computer/src/tasks/task_telemetry.cpp b/flight_computer/src/tasks/task_telemetry.cpp index 5eabccda..425ef11a 100644 --- a/flight_computer/src/tasks/task_telemetry.cpp +++ b/flight_computer/src/tasks/task_telemetry.cpp @@ -35,14 +35,15 @@ namespace task { -static uint8_t uart_char; - -#define UART_FIFO_SIZE 40 +constexpr uint8_t UART_FIFO_SIZE = 40; +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) +static uint8_t uart_char; static uint8_t usb_fifo_in_buf[UART_FIFO_SIZE]; static fifo_t uart_fifo = { .head = 0, .tail = 0, .used = 0, .size = UART_FIFO_SIZE, .buf = usb_fifo_in_buf, .mutex = false}; static stream_t uart_stream = {.fifo = &uart_fifo, .timeout_msec = 1}; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) enum state_e { STATE_OP, @@ -51,9 +52,9 @@ enum state_e { STATE_CRC, }; -#define INDEX_OP 0 -#define INDEX_LEN 1 -#define TELE_MAX_POWER 30 +constexpr uint8_t INDEX_OP = 0; +constexpr uint8_t INDEX_LEN = 1; +constexpr uint8_t TELE_MAX_POWER = 30; static constexpr uint32_t kDefaultPaGain = 34; void Telemetry::PackTxMessage(uint32_t ts, gnss_data_t* gnss, packed_tx_msg_t* tx_payload, @@ -151,6 +152,7 @@ void Telemetry::ParseRxMessage(packed_rx_msg_t* rx_payload) noexcept { } } +// NOLINTNEXTLINE(readability-function-cognitive-complexity) [[noreturn]] void Telemetry::Run() noexcept { /* Give the telemetry hardware some time to initialize */ osDelay(5000); @@ -162,6 +164,7 @@ void Telemetry::ParseRxMessage(packed_rx_msg_t* rx_payload) noexcept { if (global_cats_config.telemetry_settings.test_phrase[0] != '\0') { testing_enabled = global_cats_config.enable_testing_mode; const char* test_phrase = global_cats_config.telemetry_settings.test_phrase; + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) m_test_phrase_crc = crc32(reinterpret_cast(test_phrase), strlen(test_phrase)); } @@ -191,7 +194,7 @@ void Telemetry::ParseRxMessage(packed_rx_msg_t* rx_payload) noexcept { } /* Start the interrupt request for the UART */ - HAL_UART_Receive_IT(&TELEMETRY_UART_HANDLE, (uint8_t*)&uart_char, 1); + HAL_UART_Receive_IT(&TELEMETRY_UART_HANDLE, &uart_char, 1); uint8_t uart_buffer[20]; uint32_t uart_index = 0; @@ -224,16 +227,17 @@ void Telemetry::ParseRxMessage(packed_rx_msg_t* rx_payload) noexcept { PackTxMessage(tick_count, &gnss_data, &tx_payload, estimation_output); - SendTxPayload((uint8_t*)&tx_payload, sizeof(packed_tx_msg_t)); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + SendTxPayload(reinterpret_cast(&tx_payload), sizeof(packed_tx_msg_t)); if ((tick_count - uart_timeout) > 60000) { uart_timeout = tick_count; - HAL_UART_Receive_IT(&TELEMETRY_UART_HANDLE, (uint8_t*)&uart_char, 1); + HAL_UART_Receive_IT(&TELEMETRY_UART_HANDLE, &uart_char, 1); } /* Check for data from the Telemetry MCU */ while (stream_length(&uart_stream) > 1) { - uint8_t ch; + uint8_t ch{0}; uart_timeout = tick_count; stream_read_byte(&uart_stream, &ch); switch (state) { @@ -264,7 +268,7 @@ void Telemetry::ParseRxMessage(packed_rx_msg_t* rx_payload) noexcept { } break; case STATE_CRC: { - uint8_t crc = crc8(uart_buffer, uart_index + 2); + const uint8_t crc = crc8(uart_buffer, uart_index + 2); if (crc == ch) { gnss_position_received = Parse(uart_buffer[INDEX_OP], &uart_buffer[2], uart_buffer[INDEX_LEN], &gnss_data); } @@ -320,14 +324,10 @@ void Telemetry::ParseRxMessage(packed_rx_msg_t* rx_payload) noexcept { } } -bool Telemetry::CheckValidOpCode(uint8_t op_code) const noexcept { +bool Telemetry::CheckValidOpCode(uint8_t op_code) noexcept { /* TODO loop over all opcodes and check if it exists */ - if (op_code == CMD_GNSS_INFO || op_code == CMD_GNSS_LOC || op_code == CMD_RX || op_code == CMD_INFO || - op_code == CMD_GNSS_TIME || op_code == CMD_TEMP_INFO || op_code == CMD_VERSION_INFO) { - return true; - } else { - return false; - } + return op_code == CMD_GNSS_INFO || op_code == CMD_GNSS_LOC || op_code == CMD_RX || op_code == CMD_INFO || + op_code == CMD_GNSS_TIME || op_code == CMD_TEMP_INFO || op_code == CMD_VERSION_INFO; } /** @@ -340,7 +340,9 @@ bool Telemetry::CheckValidOpCode(uint8_t op_code) const noexcept { * @return */ bool Telemetry::Parse(uint8_t op_code, const uint8_t* buffer, uint32_t length, gnss_data_t* gnss) noexcept { - if (length < 1) return false; + if (length < 1) { + return false; + } bool gnss_position_received = false; @@ -364,7 +366,7 @@ bool Telemetry::Parse(uint8_t op_code, const uint8_t* buffer, uint32_t length, g gnss->time = (gnss_time_t){.hour = buffer[2], .min = buffer[1], .sec = buffer[0]}; log_info("[GNSS time]: %02hu:%02hu:%02hu UTC", gnss->time.hour, gnss->time.min, gnss->time.sec); } else if (op_code == CMD_TEMP_INFO) { - memcpy(const_cast(&m_amplifier_temperature), buffer, 4); + memcpy(&m_amplifier_temperature, buffer, 4); if (m_amplifier_temperature > k_amplifier_hot_limit) { add_error(CATS_ERR_TELEMETRY_HOT); } @@ -382,6 +384,7 @@ bool Telemetry::Parse(uint8_t op_code, const uint8_t* buffer, uint32_t length, g void Telemetry::SendLinkPhrase() noexcept { const char* phrase = global_cats_config.telemetry_settings.link_phrase; + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) char* and uint8_t* are interchangeable uint32_t uplink_phrase_crc = crc32(reinterpret_cast(phrase), strlen(phrase)); uint8_t out[7]; // 1 OP + 1 LEN + 4 DATA + 1 CRC out[0] = CMD_LINK_PHRASE; @@ -436,7 +439,7 @@ void Telemetry::SendDisable() noexcept { void Telemetry::SendTxPayload(uint8_t* payload, uint32_t length) noexcept { uint8_t out[18]; // 1 OP + 1 LEN + 15 DATA + 1 CRC out[0] = CMD_TX; - out[1] = (uint8_t)length; + out[1] = static_cast(length); memcpy(&out[2], payload, length); out[length + 2] = crc8(out, length + 2); HAL_UART_Transmit(&TELEMETRY_UART_HANDLE, out, length + 3, 2); @@ -444,7 +447,7 @@ void Telemetry::SendTxPayload(uint8_t* payload, uint32_t length) noexcept { extern "C" void HAL_UART_RxCpltCallback(UART_HandleTypeDef* huart) { if (huart == &TELEMETRY_UART_HANDLE) { - uint8_t tmp = uart_char; + const uint8_t tmp = uart_char; HAL_UART_Receive_IT(&TELEMETRY_UART_HANDLE, &uart_char, 1); stream_write_byte(&uart_stream, tmp); } diff --git a/flight_computer/src/tasks/task_telemetry.hpp b/flight_computer/src/tasks/task_telemetry.hpp index 377a8ee4..5c0daa3e 100644 --- a/flight_computer/src/tasks/task_telemetry.hpp +++ b/flight_computer/src/tasks/task_telemetry.hpp @@ -84,7 +84,7 @@ class Telemetry final : public Task { static void SendEnable() noexcept; static void SendDisable() noexcept; static void SendTxPayload(uint8_t* payload, uint32_t length) noexcept; - [[nodiscard]] bool CheckValidOpCode(uint8_t op_code) const noexcept; + [[nodiscard]] static bool CheckValidOpCode(uint8_t op_code) noexcept; static void RequestVersionNum() noexcept; const StateEstimation* m_task_state_estimation = nullptr; diff --git a/flight_computer/src/tasks/task_usb_device.cpp b/flight_computer/src/tasks/task_usb_device.cpp index 7422fe5d..a1fd97ce 100644 --- a/flight_computer/src/tasks/task_usb_device.cpp +++ b/flight_computer/src/tasks/task_usb_device.cpp @@ -22,6 +22,7 @@ namespace task { +// NOLINTNEXTLINE(readability-convert-member-functions-to-static) [[noreturn]] void UsbDevice::Run() noexcept { tud_init(0); while (true) { diff --git a/flight_computer/src/usb/msc_disk.c b/flight_computer/src/usb/msc_disk.c index ec6063d4..314132f9 100644 --- a/flight_computer/src/usb/msc_disk.c +++ b/flight_computer/src/usb/msc_disk.c @@ -27,6 +27,9 @@ #include "usb/msc/emfat.h" #include "usb/msc/emfat_file.h" +#include + +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern emfat_t emfat; #define CFG_TUD_MSC 1 @@ -34,6 +37,7 @@ extern emfat_t emfat; #if CFG_TUD_MSC // whether host does safe-eject +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static bool ejected = false; // Invoked when received SCSI_CMD_INQUIRY @@ -45,6 +49,7 @@ void tud_msc_inquiry_cb(uint8_t lun, uint8_t vendor_id[8], uint8_t product_id[16 const char pid[] = "Mass Storage"; const char rev[] = "1.0"; + // NOLINTNEXTLINE(clang-diagnostic-implicit-function-declaration) linter is confused memcpy(vendor_id, vid, strlen(vid)); memcpy(product_id, pid, strlen(pid)); memcpy(product_rev, rev, strlen(rev)); @@ -74,12 +79,13 @@ bool tud_msc_start_stop_cb(uint8_t lun, uint8_t power_condition, bool start, boo (void)power_condition; if (load_eject) { - if (start) { - // load disk storage - } else { + if (!start) { // unload disk storage ejected = true; } + // else { + // // load disk storage + // } } return true; @@ -121,6 +127,7 @@ void tud_msc_write10_complete_cb(uint8_t lun) {} int32_t tud_msc_scsi_cb(uint8_t lun, uint8_t const scsi_cmd[16], void* buffer, uint16_t bufsize) { // read10 & write10 has their own callback and MUST not be handled here + // NOLINTNEXTLINE(cppcoreguidelines-init-variables) linter is confused void const* response = NULL; int32_t resplen = 0; @@ -143,9 +150,10 @@ int32_t tud_msc_scsi_cb(uint8_t lun, uint8_t const scsi_cmd[16], void* buffer, u if (response && (resplen > 0)) { if (in_xfer) { memcpy(buffer, response, (size_t)resplen); - } else { - // SCSI output } + // else { + // // SCSI output + // } } return (int32_t)resplen; diff --git a/flight_computer/src/usb/tusb_config.h b/flight_computer/src/usb/tusb_config.h index 70576817..8cf78eec 100644 --- a/flight_computer/src/usb/tusb_config.h +++ b/flight_computer/src/usb/tusb_config.h @@ -23,8 +23,7 @@ * */ -#ifndef _TUSB_CONFIG_H_ -#define _TUSB_CONFIG_H_ +#pragma once #ifdef __cplusplus extern "C" { @@ -119,5 +118,3 @@ extern "C" { #ifdef __cplusplus } #endif - -#endif /* _TUSB_CONFIG_H_ */ diff --git a/flight_computer/src/usb/usb_descriptors.c b/flight_computer/src/usb/usb_descriptors.c index 729a6387..b95ae965 100644 --- a/flight_computer/src/usb/usb_descriptors.c +++ b/flight_computer/src/usb/usb_descriptors.c @@ -214,7 +214,7 @@ uint8_t const* tud_descriptor_configuration_cb(uint8_t index) { //--------------------------------------------------------------------+ // array of pointer to string descriptors -char const* string_desc_arr[] = { +const char* const string_desc_arr[] = { (const char[]){0x09, 0x04}, // 0: is supported language is English (0x0409) "TinyUSB", // 1: Manufacturer "TinyUSB Device", // 2: Product @@ -223,7 +223,8 @@ char const* string_desc_arr[] = { "TinyUSB MSC", // 5: MSC Interface }; -static uint16_t _desc_str[32]; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) +static uint16_t desc_str[32]; // Invoked when received GET STRING DESCRIPTOR request // Application return pointer to descriptor, whose contents must exist long enough for transfer to complete @@ -233,7 +234,7 @@ uint16_t const* tud_descriptor_string_cb(uint8_t index, uint16_t langid) { uint8_t chr_count; if (index == 0) { - memcpy(&_desc_str[1], string_desc_arr[0], 2); + memcpy(&desc_str[1], string_desc_arr[0], 2); chr_count = 1; } else { // Note: the 0xEE index string is a Microsoft OS 1.0 Descriptors. @@ -249,12 +250,12 @@ uint16_t const* tud_descriptor_string_cb(uint8_t index, uint16_t langid) { // Convert ASCII string into UTF-16 for (uint8_t i = 0; i < chr_count; i++) { - _desc_str[1 + i] = str[i]; + desc_str[1 + i] = str[i]; } } // first byte is length (including header), second byte is string type - _desc_str[0] = (TUSB_DESC_STRING << 8) | (2 * chr_count + 2); + desc_str[0] = (TUSB_DESC_STRING << 8) | (2 * chr_count + 2); - return _desc_str; + return desc_str; } diff --git a/flight_computer/src/util/actions.cpp b/flight_computer/src/util/actions.cpp index 1a3236c6..b68f6d5c 100644 --- a/flight_computer/src/util/actions.cpp +++ b/flight_computer/src/util/actions.cpp @@ -22,10 +22,12 @@ #include "config/globals.hpp" #include "drivers/servo.hpp" #include "flash/lfs_custom.hpp" -#include "target.h" +#include "target.hpp" +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) extern driver::Servo* global_servo1; extern driver::Servo* global_servo2; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) bool no_action_function(__attribute__((unused)) int16_t bummer); @@ -36,8 +38,8 @@ bool high_current_channel_two(int16_t state); bool low_level_channel_one(int16_t state); -bool servo_channel_one(int16_t angle); -bool servo_channel_two(int16_t angle); +bool servo_channel_one(int16_t position); +bool servo_channel_two(int16_t position); const peripheral_act_fp action_table[NUM_ACTION_FUNCTIONS] = { no_action_function, os_delay, high_current_channel_one, high_current_channel_two, @@ -68,34 +70,34 @@ bool os_delay(int16_t ticks) { // High current outputs for pyros, valves etc. bool high_current_channel_one(int16_t state) { -#if NUM_PYRO > 0 - if (state == 0 || state == 1) { - HAL_GPIO_WritePin(PYRO1_GPIO_Port, PYRO1_Pin, (GPIO_PinState)state); - return true; + if constexpr (NUM_PYRO > 0) { + if (state == 0 || state == 1) { + HAL_GPIO_WritePin(PYRO1_GPIO_Port, PYRO1_Pin, static_cast(state)); + return true; + } } -#endif return false; } bool high_current_channel_two(int16_t state) { -#if NUM_PYRO > 1 - if (state == 0 || state == 1) { - HAL_GPIO_WritePin(PYRO2_GPIO_Port, PYRO2_Pin, (GPIO_PinState)state); - return true; + if constexpr (NUM_PYRO > 1) { + if (state == 0 || state == 1) { + HAL_GPIO_WritePin(PYRO2_GPIO_Port, PYRO2_Pin, static_cast(state)); + return true; + } } -#endif return false; } // Low level (3.3V) outputs bool low_level_channel_one(int16_t state) { -#if NUM_LOW_LEVEL_IO > 0 - if (state == 0 || state == 1) { - HAL_GPIO_WritePin(IO1_GPIO_Port, IO1_Pin, (GPIO_PinState)state); - return true; + if constexpr (NUM_LOW_LEVEL_IO > 0) { + if (state == 0 || state == 1) { + HAL_GPIO_WritePin(IO1_GPIO_Port, IO1_Pin, static_cast(state)); + return true; + } } -#endif return false; } @@ -125,7 +127,7 @@ bool servo_channel_two(int16_t position) { /* TODO check if mutex should be used here */ bool set_recorder_state(int16_t state) { - volatile recorder_status_e new_rec_state = (recorder_status_e)state; + volatile auto new_rec_state = static_cast(state); if (new_rec_state < REC_OFF || new_rec_state > REC_WRITE_TO_FLASH) { return false; } @@ -151,7 +153,7 @@ bool set_recorder_state(int16_t state) { case REC_WRITE_TO_FLASH: if ((new_rec_state == REC_OFF) || (new_rec_state == REC_FILL_QUEUE)) { rec_cmd = REC_CMD_WRITE_STOP; - osStatus_t ret = osMessageQueuePut(rec_cmd_queue, &rec_cmd, 0U, 10U); + const osStatus_t ret = osMessageQueuePut(rec_cmd_queue, &rec_cmd, 0U, 10U); if (ret != osOK) { log_error("Inserting an element to the recorder command queue failed! Error: %d", ret); } @@ -169,7 +171,7 @@ bool set_recorder_state(int16_t state) { global_recorder_status = new_rec_state; if (rec_cmd != REC_CMD_INVALID) { - osStatus_t ret = osMessageQueuePut(rec_cmd_queue, &rec_cmd, 0U, 10U); + const osStatus_t ret = osMessageQueuePut(rec_cmd_queue, &rec_cmd, 0U, 10U); if (ret != osOK) { log_error("Inserting an element to the recorder command queue failed! Error: %d", ret); } diff --git a/flight_computer/src/util/actions.hpp b/flight_computer/src/util/actions.hpp index f26ea396..0823e5dc 100644 --- a/flight_computer/src/util/actions.hpp +++ b/flight_computer/src/util/actions.hpp @@ -20,7 +20,7 @@ #include -#define NUM_ACTION_FUNCTIONS 8 +inline constexpr uint8_t NUM_ACTION_FUNCTIONS = 8; using peripheral_act_fp = bool (*)(int16_t); diff --git a/flight_computer/src/util/battery.cpp b/flight_computer/src/util/battery.cpp index 7582ebf8..00cc420f 100644 --- a/flight_computer/src/util/battery.cpp +++ b/flight_computer/src/util/battery.cpp @@ -21,11 +21,12 @@ #include -#define ADC_LINFIT_A 0.00826849f -#define ADC_LINFIT_B 0.169868f +constexpr float ADC_LINFIT_A = 0.00826849F; +constexpr float ADC_LINFIT_B = 0.169868F; -#define BATTERY_VOLTAGE_HYSTERESIS 0.2f +constexpr float BATTERY_VOLTAGE_HYSTERESIS = 0.2F; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static uint32_t cell_count = 1; /* Supported batteries and their voltages @@ -43,6 +44,7 @@ const float32_t voltage_lookup[3][3] = {{3.2F, 3.4F, 4.3F}, // clang-format on enum battery_level_index_e { BAT_IDX_CRIT = 0, BAT_IDX_LOW, BAT_IDX_OK }; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static battery_type_e battery_type; /* Automatically check how many cells are connected */ @@ -52,7 +54,7 @@ void battery_monitor_init(battery_type_e type) { return; } uint32_t i = 1; - float32_t voltage = battery_voltage(); + const float32_t voltage = battery_voltage(); while ((static_cast(i) * voltage_lookup[battery_type][BAT_IDX_OK]) < voltage) { i++; } @@ -81,7 +83,7 @@ float32_t battery_cell_voltage() { return battery_voltage() / static_cast> 8); + crc = crc32_tab[(crc ^ *p++) & 0xFFU] ^ (crc >> 8U); } return crc ^ ~0U; } diff --git a/flight_computer/src/util/debug.cpp b/flight_computer/src/util/debug.cpp index 2b2c5f24..cc137632 100644 --- a/flight_computer/src/util/debug.cpp +++ b/flight_computer/src/util/debug.cpp @@ -18,11 +18,11 @@ #include "cmsis_os.h" #include "log.h" -#include "target.h" +#include "target.hpp" #include -#define STACK_OVERFLOW_PRINT_BUF_SZ 100 +constexpr uint16_t STACK_OVERFLOW_PRINT_BUF_SZ = 100; #ifdef CATS_DEBUG /** @@ -31,13 +31,13 @@ * * The function will loop forever. */ -void vApplicationStackOverflowHook(TaskHandle_t task_handle, char *task_name) { +void vApplicationStackOverflowHook(TaskHandle_t xTask [[maybe_unused]], char* pcTaskName) { while (true) { /* Toggle the red LED. */ HAL_GPIO_TogglePin(LED2_GPIO_Port, LED2_Pin); /* Todo: Fix this log_raw, it doesn't work */ - log_raw("Stack overflow detected in %s...\n", task_name); + log_raw("Stack overflow detected in %s...\n", pcTaskName); /* osDelay doesn't work here because this is an interrupt. */ HAL_Delay(1000); diff --git a/flight_computer/src/util/enum_str_maps.cpp b/flight_computer/src/util/enum_str_maps.cpp index 08295de3..91f54839 100644 --- a/flight_computer/src/util/enum_str_maps.cpp +++ b/flight_computer/src/util/enum_str_maps.cpp @@ -29,13 +29,14 @@ std::array recorder_speed_map = {}; void init_recorder_speed_map() { for (uint32_t i = 0; i < NUM_REC_SPEEDS; ++i) { - recorder_speed_map[i] = (char*)pvPortMalloc(14 * sizeof(char)); + recorder_speed_map[i] = static_cast(pvPortMalloc(14 * sizeof(char))); if (recorder_speed_map[i] == nullptr) { log_raw("Could not allocate memory for recorder_speed_map[%lu]!", i); return; } memset(recorder_speed_map[i], 0, 14 * sizeof(char)); - snprintf(recorder_speed_map[i], 14, "%.4gHz", (double)CONTROL_SAMPLING_FREQ / (i + 1)); + snprintf(recorder_speed_map[i], 14, "%.4gHz", + static_cast(CONTROL_SAMPLING_FREQ) / static_cast(i + 1)); } } diff --git a/flight_computer/src/util/error_handler.cpp b/flight_computer/src/util/error_handler.cpp index eee70a82..3f54cc86 100644 --- a/flight_computer/src/util/error_handler.cpp +++ b/flight_computer/src/util/error_handler.cpp @@ -20,6 +20,7 @@ #include "flash/recorder.hpp" #include "util/log.h" +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static uint32_t errors = 0; void add_error(cats_error_e err) { @@ -29,17 +30,17 @@ void add_error(cats_error_e err) { errors |= err; - error_info_t error_info = {.error = (cats_error_e)(errors)}; + error_info_t error_info = {.error = static_cast(errors)}; record(osKernelGetTickCount(), ERROR_INFO, &error_info); } } } void clear_error(cats_error_e err) { - if (errors & err) { + if ((errors & err) != 0) { errors &= ~err; - error_info_t error_info = {.error = (cats_error_e)(errors)}; + error_info_t error_info = {.error = static_cast(errors)}; record(osKernelGetTickCount(), ERROR_INFO, &error_info); } } @@ -48,8 +49,10 @@ void clear_error(cats_error_e err) { uint32_t get_error_count() { uint32_t count = 0; const uint32_t mask = 0x00000001; - for (int i = 0; i < 32; i++) { - if (errors & (mask << i)) count++; + for (uint32_t i = 0; i < 32; i++) { + if ((errors & (mask << i)) != 0) { + count++; + } } return count; } @@ -57,21 +60,18 @@ uint32_t get_error_count() { cats_error_e get_error_by_priority(uint32_t id) { uint32_t count = 0; const uint32_t mask = 0x00000001; - for (int i = 31; i >= 0; i--) { - if (errors & (mask << i)) { + for (int32_t i = 31; i >= 0; i--) { + if ((errors & (mask << static_cast(i))) != 0) { count++; } - if (count == (id + 1)) return (cats_error_e)(mask << i); + if (count == (id + 1)) { + return static_cast(mask << static_cast(i)); + } } return CATS_ERR_OK; } bool get_error_by_tag(cats_error_e err) { - if ((errors & err) != 0) { - /* return true if error is present */ - return true; - } else { - /* return false if error is not present */ - return false; - } + /* returns true if error is present */ + return (errors & err) != 0; } diff --git a/flight_computer/src/util/error_handler.hpp b/flight_computer/src/util/error_handler.hpp index 6cc7a76c..1b48a903 100644 --- a/flight_computer/src/util/error_handler.hpp +++ b/flight_computer/src/util/error_handler.hpp @@ -23,24 +23,24 @@ // clang-format off enum cats_error_e: uint32_t { CATS_ERR_OK = 0, - CATS_ERR_NON_USER_CFG = 1 << 0, // 0x01 - CATS_ERR_NO_PYRO = 1 << 1, // 0x02 - CATS_ERR_LOG_FULL = 1 << 2, // 0x04 - CATS_ERR_BAT_LOW = 1 << 3, // 0x08 - CATS_ERR_BAT_CRITICAL = 1 << 4, // 0x10 - CATS_ERR_IMU_0 = 1 << 5, // 0x20 - CATS_ERR_IMU_1 = 1 << 6, // 0x40 - CATS_ERR_IMU_2 = 1 << 7, // 0x80 - CATS_ERR_BARO_0 = 1 << 8, // 0x100 - CATS_ERR_BARO_1 = 1 << 9, // 0x200 - CATS_ERR_BARO_2 = 1 << 10, // 0x400 - CATS_ERR_MAG = 1 << 11, // 0x800 - CATS_ERR_ACC = 1 << 12, // 0x1000 - CATS_ERR_FILTER_ACC = 1 << 13, // 0x2000 - CATS_ERR_FILTER_HEIGHT = 1 << 14, // 0x4000 - CATS_ERR_HARD_FAULT = 1 << 15, // 0x8000 - CATS_ERR_TELEMETRY_HOT = 1 << 16, // 0x10000 - CATS_ERR_CALIB = 1 << 17, // 0x20000 + CATS_ERR_NON_USER_CFG = 1U << 0U, // 0x01 + CATS_ERR_NO_PYRO = 1U << 1U, // 0x02 + CATS_ERR_LOG_FULL = 1U << 2U, // 0x04 + CATS_ERR_BAT_LOW = 1U << 3U, // 0x08 + CATS_ERR_BAT_CRITICAL = 1U << 4U, // 0x10 + CATS_ERR_IMU_0 = 1U << 5U, // 0x20 + CATS_ERR_IMU_1 = 1U << 6U, // 0x40 + CATS_ERR_IMU_2 = 1U << 7U, // 0x80 + CATS_ERR_BARO_0 = 1U << 8U, // 0x100 + CATS_ERR_BARO_1 = 1U << 9U, // 0x200 + CATS_ERR_BARO_2 = 1U << 10U, // 0x400 + CATS_ERR_MAG = 1U << 11U, // 0x800 + CATS_ERR_ACC = 1U << 12U, // 0x1000 + CATS_ERR_FILTER_ACC = 1U << 13U, // 0x2000 + CATS_ERR_FILTER_HEIGHT = 1U << 14U, // 0x4000 + CATS_ERR_HARD_FAULT = 1U << 15U, // 0x8000 + CATS_ERR_TELEMETRY_HOT = 1U << 16U, // 0x10000 + CATS_ERR_CALIB = 1U << 17U, // 0x20000 }; // clang-format on diff --git a/flight_computer/src/util/log.cpp b/flight_computer/src/util/log.cpp index 72ab3ff2..838fc1e6 100644 --- a/flight_computer/src/util/log.cpp +++ b/flight_computer/src/util/log.cpp @@ -27,6 +27,7 @@ #define CATS_RAINBOW_LOG +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) static struct { int level; log_mode_e log_mode; @@ -37,9 +38,10 @@ static const char *level_strings[] = {"TRACE", "DEBUG", "INFO", "WARN", "ERROR", static const char *level_colors[] = {"\x1b[94m", "\x1b[36m", "\x1b[32m", "\x1b[33m", "\x1b[31m", "\x1b[35m"}; #endif -#define PRINT_BUFFER_LEN 420 +constexpr uint16_t PRINT_BUFFER_LEN = 420; static char print_buffer[PRINT_BUFFER_LEN]; #endif +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) void log_set_mode(log_mode_e mode) { #ifdef CATS_DEBUG @@ -89,7 +91,7 @@ void log_log(int level, const char *file, int line, const char *format, ...) { buf_ts[snprintf(buf_ts, sizeof(buf_ts), "%lu", osKernelGetTickCount())] = '\0'; static char buf_loc[30]; buf_loc[snprintf(buf_loc, sizeof(buf_loc), "%s:%d:", file, line)] = '\0'; - int len; + int len = 0; #ifdef CATS_RAINBOW_LOG len = snprintf(print_buffer, PRINT_BUFFER_LEN, "%6s %s%5s\x1b[0m \x1b[90m%30s\x1b[0m ", buf_ts, level_colors[level], level_strings[level], buf_loc); @@ -101,7 +103,8 @@ void log_log(int level, const char *file, int line, const char *format, ...) { len += vsnprintf(print_buffer + len, PRINT_BUFFER_LEN, format, argptr); va_end(argptr); len += snprintf(print_buffer + len, PRINT_BUFFER_LEN, "\n"); - stream_write(USB_SG.out, (uint8_t *)print_buffer, len); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + stream_write(USB_SG.out, reinterpret_cast(print_buffer), len); } #endif } @@ -113,7 +116,8 @@ void log_raw(const char *format, ...) { int len = vsnprintf(print_buffer, PRINT_BUFFER_LEN, format, argptr); va_end(argptr); len += snprintf(print_buffer + len, PRINT_BUFFER_LEN, "\n"); - stream_write(USB_SG.out, (uint8_t *)print_buffer, len); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + stream_write(USB_SG.out, reinterpret_cast(print_buffer), len); #endif } @@ -125,7 +129,8 @@ void log_sim(const char *format, ...) { int len = vsnprintf(print_buffer, PRINT_BUFFER_LEN, format, argptr); va_end(argptr); len += snprintf(print_buffer + len, PRINT_BUFFER_LEN, "\n"); - stream_write(USB_SG.out, (uint8_t *)print_buffer, len); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + stream_write(USB_SG.out, reinterpret_cast(print_buffer), len); } #endif } @@ -134,8 +139,9 @@ void log_rawr(const char *format, ...) { #ifdef CATS_DEBUG va_list argptr; va_start(argptr, format); - int len = vsnprintf(print_buffer, PRINT_BUFFER_LEN, format, argptr); + const int len = vsnprintf(print_buffer, PRINT_BUFFER_LEN, format, argptr); va_end(argptr); - stream_write(USB_SG.out, (uint8_t *)print_buffer, len); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + stream_write(USB_SG.out, reinterpret_cast(print_buffer), len); #endif } diff --git a/flight_computer/src/util/math_util.cpp b/flight_computer/src/util/math_util.cpp index 877a8ed8..9f02cacc 100644 --- a/flight_computer/src/util/math_util.cpp +++ b/flight_computer/src/util/math_util.cpp @@ -47,7 +47,7 @@ void quaternion_mat(const arm_matrix_instance_f32* input1, const arm_matrix_inst /* Extends a vector to R4 */ void extendR3(const float32_t* input, float32_t* output) { - float32_t abs_value = 1.0f - input[0] * input[0] - input[1] * input[1] - input[2] * input[2]; + const float32_t abs_value = 1.0F - input[0] * input[0] - input[1] * input[1] - input[2] * input[2]; float32_t q0 = 0; arm_sqrt_f32(abs_value, &q0); output[0] = q0; @@ -58,7 +58,7 @@ void extendR3(const float32_t* input, float32_t* output) { /* Normalized the quaternion such that abs(q) = 1 */ void normalize_q(float32_t* input) { - float32_t abs_value_sq = input[0] * input[0] + input[1] * input[1] + input[2] * input[2] + input[3] * input[3]; + const float32_t abs_value_sq = input[0] * input[0] + input[1] * input[1] + input[2] * input[2] + input[3] * input[3]; float32_t abs_value = 0; arm_sqrt_f32(abs_value_sq, &abs_value); input[0] /= abs_value; diff --git a/flight_computer/src/util/task_util.cpp b/flight_computer/src/util/task_util.cpp index 62ae330c..b73749d3 100644 --- a/flight_computer/src/util/task_util.cpp +++ b/flight_computer/src/util/task_util.cpp @@ -18,8 +18,9 @@ #include "util/task_util.hpp" -#include "target.h" +#include "target.hpp" +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) volatile bool rtos_started = false; void sysDelay(uint32_t delay) { diff --git a/flight_computer/src/util/task_util.hpp b/flight_computer/src/util/task_util.hpp index 30852bec..7115a540 100644 --- a/flight_computer/src/util/task_util.hpp +++ b/flight_computer/src/util/task_util.hpp @@ -23,6 +23,7 @@ #include "FreeRTOSConfig.h" #include "cmsis_os.h" +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern volatile bool rtos_started; void sysDelay(uint32_t delay); diff --git a/flight_computer/src/util/telemetry_reg.hpp b/flight_computer/src/util/telemetry_reg.hpp index e927086f..475d725c 100644 --- a/flight_computer/src/util/telemetry_reg.hpp +++ b/flight_computer/src/util/telemetry_reg.hpp @@ -28,25 +28,25 @@ enum transmission_mode_e { BIDIRECTIONAL = 1, }; -static constexpr uint8_t CMD_DIRECTION{0x10}; -static constexpr uint8_t CMD_PA_GAIN{0x11}; -static constexpr uint8_t CMD_POWER_LEVEL{0x12}; -static constexpr uint8_t CMD_MODE{0x13}; -static constexpr uint8_t CMD_MODE_INDEX{0x14}; +inline constexpr uint8_t CMD_DIRECTION{0x10}; +inline constexpr uint8_t CMD_PA_GAIN{0x11}; +inline constexpr uint8_t CMD_POWER_LEVEL{0x12}; +inline constexpr uint8_t CMD_MODE{0x13}; +inline constexpr uint8_t CMD_MODE_INDEX{0x14}; -static constexpr uint8_t CMD_LINK_PHRASE{0x15}; +inline constexpr uint8_t CMD_LINK_PHRASE{0x15}; -static constexpr uint8_t CMD_ENABLE{0x20}; -static constexpr uint8_t CMD_DISABLE{0x21}; +inline constexpr uint8_t CMD_ENABLE{0x20}; +inline constexpr uint8_t CMD_DISABLE{0x21}; -static constexpr uint8_t CMD_TX{0x30}; -static constexpr uint8_t CMD_RX{0x31}; -static constexpr uint8_t CMD_INFO{0x32}; +inline constexpr uint8_t CMD_TX{0x30}; +inline constexpr uint8_t CMD_RX{0x31}; +inline constexpr uint8_t CMD_INFO{0x32}; -static constexpr uint8_t CMD_GNSS_LOC{0x40}; -static constexpr uint8_t CMD_GNSS_TIME{0x41}; -static constexpr uint8_t CMD_GNSS_INFO{0x42}; +inline constexpr uint8_t CMD_GNSS_LOC{0x40}; +inline constexpr uint8_t CMD_GNSS_TIME{0x41}; +inline constexpr uint8_t CMD_GNSS_INFO{0x42}; -static constexpr uint8_t CMD_TEMP_INFO{0x50}; +inline constexpr uint8_t CMD_TEMP_INFO{0x50}; -static constexpr uint8_t CMD_VERSION_INFO{0x60}; +inline constexpr uint8_t CMD_VERSION_INFO{0x60}; diff --git a/flight_computer/src/util/types.cpp b/flight_computer/src/util/types.cpp deleted file mode 100644 index c96345ee..00000000 --- a/flight_computer/src/util/types.cpp +++ /dev/null @@ -1,25 +0,0 @@ -/* - * CATS Flight Software - * Copyright (C) 2023 Control and Telemetry Systems - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -#include "util/types.hpp" - -/* as suggested by - * https://stackoverflow.com/questions/23699719/inline-vs-static-inline-in-header-file - */ -extern inline uint16_t uint8_to_uint16(uint8_t src_high, uint8_t src_low); -extern inline int16_t uint8_to_int16(uint8_t src_high, uint8_t src_low); diff --git a/flight_computer/src/util/types.hpp b/flight_computer/src/util/types.hpp index 118bc2da..fd7e7f1b 100644 --- a/flight_computer/src/util/types.hpp +++ b/flight_computer/src/util/types.hpp @@ -18,18 +18,20 @@ #pragma once -#include -#include "target.h" +#include "config/control_config.hpp" +#include "util/actions.hpp" + +#include "target.hpp" #include "arm_math.h" #include "cmsis_os2.h" -#include "config/control_config.hpp" -#include "util/actions.hpp" -/** DEFINES **/ +#include + +/** CONSTANTS **/ -#define NUM_EVENTS 9 -#define NUM_TIMERS 4 +inline constexpr uint8_t NUM_EVENTS = 9; +inline constexpr uint8_t NUM_TIMERS = 4; /** BASIC TYPES **/ @@ -173,9 +175,9 @@ struct config_telemetry_t { /* +1 for null terminator */ char link_phrase[kMaxConnPhraseChars + 1]{}; char test_phrase[kMaxConnPhraseChars + 1]{}; - uint8_t power_level; - bool enable_telemetry; - adaptive_power_e adaptive_power; + uint8_t power_level{0}; + bool enable_telemetry{false}; + adaptive_power_e adaptive_power{OFF}; }; struct peripheral_act_t { @@ -222,10 +224,3 @@ struct cats_timer_t { }; enum battery_type_e : uint8_t { LI_ION = 0, LI_PO, ALKALINE }; - -/** CONVERSION FUNCTIONS **/ - -inline uint16_t uint8_to_uint16(uint8_t src_high, uint8_t src_low) { return (src_high << 8 | src_low); } - -/* TODO: is this really the same? It's taken from the macros.. */ -inline int16_t uint8_to_int16(uint8_t src_high, uint8_t src_low) { return (int16_t)uint8_to_uint16(src_high, src_low); } From bf77ce71231e96656c77d8192f2697119f012742 Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Sun, 3 Sep 2023 16:05:33 +0200 Subject: [PATCH 04/11] Improve version printing, distinguish betwen debug compilation & CATS_DEBUG flag --- flight_computer/src/config/globals.hpp | 18 +++++++++++++++--- 1 file changed, 15 insertions(+), 3 deletions(-) diff --git a/flight_computer/src/config/globals.hpp b/flight_computer/src/config/globals.hpp index ec37ab3b..72162bb2 100644 --- a/flight_computer/src/config/globals.hpp +++ b/flight_computer/src/config/globals.hpp @@ -58,11 +58,23 @@ extern volatile recorder_status_e global_recorder_status; extern event_action_map_elem_t* event_action_map; -#ifdef CATS_DEBUG -inline constexpr const char* code_version = FIRMWARE_VERSION "-dev"; +// clang-format off +// __PLATFORMIO_BUILD_DEBUG__ adds '-dbg', CATS_DEBUG adds '-dev' +#ifdef __PLATFORMIO_BUILD_DEBUG__ + #ifdef CATS_DEBUG + inline constexpr const char* code_version = FIRMWARE_VERSION "-dbg-dev"; + #else + inline constexpr const char* code_version = FIRMWARE_VERSION "-dbg"; + #endif #else -inline constexpr const char* code_version = FIRMWARE_VERSION; + #ifdef CATS_DEBUG + inline constexpr const char* code_version = FIRMWARE_VERSION "-dev"; + #else + inline constexpr const char* code_version = FIRMWARE_VERSION; + #endif #endif +// clang-format on + inline constexpr const char* board_name = "CATS Vega"; extern char telemetry_code_version[20]; From dee753211cfe9ce678323ead90ce954c9b3953a7 Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Sun, 3 Sep 2023 16:15:54 +0200 Subject: [PATCH 05/11] Improve workflows - Release build on Windows - Debug build + linting on Ubuntu - Fail workflow if clang-tidy warnings are encountered --- .github/workflows/merge-criteria.yml | 113 +++++++++++++++--- ...tm32f411ccux.s => startup_stm32f411ccux.S} | 0 2 files changed, 95 insertions(+), 18 deletions(-) rename flight_computer/src/target/VEGA/{startup_stm32f411ccux.s => startup_stm32f411ccux.S} (100%) diff --git a/.github/workflows/merge-criteria.yml b/.github/workflows/merge-criteria.yml index 91bff9fa..1c9a8ddb 100644 --- a/.github/workflows/merge-criteria.yml +++ b/.github/workflows/merge-criteria.yml @@ -42,17 +42,17 @@ jobs: echo "$filtered_array" echo "matrix=$filtered_array" >> "$GITHUB_OUTPUT" - + outputs: matrix: ${{ steps.changed-files-filtered.outputs.matrix }} - + format_check: if: ${{ fromJson(needs.generate_matrix.outputs.matrix) }} name: Format Check needs: generate_matrix strategy: fail-fast: false - matrix: + matrix: project: ${{ fromJson(needs.generate_matrix.outputs.matrix) }} runs-on: ubuntu-latest @@ -67,42 +67,123 @@ jobs: check-path: '${{ matrix.project }}/src' exclude-regex: '(lib|telemetry/src/st|ground_station/src/format)' - build: + build_lint: if: ${{ fromJson(needs.generate_matrix.outputs.matrix) }} needs: [generate_matrix, format_check] - name: Build + Lint - # We are running this on windows because the users get binaries compiled on windows. - # The code should also be tested in a linux build. + name: '[Ubuntu] Build + Lint' + # We are linting on Ubuntu because the linter seems to work better on Linux runs-on: ubuntu-latest timeout-minutes: 60 strategy: fail-fast: false - matrix: + matrix: + project: ${{ fromJson(needs.generate_matrix.outputs.matrix) }} + + steps: + - name: Checkout + uses: actions/checkout@v3 + + - name: Check cache + uses: actions/cache@v3 + with: + path: ~/.platformio/.cache + # Add OS to key if testing with multiple OSes + key: ${{ matrix.project }}-pio + + - name: Set up Python + uses: actions/setup-python@v3 + with: + python-version: '3.9' + cache: 'pip' + + - name: Install dependencies + run: pip install --upgrade platformio + + - name: Install PlatformIO Libraries + run: pio pkg install --global + + - name: Build + shell: bash + run: | + if [[ "${{ matrix.project }}" == "flight_computer" ]]; then + platformio run -d ${{ matrix.project }} --environment debug + else + platformio run -d ${{ matrix.project }} + fi + + - name: Generate compile_commands.json + run: | + if [[ "${{ matrix.project }}" == "flight_computer" ]]; then + platformio run -d ${{ matrix.project }} --target compiledb --environment debug + else + platformio run -d ${{ matrix.project }} --target compiledb + fi + + - name: Lint + working-directory: ./${{ matrix.project }} + run: | + if [[ "${{ matrix.project }}" == "flight_computer" ]]; then + output=$(platformio check --environment debug) + else + output=$(platformio check) + fi + + echo "$output" + + echo "Note: Warnings 'clang-diagnostic-c++17-extensions' and 'clang-analyzer-valist.Uninitialized' are excluded from checking since they seem to be false-positives. Fix everything else!" + + # filter the output to exclude false positives + filtered_output=$(echo "$output" | grep -vE 'clang-diagnostic-c\+\+17-extensions|clang-analyzer-valist.Uninitialized') + + if echo "$filtered_output" | grep -q "warning"; then + echo "clang-tidy check failed!" + exit 1 + fi + + - name: Upload Compile Commands + uses: actions/upload-artifact@v3 + with: + name: ubuntu_compile_commands + path: | + ./${{ matrix.project }}/.pio/build/**/compile_commands.json + if-no-files-found: error + retention-days: 90 + + build_upload: + if: ${{ fromJson(needs.generate_matrix.outputs.matrix) }} + needs: [generate_matrix, format_check] + name: '[Windows] Build + Upload' + # We are running this on windows because the users get binaries compiled on windows. + runs-on: windows-latest + timeout-minutes: 60 + strategy: + fail-fast: false + matrix: project: ${{ fromJson(needs.generate_matrix.outputs.matrix) }} steps: - name: Checkout uses: actions/checkout@v3 - + - name: Check cache uses: actions/cache@v3 with: path: ~/.platformio/.cache # Add OS to key if testing with multiple OSes key: ${{ matrix.project }}-pio - + - name: Set up Python uses: actions/setup-python@v3 with: python-version: '3.9' cache: 'pip' - + - name: Install dependencies run: pip install --upgrade platformio - + - name: Install PlatformIO Libraries run: pio pkg install --global - + - name: Build shell: bash run: | @@ -113,11 +194,7 @@ jobs: - name: Generate compile_commands.json run: platformio run -d ${{ matrix.project }} --target compiledb - - - name: Lint - working-directory: ./${{ matrix.project }} - run: platformio check - + - name: Upload Artifacts uses: actions/upload-artifact@v3 with: diff --git a/flight_computer/src/target/VEGA/startup_stm32f411ccux.s b/flight_computer/src/target/VEGA/startup_stm32f411ccux.S similarity index 100% rename from flight_computer/src/target/VEGA/startup_stm32f411ccux.s rename to flight_computer/src/target/VEGA/startup_stm32f411ccux.S From 0263e45897f8beccf12a8508754a144c669f9b07 Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Sat, 16 Sep 2023 17:27:34 +0200 Subject: [PATCH 06/11] Fix clang-tidy issues after rebase --- flight_computer/src/cli/cli_commands.cpp | 2 +- flight_computer/src/usb/msc/emfat.h | 2 +- flight_computer/src/usb/msc/emfat_file.cpp | 107 +++++++++++---------- flight_computer/src/usb/msc_disk.c | 3 +- flight_computer/src/util/enum_str_maps.cpp | 1 + flight_computer/src/util/enum_str_maps.hpp | 1 + 6 files changed, 61 insertions(+), 55 deletions(-) diff --git a/flight_computer/src/cli/cli_commands.cpp b/flight_computer/src/cli/cli_commands.cpp index 94ecc93a..7db7c063 100644 --- a/flight_computer/src/cli/cli_commands.cpp +++ b/flight_computer/src/cli/cli_commands.cpp @@ -883,7 +883,7 @@ static void print_action_config() { config_action_t action{}; for (int i = 0; i < NUM_EVENTS; i++) { const auto ev = static_cast(i); - int nr_actions = cc_get_num_actions(ev); + const int nr_actions = cc_get_num_actions(ev); if (nr_actions > 0) { cli_printf("\n%s\n", GetStr(ev, p_event_table)); cli_printf(" Number of Actions: %d\n", nr_actions); diff --git a/flight_computer/src/usb/msc/emfat.h b/flight_computer/src/usb/msc/emfat.h index d853f63d..cbaa6e70 100644 --- a/flight_computer/src/usb/msc/emfat.h +++ b/flight_computer/src/usb/msc/emfat.h @@ -91,7 +91,7 @@ void emfat_read(emfat_t *emfat, uint8_t *data, uint32_t sector, int num_sectors) void emfat_write(emfat_t *emfat, const uint8_t *data, uint32_t sector, int num_sectors); #define EMFAT_ENCODE_CMA_TIME(D, M, Y, h, m, s) \ - ((((((Y)-1980) << 9) | ((M) << 5) | (D)) << 16) | (((h) << 11) | ((m) << 5) | ((s) >> 1))) + ((((((Y)-1980U) << 9U) | ((M) << 5U) | (D)) << 16U) | (((h) << 11U) | ((m) << 5U) | ((s) >> 1U))) static inline uint32_t emfat_encode_cma_time(int D, int M, int Y, int h, int m, int s) { return EMFAT_ENCODE_CMA_TIME(D, M, Y, h, m, s); diff --git a/flight_computer/src/usb/msc/emfat_file.cpp b/flight_computer/src/usb/msc/emfat_file.cpp index 8ccecb47..f73f4290 100644 --- a/flight_computer/src/usb/msc/emfat_file.cpp +++ b/flight_computer/src/usb/msc/emfat_file.cpp @@ -36,7 +36,7 @@ #include "flash/lfs_custom.hpp" #include "util/log.h" -#define CMA_TIME EMFAT_ENCODE_CMA_TIME(1, 1, 2023, 13, 0, 0) +#define CMA_TIME EMFAT_ENCODE_CMA_TIME(1U, 1U, 2023U, 13U, 0U, 0U) #define CMA \ { CMA_TIME, CMA_TIME, CMA_TIME } @@ -54,31 +54,31 @@ static void lfs_read_file(uint8_t *dest, int size, uint32_t offset, emfat_entry_ } // Assume the files starting with 'f' are flight logs; all others are considered to be stats files. - const bool flight_log = entry->name != NULL && entry->name[0] == 'f'; + const bool flight_log = entry->name != nullptr && entry->name[0] == 'f'; snprintf(filename, 32, flight_log ? "/flights/flight_%05hu" : "/stats/stats_%05hu.txt", entry->lfs_flight_idx); - int err = lfs_file_open(&lfs, &curr_file, filename, LFS_O_RDONLY); - if (err) { + const int err = lfs_file_open(&lfs, &curr_file, filename, LFS_O_RDONLY); + if (err < 0) { return; } file_open = true; } - lfs_file_seek(&lfs, &curr_file, (int32_t)offset, LFS_SEEK_SET); + lfs_file_seek(&lfs, &curr_file, static_cast(offset), LFS_SEEK_SET); lfs_file_read(&lfs, &curr_file, dest, size); } static void memory_read_proc(uint8_t *dest, int size, uint32_t offset, emfat_entry_t *entry) { - int len = 0; + int32_t len = 0; if (offset > entry->curr_size) { return; } if (offset + size > entry->curr_size) { - len = entry->curr_size - offset; + len = static_cast(entry->curr_size - offset); } else { len = size; } - - memcpy(dest, &((char *)entry->user_data)[offset], len); + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) + memcpy(dest, &(reinterpret_cast(entry->user_data))[offset], len); } static const char readme_file[] = @@ -89,8 +89,8 @@ static const char readme_file[] = "The number of logs exposed via Mass Storage Controller is limited to 50 flight log files and 50 stats files.\r\n"; #define README_SIZE_BYTES (sizeof(readme_file) - 1) -#define PREDEFINED_ENTRY_COUNT 2 -#define README_FILE_IDX 1 +constexpr uint8_t PREDEFINED_ENTRY_COUNT = 2; +constexpr uint8_t README_FILE_IDX = 1; // We are limited to 50 flight logs & 50 stats files due to RAM memory limits // TODO: It seems the number has to be 1 more than the actual limit, this should be investigated @@ -100,41 +100,46 @@ static_assert(kMaxNumVisibleLogs > 0 && kMaxNumVisibleLogs % 2 == 0, #define EMFAT_MAX_ENTRY (PREDEFINED_ENTRY_COUNT + kMaxNumVisibleLogs) +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) static char logNames[EMFAT_MAX_ENTRY][8 + 1 + 3 + 1] = {"", "readme.txt"}; -static const emfat_entry_t entriesPredefined[] = {{ - logNames[0], // name - true, // dir - ATTR_DIR, // attr - 0, // level - 0, // offset - 0, // number - 0, // curr_size - 0, // max_size - 0, // user_data - CMA, // cma_time[3] - NULL, // readcb - NULL // writecb - }, - { - logNames[1], // name - false, // dir - ATTR_READ, // attr - 1, // level - 0, // offset - 0, // number - README_SIZE_BYTES, // curr_size - README_SIZE_BYTES, // max_siize - (long)readme_file, // user_data - CMA, // cma_time[3] - memory_read_proc, // readcb - NULL // writecb - }}; - +static const emfat_entry_t entriesPredefined[] = { + { + logNames[0], // name + true, // dir + ATTR_DIR, // attr + 0, // level + 0, // offset + 0, // number + 0, // curr_size + 0, // max_size + 0, // user_data + CMA, // cma_time[3] + nullptr, // readcb + nullptr // writecb + }, + { + logNames[1], // name + false, // dir + ATTR_READ, // attr + 1, // level + 0, // offset + 0, // number + README_SIZE_BYTES, // curr_size + README_SIZE_BYTES, // max_size + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast,google-runtime-int) + reinterpret_cast(readme_file), // user_data + CMA, // cma_time[3] + memory_read_proc, // readcb + nullptr // writecb + }}; + +// NOLINTBEGIN(cppcoreguidelines-avoid-non-const-global-variables) static emfat_entry_t entries[EMFAT_MAX_ENTRY]{}; - emfat_t emfat; -static uint32_t cmaTime = CMA_TIME; +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) + +constexpr uint32_t cmaTime = CMA_TIME; static void emfat_set_entry_cma(emfat_entry_t *entry) { // Set file creation/modification/access times to be the same, either the default date or that from the RTC @@ -144,29 +149,29 @@ static void emfat_set_entry_cma(emfat_entry_t *entry) { entry->cma_time[2] = cmaTime; } -typedef enum { FLIGHT_LOG, STATS_LOG } log_type_e; +enum log_type_e { FLIGHT_LOG, STATS_LOG }; static void emfat_add_log(emfat_entry_t *entry, uint32_t size, const char *name, log_type_e log_type) { const uint64_t entry_idx = entry - entries; uint16_t lfs_flight_idx = 0; - int idx_start = log_type == FLIGHT_LOG ? 7 : 6; + const int idx_start = log_type == FLIGHT_LOG ? 7 : 6; // flight_000xx, stats_000xx.txt if (sscanf(&name[idx_start], "%hu", &lfs_flight_idx) > 0) { log_error("Reading lfs_flight_idx failed: %hu", lfs_flight_idx); } - snprintf(logNames[entry_idx], 12, "%s%03d.%s", log_type == FLIGHT_LOG ? "fl" : "st", (uint8_t)lfs_flight_idx, - log_type == FLIGHT_LOG ? "cfl" : "txt"); + snprintf(logNames[entry_idx], 12, "%s%03d.%s", log_type == FLIGHT_LOG ? "fl" : "st", + static_cast(lfs_flight_idx), log_type == FLIGHT_LOG ? "cfl" : "txt"); entry->name = logNames[entry_idx]; entry->level = 1; - entry->number = entry_idx; + entry->number = static_cast(entry_idx); entry->lfs_flight_idx = lfs_flight_idx; entry->curr_size = size; entry->max_size = entry->curr_size; entry->readcb = lfs_read_file; - entry->writecb = NULL; + entry->writecb = nullptr; emfat_set_entry_cma(entry); } @@ -174,9 +179,9 @@ static void emfat_add_log(emfat_entry_t *entry, uint32_t size, const char *name, * @brief Add file from path, returns 0 on success. */ static void add_logs_from_path(emfat_entry_t **entry, const char *path, log_type_e log_type, uint32_t max_logs_to_add) { - struct lfs_info info; + struct lfs_info info {}; lfs_dir_t dir; - int err = lfs_dir_open(&lfs, &dir, path); + const int err = lfs_dir_open(&lfs, &dir, path); if (err < 0) { return; } @@ -196,8 +201,6 @@ static void add_logs_from_path(emfat_entry_t **entry, const char *path, log_type } lfs_dir_close(&lfs, &dir); - - return; } static void emfat_find_logs(emfat_entry_t *entry) { diff --git a/flight_computer/src/usb/msc_disk.c b/flight_computer/src/usb/msc_disk.c index 314132f9..0fd2e3b4 100644 --- a/flight_computer/src/usb/msc_disk.c +++ b/flight_computer/src/usb/msc_disk.c @@ -25,10 +25,11 @@ #include "tusb.h" #include "usb/msc/emfat.h" -#include "usb/msc/emfat_file.h" #include +extern bool emfat_init_files(); + // NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern emfat_t emfat; diff --git a/flight_computer/src/util/enum_str_maps.cpp b/flight_computer/src/util/enum_str_maps.cpp index 91f54839..7b695f74 100644 --- a/flight_computer/src/util/enum_str_maps.cpp +++ b/flight_computer/src/util/enum_str_maps.cpp @@ -25,6 +25,7 @@ #include // Filled later depending on tick frequency +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) std::array recorder_speed_map = {}; void init_recorder_speed_map() { diff --git a/flight_computer/src/util/enum_str_maps.hpp b/flight_computer/src/util/enum_str_maps.hpp index d9a2bc33..f6dd20cb 100644 --- a/flight_computer/src/util/enum_str_maps.hpp +++ b/flight_computer/src/util/enum_str_maps.hpp @@ -62,6 +62,7 @@ inline constexpr std::array on_off_map{ inline constexpr std::array battery_map{"LI-ION", "LI-PO", "ALKALINE"}; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) extern std::array recorder_speed_map; void init_recorder_speed_map(); From 4c7d8a4229ef8f53b170573edadbd3dac7c64a85 Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Sun, 15 Oct 2023 11:47:29 +0200 Subject: [PATCH 07/11] More fixes after rebase --- ground_station/src/hmi/hmi.cpp | 2 +- ground_station/src/hmi/window.cpp | 10 +++++----- ground_station/src/hmi/window.hpp | 2 +- ground_station/src/logging/recorder.cpp | 8 +++++--- ground_station/src/telemetry/telemetry.cpp | 1 + 5 files changed, 13 insertions(+), 10 deletions(-) diff --git a/ground_station/src/hmi/hmi.cpp b/ground_station/src/hmi/hmi.cpp index cfc10ffa..ccb7f611 100644 --- a/ground_station/src/hmi/hmi.cpp +++ b/ground_station/src/hmi/hmi.cpp @@ -572,7 +572,7 @@ void Hmi::update(void *pvParameter) { if (millis() - barUpdate >= 1000) { barUpdate = millis(); - float voltage = static_cast(analogRead(18)) * 0.00059154929F; + const float voltage = static_cast(analogRead(18)) * 0.00059154929F; if (!ref->isLogging) { ref->flashFreeMemory = Utils::getFlashMemoryUsage(); } diff --git a/ground_station/src/hmi/window.cpp b/ground_station/src/hmi/window.cpp index af9e531b..232745a4 100644 --- a/ground_station/src/hmi/window.cpp +++ b/ground_station/src/hmi/window.cpp @@ -68,26 +68,26 @@ void Window::initBar() { display.drawLine(0, 18, 400, 18, BLACK); } -void Window::updateBar(float batteryVoltage, bool usb, bool logging, bool location, bool time, int32_t free_memory) { +void Window::updateBar(float batteryVoltage, bool usb, bool logging, bool location, bool time, uint32_t free_memory) { static int32_t oldHour = 0; static int32_t oldMinute = 0; static bool oldUsbStatus = false; static bool oldLoggingStatus = false; - static int32_t oldFreeMemory = 0; + static uint32_t oldFreeMemory = 0; static bool blinkStatus = false; // Logging if (logging != oldLoggingStatus) { - display.drawBitmap(75, 1, bar_download, 16, 16, !logging); + display.drawBitmap(75, 1, bar_download, 16, 16, static_cast(!logging)); oldLoggingStatus = logging; } if (logging) { - display.drawBitmap(75, 1, bar_download, 16, 16, blinkStatus); + display.drawBitmap(75, 1, bar_download, 16, 16, static_cast(blinkStatus)); } // Location if (location) { - display.drawBitmap(329, 1, bar_location, 16, 16, !location); + display.drawBitmap(329, 1, bar_location, 16, 16, static_cast(!location)); } // Memory Usage diff --git a/ground_station/src/hmi/window.hpp b/ground_station/src/hmi/window.hpp index 16ff1cc7..24b97d3e 100644 --- a/ground_station/src/hmi/window.hpp +++ b/ground_station/src/hmi/window.hpp @@ -31,7 +31,7 @@ class Window { void initBar(); void updateBar(float batteryVoltage, bool usb = false, bool logging = false, bool location = false, bool time = false, - int32_t free_memory = 100); + uint32_t free_memory = 100); void initMenu(int16_t index); void updateMenu(int16_t index); diff --git a/ground_station/src/logging/recorder.cpp b/ground_station/src/logging/recorder.cpp index 2c1130eb..7ebc7416 100644 --- a/ground_station/src/logging/recorder.cpp +++ b/ground_station/src/logging/recorder.cpp @@ -50,9 +50,11 @@ void Recorder::recordTask(void *pvParameter) { ref->createFile(); } const auto &data = element.data; - snprintf(line, 128, "%hu,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d", element.source, data.timestamp, data.state, data.errors, - data.lat, data.lon, data.altitude, data.velocity, data.voltage, - static_cast(data.pyro_continuity & 0x01), static_cast(data.pyro_continuity & 0x02)); + const auto pyro1_continuity = static_cast(data.pyro_continuity & 0x01U); + const auto pyro2_continuity = static_cast(data.pyro_continuity & 0x02U); + snprintf(line, 128, "%hu,%d,%d,%d,%d,%d,%d,%d,%d,%hu,%hu", element.source, data.timestamp, data.state, + data.errors, data.lat, data.lon, data.altitude, data.velocity, data.voltage, + static_cast(pyro1_continuity), static_cast(pyro2_continuity)); ref->file.println(line); count++; diff --git a/ground_station/src/telemetry/telemetry.cpp b/ground_station/src/telemetry/telemetry.cpp index b7638f2c..fa648c71 100644 --- a/ground_station/src/telemetry/telemetry.cpp +++ b/ground_station/src/telemetry/telemetry.cpp @@ -69,6 +69,7 @@ void Telemetry::initLink() { } if (testingPhrase[0] != 0) { + // NOLINTNEXTLINE(cppcoreguidelines-pro-type-reinterpret-cast) uint8 to char is OK testingCrc = crc32(testingPhrase, strlen(reinterpret_cast(testingPhrase))); } } From bb7420d007beca193831d65c257d093e6c66f944 Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Sun, 15 Oct 2023 12:24:29 +0200 Subject: [PATCH 08/11] Rename Telemetry & GS Projects --- .github/workflows/merge-criteria.yml | 2 +- ground_station/platformio.ini | 18 +++++++++--------- ground_station/uf2_loader.py | 2 +- telemetry/platformio.ini | 2 +- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/.github/workflows/merge-criteria.yml b/.github/workflows/merge-criteria.yml index 1c9a8ddb..537f3f81 100644 --- a/.github/workflows/merge-criteria.yml +++ b/.github/workflows/merge-criteria.yml @@ -189,7 +189,7 @@ jobs: run: | platformio run -d ${{ matrix.project }} if [[ "${{ matrix.project }}" == "ground_station" ]]; then - python ${{ matrix.project }}/uf2_loader.py ${{ matrix.project }}/.pio/build/esp32-s2-saola-1/firmware + python ${{ matrix.project }}/uf2_loader.py ${{ matrix.project }}/.pio/build/ground_station/firmware fi - name: Generate compile_commands.json diff --git a/ground_station/platformio.ini b/ground_station/platformio.ini index c6464373..7c6147a1 100644 --- a/ground_station/platformio.ini +++ b/ground_station/platformio.ini @@ -30,7 +30,7 @@ ; SOFTWARE. ;****************************************************************************** -[env:esp32-s2-saola-1] +[env:ground_station] board = esp32-s2-saola-1 framework = arduino platform = https://github.com/tasmota/platform-espressif32/releases/download/2023.06.04/platform-espressif32.zip @@ -67,7 +67,7 @@ build_flags = -DCFG_TUSB_CONFIG_FILE='"sdkconfig.h"' ; Use default TinyUSB configuration -DFIRMWARE_VERSION='"1.1.0"' ; Enter Firmware Version here -DUSB_MANUFACTURER='"CATS"' ; USB Manufacturer string - -DUSB_PRODUCT='"CATS Groundstation"' ; USB Product String + -DUSB_PRODUCT='"CATS Ground Station"' ; USB Product String -D USB_SERIAL="0" ; Enter Device Serial Number here -D USB_VID=0x239A ; Default Adafruit USB VID -D USB_PID=0x80AB ; Default Adafruit USB PID @@ -114,13 +114,13 @@ extra_scripts = upload_protocol = custom upload_flags = - ${env:esp32-s2-saola-1.build_flags} ; Pass build flags as argument to python script - COMPARE_SERIAL_NUMBER=false ; Download only to devices with specified USB Serial Number, otherwise to all connected devices - USE_SERIAL_NUMBER_LIST=false ; Overwrite single USB Serial Number (USB_SERIAL) with list of accepted Serial Numbers - SERIAL_NUMBER_LIST=["0", "1", "2"] ; List of specific USB Serial Numbers to program and open COM-Port (if enabled) - ENABLE_AUTOMATIC_CONSOLE=false ; Enables automatic opening of serial ports - COMPARE_VID_PID_CONSOLE=true ; Open only COM-Ports with same VID/PID as specified above (USB_VID, USB_PID) - USE_TABS_CONSOLE=true ; Use Windows Terminal Tabs-Feature (One Tab for each COM-Port) -> Not fully implemented yet + ${env:ground_station.build_flags} ; Pass build flags as argument to python script + COMPARE_SERIAL_NUMBER=false ; Download only to devices with specified USB Serial Number, otherwise to all connected devices + USE_SERIAL_NUMBER_LIST=false ; Overwrite single USB Serial Number (USB_SERIAL) with list of accepted Serial Numbers + SERIAL_NUMBER_LIST=["0", "1", "2"] ; List of specific USB Serial Numbers to program and open COM-Port (if enabled) + ENABLE_AUTOMATIC_CONSOLE=false ; Enables automatic opening of serial ports + COMPARE_VID_PID_CONSOLE=true ; Open only COM-Ports with same VID/PID as specified above (USB_VID, USB_PID) + USE_TABS_CONSOLE=true ; Use Windows Terminal Tabs-Feature (One Tab for each COM-Port) -> Not fully implemented yet check_tool = clangtidy check_flags = diff --git a/ground_station/uf2_loader.py b/ground_station/uf2_loader.py index c3952f79..c09c877f 100644 --- a/ground_station/uf2_loader.py +++ b/ground_station/uf2_loader.py @@ -294,7 +294,7 @@ def download(self, inputPath): # If this script is called directly, it converts the .bin binary into the .UF2 binary if __name__ == "__main__": loader = UF2Loader("ESP32S2", 0) - binary_path = ".pio/build/esp32-s2-saola-1/firmware" + binary_path = ".pio/build/ground_station/firmware" # if an argument is passed to the script, use it as the path to the binary if len(sys.argv) > 1: binary_path = sys.argv[1] diff --git a/telemetry/platformio.ini b/telemetry/platformio.ini index 7008acd7..f02ddfd1 100644 --- a/telemetry/platformio.ini +++ b/telemetry/platformio.ini @@ -8,7 +8,7 @@ ; Please visit documentation for the other options and examples ; https://docs.platformio.org/page/projectconf.html -[env:g071] +[env:telemetry] platform = ststm32 platform_packages = platformio/toolchain-gccarmnoneeabi@^1.100301.220327 From bc4613db372d0e0c555a136fda48cb07a8f5e2c8 Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Mon, 16 Oct 2023 21:55:45 +0200 Subject: [PATCH 09/11] File cleanup --- ground_station/LICENSE | 21 --------------------- ground_station/net.ini | 8 -------- ground_station/src/config.cpp | 24 ------------------------ ground_station/src/utils.hpp | 5 +---- ground_station/system.json | 7 ------- 5 files changed, 1 insertion(+), 64 deletions(-) delete mode 100644 ground_station/LICENSE delete mode 100644 ground_station/net.ini delete mode 100644 ground_station/system.json diff --git a/ground_station/LICENSE b/ground_station/LICENSE deleted file mode 100644 index c03bfbf6..00000000 --- a/ground_station/LICENSE +++ /dev/null @@ -1,21 +0,0 @@ -MIT License - -Copyright (c) 2022 Florian Baumgartner - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. diff --git a/ground_station/net.ini b/ground_station/net.ini deleted file mode 100644 index 2b0fcd7e..00000000 --- a/ground_station/net.ini +++ /dev/null @@ -1,8 +0,0 @@ -[system] -serial number = 0 -usb vid = 0x303A -usb pid = 0x0002 - -[network] -ssid = WLAN -password = zyxel2010 diff --git a/ground_station/src/config.cpp b/ground_station/src/config.cpp index 0870006e..89e26402 100644 --- a/ground_station/src/config.cpp +++ b/ground_station/src/config.cpp @@ -9,30 +9,6 @@ SystemParser systemParser{}; Config systemConfig{}; // NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) -/* -if(systemParser.loadFile(configFileName)) - { - if(systemParser.getUsbVid() != -1) - { - vid = systemParser.getUsbVid(); - } - if(systemParser.getUsbPid() != -1) - { - pid = systemParser.getUsbPid(); - } - if(strlen(systemParser.getUsbSerial())) - { - serial = systemParser.getUsbSerial(); - } - console.ok.println("[UTILS] System config loading was successful."); - } - else - { - console.error.println("[UTILS] System config loading failed."); - status = false; - } - */ - void Config::save() { systemParser.setTestingPhrase(config.testingPhrase); systemParser.setLinkPhrase1(config.linkPhrase1); diff --git a/ground_station/src/utils.hpp b/ground_station/src/utils.hpp index c98ec31b..e2f1ee86 100644 --- a/ground_station/src/utils.hpp +++ b/ground_station/src/utils.hpp @@ -34,8 +34,6 @@ #include #include -inline constexpr const char *DEFAULT_CONFIG_FILE_NAME = "system.json"; - constexpr float PI_F = static_cast(PI); // NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) @@ -43,7 +41,7 @@ extern FatFileSystem fatfs; class Utils { public: - explicit Utils(const char *systemConfigFilename = DEFAULT_CONFIG_FILE_NAME) : configFileName(systemConfigFilename) {} + explicit Utils() = default; bool begin(uint32_t watchdogTimeout = 0, const char *labelName = "DRIVE", bool forceFormat = false); static void startBootloader(); static void startWatchdog(uint32_t seconds); @@ -57,7 +55,6 @@ class Utils { explicit operator bool() const { return mscReady; } private: - const char *configFileName; const char *serial = "0"; volatile bool mscReady = false; diff --git a/ground_station/system.json b/ground_station/system.json deleted file mode 100644 index 4e15bb60..00000000 --- a/ground_station/system.json +++ /dev/null @@ -1,7 +0,0 @@ -{ - "usb_serial":"0", - "usb_vid":"0x239A", - "usb_pid":"0x80AB", - "ssid":"WLAN", - "password":"zyxel2010" -} \ No newline at end of file From 31e3e6e280eb4abc0bb7c53bd53aae5ea4513d5c Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Wed, 25 Oct 2023 18:39:27 +0200 Subject: [PATCH 10/11] Address review comments --- flight_computer/src/config/globals.hpp | 2 +- flight_computer/src/drivers/buzzer.cpp | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/flight_computer/src/config/globals.hpp b/flight_computer/src/config/globals.hpp index 72162bb2..09933518 100644 --- a/flight_computer/src/config/globals.hpp +++ b/flight_computer/src/config/globals.hpp @@ -78,4 +78,4 @@ extern event_action_map_elem_t* event_action_map; inline constexpr const char* board_name = "CATS Vega"; extern char telemetry_code_version[20]; -// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) \ No newline at end of file +// NOLINTEND(cppcoreguidelines-avoid-non-const-global-variables) diff --git a/flight_computer/src/drivers/buzzer.cpp b/flight_computer/src/drivers/buzzer.cpp index 0c492c37..fa1001cd 100644 --- a/flight_computer/src/drivers/buzzer.cpp +++ b/flight_computer/src/drivers/buzzer.cpp @@ -22,9 +22,10 @@ namespace driver { void Buzzer::SetVolume(uint16_t volume) { const uint16_t pwm_depth = m_pwm_channel.GetPwmDepth(); + // Limit volume to 100% + volume = std::min(100U, volume); // 100% volume = 50% pwm - // NOLINTNEXTLINE(bugprone-implicit-widening-of-multiplication-result) - const uint32_t pwm_ticks = (pwm_depth / 200U) * volume; + const uint32_t pwm_ticks = (static_cast(pwm_depth) / 200U) * volume; m_pwm_channel.SetDutyCycleTicks(pwm_ticks); } From faf3e7e92a7911d045a890d3f0c9de8991b252e6 Mon Sep 17 00:00:00 2001 From: Nemanja Stojoski Date: Sun, 3 Sep 2023 10:46:36 +0200 Subject: [PATCH 11/11] Bump up code versions --- flight_computer/platformio.ini | 2 +- ground_station/platformio.ini | 2 +- telemetry/platformio.ini | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/flight_computer/platformio.ini b/flight_computer/platformio.ini index 78c88178..b0727f0a 100644 --- a/flight_computer/platformio.ini +++ b/flight_computer/platformio.ini @@ -35,7 +35,7 @@ check_src_filters = build_unflags=-fno-rtti build_flags = - -D FIRMWARE_VERSION='"3.0.1"' + -D FIRMWARE_VERSION='"3.0.2"' -D ARM_MATH_CM4 -D ARM_MATH_MATRIX_CHECK -D ARM_MATH_ROUNDING diff --git a/ground_station/platformio.ini b/ground_station/platformio.ini index 7c6147a1..dac82bf9 100644 --- a/ground_station/platformio.ini +++ b/ground_station/platformio.ini @@ -65,7 +65,7 @@ lib_deps = build_flags = -DCFG_TUSB_CONFIG_FILE='"sdkconfig.h"' ; Use default TinyUSB configuration - -DFIRMWARE_VERSION='"1.1.0"' ; Enter Firmware Version here + -DFIRMWARE_VERSION='"1.1.1"' ; Enter Firmware Version here -DUSB_MANUFACTURER='"CATS"' ; USB Manufacturer string -DUSB_PRODUCT='"CATS Ground Station"' ; USB Product String -D USB_SERIAL="0" ; Enter Device Serial Number here diff --git a/telemetry/platformio.ini b/telemetry/platformio.ini index f02ddfd1..1c4b67a7 100644 --- a/telemetry/platformio.ini +++ b/telemetry/platformio.ini @@ -19,7 +19,7 @@ extra_scripts = pre:pre_config.py build_flags = - -D FIRMWARE_VERSION='"1.1.1"' + -D FIRMWARE_VERSION='"1.1.2"' check_tool = clangtidy check_src_filters =