Skip to content
Merged
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
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
// Copyright 2026 mfaferek93
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include <chrono>

#include "rclcpp/rclcpp.hpp"

namespace ros2_medkit_fault_manager {

/// Get current wall clock time in nanoseconds.
/// This is not affected by use_sim_time parameter.
inline int64_t get_wall_clock_ns() {
auto now = std::chrono::system_clock::now();
return std::chrono::duration_cast<std::chrono::nanoseconds>(now.time_since_epoch()).count();
}

/// Get current wall clock time as rclcpp::Time.
/// This is not affected by use_sim_time parameter.
inline rclcpp::Time get_wall_clock_time() {
return rclcpp::Time(get_wall_clock_ns(), RCL_SYSTEM_TIME);
}

} // namespace ros2_medkit_fault_manager
9 changes: 5 additions & 4 deletions src/ros2_medkit_fault_manager/src/fault_manager_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

#include "ros2_medkit_fault_manager/correlation/config_parser.hpp"
#include "ros2_medkit_fault_manager/sqlite_fault_storage.hpp"
#include "ros2_medkit_fault_manager/time_utils.hpp"
#include "ros2_medkit_msgs/msg/cluster_info.hpp"
#include "ros2_medkit_msgs/msg/muted_fault_info.hpp"

Expand Down Expand Up @@ -172,7 +173,7 @@ FaultManagerNode::FaultManagerNode(const rclcpp::NodeOptions & options) : Node("
// Create auto-confirmation timer if enabled
if (auto_confirm_after_sec_ > 0.0) {
auto_confirm_timer_ = create_wall_timer(std::chrono::seconds(1), [this]() {
size_t confirmed = storage_->check_time_based_confirmation(now());
size_t confirmed = storage_->check_time_based_confirmation(get_wall_clock_time());
if (confirmed > 0) {
RCLCPP_INFO(get_logger(), "Auto-confirmed %zu PREFAILED fault(s) due to time threshold", confirmed);
}
Expand Down Expand Up @@ -258,9 +259,9 @@ void FaultManagerNode::handle_report_fault(
auto fault_before = storage_->get_fault(request->fault_code);
std::string status_before = fault_before ? fault_before->status : "";

// Report the fault event
// Report the fault event (use wall clock time, not sim time, for proper timestamps)
bool is_new = storage_->report_fault_event(request->fault_code, request->event_type, request->severity,
request->description, request->source_id, now());
request->description, request->source_id, get_wall_clock_time());

response->accepted = true;

Expand Down Expand Up @@ -471,7 +472,7 @@ void FaultManagerNode::publish_fault_event(const std::string & event_type, const
ros2_medkit_msgs::msg::FaultEvent event;
event.event_type = event_type;
event.fault = fault;
event.timestamp = now();
event.timestamp = get_wall_clock_time();
event.auto_cleared_codes = auto_cleared_codes;

event_publisher_->publish(event);
Expand Down
13 changes: 8 additions & 5 deletions src/ros2_medkit_fault_manager/src/rosbag_capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,14 @@
#include <unistd.h>

#include <algorithm>
#include <chrono>
#include <filesystem>
#include <rosbag2_cpp/writer.hpp>
#include <rosbag2_storage/storage_options.hpp>
#include <set>
#include <sstream>

#include "ros2_medkit_fault_manager/time_utils.hpp"

namespace ros2_medkit_fault_manager {

namespace {
Expand Down Expand Up @@ -213,7 +214,7 @@ void RosbagCapture::on_fault_confirmed(const std::string & fault_code) {
info.format = config_.format;
info.duration_sec = config_.duration_sec;
info.size_bytes = bag_size;
info.created_at_ns = node_->now().nanoseconds();
info.created_at_ns = get_wall_clock_ns();

storage_->store_rosbag_file(info);
enforce_storage_limits();
Expand Down Expand Up @@ -336,7 +337,8 @@ void RosbagCapture::message_callback(const std::string & topic, const std::strin
return;
}

int64_t timestamp_ns = node_->now().nanoseconds();
// Use wall clock time, not sim time, for proper timestamps
int64_t timestamp_ns = get_wall_clock_ns();

// During post-fault recording, write directly to bag (no buffering)
if (recording_post_fault_.load()) {
Expand Down Expand Up @@ -394,7 +396,8 @@ void RosbagCapture::prune_buffer() {
return;
}

int64_t now_ns = node_->now().nanoseconds();
// Use wall clock time, not sim time, for consistent buffer pruning
int64_t now_ns = get_wall_clock_ns();
int64_t duration_ns = static_cast<int64_t>(config_.duration_sec * 1e9);
int64_t cutoff_ns = now_ns - duration_ns;

Expand Down Expand Up @@ -651,7 +654,7 @@ void RosbagCapture::post_fault_timer_callback() {
info.format = config_.format;
info.duration_sec = config_.duration_sec + config_.duration_after_sec;
info.size_bytes = bag_size;
info.created_at_ns = node_->now().nanoseconds();
info.created_at_ns = get_wall_clock_ns();

storage_->store_rosbag_file(info);
enforce_storage_limits();
Expand Down
9 changes: 5 additions & 4 deletions src/ros2_medkit_fault_manager/src/snapshot_capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,14 @@

#include "ros2_medkit_fault_manager/snapshot_capture.hpp"

#include <chrono>
#include <set>
#include <thread>

#include <rclcpp/generic_subscription.hpp>
#include <rclcpp/serialization.hpp>
#include <rclcpp/serialized_message.hpp>

#include "ros2_medkit_fault_manager/time_utils.hpp"
#include "ros2_medkit_serialization/json_serializer.hpp"
#include "ros2_medkit_serialization/serialization_error.hpp"

Expand Down Expand Up @@ -213,13 +213,13 @@ bool SnapshotCapture::capture_topic_on_demand(const std::string & fault_code, co
ros2_medkit_serialization::JsonSerializer serializer;
auto json_data = serializer.deserialize(msg_type, captured_msg);

// Store snapshot
// Store snapshot (use wall clock time, not sim time, for proper timestamps)
SnapshotData snapshot;
snapshot.fault_code = fault_code;
snapshot.topic = topic;
snapshot.message_type = msg_type;
snapshot.data = json_data.dump();
snapshot.captured_at_ns = node_->now().nanoseconds();
snapshot.captured_at_ns = get_wall_clock_ns();

storage_->store_snapshot(snapshot);

Expand Down Expand Up @@ -299,7 +299,8 @@ void SnapshotCapture::init_background_subscriptions() {
cached.topic = topic;
cached.message_type = msg_type;
cached.data = json_data.dump();
cached.timestamp_ns = node_->now().nanoseconds();
// Use wall clock time, not sim time, for proper timestamps
cached.timestamp_ns = get_wall_clock_ns();

} catch (const std::exception & e) {
RCLCPP_DEBUG(node_->get_logger(), "Failed to cache message from '%s': %s", topic.c_str(), e.what());
Expand Down
28 changes: 28 additions & 0 deletions src/ros2_medkit_fault_manager/test/test_fault_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -859,6 +859,34 @@ TEST_F(FaultEventPublishingTest, EventContainsFullFaultData) {
EXPECT_EQ(fault.reporting_sources[0], "/sensor/temperature");
}

TEST_F(FaultEventPublishingTest, TimestampUsesWallClockNotSimTime) {
// Get current wall clock time
auto wall_before = std::chrono::system_clock::now();
auto wall_before_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(wall_before.time_since_epoch()).count();

ASSERT_TRUE(call_report_fault("WALL_CLOCK_TEST", Fault::SEVERITY_WARN, "/test_node"));
spin_for(std::chrono::milliseconds(100));

auto wall_after = std::chrono::system_clock::now();
auto wall_after_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(wall_after.time_since_epoch()).count();

ASSERT_EQ(received_events_.size(), 1u);

// Convert event timestamp to nanoseconds
rclcpp::Time event_time(received_events_[0].timestamp);
int64_t event_ns = event_time.nanoseconds();

// Verify timestamp is close to wall clock time (within 5 seconds to be safe)
// This catches the bug where sim time (e.g., 148 seconds) would be far from wall clock
EXPECT_GE(event_ns, wall_before_ns - 5'000'000'000LL);
EXPECT_LE(event_ns, wall_after_ns + 5'000'000'000LL);

// Also verify it's a reasonable Unix timestamp (after year 2020)
// This catches the "1970" bug from the issue
constexpr int64_t YEAR_2020_NS = 1577836800LL * 1'000'000'000LL; // 2020-01-01 00:00:00 UTC
EXPECT_GT(event_ns, YEAR_2020_NS);
}

int main(int argc, char ** argv) {
rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);
Expand Down