diff --git a/data_tamer_cpp/.clang-format b/.clang-format similarity index 69% rename from data_tamer_cpp/.clang-format rename to .clang-format index 40d1a25..80f4f71 100644 --- a/data_tamer_cpp/.clang-format +++ b/.clang-format @@ -1,5 +1,5 @@ --- -BasedOnStyle: Google +BasedOnStyle: Google AccessModifierOffset: -2 ConstructorInitializerIndentWidth: 2 AlignEscapedNewlinesLeft: false @@ -7,15 +7,14 @@ AlignTrailingComments: true AllowAllParametersOfDeclarationOnNextLine: false AllowShortIfStatementsOnASingleLine: false AllowShortLoopsOnASingleLine: false -AllowShortFunctionsOnASingleLine: Inline +AllowShortFunctionsOnASingleLine: None AlwaysBreakTemplateDeclarations: true AlwaysBreakBeforeMultilineStrings: false BreakBeforeBinaryOperators: false BreakBeforeTernaryOperators: false -BreakConstructorInitializersBeforeComma: false -BreakConstructorInitializers: AfterColon +BreakConstructorInitializers: BeforeComma BinPackParameters: true -ColumnLimit: 90 +ColumnLimit: 90 ConstructorInitializerAllOnOneLineOrOnePerLine: true DerivePointerBinding: false PointerBindsToType: true @@ -30,19 +29,20 @@ PenaltyBreakString: 1 PenaltyBreakFirstLessLess: 1000 PenaltyExcessCharacter: 1000 PenaltyReturnTypeOnItsOwnLine: 90 -SpacesBeforeTrailingComments: 3 -Cpp11BracedListStyle: true -Standard: Auto -IndentWidth: 2 -TabWidth: 2 -UseTab: Never +SpacesBeforeTrailingComments: 2 +Cpp11BracedListStyle: false +Standard: Auto +IndentWidth: 2 +TabWidth: 2 +UseTab: Never IndentFunctionDeclarationAfterType: false SpacesInParentheses: false -SpacesInAngles: false +SpacesInAngles: false SpaceInEmptyParentheses: false SpacesInCStyleCastParentheses: false SpaceAfterControlStatementKeyword: true SpaceBeforeAssignmentOperators: true +SpaceBeforeParens: Never ContinuationIndentWidth: 4 SortIncludes: false SpaceAfterCStyleCast: false @@ -53,17 +53,16 @@ BreakBeforeBraces: Custom # Control of individual brace wrapping cases BraceWrapping: { - AfterClass: 'true' - AfterControlStatement: 'true' - AfterEnum : 'true' - AfterFunction : 'true' - AfterNamespace : 'true' - AfterStruct : 'true' - AfterUnion : 'true' - BeforeCatch : 'true' - BeforeElse : 'true' - IndentBraces : 'false' + AfterClass: 'true', + AfterControlStatement: 'true', + AfterEnum : 'true', + AfterFunction : 'true', + AfterNamespace : 'true', + AfterStruct : 'true', + AfterUnion : 'true', + BeforeCatch : 'true', + BeforeElse : 'true', + IndentBraces : 'false', SplitEmptyFunction: 'false' } ... - diff --git a/.github/workflows/cmake_ubuntu.yml b/.github/workflows/cmake_ubuntu.yml index c82856d..66d7237 100644 --- a/.github/workflows/cmake_ubuntu.yml +++ b/.github/workflows/cmake_ubuntu.yml @@ -20,13 +20,13 @@ jobs: steps: - uses: actions/checkout@v2 - + - name: Install Conan id: conan uses: turtlebrowser/get-conan@main with: version: 2.0.13 - + - name: Create default profile run: conan profile detect @@ -48,17 +48,16 @@ jobs: shell: bash working-directory: ${{github.workspace}}/build run: cmake --build . --config Debug - + - name: run test (Linux) working-directory: ${{github.workspace}}/build run: ctest -T test -T Coverage - + - name: Upload coverage reports to Codecov uses: codecov/codecov-action@v3 - with: + with: directory: ${{github.workspace}}/build gcov_ignore: ${{github.workspace}}/3rdparty verbose: true env: CODECOV_TOKEN: ${{ secrets.CODECOV_TOKEN }} - diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 0000000..f1fb770 --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,44 @@ + +# To use: +# +# pre-commit run -a +# +# Or: +# +# pre-commit install # (runs every time you commit in git) +# +# To update this file: +# +# pre-commit autoupdate +# +# See https://github.com/pre-commit/pre-commit + +exclude: ^data_tamer_cpp/3rdparty/ +repos: + + # Standard hooks + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v4.5.0 + hooks: + - id: check-added-large-files + - id: check-ast + - id: check-case-conflict + - id: check-docstring-first + - id: check-merge-conflict + - id: check-symlinks + - id: check-xml + - id: check-yaml + - id: debug-statements + - id: end-of-file-fixer + exclude_types: [svg] + - id: mixed-line-ending + - id: trailing-whitespace + exclude_types: [svg] + - id: fix-byte-order-marker + + # CPP hooks + - repo: https://github.com/pre-commit/mirrors-clang-format + rev: v18.1.2 + hooks: + - id: clang-format + args: ['-fallback-style=none', '-i'] diff --git a/README.md b/README.md index ccd6e09..c0e3936 100644 --- a/README.md +++ b/README.md @@ -3,17 +3,17 @@ [![cmake Ubuntu](https://github.com/facontidavide/data_tamer/actions/workflows/cmake_ubuntu.yml/badge.svg)](https://github.com/facontidavide/data_tamer/actions/workflows/cmake_ubuntu.yml) [![ros2](https://github.com/PickNikRobotics/data_tamer/actions/workflows/ros2.yml/badge.svg)](https://github.com/PickNikRobotics/data_tamer/actions/workflows/ros2.yml) [![codecov](https://codecov.io/gh/facontidavide/data_tamer/graph/badge.svg?token=D0wtsntWds)](https://codecov.io/gh/facontidavide/data_tamer) - + **DataTamer** is a library to log/trace numerical variables over time and takes periodic "snapshots" of their values, to later visualize them as **timeseries**. It works great with [PlotJuggler](https://github.com/facontidavide/PlotJuggler), the timeseries visualization tool (note: you will need PlotJuggler **3.8.2** or later). -**DataTamer** is "fearless data logger" because you can record hundreds or **thousands of variables**: +**DataTamer** is "fearless data logger" because you can record hundreds or **thousands of variables**: even 1 million points per second should have a fairly small CPU overhead. -Since all the values are aggregated in a single "snapshot", it is usually meant to +Since all the values are aggregated in a single "snapshot", it is usually meant to record data in a periodic loop (a very frequent use case, in robotics applications). Kudos to [pal_statistics](https://github.com/pal-robotics/pal_statistics), for inspiring this project. @@ -27,20 +27,20 @@ DataTamer can be used to monitor multiple variables in your applications. **Channels** are used to take "snapshots" of a subset of variables at a given time. If you want to record at different frequencies, you can use different channels. -DataTamer will forward the collected data to 1 or multiple **sinks**; +DataTamer will forward the collected data to 1 or multiple **sinks**; a sink may save the information immediately in a file (currently, we support [MCAP](https://mcap.dev/)) or publish it using an inter-process communication, for instance, a ROS2 publisher. You can easily create your own, specialized sinks. Use [PlotJuggler](https://github.com/facontidavide/PlotJuggler) to -visualize your logs offline or in real-time. +visualize your logs offline or in real-time. ## Features - **Serialization schema is created at run-time**: no need to do code generation. - **Suitable for real-time applications**: very low latency (on the side of the callee). -- **Multi-sink architecture**: recorded data can be forwarded to multiple "backends". +- **Multi-sink architecture**: recorded data can be forwarded to multiple "backends". - **Very low serialization overhead**, in the order of 1 bit per traced value. - The user can enable/disable traced variables at run-time. @@ -176,11 +176,7 @@ cmake --build build/Debug --parallel # How to deserialize data recorded with DataTamer I will write more extensively about the serialization format used by DataTamer, but for the time being I -created a single header file without external dependencies that you can just copy into your project: +created a single header file without external dependencies that you can just copy into your project: [data_tamer_parser.hpp](data_tamer/include/data_tamer_parser) You can see how it is used in this example: [mcap_reader](data_tamer/examples/mcap_reader.cpp) - - - - diff --git a/data_tamer_cpp/CMakeLists.txt b/data_tamer_cpp/CMakeLists.txt index 6ad6dde..02ed2b4 100644 --- a/data_tamer_cpp/CMakeLists.txt +++ b/data_tamer_cpp/CMakeLists.txt @@ -19,7 +19,7 @@ option(BUILD_SHARED_LIBS "Build using shared libraries" ON) find_package(ament_cmake QUIET) if (ament_cmake_FOUND) - set(ROS2_SINK + set(ROS2_SINK src/sinks/ros2_publisher_sink.cpp) endif() @@ -139,7 +139,7 @@ endif() if(DATA_TAMER_BUILD_TESTS) include(CTest) - enable_testing() + enable_testing() add_subdirectory(tests) endif() @@ -153,4 +153,3 @@ if(benchmark_FOUND) else() message("Google Benchmark library not found") endif() - diff --git a/data_tamer_cpp/benchmarks/CMakeLists.txt b/data_tamer_cpp/benchmarks/CMakeLists.txt index 97ce2a7..ec76e6c 100644 --- a/data_tamer_cpp/benchmarks/CMakeLists.txt +++ b/data_tamer_cpp/benchmarks/CMakeLists.txt @@ -3,4 +3,3 @@ add_executable(dt_benchmark data_tamer_benchmark.cpp) target_include_directories(dt_benchmark PUBLIC $) target_link_libraries(dt_benchmark data_tamer benchmark) - diff --git a/data_tamer_cpp/benchmarks/data_tamer_benchmark.cpp b/data_tamer_cpp/benchmarks/data_tamer_benchmark.cpp index f644d93..317cd68 100644 --- a/data_tamer_cpp/benchmarks/data_tamer_benchmark.cpp +++ b/data_tamer_cpp/benchmarks/data_tamer_benchmark.cpp @@ -8,9 +8,16 @@ using namespace DataTamer; class NullSink : public DataSinkBase { public: - ~NullSink() override { stopThread(); } - void addChannel(std::string const&, Schema const&) override {} - bool storeSnapshot(const Snapshot&) override { return true; } + ~NullSink() override + { + stopThread(); + } + void addChannel(std::string const&, Schema const&) override + {} + bool storeSnapshot(const Snapshot&) override + { + return true; + } }; static void DT_Doubles(benchmark::State& state) @@ -23,7 +30,7 @@ static void DT_Doubles(benchmark::State& state) channel->registerValue("values", &values); - for (auto _ : state) + for(auto _ : state) { channel->takeSnapshot(); } @@ -39,7 +46,7 @@ static void DT_PoseType(benchmark::State& state) channel->registerValue("values", &poses); - for (auto _ : state) + for(auto _ : state) { channel->takeSnapshot(); } diff --git a/data_tamer_cpp/examples/CMakeLists.txt b/data_tamer_cpp/examples/CMakeLists.txt index dbb350a..292d44e 100644 --- a/data_tamer_cpp/examples/CMakeLists.txt +++ b/data_tamer_cpp/examples/CMakeLists.txt @@ -29,4 +29,3 @@ else() $ ) endif() - diff --git a/data_tamer_cpp/examples/custom_types.cpp b/data_tamer_cpp/examples/custom_types.cpp index be254ab..1ebb060 100644 --- a/data_tamer_cpp/examples/custom_types.cpp +++ b/data_tamer_cpp/examples/custom_types.cpp @@ -35,10 +35,11 @@ int main() // Note has the size of the message is almost the same as the raw data. // The only overhead is the size of points_vect - size_t expected_size = sizeof(double) * 3 + // point - sizeof(double) * 7 + // pose - sizeof(uint32_t) + 5 * (sizeof(double) * 3) + // points_vect and its size - sizeof(int32_t) * 3; // value_array + size_t expected_size = sizeof(double) * 3 + // point + sizeof(double) * 7 + // pose + sizeof(uint32_t) + + 5 * (sizeof(double) * 3) + // points_vect and its size + sizeof(int32_t) * 3; // value_array channel->takeSnapshot(); std::this_thread::sleep_for(std::chrono::milliseconds(10)); diff --git a/data_tamer_cpp/examples/geometry_types.hpp b/data_tamer_cpp/examples/geometry_types.hpp index 20dc951..7a62f3b 100644 --- a/data_tamer_cpp/examples/geometry_types.hpp +++ b/data_tamer_cpp/examples/geometry_types.hpp @@ -32,13 +32,26 @@ class Vector2d public: Vector2d() = default; - Vector2d(double x, double y) : _x(x), _y(y) {} + Vector2d(double x, double y) : _x(x), _y(y) + {} - const double& x() const { return _x; } - const double& y() const { return _y; } + const double& x() const + { + return _x; + } + const double& y() const + { + return _y; + } - double& x() { return _x; } - double& y() { return _y; } + double& x() + { + return _x; + } + double& y() + { + return _y; + } }; namespace DataTamer @@ -47,7 +60,10 @@ namespace DataTamer template <> struct TypeDefinition { - std::string typeName() const { return "Point3D"; } + std::string typeName() const + { + return "Point3D"; + } template void typeDef(Function& addField) @@ -61,7 +77,10 @@ struct TypeDefinition template <> struct TypeDefinition { - std::string typeName() const { return "Quaternion"; } + std::string typeName() const + { + return "Quaternion"; + } template void typeDef(Function& addField) @@ -76,7 +95,10 @@ struct TypeDefinition template <> struct TypeDefinition { - std::string typeName() const { return "Pose"; } + std::string typeName() const + { + return "Pose"; + } template void typeDef(Function& addField) @@ -89,7 +111,10 @@ struct TypeDefinition template <> struct TypeDefinition { - std::string typeName() const { return "Vector2d"; } + std::string typeName() const + { + return "Vector2d"; + } // typeDef must use a different overload and x() and y() must return const reference to // a class attribute @@ -101,4 +126,4 @@ struct TypeDefinition } }; -} // namespace DataTamer +} // namespace DataTamer diff --git a/data_tamer_cpp/examples/mcap_1m_per_sec.cpp b/data_tamer_cpp/examples/mcap_1m_per_sec.cpp index 9d1488d..3543508 100644 --- a/data_tamer_cpp/examples/mcap_1m_per_sec.cpp +++ b/data_tamer_cpp/examples/mcap_1m_per_sec.cpp @@ -18,7 +18,8 @@ void WritingThread(const std::string& channel_name) std::vector real32(vect_size); std::vector int16(vect_size); - enum Color: uint8_t { + enum Color : uint8_t + { RED = 0, GREEN = 1, BLUE = 2 @@ -30,13 +31,12 @@ void WritingThread(const std::string& channel_name) channel->registerValue("int16", &int16); channel->registerValue("color", &color); - int count = 0; double t = 0; - while (t < 10) // 10 simulated seconds + while(t < 10) // 10 simulated seconds { auto S = std::sin(t); - for (size_t i = 0; i < vect_size; i++) + for(size_t i = 0; i < vect_size; i++) { const auto value = static_cast(i) + S; real64[i] = value; @@ -45,13 +45,13 @@ void WritingThread(const std::string& channel_name) } color = static_cast(count % 3); - if (count++ % 1000 == 0) + if(count++ % 1000 == 0) { printf("[%s] time: %.1f\n", channel_name.c_str(), t); std::flush(std::cout); } auto t1 = std::chrono::system_clock::now(); - if (!channel->takeSnapshot()) + if(!channel->takeSnapshot()) { std::cout << "pushing failed\n"; } @@ -82,12 +82,12 @@ int main() // for 10 seconds (12 million data points) const int N = 4; std::thread writers[N]; - for (int i = 0; i < N; i++) + for(int i = 0; i < N; i++) { writers[i] = std::thread(WritingThread, std::string("channel_") + std::to_string(i)); } - for (int i = 0; i < N; i++) + for(int i = 0; i < N; i++) { writers[i].join(); } diff --git a/data_tamer_cpp/examples/mcap_reader.cpp b/data_tamer_cpp/examples/mcap_reader.cpp index 8836bc3..49fafb8 100644 --- a/data_tamer_cpp/examples/mcap_reader.cpp +++ b/data_tamer_cpp/examples/mcap_reader.cpp @@ -5,7 +5,7 @@ // using examples/mcap_writer_sample.cpp int main(int argc, char** argv) { - if (argc != 2) + if(argc != 2) { std::cout << "add the MCAP file as argument" << std::endl; return 1; @@ -16,7 +16,7 @@ int main(int argc, char** argv) mcap::McapReader reader; { auto const res = reader.open(filepath); - if (!res.ok()) + if(!res.ok()) { throw std::runtime_error("Can't open MCAP file"); } @@ -27,7 +27,7 @@ int main(int argc, char** argv) std::unordered_map hash_to_schema; // must call this, before accessing the schemas auto summary = reader.readSummary(mcap::ReadSummaryMethod::NoFallbackScan); - for (const auto& [schema_id, mcap_schema] : reader.schemas()) + for(const auto& [schema_id, mcap_schema] : reader.schemas()) { std::string schema_text(reinterpret_cast(mcap_schema->data.data()), mcap_schema->data.size()); @@ -45,7 +45,7 @@ int main(int argc, char** argv) auto IncrementCounter = [&](const std::string& series_name, MessageCount& message_counts) { auto it = message_counts.find(series_name); - if (it == message_counts.end()) + if(it == message_counts.end()) { message_counts[series_name] = 1; } @@ -56,7 +56,7 @@ int main(int argc, char** argv) }; // parse all messages - for (const auto& msg : reader.readMessages()) + for(const auto& msg : reader.readMessages()) { // start updating the fields of SnapshotView DataTamerParser::SnapshotView snapshot; @@ -67,7 +67,8 @@ int main(int argc, char** argv) // msg_buffer contains both active_mask and payload, serialized // one after the other. DataTamerParser::BufferSpan msg_buffer = { - reinterpret_cast(msg.message.data), msg.message.dataSize}; + reinterpret_cast(msg.message.data), msg.message.dataSize + }; const uint32_t mask_size = DataTamerParser::Deserialize(msg_buffer); snapshot.active_mask.data = msg_buffer.data; @@ -91,10 +92,10 @@ int main(int argc, char** argv) } // display the counted data samples - for (const auto& [channel_name, msg_counts] : message_counts_per_channel) + for(const auto& [channel_name, msg_counts] : message_counts_per_channel) { std::cout << channel_name << ":" << std::endl; - for (const auto& [name, count] : msg_counts) + for(const auto& [name, count] : msg_counts) { std::cout << " " << name << ":" << count << std::endl; } diff --git a/data_tamer_cpp/examples/mcap_writer_sample.cpp b/data_tamer_cpp/examples/mcap_writer_sample.cpp index cf10c42..b65ae26 100644 --- a/data_tamer_cpp/examples/mcap_writer_sample.cpp +++ b/data_tamer_cpp/examples/mcap_writer_sample.cpp @@ -17,12 +17,12 @@ int main() // logs in channelA std::vector v1(10, 0); - std::array v2 = {1, 2, 3, 4}; + std::array v2 = { 1, 2, 3, 4 }; int32_t v3 = 5; uint16_t v4 = 6; Pose pose; - pose.pos = {1, 2, 3}; - pose.rot = {0.4, 0.5, 0.6, 0.7}; + pose.pos = { 1, 2, 3 }; + pose.rot = { 0.4, 0.5, 0.6, 0.7 }; channelA->registerValue("vector_10", &v1); channelA->registerValue("array_4", &v2); @@ -34,10 +34,10 @@ int main() double v5 = 10; uint16_t v6 = 11; std::vector v7(4, 12); - std::array v8 = {13, 14, 15}; + std::array v8 = { 13, 14, 15 }; std::vector points(2); - points[0] = {1, 2, 3}; - points[1] = {4, 5, 6}; + points[0] = { 1, 2, 3 }; + points[1] = { 4, 5, 6 }; channelB->registerValue("real_value", &v5); channelB->registerValue("short_int", &v6); @@ -45,10 +45,10 @@ int main() channelB->registerValue("array_3", &v8); channelB->registerValue("points", &points); - for (size_t i = 0; i < 1000; i++) + for(size_t i = 0; i < 1000; i++) { channelA->takeSnapshot(); - if (i % 2 == 0) + if(i % 2 == 0) { channelB->takeSnapshot(); } diff --git a/data_tamer_cpp/examples/ros2_publisher.cpp b/data_tamer_cpp/examples/ros2_publisher.cpp index f262b6e..ecd0ef7 100644 --- a/data_tamer_cpp/examples/ros2_publisher.cpp +++ b/data_tamer_cpp/examples/ros2_publisher.cpp @@ -29,21 +29,21 @@ int main(int argc, char* argv[]) int count = 0; double t = 0; - while (rclcpp::ok()) + while(rclcpp::ok()) { double S = std::sin(t); - for (size_t i = 0; i < vect_size; i++) + for(size_t i = 0; i < vect_size; i++) { const double val = double(i) + S; real64[i] = val; real32[i] = float(val); int16[i] = int16_t(10 * (val)); } - if (count++ % 500 == 0) + if(count++ % 500 == 0) { RCLCPP_INFO(node->get_logger(), "snapshots: %d\n", count); } - if (!channel->takeSnapshot()) + if(!channel->takeSnapshot()) { RCLCPP_ERROR(node->get_logger(), "pushing failed"); } diff --git a/data_tamer_cpp/include/data_tamer/channel.hpp b/data_tamer_cpp/include/data_tamer/channel.hpp index c0fe2c9..d80af04 100644 --- a/data_tamer_cpp/include/data_tamer/channel.hpp +++ b/data_tamer_cpp/include/data_tamer/channel.hpp @@ -38,7 +38,8 @@ class LoggedValue friend LogChannel; public: - LoggedValue() {} + LoggedValue() + {} ~LoggedValue(); @@ -64,7 +65,10 @@ class LoggedValue /// @brief Disabling a LoggedValue means that we will not record it in the snapshot void setEnabled(bool enabled); - [[nodiscard]] bool isEnabled() const { return enabled_; } + [[nodiscard]] bool isEnabled() const + { + return enabled_; + } private: std::weak_ptr channel_; @@ -266,11 +270,11 @@ void LogChannel::updateTypeRegistryImpl(FieldsVector& fields, const char* field_ field.field_name = field_name; field.type = GetBasicType(); - if constexpr (GetBasicType() == BasicType::OTHER) + if constexpr(GetBasicType() == BasicType::OTHER) { field.type_name = TypeDefinition().typeName(); - if constexpr (container_info::is_container) + if constexpr(container_info::is_container) { field.is_vector = true; field.array_size = container_info::size; @@ -290,13 +294,13 @@ inline void LogChannel::updateTypeRegistry() { FieldsVector fields; - if constexpr (!IsNumericType()) - { + if constexpr(!IsNumericType()) + { const auto& type_name = DataTamer::TypeDefinition().typeName(); auto added_serializer = _type_registry.addType(type_name, true); - if (added_serializer) + if(added_serializer) { - if constexpr (has_typedef_with_object()) + if constexpr(has_typedef_with_object()) { auto func = [this, &fields](const char* field_name, const auto* member) { using MemberType = @@ -322,7 +326,7 @@ template inline RegistrationID LogChannel::registerValue(const std::string& name, const T* value_ptr) { - if constexpr (IsNumericType()) + if constexpr(IsNumericType()) { return registerValueImpl(name, ValuePtr(value_ptr), {}); } @@ -348,7 +352,7 @@ template