Class RosbagCapture
Defined in File rosbag_capture.hpp
Class Documentation
-
class RosbagCapture
Manages rosbag recording with ring buffer for time-window capture
This class implements a “black box” style recording where messages are continuously buffered in memory. When a fault is confirmed, the buffer is flushed to a bag file along with continued recording for a short period after the fault.
Lifecycle:
start() begins buffering messages (or lazy_start waits for PREFAILED)
on_fault_confirmed() flushes buffer to bag file
on_fault_cleared() deletes bag file if auto_cleanup enabled
Public Functions
-
RosbagCapture(rclcpp::Node *node, FaultStorage *storage, const RosbagConfig &config, const SnapshotConfig &snapshot_config)
Create rosbag capture
- Parameters:
node – ROS 2 node for creating subscriptions and timers
storage – Fault storage for persisting bag file metadata
config – Rosbag configuration
snapshot_config – Snapshot configuration (for topic resolution when topics=”config”)
-
~RosbagCapture()
-
RosbagCapture(const RosbagCapture&) = delete
-
RosbagCapture &operator=(const RosbagCapture&) = delete
-
RosbagCapture(RosbagCapture&&) = delete
-
RosbagCapture &operator=(RosbagCapture&&) = delete
-
void start()
Start the ring buffer recording If lazy_start is false, this is called automatically on construction
-
void stop()
Stop recording and clean up subscriptions.
-
bool is_running() const
Check if ring buffer is currently running.
-
void on_fault_prefailed(const std::string &fault_code)
Called when a fault enters PREFAILED state (for lazy_start mode)
- Parameters:
fault_code – The fault code that entered PREFAILED
-
void on_fault_confirmed(const std::string &fault_code)
Called when a fault is confirmed - flushes buffer to bag file
- Parameters:
fault_code – The fault code that was confirmed
-
void on_fault_cleared(const std::string &fault_code)
Called when a fault is cleared - deletes bag file if auto_cleanup
- Parameters:
fault_code – The fault code that was cleared
-
inline const RosbagConfig &config() const
Get current configuration.
-
inline bool is_enabled() const
Check if rosbag capture is enabled.