Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion src/lib/xbot_monitoring/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@ find_package(catkin REQUIRED COMPONENTS
grid_map_core
grid_map_ros
grid_map_msgs
xbot_rpc
xbot_mqtt
mower_msgs
)


Expand All @@ -31,6 +32,7 @@ catkin_package(
# LIBRARIES mower_comms
# CATKIN_DEPENDS mower_msgs roscpp serial
# DEPENDS system_lib
CATKIN_DEPENDS mower_msgs
DEPENDS PahoMqttCpp

)
Expand Down
3 changes: 2 additions & 1 deletion src/lib/xbot_monitoring/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,8 @@
<depend>grid_map_core</depend>
<depend>grid_map_ros</depend>
<depend>grid_map_msgs</depend>
<depend>xbot_rpc</depend>
<depend>xbot_mqtt</depend>
<depend>mower_msgs</depend>

<!-- The export tag contains other, unspecified, tags -->
<export>
Expand Down
70 changes: 70 additions & 0 deletions src/lib/xbot_monitoring/src/EventHistory.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
#pragma once

#include <deque>
#include <fstream>
#include <mutex>
#include <string>

#include <nlohmann/json.hpp>

using json = nlohmann::ordered_json;

class EventHistory {
public:
EventHistory() = default;

void init(size_t max_size) {
max_size_ = max_size;
file_path_ = "events.jsonl";
loadFromDisk();
Comment thread
rovo89 marked this conversation as resolved.
}

// Appends a raw JSON string to the ring buffer and persists it.
// No JSON parsing — stored as-is, parsed only on getAll().
void add(const std::string& json_payload) {
std::lock_guard<std::mutex> lk(mutex_);
if (buffer_.size() >= max_size_) {
buffer_.pop_front();
}
buffer_.push_back(json_payload);
appendToDisk(json_payload);
}
Comment thread
rovo89 marked this conversation as resolved.

// Returns all buffered events as a JSON array. Parses on read.
json getAll() const {
std::lock_guard<std::mutex> lk(mutex_);
json arr = json::array();
for (const auto& line : buffer_) {
try {
arr.push_back(json::parse(line));
} catch (...) {
// skip malformed lines
}
}
return arr;
}

private:
void loadFromDisk() {
std::ifstream f(file_path_);
if (!f.is_open()) return;
std::string line;
while (std::getline(f, line)) {
if (line.empty()) continue;
if (buffer_.size() >= max_size_) buffer_.pop_front();
buffer_.push_back(std::move(line));
}
}

void appendToDisk(const std::string& json_payload) {
std::ofstream f(file_path_, std::ios::app);
if (f.is_open()) {
f << json_payload << "\n";
}
}

std::string file_path_;
size_t max_size_ = 100;
std::deque<std::string> buffer_;
mutable std::mutex mutex_;
};
Loading
Loading