From 06f1da533ebe53c5d3dd64dc14d357dce65795ef Mon Sep 17 00:00:00 2001
From: FARHANG <farhang.nba@gmail.com>
Date: Thu, 12 Sep 2024 11:28:11 -0400
Subject: [PATCH 01/19] Rev1

---
 COMPILE.md | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/COMPILE.md b/COMPILE.md
index fbae2d4e0..4a780ae83 100644
--- a/COMPILE.md
+++ b/COMPILE.md
@@ -93,7 +93,7 @@ brew install cmake qt@5 protobuf mosquitto zeromq zstd
 If a newer version of qt is installed, you may need to temporarily link to qt5
 
 ```shell
-brew link qt@5 --override
+brew link qt@5 --overwrite
 # brew link qt --override # Run once you are done building to restore the original linking
 ```
 
@@ -118,7 +118,7 @@ export LDFLAGS="$QT_HOME/lib"
 Clone the repository into **~/plotjuggler_ws**:
 
 ```shell
-git clone https://github.com/facontidavide/PlotJuggler.git ~/plotjuggler_ws/src/PlotJuggler
+git clone https://github.com/PX4/PlotJuggler.git ~/plotjuggler_ws/src/PlotJuggler
 cd ~/plotjuggler_ws
 ```
 

From 77c10fff7b9adb99ea9f7e7622d1b67e09d3ae99 Mon Sep 17 00:00:00 2001
From: FARHANG <farhang.nba@gmail.com>
Date: Thu, 12 Sep 2024 21:22:38 -0400
Subject: [PATCH 02/19] Rev2

---
 COMPILE.md                                    |  2 +-
 cmake/FindZeroMQ.cmake                        | 14 +++-----
 .../DataStreamZMQ/CMakeLists.txt              | 33 ++++++++++++++----
 .../ParserProtobuf/error_collectors.cpp       |  9 +++++
 .../ParserProtobuf/error_collectors.h         | 34 +++++++++++--------
 5 files changed, 62 insertions(+), 30 deletions(-)

diff --git a/COMPILE.md b/COMPILE.md
index 4a780ae83..ff7ac0254 100644
--- a/COMPILE.md
+++ b/COMPILE.md
@@ -94,7 +94,7 @@ If a newer version of qt is installed, you may need to temporarily link to qt5
 
 ```shell
 brew link qt@5 --overwrite
-# brew link qt --override # Run once you are done building to restore the original linking
+# brew link qt --overwrite # Run once you are done building to restore the original linking
 ```
 
 Add CMake into your env-vars to be detected by cmake
diff --git a/cmake/FindZeroMQ.cmake b/cmake/FindZeroMQ.cmake
index b4a9da124..f4acf7da5 100644
--- a/cmake/FindZeroMQ.cmake
+++ b/cmake/FindZeroMQ.cmake
@@ -5,13 +5,9 @@
 # ZeroMQ_LIBRARIES - The libraries needed to use ZeroMQ
 # ZeroMQ_DEFINITIONS - Compiler switches required for using ZeroMQ
 
-find_path ( ZeroMQ_INCLUDE_DIR zmq.h )
-find_library ( ZeroMQ_LIBRARY NAMES zmq )
+find_package(PkgConfig REQUIRED)
+pkg_check_modules(ZMQ REQUIRED libzmq)
 
-set ( ZeroMQ_LIBRARIES ${ZeroMQ_LIBRARY} )
-set ( ZeroMQ_INCLUDE_DIRS ${ZeroMQ_INCLUDE_DIR} )
-
-include ( FindPackageHandleStandardArgs )
-# handle the QUIETLY and REQUIRED arguments and set ZeroMQ_FOUND to TRUE
-# if all listed variables are TRUE
-find_package_handle_standard_args ( ZeroMQ DEFAULT_MSG ZeroMQ_LIBRARY ZeroMQ_INCLUDE_DIR )
+set(ZeroMQ_FOUND TRUE)
+set(ZeroMQ_INCLUDE_DIRS ${ZMQ_INCLUDE_DIRS})
+set(ZeroMQ_LIBRARIES ${ZMQ_LIBRARIES})
diff --git a/plotjuggler_plugins/DataStreamZMQ/CMakeLists.txt b/plotjuggler_plugins/DataStreamZMQ/CMakeLists.txt
index d7622ea98..37a48c941 100644
--- a/plotjuggler_plugins/DataStreamZMQ/CMakeLists.txt
+++ b/plotjuggler_plugins/DataStreamZMQ/CMakeLists.txt
@@ -1,33 +1,54 @@
+# Check for vcpkg, conan, or manual build environments
 if(BUILDING_WITH_VCPKG)
     message(STATUS "Finding ZeroMQ with vcpkg")
 elseif(BUILDING_WITH_CONAN)
     message(STATUS "Finding ZeroMQ with conan")
 else()
     message(STATUS "Finding ZeroMQ without package managers")
-    set(ZeroMQ_LIBS ${ZeroMQ_LIBRARIES})
+
+    # Find ZeroMQ using PkgConfig
+    find_package(PkgConfig REQUIRED)
+    pkg_check_modules(ZMQ REQUIRED libzmq)
+
+    # Set the ZeroMQ libraries and include directories for manual configuration
+    set(ZeroMQ_LIBRARIES ${ZMQ_LIBRARIES})
+    set(ZeroMQ_INCLUDE_DIRS ${ZMQ_INCLUDE_DIRS})
+    set(ZeroMQ_LIBRARY_DIRS /opt/homebrew/lib)  # Add this line
+
+    # Add the library path explicitly
+    link_directories(${ZeroMQ_LIBRARY_DIRS})  # Add this line
 endif()
 
+# Find ZeroMQ library
 find_package(ZeroMQ QUIET)
 
+# Check if ZeroMQ was found
 if(ZeroMQ_FOUND)
     message(STATUS "[ZeroMQ] found")
 
+    # Add QT definitions if needed
     add_definitions(${QT_DEFINITIONS})
     add_definitions(-DQT_PLUGIN)
 
-    QT5_WRAP_UI ( UI_SRC  datastream_zmq.ui  )
+    # Wrap the UI file for Qt
+    QT5_WRAP_UI(UI_SRC datastream_zmq.ui)
 
-    add_library(DataStreamZMQ SHARED datastream_zmq.cpp ${UI_SRC}  )
+    # Add the DataStreamZMQ library
+    add_library(DataStreamZMQ SHARED datastream_zmq.cpp ${UI_SRC})
 
+    # Link Qt5Widgets and the plotjuggler_base target to DataStreamZMQ
     target_link_libraries(DataStreamZMQ ${Qt5Widgets_LIBRARIES} plotjuggler_base)
 
+    # Handle different library linking for vcpkg, conan, or manual builds
     if(BUILDING_WITH_VCPKG OR BUILDING_WITH_CONAN)
         target_link_libraries(DataStreamZMQ libzmq-static)
     else()
-        target_link_libraries(DataStreamZMQ ${ZeroMQ_LIBRARIES})
+        target_include_directories(DataStreamZMQ PRIVATE ${ZeroMQ_INCLUDE_DIRS})
+        target_link_libraries(DataStreamZMQ zmq)  # Changed this to just 'zmq'
     endif()
 
-    install(TARGETS DataStreamZMQ DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY}  )
+    # Install the plugin
+    install(TARGETS DataStreamZMQ DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY})
 else()
-    message("[ZeroMQ] not found. Skipping plugin DataStreamZMQ.")
+    message(STATUS "[ZeroMQ] not found. Skipping plugin DataStreamZMQ.")
 endif()
diff --git a/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp b/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp
index 761e0b739..19342e931 100644
--- a/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp
+++ b/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp
@@ -23,6 +23,15 @@ void FileErrorCollector::AddWarning(const std::string& filename, int line, int,
   qDebug() << msg;
 }
 
+void FileErrorCollector::RecordError(absl::string_view filename, int line, int column,
+                                     absl::string_view message) {
+    QString errorMessage = QString("Error in file: %1 at line: %2, column: %3: %4")
+                               .arg(QString::fromStdString(std::string(filename)))
+                               .arg(line)
+                               .arg(column)
+                               .arg(QString::fromStdString(std::string(message)));
+    _errors << errorMessage;
+}
 void IoErrorCollector::AddError(int line, google::protobuf::io::ColumnNumber,
                                 const std::string& message)
 {
diff --git a/plotjuggler_plugins/ParserProtobuf/error_collectors.h b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
index f70a881f5..d6346b341 100644
--- a/plotjuggler_plugins/ParserProtobuf/error_collectors.h
+++ b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
@@ -10,10 +10,10 @@ class IoErrorCollector : public google::protobuf::io::ErrorCollector
 {
 public:
   void AddError(int line, google::protobuf::io::ColumnNumber column,
-                const std::string& message) override;
+                const std::string& message) ;
 
   void AddWarning(int line, google::protobuf::io::ColumnNumber column,
-                  const std::string& message) override;
+                  const std::string& message);
 
   const QStringList& errors()
   {
@@ -27,19 +27,25 @@ class IoErrorCollector : public google::protobuf::io::ErrorCollector
 class FileErrorCollector : public google::protobuf::compiler::MultiFileErrorCollector
 {
 public:
-  void AddError(const std::string& filename, int line, int,
-                const std::string& message) override;
-
-  void AddWarning(const std::string& filename, int line, int,
-                  const std::string& message) override;
-
-  const QStringList& errors()
-  {
-    return _errors;
-  }
-
+    void AddError(const std::string& filename, int line, int column,
+                  const std::string& message);
+
+    void AddWarning(const std::string& filename, int line, int column,
+                    const std::string& message);
+    void RecordError(absl::string_view filename, int line, int column,
+                     absl::string_view message) override;
+
+    const QStringList& errors() const {
+        return _errors;
+    }
+
+    // Accessor for the collected warnings
+    const QStringList& warnings() const {
+        return _warnings;
+    }
 private:
-  QStringList _errors;
+    QStringList _errors;
+    QStringList _warnings;
 };
 
 #endif  // ERROR_COLLECTORS_H

From d0d157fb3d0e734d4df67594542f3078ff36646c Mon Sep 17 00:00:00 2001
From: Farhang <46557204+farhangnaderi@users.noreply.github.com>
Date: Fri, 20 Sep 2024 11:33:14 -0400
Subject: [PATCH 03/19] Added force relinking qt@5

---
 COMPILE.md | 2 ++
 1 file changed, 2 insertions(+)

diff --git a/COMPILE.md b/COMPILE.md
index ff7ac0254..9d85c7036 100644
--- a/COMPILE.md
+++ b/COMPILE.md
@@ -94,6 +94,8 @@ If a newer version of qt is installed, you may need to temporarily link to qt5
 
 ```shell
 brew link qt@5 --overwrite
+#In case needed and still qt@5 was not found by cmake you can do:
+brew unlink qt@5 && brew link --force qt@5
 # brew link qt --overwrite # Run once you are done building to restore the original linking
 ```
 

From 43905695ff33b36d6a91b83640c226b27c96a242 Mon Sep 17 00:00:00 2001
From: FARHANG <farhang.nba@gmail.com>
Date: Thu, 14 Nov 2024 13:58:37 -0500
Subject: [PATCH 04/19] ci add tmate

---
 .github/workflows/macos.yaml                  |  4 +++
 .github/workflows/ubuntu.yaml                 |  4 +++
 .github/workflows/windows.yaml                |  5 +++
 .../ParserProtobuf/CMakeLists.txt             | 25 ++++++-------
 .../ParserProtobuf/error_collectors.h         | 36 ++++++++++---------
 5 files changed, 46 insertions(+), 28 deletions(-)

diff --git a/.github/workflows/macos.yaml b/.github/workflows/macos.yaml
index 62e79945e..49b2777f2 100644
--- a/.github/workflows/macos.yaml
+++ b/.github/workflows/macos.yaml
@@ -36,3 +36,7 @@ jobs:
         run: >
           cmake -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler;
           cmake --build build --target install
+          
+      - name: Setup tmate session
+        if: ${{ failure() }}
+        uses: mxschmitt/action-tmate@v3
diff --git a/.github/workflows/ubuntu.yaml b/.github/workflows/ubuntu.yaml
index de7fad83f..733d5449d 100644
--- a/.github/workflows/ubuntu.yaml
+++ b/.github/workflows/ubuntu.yaml
@@ -34,3 +34,7 @@ jobs:
         run: |
             cmake -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler;
             cmake --build build --target install
+
+      - name: Setup tmate session
+        if: ${{ failure() }}
+        uses: mxschmitt/action-tmate@v3
diff --git a/.github/workflows/windows.yaml b/.github/workflows/windows.yaml
index 177802f73..1c836d80e 100644
--- a/.github/workflows/windows.yaml
+++ b/.github/workflows/windows.yaml
@@ -39,3 +39,8 @@ jobs:
         run: >
           cmake -Ax64 -T host=x64 -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler;
           cmake --build build --target install
+
+      - name: Setup tmate session
+        if: ${{ failure() }}
+        uses: mxschmitt/action-tmate@v3
+
diff --git a/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt b/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt
index f399fdad9..cb7613785 100644
--- a/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt
+++ b/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt
@@ -8,29 +8,29 @@ else()
 endif()
 
 find_package(Protobuf QUIET)
+find_package(absl REQUIRED)
 
-if( Protobuf_FOUND)
-
+if(Protobuf_FOUND)
     include_directories( ../ )
+    include_directories(${Protobuf_INCLUDE_DIRS})
+    include_directories(${absl_INCLUDE_DIRS})
+
     add_definitions(${QT_DEFINITIONS})
     add_definitions(-DQT_PLUGIN)
 
     message(STATUS "[Protobuf] found")
-    QT5_WRAP_UI ( UI_SRC  protobuf_parser.ui )
-
-    include_directories(${Protobuf_INCLUDE_DIRS})
+    QT5_WRAP_UI(UI_SRC protobuf_parser.ui)
 
     add_library(ProtobufParser SHARED
         error_collectors.cpp
         protobuf_parser.cpp
         protobuf_factory.cpp
         protobuf_parser.h
-        ${UI_SRC}  )
+        ${UI_SRC})
 
-    if (${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
+    if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
         find_library(ABSL_SPINLOCK_WAIT_LIB absl_spinlock_wait)
-
-        target_link_libraries(ProtobufParser ${ABSL_SPINLOCK_WAIT_LIB} )
+        target_link_libraries(ProtobufParser ${ABSL_SPINLOCK_WAIT_LIB})
     endif()
 
     target_link_libraries(ProtobufParser
@@ -38,9 +38,10 @@ if( Protobuf_FOUND)
         ${Qt5Xml_LIBRARIES}
         ${Protobuf_LIBS}
         plotjuggler_base
-        plotjuggler_qwt)
+        plotjuggler_qwt
+        absl::strings)
 
-    install(TARGETS ProtobufParser DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY}  )
+    install(TARGETS ProtobufParser DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY})
 else()
-    message("[Protobuf] not found: skipping compilatiopn of plugin ProtobufParser")
+    message("[Protobuf] not found: skipping compilation of plugin ProtobufParser")
 endif()
diff --git a/plotjuggler_plugins/ParserProtobuf/error_collectors.h b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
index d6346b341..9cad9d166 100644
--- a/plotjuggler_plugins/ParserProtobuf/error_collectors.h
+++ b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
@@ -3,14 +3,14 @@
 
 #include <google/protobuf/io/tokenizer.h>
 #include <google/protobuf/compiler/importer.h>
-
 #include <QStringList>
+#include "absl/strings/string_view.h"
 
 class IoErrorCollector : public google::protobuf::io::ErrorCollector
 {
 public:
   void AddError(int line, google::protobuf::io::ColumnNumber column,
-                const std::string& message) ;
+                const std::string& message);
 
   void AddWarning(int line, google::protobuf::io::ColumnNumber column,
                   const std::string& message);
@@ -27,25 +27,29 @@ class IoErrorCollector : public google::protobuf::io::ErrorCollector
 class FileErrorCollector : public google::protobuf::compiler::MultiFileErrorCollector
 {
 public:
-    void AddError(const std::string& filename, int line, int column,
+  void AddError(const std::string& filename, int line, int column,
+                const std::string& message);
+
+  void AddWarning(const std::string& filename, int line, int column,
                   const std::string& message);
 
-    void AddWarning(const std::string& filename, int line, int column,
-                    const std::string& message);
-    void RecordError(absl::string_view filename, int line, int column,
-                     absl::string_view message) override;
+  void RecordError(absl::string_view filename, int line, int column,
+                   absl::string_view message);
 
-    const QStringList& errors() const {
-        return _errors;
-    }
+  const QStringList& errors() const
+  {
+    return _errors;
+  }
+
+  // Accessor for the collected warnings
+  const QStringList& warnings() const
+  {
+    return _warnings;
+  }
 
-    // Accessor for the collected warnings
-    const QStringList& warnings() const {
-        return _warnings;
-    }
 private:
-    QStringList _errors;
-    QStringList _warnings;
+  QStringList _errors;
+  QStringList _warnings;
 };
 
 #endif  // ERROR_COLLECTORS_H

From cacf700dd0a454c5d4655df6585b236346f71e5a Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 17:03:50 -0500
Subject: [PATCH 05/19] absl added to ubuntu workflow

---
 .github/workflows/ubuntu.yaml | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/.github/workflows/ubuntu.yaml b/.github/workflows/ubuntu.yaml
index 733d5449d..2222eab98 100644
--- a/.github/workflows/ubuntu.yaml
+++ b/.github/workflows/ubuntu.yaml
@@ -28,7 +28,8 @@ jobs:
                 libqt5x11extras5-dev \
                 libprotoc-dev \
                 libzmq3-dev \
-                liblz4-dev libzstd-dev
+                liblz4-dev libzstd-dev \
+                libabsl-dev
 
       - name: Build Plotjuggler
         run: |

From 68231ce6b41d2c10946a2c312dac66182401c725 Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 17:34:47 -0500
Subject: [PATCH 06/19] workflow corrections macos windows ubuntu

---
 .github/workflows/macos.yaml   | 50 ++++++++++++++++++----------------
 .github/workflows/ubuntu.yaml  | 15 ++++++++--
 .github/workflows/windows.yaml | 12 ++++++--
 3 files changed, 48 insertions(+), 29 deletions(-)

diff --git a/.github/workflows/macos.yaml b/.github/workflows/macos.yaml
index 49b2777f2..b3a0d17a9 100644
--- a/.github/workflows/macos.yaml
+++ b/.github/workflows/macos.yaml
@@ -1,42 +1,46 @@
 name: macos
 
+# on:
+#   push:
+#     branches:
+#     - 'main'
+#   pull_request:
+#     branches:
+#     - '*'
 on: [push, pull_request]
 
 jobs:
-
   macos-build:
-    runs-on: ${{ matrix.macos-version }}
+    runs-on: ${{ matrix.os }}
     strategy:
       fail-fast: false
       matrix:
-        macos-version:
-          - 'macos-latest'
+        os:
+          - macos-13
+          - macos-latest
 
     steps:
       - name: Sync repository
         uses: actions/checkout@v2
 
-      - name: Cache Qt
-        id: cache-qt
-        uses: actions/cache@v1  # not v2!
-        with:
-          path: '${{ github.workspace }}/qt_installation/'
-          key: ${{ runner.os }}-QtCache
+      - name: Prepare Homebrew and Install Dependencies
+        run: |
+          rm -rf /usr/local/var/homebrew/locks
+          brew cleanup -s
+          brew update
+          brew install mosquitto zeromq qt@5
 
-      - name: Install Qt
-        uses: jurplel/install-qt-action@v2.13.0
-        with:
-          version: '5.15.2'
-          host: 'mac'
-          dir: '${{ github.workspace }}/qt_installation/'
-          cached: ${{ steps.cache-qt.outputs.cache-hit }}
+      - name: Build PlotJuggler
+        run: |
+          export CMAKE_PREFIX_PATH=$(brew --prefix qt@5):$(brew --prefix zeromq)
+          export LDFLAGS="-L/usr/local/opt/zeromq/lib"
+          export CPPFLAGS="-I/usr/local/opt/zeromq/include"
+          export LIBRARY_PATH=/usr/local/opt/zeromq/lib
+          export CPATH=/usr/local/opt/zeromq/include
 
-      - name: Build Plotjuggler
-        shell: pwsh
-        run: >
-          cmake -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler;
+          cmake -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler
           cmake --build build --target install
-          
+
       - name: Setup tmate session
         if: ${{ failure() }}
-        uses: mxschmitt/action-tmate@v3
+        uses: mxschmitt/action-tmate@v3
\ No newline at end of file
diff --git a/.github/workflows/ubuntu.yaml b/.github/workflows/ubuntu.yaml
index 2222eab98..4c5d6e33f 100644
--- a/.github/workflows/ubuntu.yaml
+++ b/.github/workflows/ubuntu.yaml
@@ -3,7 +3,6 @@ name: ubuntu
 on: [push, pull_request]
 
 jobs:
-
   ubuntu-build:
     runs-on: ${{ matrix.ubuntu-distro }}
     strategy:
@@ -28,8 +27,18 @@ jobs:
                 libqt5x11extras5-dev \
                 libprotoc-dev \
                 libzmq3-dev \
-                liblz4-dev libzstd-dev \
-                libabsl-dev
+                liblz4-dev libzstd-dev 
+              if [[ "${{ matrix.ubuntu-distro }}" == "ubuntu-22.04" ]]; then
+                sudo apt -y install libabsl-dev;
+              elif [[ "${{ matrix.ubuntu-distro }}" == "ubuntu-20.04" ]]; then
+                git clone https://github.com/abseil/abseil-cpp.git;
+                cd abseil-cpp;
+                mkdir build;
+                cd build;
+                cmake ..;
+                make -j$(nproc);
+                sudo make install;
+              fi
 
       - name: Build Plotjuggler
         run: |
diff --git a/.github/workflows/windows.yaml b/.github/workflows/windows.yaml
index 1c836d80e..2c5a50606 100644
--- a/.github/workflows/windows.yaml
+++ b/.github/workflows/windows.yaml
@@ -19,6 +19,13 @@ jobs:
       - name: Sync repository
         uses: actions/checkout@v2
 
+      - name: Set up vcpkg
+        run: |
+          git clone https://github.com/microsoft/vcpkg.git
+          ./vcpkg/bootstrap-vcpkg.sh
+          ./vcpkg install protobuf mosquitto zeromq
+          echo "VCPKG_ROOT=$(pwd)/vcpkg" >> $GITHUB_ENV
+
       - name: Cache Qt
         id: cache-qt
         uses: actions/cache@v1  # not v2!
@@ -36,11 +43,10 @@ jobs:
 
       - name: Build Plotjuggler
         shell: pwsh
-        run: >
-          cmake -Ax64 -T host=x64 -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler;
+        run: |
+          cmake -Ax64 -T host=x64 -B build -DCMAKE_INSTALL_PREFIX=install -DCMAKE_TOOLCHAIN_FILE=${{ env.VCPKG_ROOT }}/scripts/buildsystems/vcpkg.cmake PlotJuggler;
           cmake --build build --target install
 
       - name: Setup tmate session
         if: ${{ failure() }}
         uses: mxschmitt/action-tmate@v3
-

From f0c06940d9b222a7398a0aa47f1e487bc43361cd Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 18:55:51 -0500
Subject: [PATCH 07/19] mac os add abseil windows removed manifest packages
 from vcpkg

---
 .github/workflows/macos.yaml   | 2 +-
 .github/workflows/windows.yaml | 2 +-
 2 files changed, 2 insertions(+), 2 deletions(-)

diff --git a/.github/workflows/macos.yaml b/.github/workflows/macos.yaml
index b3a0d17a9..af72609a8 100644
--- a/.github/workflows/macos.yaml
+++ b/.github/workflows/macos.yaml
@@ -28,7 +28,7 @@ jobs:
           rm -rf /usr/local/var/homebrew/locks
           brew cleanup -s
           brew update
-          brew install mosquitto zeromq qt@5
+          brew install mosquitto zeromq qt@5 abseil
 
       - name: Build PlotJuggler
         run: |
diff --git a/.github/workflows/windows.yaml b/.github/workflows/windows.yaml
index 2c5a50606..42d5a1312 100644
--- a/.github/workflows/windows.yaml
+++ b/.github/workflows/windows.yaml
@@ -23,7 +23,7 @@ jobs:
         run: |
           git clone https://github.com/microsoft/vcpkg.git
           ./vcpkg/bootstrap-vcpkg.sh
-          ./vcpkg install protobuf mosquitto zeromq
+          ./vcpkg install
           echo "VCPKG_ROOT=$(pwd)/vcpkg" >> $GITHUB_ENV
 
       - name: Cache Qt

From c0e3db7435df216c18e9eaa4747809e3bb5babba Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 19:15:09 -0500
Subject: [PATCH 08/19] ros1 ros2 fix

---
 .github/workflows/ros1.yaml | 18 +++++++++++++++---
 .github/workflows/ros2.yaml | 18 +++++++++++++++---
 2 files changed, 30 insertions(+), 6 deletions(-)

diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml
index a5c75e7ea..656d6fb5b 100644
--- a/.github/workflows/ros1.yaml
+++ b/.github/workflows/ros1.yaml
@@ -11,7 +11,19 @@ jobs:
     runs-on: ubuntu-latest
     steps:
       - uses: actions/checkout@v3
-      - uses: 'ros-industrial/industrial_ci@master'
-        env: ${{matrix.env}}
+      - name: Install dependencies
+        run: |
+          sudo apt update
+          sudo apt install -y libmosquitto-dev libqtav-dev libparquet-dev
+          git clone https://github.com/abseil/abseil-cpp.git
+          cd abseil-cpp
+          mkdir build && cd build
+          cmake -DCMAKE_POSITION_INDEPENDENT_CODE=ON -DCMAKE_INSTALL_PREFIX=/usr/local ..
+          make -j$(nproc)
+          sudo make install
+      - name: Run industrial_ci
+        uses: ros-industrial/industrial_ci@master
+        env: ${{ matrix.env }}
         with:
-            package-name: plotjuggler
+          config: |
+            - name: plotjuggler
diff --git a/.github/workflows/ros2.yaml b/.github/workflows/ros2.yaml
index afdccc466..907dacee8 100644
--- a/.github/workflows/ros2.yaml
+++ b/.github/workflows/ros2.yaml
@@ -12,7 +12,19 @@ jobs:
     runs-on: ubuntu-latest
     steps:
       - uses: actions/checkout@v3
-      - uses: 'ros-industrial/industrial_ci@master'
-        env: ${{matrix.env}}
+      - name: Install dependencies
+        run: |
+          sudo apt update
+          sudo apt install -y pkg-config libmosquitto-dev libqtav-dev libparquet-dev
+          git clone https://github.com/abseil/abseil-cpp.git
+          cd abseil-cpp
+          mkdir build && cd build
+          cmake -DCMAKE_POSITION_INDEPENDENT_CODE=ON -DCMAKE_INSTALL_PREFIX=/usr/local ..
+          make -j$(nproc)
+          sudo make install
+      - name: Run industrial_ci
+        uses: ros-industrial/industrial_ci@master
+        env: ${{ matrix.env }}
         with:
-            package-name: plotjuggler
+          config: |
+            - name: plotjuggler

From 65cd30b2f0cd1a780f2d115dc350c00cb4b91cb9 Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 19:25:23 -0500
Subject: [PATCH 09/19] ci fix windows ros1 ros2

---
 .github/workflows/ros1.yaml    | 6 +++++-
 .github/workflows/ros2.yaml    | 9 +++++++++
 .github/workflows/windows.yaml | 2 +-
 3 files changed, 15 insertions(+), 2 deletions(-)

diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml
index 656d6fb5b..ff7358679 100644
--- a/.github/workflows/ros1.yaml
+++ b/.github/workflows/ros1.yaml
@@ -13,8 +13,12 @@ jobs:
       - uses: actions/checkout@v3
       - name: Install dependencies
         run: |
+          wget -qO - https://dist.apache.org/repos/dist/release/arrow/KEYS | gpg --dearmor -o /usr/share/keyrings/apache-arrow-keyring.gpg
+          echo "deb [arch=amd64 signed-by=/usr/share/keyrings/apache-arrow-keyring.gpg] https://apache.jfrog.io/artifactory/arrow/ubuntu/ $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/apache-arrow.list
+
           sudo apt update
-          sudo apt install -y libmosquitto-dev libqtav-dev libparquet-dev
+          sudo apt install -y libmosquitto-dev libqtav-dev libarrow-dev libparquet-dev pkg-config
+
           git clone https://github.com/abseil/abseil-cpp.git
           cd abseil-cpp
           mkdir build && cd build
diff --git a/.github/workflows/ros2.yaml b/.github/workflows/ros2.yaml
index 907dacee8..1e2a7839e 100644
--- a/.github/workflows/ros2.yaml
+++ b/.github/workflows/ros2.yaml
@@ -22,6 +22,15 @@ jobs:
           cmake -DCMAKE_POSITION_INDEPENDENT_CODE=ON -DCMAKE_INSTALL_PREFIX=/usr/local ..
           make -j$(nproc)
           sudo make install
+
+          cd ~
+          git clone https://github.com/apache/arrow.git
+          cd arrow/cpp
+          mkdir build && cd build
+          cmake -DARROW_PARQUET=ON -DARROW_PYTHON=OFF -DARROW_BUILD_SHARED=ON -DCMAKE_INSTALL_PREFIX=/usr/local ..
+          make -j$(nproc)
+          sudo make install
+          
       - name: Run industrial_ci
         uses: ros-industrial/industrial_ci@master
         env: ${{ matrix.env }}
diff --git a/.github/workflows/windows.yaml b/.github/workflows/windows.yaml
index 42d5a1312..af2e9b763 100644
--- a/.github/workflows/windows.yaml
+++ b/.github/workflows/windows.yaml
@@ -23,7 +23,7 @@ jobs:
         run: |
           git clone https://github.com/microsoft/vcpkg.git
           ./vcpkg/bootstrap-vcpkg.sh
-          ./vcpkg install
+          ./vcpkg/vcpkg.exe install
           echo "VCPKG_ROOT=$(pwd)/vcpkg" >> $GITHUB_ENV
 
       - name: Cache Qt

From accca6fe4b0eae8832f59c65dffb2b250f169f2d Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 19:34:29 -0500
Subject: [PATCH 10/19] force bash for windows

---
 .github/workflows/windows.yaml | 1 +
 1 file changed, 1 insertion(+)

diff --git a/.github/workflows/windows.yaml b/.github/workflows/windows.yaml
index af2e9b763..8786dbd22 100644
--- a/.github/workflows/windows.yaml
+++ b/.github/workflows/windows.yaml
@@ -20,6 +20,7 @@ jobs:
         uses: actions/checkout@v2
 
       - name: Set up vcpkg
+        shell: bash
         run: |
           git clone https://github.com/microsoft/vcpkg.git
           ./vcpkg/bootstrap-vcpkg.sh

From 4baec751f413275e79ebbdcd106e6ca602cbce9d Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 20:55:12 -0500
Subject: [PATCH 11/19] windows,ros1, ros2 ci back to default

---
 .github/workflows/ros1.yaml    | 22 +++-------------------
 .github/workflows/ros2.yaml    | 27 +++------------------------
 .github/workflows/windows.yaml | 15 +++------------
 3 files changed, 9 insertions(+), 55 deletions(-)

diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml
index ff7358679..c972e5429 100644
--- a/.github/workflows/ros1.yaml
+++ b/.github/workflows/ros1.yaml
@@ -11,23 +11,7 @@ jobs:
     runs-on: ubuntu-latest
     steps:
       - uses: actions/checkout@v3
-      - name: Install dependencies
-        run: |
-          wget -qO - https://dist.apache.org/repos/dist/release/arrow/KEYS | gpg --dearmor -o /usr/share/keyrings/apache-arrow-keyring.gpg
-          echo "deb [arch=amd64 signed-by=/usr/share/keyrings/apache-arrow-keyring.gpg] https://apache.jfrog.io/artifactory/arrow/ubuntu/ $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/apache-arrow.list
-
-          sudo apt update
-          sudo apt install -y libmosquitto-dev libqtav-dev libarrow-dev libparquet-dev pkg-config
-
-          git clone https://github.com/abseil/abseil-cpp.git
-          cd abseil-cpp
-          mkdir build && cd build
-          cmake -DCMAKE_POSITION_INDEPENDENT_CODE=ON -DCMAKE_INSTALL_PREFIX=/usr/local ..
-          make -j$(nproc)
-          sudo make install
-      - name: Run industrial_ci
-        uses: ros-industrial/industrial_ci@master
-        env: ${{ matrix.env }}
+      - uses: 'ros-industrial/industrial_ci@master'
+        env: ${{matrix.env}}
         with:
-          config: |
-            - name: plotjuggler
+            package-name: plotjuggler
\ No newline at end of file
diff --git a/.github/workflows/ros2.yaml b/.github/workflows/ros2.yaml
index 1e2a7839e..53cb664d7 100644
--- a/.github/workflows/ros2.yaml
+++ b/.github/workflows/ros2.yaml
@@ -12,28 +12,7 @@ jobs:
     runs-on: ubuntu-latest
     steps:
       - uses: actions/checkout@v3
-      - name: Install dependencies
-        run: |
-          sudo apt update
-          sudo apt install -y pkg-config libmosquitto-dev libqtav-dev libparquet-dev
-          git clone https://github.com/abseil/abseil-cpp.git
-          cd abseil-cpp
-          mkdir build && cd build
-          cmake -DCMAKE_POSITION_INDEPENDENT_CODE=ON -DCMAKE_INSTALL_PREFIX=/usr/local ..
-          make -j$(nproc)
-          sudo make install
-
-          cd ~
-          git clone https://github.com/apache/arrow.git
-          cd arrow/cpp
-          mkdir build && cd build
-          cmake -DARROW_PARQUET=ON -DARROW_PYTHON=OFF -DARROW_BUILD_SHARED=ON -DCMAKE_INSTALL_PREFIX=/usr/local ..
-          make -j$(nproc)
-          sudo make install
-          
-      - name: Run industrial_ci
-        uses: ros-industrial/industrial_ci@master
-        env: ${{ matrix.env }}
+      - uses: 'ros-industrial/industrial_ci@master'
+        env: ${{matrix.env}}
         with:
-          config: |
-            - name: plotjuggler
+            package-name: plotjuggler
\ No newline at end of file
diff --git a/.github/workflows/windows.yaml b/.github/workflows/windows.yaml
index 8786dbd22..4eb48bb7a 100644
--- a/.github/workflows/windows.yaml
+++ b/.github/workflows/windows.yaml
@@ -19,14 +19,6 @@ jobs:
       - name: Sync repository
         uses: actions/checkout@v2
 
-      - name: Set up vcpkg
-        shell: bash
-        run: |
-          git clone https://github.com/microsoft/vcpkg.git
-          ./vcpkg/bootstrap-vcpkg.sh
-          ./vcpkg/vcpkg.exe install
-          echo "VCPKG_ROOT=$(pwd)/vcpkg" >> $GITHUB_ENV
-
       - name: Cache Qt
         id: cache-qt
         uses: actions/cache@v1  # not v2!
@@ -44,10 +36,9 @@ jobs:
 
       - name: Build Plotjuggler
         shell: pwsh
-        run: |
-          cmake -Ax64 -T host=x64 -B build -DCMAKE_INSTALL_PREFIX=install -DCMAKE_TOOLCHAIN_FILE=${{ env.VCPKG_ROOT }}/scripts/buildsystems/vcpkg.cmake PlotJuggler;
+        run: >
+          cmake -Ax64 -T host=x64 -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler;
           cmake --build build --target install
-
       - name: Setup tmate session
         if: ${{ failure() }}
-        uses: mxschmitt/action-tmate@v3
+        uses: mxschmitt/action-tmate@v3
\ No newline at end of file

From 29fcf18f0c6ebab467027732dba416d7a74c43c8 Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 21:13:53 -0500
Subject: [PATCH 12/19] temp zero MQ find rev1

---
 cmake/FindZeroMQ.cmake | 45 +++++++++++++++++++++++++++++++++++++-----
 1 file changed, 40 insertions(+), 5 deletions(-)

diff --git a/cmake/FindZeroMQ.cmake b/cmake/FindZeroMQ.cmake
index f4acf7da5..45827a5d2 100644
--- a/cmake/FindZeroMQ.cmake
+++ b/cmake/FindZeroMQ.cmake
@@ -5,9 +5,44 @@
 # ZeroMQ_LIBRARIES - The libraries needed to use ZeroMQ
 # ZeroMQ_DEFINITIONS - Compiler switches required for using ZeroMQ
 
-find_package(PkgConfig REQUIRED)
-pkg_check_modules(ZMQ REQUIRED libzmq)
+# find_package(PkgConfig REQUIRED)
+# pkg_check_modules(ZMQ REQUIRED libzmq)
 
-set(ZeroMQ_FOUND TRUE)
-set(ZeroMQ_INCLUDE_DIRS ${ZMQ_INCLUDE_DIRS})
-set(ZeroMQ_LIBRARIES ${ZMQ_LIBRARIES})
+# set(ZeroMQ_FOUND TRUE)
+# set(ZeroMQ_INCLUDE_DIRS ${ZMQ_INCLUDE_DIRS})
+# set(ZeroMQ_LIBRARIES ${ZMQ_LIBRARIES})
+# First, try to use PkgConfig to find ZeroMQ
+
+find_package(PkgConfig QUIET)
+if (PKG_CONFIG_FOUND)
+    pkg_check_modules(ZMQ libzmq)
+
+    if (ZMQ_FOUND)
+        message(STATUS "Found ZeroMQ using pkg-config")
+        set(ZeroMQ_FOUND TRUE)
+        set(ZeroMQ_INCLUDE_DIRS ${ZMQ_INCLUDE_DIRS})
+        set(ZeroMQ_LIBRARIES ${ZMQ_LIBRARIES})
+    else()
+        message(WARNING "PkgConfig could not find ZeroMQ, falling back to manual search")
+    endif()
+endif()
+
+# Fallback: if PkgConfig was not found or ZeroMQ was not found with pkg-config, use manual find
+if (NOT ZeroMQ_FOUND)
+    message(STATUS "Attempting to find ZeroMQ using manual search")
+
+    find_path(ZeroMQ_INCLUDE_DIR zmq.h)
+    find_library(ZeroMQ_LIBRARY NAMES zmq)
+
+    set(ZeroMQ_LIBRARIES ${ZeroMQ_LIBRARY})
+    set(ZeroMQ_INCLUDE_DIRS ${ZeroMQ_INCLUDE_DIR})
+
+    include(FindPackageHandleStandardArgs)
+    find_package_handle_standard_args(ZeroMQ DEFAULT_MSG ZeroMQ_LIBRARY ZeroMQ_INCLUDE_DIR)
+
+    if (ZeroMQ_FOUND)
+        message(STATUS "Found ZeroMQ using manual search")
+    else()
+        message(WARNING "ZeroMQ not found. Some features may be disabled.")
+    endif()
+endif()
\ No newline at end of file

From d487a0a42510d44f0546c9e73e5d7bc918c7e6e0 Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 21:35:02 -0500
Subject: [PATCH 13/19] revert zmq CMake

---
 cmake/FindZeroMQ.cmake                        | 40 +++------------
 .../DataStreamZMQ/CMakeLists.txt              | 49 ++++++-------------
 2 files changed, 22 insertions(+), 67 deletions(-)

diff --git a/cmake/FindZeroMQ.cmake b/cmake/FindZeroMQ.cmake
index 45827a5d2..67a72730d 100644
--- a/cmake/FindZeroMQ.cmake
+++ b/cmake/FindZeroMQ.cmake
@@ -11,38 +11,14 @@
 # set(ZeroMQ_FOUND TRUE)
 # set(ZeroMQ_INCLUDE_DIRS ${ZMQ_INCLUDE_DIRS})
 # set(ZeroMQ_LIBRARIES ${ZMQ_LIBRARIES})
-# First, try to use PkgConfig to find ZeroMQ
 
-find_package(PkgConfig QUIET)
-if (PKG_CONFIG_FOUND)
-    pkg_check_modules(ZMQ libzmq)
+find_path ( ZeroMQ_INCLUDE_DIR zmq.h )
+find_library ( ZeroMQ_LIBRARY NAMES zmq )
 
-    if (ZMQ_FOUND)
-        message(STATUS "Found ZeroMQ using pkg-config")
-        set(ZeroMQ_FOUND TRUE)
-        set(ZeroMQ_INCLUDE_DIRS ${ZMQ_INCLUDE_DIRS})
-        set(ZeroMQ_LIBRARIES ${ZMQ_LIBRARIES})
-    else()
-        message(WARNING "PkgConfig could not find ZeroMQ, falling back to manual search")
-    endif()
-endif()
+set ( ZeroMQ_LIBRARIES ${ZeroMQ_LIBRARY} )
+set ( ZeroMQ_INCLUDE_DIRS ${ZeroMQ_INCLUDE_DIR} )
 
-# Fallback: if PkgConfig was not found or ZeroMQ was not found with pkg-config, use manual find
-if (NOT ZeroMQ_FOUND)
-    message(STATUS "Attempting to find ZeroMQ using manual search")
-
-    find_path(ZeroMQ_INCLUDE_DIR zmq.h)
-    find_library(ZeroMQ_LIBRARY NAMES zmq)
-
-    set(ZeroMQ_LIBRARIES ${ZeroMQ_LIBRARY})
-    set(ZeroMQ_INCLUDE_DIRS ${ZeroMQ_INCLUDE_DIR})
-
-    include(FindPackageHandleStandardArgs)
-    find_package_handle_standard_args(ZeroMQ DEFAULT_MSG ZeroMQ_LIBRARY ZeroMQ_INCLUDE_DIR)
-
-    if (ZeroMQ_FOUND)
-        message(STATUS "Found ZeroMQ using manual search")
-    else()
-        message(WARNING "ZeroMQ not found. Some features may be disabled.")
-    endif()
-endif()
\ No newline at end of file
+include ( FindPackageHandleStandardArgs )
+# handle the QUIETLY and REQUIRED arguments and set ZeroMQ_FOUND to TRUE
+# if all listed variables are TRUE
+find_package_handle_standard_args ( ZeroMQ DEFAULT_MSG ZeroMQ_LIBRARY ZeroMQ_INCLUDE_DIR )
diff --git a/plotjuggler_plugins/DataStreamZMQ/CMakeLists.txt b/plotjuggler_plugins/DataStreamZMQ/CMakeLists.txt
index 37a48c941..0a2040d29 100644
--- a/plotjuggler_plugins/DataStreamZMQ/CMakeLists.txt
+++ b/plotjuggler_plugins/DataStreamZMQ/CMakeLists.txt
@@ -1,54 +1,33 @@
-# Check for vcpkg, conan, or manual build environments
 if(BUILDING_WITH_VCPKG)
     message(STATUS "Finding ZeroMQ with vcpkg")
 elseif(BUILDING_WITH_CONAN)
     message(STATUS "Finding ZeroMQ with conan")
 else()
     message(STATUS "Finding ZeroMQ without package managers")
-
-    # Find ZeroMQ using PkgConfig
-    find_package(PkgConfig REQUIRED)
-    pkg_check_modules(ZMQ REQUIRED libzmq)
-
-    # Set the ZeroMQ libraries and include directories for manual configuration
-    set(ZeroMQ_LIBRARIES ${ZMQ_LIBRARIES})
-    set(ZeroMQ_INCLUDE_DIRS ${ZMQ_INCLUDE_DIRS})
-    set(ZeroMQ_LIBRARY_DIRS /opt/homebrew/lib)  # Add this line
-
-    # Add the library path explicitly
-    link_directories(${ZeroMQ_LIBRARY_DIRS})  # Add this line
+    set(ZeroMQ_LIBS ${ZeroMQ_LIBRARIES})
 endif()
 
-# Find ZeroMQ library
 find_package(ZeroMQ QUIET)
 
-# Check if ZeroMQ was found
 if(ZeroMQ_FOUND)
-    message(STATUS "[ZeroMQ] found")
+    # message(STATUS "[ZeroMQ] found")
 
-    # Add QT definitions if needed
-    add_definitions(${QT_DEFINITIONS})
-    add_definitions(-DQT_PLUGIN)
+    # add_definitions(${QT_DEFINITIONS})
+    # add_definitions(-DQT_PLUGIN)
 
-    # Wrap the UI file for Qt
-    QT5_WRAP_UI(UI_SRC datastream_zmq.ui)
+    # QT5_WRAP_UI ( UI_SRC  datastream_zmq.ui  )
 
-    # Add the DataStreamZMQ library
-    add_library(DataStreamZMQ SHARED datastream_zmq.cpp ${UI_SRC})
+    # add_library(DataStreamZMQ SHARED datastream_zmq.cpp ${UI_SRC}  )
 
-    # Link Qt5Widgets and the plotjuggler_base target to DataStreamZMQ
-    target_link_libraries(DataStreamZMQ ${Qt5Widgets_LIBRARIES} plotjuggler_base)
+    # target_link_libraries(DataStreamZMQ ${Qt5Widgets_LIBRARIES} plotjuggler_base)
 
-    # Handle different library linking for vcpkg, conan, or manual builds
-    if(BUILDING_WITH_VCPKG OR BUILDING_WITH_CONAN)
-        target_link_libraries(DataStreamZMQ libzmq-static)
-    else()
-        target_include_directories(DataStreamZMQ PRIVATE ${ZeroMQ_INCLUDE_DIRS})
-        target_link_libraries(DataStreamZMQ zmq)  # Changed this to just 'zmq'
-    endif()
+    # if(BUILDING_WITH_VCPKG OR BUILDING_WITH_CONAN)
+    #     target_link_libraries(DataStreamZMQ libzmq-static)
+    # else()
+    #     target_link_libraries(DataStreamZMQ ${ZeroMQ_LIBRARIES})
+    # endif()
 
-    # Install the plugin
-    install(TARGETS DataStreamZMQ DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY})
+    # install(TARGETS DataStreamZMQ DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY}  )
 else()
-    message(STATUS "[ZeroMQ] not found. Skipping plugin DataStreamZMQ.")
+    message("[ZeroMQ] not found. Skipping plugin DataStreamZMQ.")
 endif()

From ff55a600a5f02ce33d4fa530bfb9dd4fec8b50c9 Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 21:49:33 -0500
Subject: [PATCH 14/19] libasl dependency added to windows, ros1, ros2

---
 .github/workflows/ros1.yaml         | 6 ++++--
 .github/workflows/ros2-rolling.yaml | 4 +++-
 .github/workflows/ros2.yaml         | 6 ++++--
 vcpkg.json                          | 5 +++--
 4 files changed, 14 insertions(+), 7 deletions(-)

diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml
index c972e5429..47d5cf82c 100644
--- a/.github/workflows/ros1.yaml
+++ b/.github/workflows/ros1.yaml
@@ -12,6 +12,8 @@ jobs:
     steps:
       - uses: actions/checkout@v3
       - uses: 'ros-industrial/industrial_ci@master'
-        env: ${{matrix.env}}
+        env: ${{ matrix.env }}
         with:
-            package-name: plotjuggler
\ No newline at end of file
+          config: |
+            PACKAGE_NAME=plotjuggler
+            APT_DEPENDENCIES=libabsl-dev
diff --git a/.github/workflows/ros2-rolling.yaml b/.github/workflows/ros2-rolling.yaml
index cb5004506..0a27aa3d0 100644
--- a/.github/workflows/ros2-rolling.yaml
+++ b/.github/workflows/ros2-rolling.yaml
@@ -14,4 +14,6 @@ jobs:
       - uses: 'ros-industrial/industrial_ci@master'
         env: ${{matrix.env}}
         with:
-            package-name: plotjuggler
+          config: |
+            PACKAGE_NAME=plotjuggler
+            APT_DEPENDENCIES=libabsl-dev
diff --git a/.github/workflows/ros2.yaml b/.github/workflows/ros2.yaml
index 53cb664d7..a60775f62 100644
--- a/.github/workflows/ros2.yaml
+++ b/.github/workflows/ros2.yaml
@@ -13,6 +13,8 @@ jobs:
     steps:
       - uses: actions/checkout@v3
       - uses: 'ros-industrial/industrial_ci@master'
-        env: ${{matrix.env}}
+        env: ${{ matrix.env }}
         with:
-            package-name: plotjuggler
\ No newline at end of file
+          config: |
+            PACKAGE_NAME=plotjuggler
+            APT_DEPENDENCIES=libabsl-dev
diff --git a/vcpkg.json b/vcpkg.json
index b576855a5..222b9d8e6 100644
--- a/vcpkg.json
+++ b/vcpkg.json
@@ -10,6 +10,7 @@
       "features": [
         "parquet"
       ]
-    }
+    },
+    "abseil"  
   ]
-}
+}
\ No newline at end of file

From 86dcc62958e2479525dbf67a3c5846de91357b2c Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 22:05:29 -0500
Subject: [PATCH 15/19] reverting absl

---
 .github/workflows/ros1.yaml                   | 11 ++-
 .github/workflows/ros2-rolling.yaml           |  4 +-
 .github/workflows/ros2.yaml                   |  6 +-
 .../ParserProtobuf/CMakeLists.txt             | 27 +++---
 .../ParserProtobuf/error_collectors.cpp       | 11 +--
 .../ParserProtobuf/error_collectors.h         | 82 ++++++++-----------
 vcpkg.json                                    |  3 +-
 7 files changed, 56 insertions(+), 88 deletions(-)

diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml
index 47d5cf82c..53cb664d7 100644
--- a/.github/workflows/ros1.yaml
+++ b/.github/workflows/ros1.yaml
@@ -1,4 +1,4 @@
-name: ros1
+name: ros2
 
 on: [push, pull_request]
 
@@ -7,13 +7,12 @@ jobs:
     strategy:
       matrix:
         env:
-          - {ROS_DISTRO: noetic, ROS_REPO: main}
+          - {ROS_DISTRO: humble, ROS_REPO: main}
+          - {ROS_DISTRO: iron, ROS_REPO: main}
     runs-on: ubuntu-latest
     steps:
       - uses: actions/checkout@v3
       - uses: 'ros-industrial/industrial_ci@master'
-        env: ${{ matrix.env }}
+        env: ${{matrix.env}}
         with:
-          config: |
-            PACKAGE_NAME=plotjuggler
-            APT_DEPENDENCIES=libabsl-dev
+            package-name: plotjuggler
\ No newline at end of file
diff --git a/.github/workflows/ros2-rolling.yaml b/.github/workflows/ros2-rolling.yaml
index 0a27aa3d0..fc4d907a3 100644
--- a/.github/workflows/ros2-rolling.yaml
+++ b/.github/workflows/ros2-rolling.yaml
@@ -14,6 +14,4 @@ jobs:
       - uses: 'ros-industrial/industrial_ci@master'
         env: ${{matrix.env}}
         with:
-          config: |
-            PACKAGE_NAME=plotjuggler
-            APT_DEPENDENCIES=libabsl-dev
+            package-name: plotjuggler
\ No newline at end of file
diff --git a/.github/workflows/ros2.yaml b/.github/workflows/ros2.yaml
index a60775f62..53cb664d7 100644
--- a/.github/workflows/ros2.yaml
+++ b/.github/workflows/ros2.yaml
@@ -13,8 +13,6 @@ jobs:
     steps:
       - uses: actions/checkout@v3
       - uses: 'ros-industrial/industrial_ci@master'
-        env: ${{ matrix.env }}
+        env: ${{matrix.env}}
         with:
-          config: |
-            PACKAGE_NAME=plotjuggler
-            APT_DEPENDENCIES=libabsl-dev
+            package-name: plotjuggler
\ No newline at end of file
diff --git a/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt b/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt
index cb7613785..c0bb2d8aa 100644
--- a/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt
+++ b/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt
@@ -8,29 +8,29 @@ else()
 endif()
 
 find_package(Protobuf QUIET)
-find_package(absl REQUIRED)
 
-if(Protobuf_FOUND)
-    include_directories( ../ )
-    include_directories(${Protobuf_INCLUDE_DIRS})
-    include_directories(${absl_INCLUDE_DIRS})
+if( Protobuf_FOUND)
 
+    include_directories( ../ )
     add_definitions(${QT_DEFINITIONS})
     add_definitions(-DQT_PLUGIN)
 
     message(STATUS "[Protobuf] found")
-    QT5_WRAP_UI(UI_SRC protobuf_parser.ui)
+    QT5_WRAP_UI ( UI_SRC  protobuf_parser.ui )
+
+    include_directories(${Protobuf_INCLUDE_DIRS})
 
     add_library(ProtobufParser SHARED
         error_collectors.cpp
         protobuf_parser.cpp
         protobuf_factory.cpp
         protobuf_parser.h
-        ${UI_SRC})
+        ${UI_SRC}  )
 
-    if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
+    if (${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
         find_library(ABSL_SPINLOCK_WAIT_LIB absl_spinlock_wait)
-        target_link_libraries(ProtobufParser ${ABSL_SPINLOCK_WAIT_LIB})
+
+        target_link_libraries(ProtobufParser ${ABSL_SPINLOCK_WAIT_LIB} )
     endif()
 
     target_link_libraries(ProtobufParser
@@ -38,10 +38,9 @@ if(Protobuf_FOUND)
         ${Qt5Xml_LIBRARIES}
         ${Protobuf_LIBS}
         plotjuggler_base
-        plotjuggler_qwt
-        absl::strings)
+        plotjuggler_qwt)
 
-    install(TARGETS ProtobufParser DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY})
+    install(TARGETS ProtobufParser DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY}  )
 else()
-    message("[Protobuf] not found: skipping compilation of plugin ProtobufParser")
-endif()
+    message("[Protobuf] not found: skipping compilatiopn of plugin ProtobufParser")
+endif()
\ No newline at end of file
diff --git a/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp b/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp
index 19342e931..3768499bf 100644
--- a/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp
+++ b/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp
@@ -23,15 +23,6 @@ void FileErrorCollector::AddWarning(const std::string& filename, int line, int,
   qDebug() << msg;
 }
 
-void FileErrorCollector::RecordError(absl::string_view filename, int line, int column,
-                                     absl::string_view message) {
-    QString errorMessage = QString("Error in file: %1 at line: %2, column: %3: %4")
-                               .arg(QString::fromStdString(std::string(filename)))
-                               .arg(line)
-                               .arg(column)
-                               .arg(QString::fromStdString(std::string(message)));
-    _errors << errorMessage;
-}
 void IoErrorCollector::AddError(int line, google::protobuf::io::ColumnNumber,
                                 const std::string& message)
 {
@@ -45,4 +36,4 @@ void IoErrorCollector::AddWarning(int line, google::protobuf::io::ColumnNumber c
   qDebug() << QString("Line: [%1] Message: %2\n")
                   .arg(line)
                   .arg(QString::fromStdString(message));
-}
+}
\ No newline at end of file
diff --git a/plotjuggler_plugins/ParserProtobuf/error_collectors.h b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
index 9cad9d166..3768499bf 100644
--- a/plotjuggler_plugins/ParserProtobuf/error_collectors.h
+++ b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
@@ -1,55 +1,39 @@
-#ifndef ERROR_COLLECTORS_H
-#define ERROR_COLLECTORS_H
+#include "error_collectors.h"
+#include <QMessageBox>
+#include <QDebug>
 
-#include <google/protobuf/io/tokenizer.h>
-#include <google/protobuf/compiler/importer.h>
-#include <QStringList>
-#include "absl/strings/string_view.h"
-
-class IoErrorCollector : public google::protobuf::io::ErrorCollector
+void FileErrorCollector::AddError(const std::string& filename, int line, int,
+                                  const std::string& message)
 {
-public:
-  void AddError(int line, google::protobuf::io::ColumnNumber column,
-                const std::string& message);
-
-  void AddWarning(int line, google::protobuf::io::ColumnNumber column,
-                  const std::string& message);
-
-  const QStringList& errors()
-  {
-    return _errors;
-  }
+  auto msg = QString("File: [%1] Line: [%2] Message: %3\n\n")
+                 .arg(QString::fromStdString(filename))
+                 .arg(line)
+                 .arg(QString::fromStdString(message));
 
-private:
-  QStringList _errors;
-};
+  _errors.push_back(msg);
+}
 
-class FileErrorCollector : public google::protobuf::compiler::MultiFileErrorCollector
+void FileErrorCollector::AddWarning(const std::string& filename, int line, int,
+                                    const std::string& message)
 {
-public:
-  void AddError(const std::string& filename, int line, int column,
-                const std::string& message);
-
-  void AddWarning(const std::string& filename, int line, int column,
-                  const std::string& message);
-
-  void RecordError(absl::string_view filename, int line, int column,
-                   absl::string_view message);
-
-  const QStringList& errors() const
-  {
-    return _errors;
-  }
-
-  // Accessor for the collected warnings
-  const QStringList& warnings() const
-  {
-    return _warnings;
-  }
-
-private:
-  QStringList _errors;
-  QStringList _warnings;
-};
+  auto msg = QString("Warning [%1] line %2: %3")
+                 .arg(QString::fromStdString(filename))
+                 .arg(line)
+                 .arg(QString::fromStdString(message));
+  qDebug() << msg;
+}
+
+void IoErrorCollector::AddError(int line, google::protobuf::io::ColumnNumber,
+                                const std::string& message)
+{
+  _errors.push_back(
+      QString("Line: [%1] Message: %2\n").arg(line).arg(QString::fromStdString(message)));
+}
 
-#endif  // ERROR_COLLECTORS_H
+void IoErrorCollector::AddWarning(int line, google::protobuf::io::ColumnNumber column,
+                                  const std::string& message)
+{
+  qDebug() << QString("Line: [%1] Message: %2\n")
+                  .arg(line)
+                  .arg(QString::fromStdString(message));
+}
\ No newline at end of file
diff --git a/vcpkg.json b/vcpkg.json
index 222b9d8e6..a855b8fc5 100644
--- a/vcpkg.json
+++ b/vcpkg.json
@@ -10,7 +10,6 @@
       "features": [
         "parquet"
       ]
-    },
-    "abseil"  
+    }
   ]
 }
\ No newline at end of file

From ed9d0cff5e50aafe98706450e15274c1967ad547 Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 22:24:53 -0500
Subject: [PATCH 16/19] error collectors correction

---
 .github/workflows/macos.yaml                  |  2 +-
 .github/workflows/ros1.yaml                   |  5 +-
 .github/workflows/ubuntu.yaml                 | 11 ---
 .../ParserProtobuf/error_collectors.h         | 72 ++++++++++---------
 4 files changed, 42 insertions(+), 48 deletions(-)

diff --git a/.github/workflows/macos.yaml b/.github/workflows/macos.yaml
index af72609a8..b3a0d17a9 100644
--- a/.github/workflows/macos.yaml
+++ b/.github/workflows/macos.yaml
@@ -28,7 +28,7 @@ jobs:
           rm -rf /usr/local/var/homebrew/locks
           brew cleanup -s
           brew update
-          brew install mosquitto zeromq qt@5 abseil
+          brew install mosquitto zeromq qt@5
 
       - name: Build PlotJuggler
         run: |
diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml
index 53cb664d7..c972e5429 100644
--- a/.github/workflows/ros1.yaml
+++ b/.github/workflows/ros1.yaml
@@ -1,4 +1,4 @@
-name: ros2
+name: ros1
 
 on: [push, pull_request]
 
@@ -7,8 +7,7 @@ jobs:
     strategy:
       matrix:
         env:
-          - {ROS_DISTRO: humble, ROS_REPO: main}
-          - {ROS_DISTRO: iron, ROS_REPO: main}
+          - {ROS_DISTRO: noetic, ROS_REPO: main}
     runs-on: ubuntu-latest
     steps:
       - uses: actions/checkout@v3
diff --git a/.github/workflows/ubuntu.yaml b/.github/workflows/ubuntu.yaml
index 4c5d6e33f..a48298659 100644
--- a/.github/workflows/ubuntu.yaml
+++ b/.github/workflows/ubuntu.yaml
@@ -28,17 +28,6 @@ jobs:
                 libprotoc-dev \
                 libzmq3-dev \
                 liblz4-dev libzstd-dev 
-              if [[ "${{ matrix.ubuntu-distro }}" == "ubuntu-22.04" ]]; then
-                sudo apt -y install libabsl-dev;
-              elif [[ "${{ matrix.ubuntu-distro }}" == "ubuntu-20.04" ]]; then
-                git clone https://github.com/abseil/abseil-cpp.git;
-                cd abseil-cpp;
-                mkdir build;
-                cd build;
-                cmake ..;
-                make -j$(nproc);
-                sudo make install;
-              fi
 
       - name: Build Plotjuggler
         run: |
diff --git a/plotjuggler_plugins/ParserProtobuf/error_collectors.h b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
index 3768499bf..d3e9c5291 100644
--- a/plotjuggler_plugins/ParserProtobuf/error_collectors.h
+++ b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
@@ -1,39 +1,45 @@
-#include "error_collectors.h"
-#include <QMessageBox>
-#include <QDebug>
+#ifndef ERROR_COLLECTORS_H
+#define ERROR_COLLECTORS_H
 
-void FileErrorCollector::AddError(const std::string& filename, int line, int,
-                                  const std::string& message)
-{
-  auto msg = QString("File: [%1] Line: [%2] Message: %3\n\n")
-                 .arg(QString::fromStdString(filename))
-                 .arg(line)
-                 .arg(QString::fromStdString(message));
+#include <google/protobuf/io/tokenizer.h>
+#include <google/protobuf/compiler/importer.h>
 
-  _errors.push_back(msg);
-}
+#include <QStringList>
 
-void FileErrorCollector::AddWarning(const std::string& filename, int line, int,
-                                    const std::string& message)
-{
-  auto msg = QString("Warning [%1] line %2: %3")
-                 .arg(QString::fromStdString(filename))
-                 .arg(line)
-                 .arg(QString::fromStdString(message));
-  qDebug() << msg;
-}
-
-void IoErrorCollector::AddError(int line, google::protobuf::io::ColumnNumber,
-                                const std::string& message)
+class IoErrorCollector : public google::protobuf::io::ErrorCollector
 {
-  _errors.push_back(
-      QString("Line: [%1] Message: %2\n").arg(line).arg(QString::fromStdString(message)));
-}
+public:
+  void AddError(int line, google::protobuf::io::ColumnNumber column,
+                const std::string& message);
+
+  void AddWarning(int line, google::protobuf::io::ColumnNumber column,
+                  const std::string& message);
+
+  const QStringList& errors()
+  {
+    return _errors;
+  }
+
+private:
+  QStringList _errors;
+};
 
-void IoErrorCollector::AddWarning(int line, google::protobuf::io::ColumnNumber column,
-                                  const std::string& message)
+class FileErrorCollector : public google::protobuf::compiler::MultiFileErrorCollector
 {
-  qDebug() << QString("Line: [%1] Message: %2\n")
-                  .arg(line)
-                  .arg(QString::fromStdString(message));
-}
\ No newline at end of file
+public:
+  void AddError(const std::string& filename, int line, int,
+                const std::string& message);
+
+  void AddWarning(const std::string& filename, int line, int,
+                  const std::string& message);
+
+  const QStringList& errors()
+  {
+    return _errors;
+  }
+
+private:
+  QStringList _errors;
+};
+
+#endif  // ERROR_COLLECTORS_H
\ No newline at end of file

From 33654df88041b3be7a7872aac30cbfcf9f7d0ef1 Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 22:42:09 -0500
Subject: [PATCH 17/19] macos CI bring back triggers

---
 .github/workflows/macos.yaml | 15 +++++++--------
 1 file changed, 7 insertions(+), 8 deletions(-)

diff --git a/.github/workflows/macos.yaml b/.github/workflows/macos.yaml
index b3a0d17a9..3d70d41ab 100644
--- a/.github/workflows/macos.yaml
+++ b/.github/workflows/macos.yaml
@@ -1,13 +1,12 @@
 name: macos
 
-# on:
-#   push:
-#     branches:
-#     - 'main'
-#   pull_request:
-#     branches:
-#     - '*'
-on: [push, pull_request]
+on:
+  push:
+    branches:
+    - 'main'
+  pull_request:
+    branches:
+    - '*'
 
 jobs:
   macos-build:

From 536fe0873ace680b2bf38e793d6bc5f3414f9fef Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 23:27:14 -0500
Subject: [PATCH 18/19] remove absl string

---
 .github/workflows/macos.yaml                         |  4 ----
 .../ParserProtobuf/error_collectors.cpp              | 12 +-----------
 2 files changed, 1 insertion(+), 15 deletions(-)

diff --git a/.github/workflows/macos.yaml b/.github/workflows/macos.yaml
index 3d70d41ab..b3d7eef72 100644
--- a/.github/workflows/macos.yaml
+++ b/.github/workflows/macos.yaml
@@ -39,7 +39,3 @@ jobs:
 
           cmake -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler
           cmake --build build --target install
-
-      - name: Setup tmate session
-        if: ${{ failure() }}
-        uses: mxschmitt/action-tmate@v3
\ No newline at end of file
diff --git a/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp b/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp
index f0a29e083..761e0b739 100644
--- a/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp
+++ b/plotjuggler_plugins/ParserProtobuf/error_collectors.cpp
@@ -23,16 +23,6 @@ void FileErrorCollector::AddWarning(const std::string& filename, int line, int,
   qDebug() << msg;
 }
 
-void FileErrorCollector::RecordError(absl::string_view filename, int line, int column,
-                                     absl::string_view message)
-{
-  QString errorMessage = QString("Error in file: %1 at line: %2, column: %3: %4")
-                             .arg(QString::fromStdString(std::string(filename)))
-                             .arg(line)
-                             .arg(column)
-                             .arg(QString::fromStdString(std::string(message)));
-  _errors << errorMessage;
-}
 void IoErrorCollector::AddError(int line, google::protobuf::io::ColumnNumber,
                                 const std::string& message)
 {
@@ -46,4 +36,4 @@ void IoErrorCollector::AddWarning(int line, google::protobuf::io::ColumnNumber c
   qDebug() << QString("Line: [%1] Message: %2\n")
                   .arg(line)
                   .arg(QString::fromStdString(message));
-}
\ No newline at end of file
+}

From 009ad161befd86042ff58b84aee3b6ffe48f2457 Mon Sep 17 00:00:00 2001
From: farhangnaderi <farhang.nba@gmail.com>
Date: Sun, 17 Nov 2024 23:43:56 -0500
Subject: [PATCH 19/19] fix pre-commit ci fix

---
 .github/workflows/ros1.yaml                                | 2 +-
 .github/workflows/ros2-rolling.yaml                        | 2 +-
 .github/workflows/ros2.yaml                                | 2 +-
 .github/workflows/ubuntu.yaml                              | 6 +-----
 .github/workflows/windows.yaml                             | 3 ---
 cmake/FindZeroMQ.cmake                                     | 1 -
 installer/io.plotjuggler.application/meta/installscript.qs | 2 +-
 installer/io.plotjuggler.application/meta/targetwidget.ui  | 2 +-
 plotjuggler_plugins/ParserProtobuf/CMakeLists.txt          | 2 +-
 plotjuggler_plugins/ParserProtobuf/error_collectors.h      | 6 ++----
 vcpkg.json                                                 | 2 +-
 11 files changed, 10 insertions(+), 20 deletions(-)

diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml
index c972e5429..a5c75e7ea 100644
--- a/.github/workflows/ros1.yaml
+++ b/.github/workflows/ros1.yaml
@@ -14,4 +14,4 @@ jobs:
       - uses: 'ros-industrial/industrial_ci@master'
         env: ${{matrix.env}}
         with:
-            package-name: plotjuggler
\ No newline at end of file
+            package-name: plotjuggler
diff --git a/.github/workflows/ros2-rolling.yaml b/.github/workflows/ros2-rolling.yaml
index fc4d907a3..cb5004506 100644
--- a/.github/workflows/ros2-rolling.yaml
+++ b/.github/workflows/ros2-rolling.yaml
@@ -14,4 +14,4 @@ jobs:
       - uses: 'ros-industrial/industrial_ci@master'
         env: ${{matrix.env}}
         with:
-            package-name: plotjuggler
\ No newline at end of file
+            package-name: plotjuggler
diff --git a/.github/workflows/ros2.yaml b/.github/workflows/ros2.yaml
index 53cb664d7..afdccc466 100644
--- a/.github/workflows/ros2.yaml
+++ b/.github/workflows/ros2.yaml
@@ -15,4 +15,4 @@ jobs:
       - uses: 'ros-industrial/industrial_ci@master'
         env: ${{matrix.env}}
         with:
-            package-name: plotjuggler
\ No newline at end of file
+            package-name: plotjuggler
diff --git a/.github/workflows/ubuntu.yaml b/.github/workflows/ubuntu.yaml
index a48298659..9aeb04873 100644
--- a/.github/workflows/ubuntu.yaml
+++ b/.github/workflows/ubuntu.yaml
@@ -27,13 +27,9 @@ jobs:
                 libqt5x11extras5-dev \
                 libprotoc-dev \
                 libzmq3-dev \
-                liblz4-dev libzstd-dev 
+                liblz4-dev libzstd-dev
 
       - name: Build Plotjuggler
         run: |
             cmake -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler;
             cmake --build build --target install
-
-      - name: Setup tmate session
-        if: ${{ failure() }}
-        uses: mxschmitt/action-tmate@v3
diff --git a/.github/workflows/windows.yaml b/.github/workflows/windows.yaml
index 4eb48bb7a..177802f73 100644
--- a/.github/workflows/windows.yaml
+++ b/.github/workflows/windows.yaml
@@ -39,6 +39,3 @@ jobs:
         run: >
           cmake -Ax64 -T host=x64 -B build -DCMAKE_INSTALL_PREFIX=install PlotJuggler;
           cmake --build build --target install
-      - name: Setup tmate session
-        if: ${{ failure() }}
-        uses: mxschmitt/action-tmate@v3
\ No newline at end of file
diff --git a/cmake/FindZeroMQ.cmake b/cmake/FindZeroMQ.cmake
index 27eaa8ae1..b4a9da124 100644
--- a/cmake/FindZeroMQ.cmake
+++ b/cmake/FindZeroMQ.cmake
@@ -15,4 +15,3 @@ include ( FindPackageHandleStandardArgs )
 # handle the QUIETLY and REQUIRED arguments and set ZeroMQ_FOUND to TRUE
 # if all listed variables are TRUE
 find_package_handle_standard_args ( ZeroMQ DEFAULT_MSG ZeroMQ_LIBRARY ZeroMQ_INCLUDE_DIR )
-
diff --git a/installer/io.plotjuggler.application/meta/installscript.qs b/installer/io.plotjuggler.application/meta/installscript.qs
index 4605ae660..4a1c1942b 100644
--- a/installer/io.plotjuggler.application/meta/installscript.qs
+++ b/installer/io.plotjuggler.application/meta/installscript.qs
@@ -101,4 +101,4 @@ Component.prototype.componentSelectionPageEntered = function()
     if (installer.fileExists(dir) && installer.fileExists(dir + "/maintenancetool.exe")) {
         installer.execute(dir + "/maintenancetool.exe", ["purge", "-c"]);
     }
-}
\ No newline at end of file
+}
diff --git a/installer/io.plotjuggler.application/meta/targetwidget.ui b/installer/io.plotjuggler.application/meta/targetwidget.ui
index 623733204..04d7be70c 100644
--- a/installer/io.plotjuggler.application/meta/targetwidget.ui
+++ b/installer/io.plotjuggler.application/meta/targetwidget.ui
@@ -110,4 +110,4 @@
  </widget>
  <resources/>
  <connections/>
-</ui>
\ No newline at end of file
+</ui>
diff --git a/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt b/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt
index c0bb2d8aa..f399fdad9 100644
--- a/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt
+++ b/plotjuggler_plugins/ParserProtobuf/CMakeLists.txt
@@ -43,4 +43,4 @@ if( Protobuf_FOUND)
     install(TARGETS ProtobufParser DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY}  )
 else()
     message("[Protobuf] not found: skipping compilatiopn of plugin ProtobufParser")
-endif()
\ No newline at end of file
+endif()
diff --git a/plotjuggler_plugins/ParserProtobuf/error_collectors.h b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
index 60f2591a1..4f1cf826c 100644
--- a/plotjuggler_plugins/ParserProtobuf/error_collectors.h
+++ b/plotjuggler_plugins/ParserProtobuf/error_collectors.h
@@ -27,11 +27,9 @@ class IoErrorCollector : public google::protobuf::io::ErrorCollector
 class FileErrorCollector : public google::protobuf::compiler::MultiFileErrorCollector
 {
 public:
-  void AddError(const std::string& filename, int line, int,
-                const std::string& message);
+  void AddError(const std::string& filename, int line, int, const std::string& message);
 
-  void AddWarning(const std::string& filename, int line, int,
-                  const std::string& message);
+  void AddWarning(const std::string& filename, int line, int, const std::string& message);
 
   const QStringList& errors()
   {
diff --git a/vcpkg.json b/vcpkg.json
index a855b8fc5..b576855a5 100644
--- a/vcpkg.json
+++ b/vcpkg.json
@@ -12,4 +12,4 @@
       ]
     }
   ]
-}
\ No newline at end of file
+}