From 2cb2d57c2eb7a5c7abd2e508dd7a52780825b3d6 Mon Sep 17 00:00:00 2001 From: Liangwei XU Date: Mon, 2 Feb 2026 11:36:40 +0800 Subject: [PATCH 1/6] feat(recorder): add simple mode for direct recording without HTTP RPC --- apps/axon_recorder/axon_recorder.cpp | 163 ++++++++++++------ .../config/default_config_ros2.yaml | 31 ++-- apps/axon_recorder/recorder.cpp | 8 +- 3 files changed, 135 insertions(+), 67 deletions(-) diff --git a/apps/axon_recorder/axon_recorder.cpp b/apps/axon_recorder/axon_recorder.cpp index 981c6ed..44b8fb3 100644 --- a/apps/axon_recorder/axon_recorder.cpp +++ b/apps/axon_recorder/axon_recorder.cpp @@ -2,11 +2,14 @@ // // SPDX-License-Identifier: MulanPSL-2.0 +#include #include #include #include #include +#include #include +#include #include #include "config_parser.hpp" @@ -47,12 +50,11 @@ void print_usage(const char* program_name) { << "Version: " << axon::recorder::get_version() << "\n" << "\n" << "Options:\n" + << " --simple Simple mode: start recording immediately without HTTP RPC\n" + << " --output FILE Output file path (default: auto-generated timestamp)\n" << " --config PATH Path to YAML configuration file\n" << " --plugin PATH Path to ROS plugin shared library (.so)\n" << " --path PATH Output directory path (default: .)\n" - << " --topic NAME Subscribe to topic (can be used multiple times)\n" - << " --type TYPE Message type for last --topic (e.g., " - "sensor_msgs/msg/Image)\n" << " --profile PROFILE ROS profile: ros1 or ros2 (default: ros2)\n" << " --compression ALG Compression: none, zstd, lz4 (default: zstd)\n" << " --level LEVEL Compression level (default: 3)\n" @@ -60,8 +62,17 @@ void print_usage(const char* program_name) { << " --version Show version information\n" << " --help Show this help message\n" << "\n" + << "Simple Mode:\n" + << " When --simple is specified, the recorder starts immediately without waiting for\n" + << " HTTP RPC commands. The output filename is either:\n" + << " - Specified via --output FILE\n" + << " - Auto-generated as YYYYMMDD_HHMMSS.mcap (e.g., 20240102_143000.mcap)\n" + << "\n" + << " In simple mode, topics must be configured either via config file subscriptions\n" + << " or CLI parameters. No HTTP RPC server is started.\n" + << "\n" << "HTTP RPC Server:\n" - << " The recorder starts an HTTP RPC server on port 8080 for remote control.\n" + << " Without --simple, the recorder starts an HTTP RPC server on port 8080 for remote control.\n" << " The recorder starts in IDLE state and waits for RPC commands.\n" << " Available endpoints:\n" << " POST /rpc/config - Set task configuration (IDLE->READY)\n" @@ -95,25 +106,26 @@ void print_usage(const char* program_name) { << " compression_level: 3\n" << "\n" << "Output File Naming:\n" - << " When using HTTP RPC mode, output files are named as: /.mcap\n" - << " The task_id is provided via the /rpc/config endpoint.\n" + << " Simple mode (--simple):\n" + << " - --output my_recording.mcap -> Use specified filename\n" + << " - No --output -> Auto-generated: YYYYMMDD_HHMMSS.mcap\n" + << " HTTP RPC mode:\n" + << " Output files are named as: /.mcap\n" + << " The task_id is provided via the /rpc/config endpoint.\n" << "\n" << "Examples:\n" + << " # Simple mode with auto-generated filename\n" + << " " << program_name << " --simple --plugin ./ros2_plugin.so --config config/default_config_ros2.yaml\n" + << "\n" + << " # Simple mode with custom filename\n" + << " " << program_name << " --simple --output /data/my_recording.mcap --plugin ./ros2_plugin.so\n" + << "\n" << " # Use config file only\n" << " " << program_name << " --config config/default_config_ros2.yaml\n" << "\n" << " # Override plugin path from config file\n" << " " << program_name << " --config config/default_config_ros2.yaml \\\n" << " --plugin /custom/path/to/libaxon_ros2_plugin.so\n" - << "\n" - << " # Override output directory and compression level\n" - << " " << program_name << " --config config/default_config_ros2.yaml \\\n" - << " --path /tmp/recordings --level 5\n" - << "\n" - << " # CLI only (no config file)\n" - << " " << program_name << " --plugin ./ros2_plugin.so \\\n" - << " --path /data/recordings \\\n" - << " --topic /camera/image_raw --type sensor_msgs/msg/Image\n" << std::endl; } @@ -126,6 +138,19 @@ void print_statistics(const AxonRecorder::Statistics& stats) { << std::endl; } +/** + * Generate timestamp-based filename + * Format: YYYYMMDD_HHMMSS.mcap (e.g., 20240102_143000.mcap) + */ +std::string generate_timestamp_filename() { + auto now = std::chrono::system_clock::now(); + auto time_t_now = std::chrono::system_clock::to_time_t(now); + + std::stringstream ss; + ss << std::put_time(std::localtime(&time_t_now), "%Y%m%d_%H%M%S"); + return ss.str() + ".mcap"; +} + } // namespace } // namespace recorder @@ -151,13 +176,22 @@ int main(int argc, char* argv[]) { std::string cli_dataset_path; std::string cli_profile; std::string cli_compression; + std::string cli_output_file; int cli_compression_level = -1; size_t cli_queue_capacity = 0; - std::vector cli_subscriptions; - std::string current_topic; + bool simple_mode = false; for (int i = 1; i < argc; ++i) { - if (strcmp(argv[i], "--config") == 0) { + if (strcmp(argv[i], "--simple") == 0) { + simple_mode = true; + } else if (strcmp(argv[i], "--output") == 0) { + if (i + 1 < argc) { + cli_output_file = argv[++i]; + } else { + std::cerr << "Error: --output requires a file argument" << std::endl; + return 1; + } + } else if (strcmp(argv[i], "--config") == 0) { if (i + 1 < argc) { config_file = argv[++i]; } else { @@ -178,26 +212,6 @@ int main(int argc, char* argv[]) { std::cerr << "Error: --path requires a directory argument" << std::endl; return 1; } - } else if (strcmp(argv[i], "--topic") == 0) { - if (i + 1 < argc) { - current_topic = argv[++i]; - } else { - std::cerr << "Error: --topic requires a name argument" << std::endl; - return 1; - } - } else if (strcmp(argv[i], "--type") == 0) { - if (i + 1 < argc) { - if (current_topic.empty()) { - std::cerr << "Error: --type must follow --topic" << std::endl; - return 1; - } - std::string message_type = argv[++i]; - cli_subscriptions.push_back({current_topic, message_type}); - current_topic.clear(); - } else { - std::cerr << "Error: --type requires a type argument" << std::endl; - return 1; - } } else if (strcmp(argv[i], "--profile") == 0) { if (i + 1 < argc) { cli_profile = argv[++i]; @@ -263,8 +277,16 @@ int main(int argc, char* argv[]) { if (cli_queue_capacity > 0) { config.queue_capacity = cli_queue_capacity; } - if (!cli_subscriptions.empty()) { - config.subscriptions = cli_subscriptions; + + // Handle output filename in simple mode + if (simple_mode) { + if (!cli_output_file.empty()) { + // User specified output file + config.output_file = cli_output_file; + } else { + // Auto-generate timestamp-based filename + config.output_file = generate_timestamp_filename(); + } } // Validate required arguments @@ -274,23 +296,25 @@ int main(int argc, char* argv[]) { return 1; } - if (config.subscriptions.empty()) { - std::cerr << "Error: At least one --topic/--type pair is required" << std::endl; - print_usage(argv[0]); - return 1; - } - // Print configuration std::cout << "Axon Recorder Configuration:\n" + << " Mode: " << (simple_mode ? "Simple (direct recording)" : "HTTP RPC") << "\n" << " Plugin: " << config.plugin_path << "\n" + << " Output: " << config.output_file << "\n" << " Dataset: " << config.dataset.path << "\n" << " Profile: " << config.profile << "\n" << " Compression: " << config.compression << " level " << config.compression_level << "\n" - << " Queue size: " << config.queue_capacity << "\n" - << " Topics:\n"; - for (const auto& sub : config.subscriptions) { - std::cout << " - " << sub.topic_name << " (" << sub.message_type << ")\n"; + << " Queue size: " << config.queue_capacity << "\n"; + + // Show topics if configured + if (!config.subscriptions.empty()) { + std::cout << " Topics:\n"; + for (const auto& sub : config.subscriptions) { + std::cout << " - " << sub.topic_name << " (" << sub.message_type << ")\n"; + } + } else { + std::cout << " Topics: (no subscriptions configured)" << std::endl; } std::cout << std::endl; @@ -307,6 +331,45 @@ int main(int argc, char* argv[]) { return 1; } + if (simple_mode) { + // Simple mode: start recording immediately without HTTP RPC + std::cout << "Starting recording in simple mode..." << std::endl; + + if (!recorder.start()) { + std::cerr << "Error: Failed to start recording: " << recorder.get_last_error() << std::endl; + return 1; + } + + std::cout << "Recording started. Press Ctrl+C to stop." << std::endl; + + // Wait for quit signal + while (!g_should_exit.load()) { + std::this_thread::sleep_for(std::chrono::seconds(1)); + + // Print statistics if recording is active + if (recorder.is_running()) { + auto stats = recorder.get_statistics(); + if (stats.messages_written > 0) { + std::cout << "\rMessages: " << stats.messages_written << " written, " + << stats.messages_received << " received, " << stats.messages_dropped + << " dropped " << std::flush; + } + } + } + + std::cout << "\nStopping recording..." << std::endl; + + // Stop recording + recorder.stop(); + + // Print final statistics + auto final_stats = recorder.get_statistics(); + print_statistics(final_stats); + + return 0; + } + + // HTTP RPC mode: start HTTP server and wait for commands // Start HTTP RPC server std::cout << "Starting HTTP RPC server on " << config.http_server.host << ":" << config.http_server.port << "..." << std::endl; diff --git a/apps/axon_recorder/config/default_config_ros2.yaml b/apps/axon_recorder/config/default_config_ros2.yaml index fd14fa8..02ed38e 100644 --- a/apps/axon_recorder/config/default_config_ros2.yaml +++ b/apps/axon_recorder/config/default_config_ros2.yaml @@ -22,10 +22,11 @@ plugin: # ============================================================================ dataset: # Output directory for MCAP files - # When using HTTP RPC mode, output files are named as: /.mcap - # The task_id is provided via the /rpc/config endpoint path: /data/recordings + # Output filename (optional, defaults to /recording.mcap) + output_file: recording.mcap + # Per-topic queue capacity (number of messages) # Recommended: 4096-8192 for high-frequency topics (camera, IMU) # 1024-2048 for low-frequency topics (status, diagnostics) @@ -40,40 +41,40 @@ dataset: subscriptions: # IMU data - high frequency (5 seconds of data per batch) - name: /imu/data - message_type: sensor_msgs/Imu + message_type: sensor_msgs/msg/Imu batch_size: 5000 flush_interval_ms: 5000 # Camera 0 - RGB and Depth (10 seconds of data per batch at 30fps) - - name: /camera/cam_hand_left/image - message_type: sensor_msgs/CompressedImage + - name: /camera0/rgb + message_type: sensor_msgs/msg/Image batch_size: 300 flush_interval_ms: 10000 - - name: /camera/cam_hand_right/image - message_type: sensor_msgs/CompressedImage + - name: /camera0/depth + message_type: sensor_msgs/msg/Image batch_size: 300 flush_interval_ms: 10000 # Camera 1 - RGB and Depth - - name: /camera/cam_top_head/image - message_type: sensor_msgs/CompressedImage + - name: /camera1/rgb + message_type: sensor_msgs/msg/Image batch_size: 300 flush_interval_ms: 10000 - - name: /io_teleop/joint_cmd - message_type: sensor_msgs/JointState + - name: /camera1/depth + message_type: sensor_msgs/msg/Image batch_size: 300 flush_interval_ms: 10000 # Camera 2 - RGB and Depth - - name: /io_teleop/joint_states - message_type: sensor_msgs/JointState + - name: /camera2/rgb + message_type: sensor_msgs/msg/Image batch_size: 300 flush_interval_ms: 10000 - - name: /io_teleop/robot_info - message_type: std_msgs/String + - name: /camera2/depth + message_type: sensor_msgs/msg/Image batch_size: 300 flush_interval_ms: 10000 diff --git a/apps/axon_recorder/recorder.cpp b/apps/axon_recorder/recorder.cpp index 4bac221..db356db 100644 --- a/apps/axon_recorder/recorder.cpp +++ b/apps/axon_recorder/recorder.cpp @@ -125,7 +125,11 @@ bool AxonRecorder::start() { // Construct output file path: dataset.path/task_id.mcap std::string output_file; - if (!config_.dataset.path.empty()) { + + // If user specified a custom output file (via --output in simple mode), use it + if (!config_.output_file.empty() && config_.output_file != "output.mcap") { + output_file = config_.output_file; + } else if (!config_.dataset.path.empty()) { // Ensure path ends with / std::string path = config_.dataset.path; if (!path.empty() && path.back() != '/') { @@ -142,7 +146,7 @@ bool AxonRecorder::start() { output_file = path + filename; } else { - // Fallback to legacy output_file if dataset.path is not configured + // Fallback to default output_file output_file = config_.output_file; } From 3dbb0bd1167d8130277e5d41ccbf4f70c2e6a5ad Mon Sep 17 00:00:00 2001 From: Liangwei XU Date: Mon, 2 Feb 2026 11:52:14 +0800 Subject: [PATCH 2/6] fix(doc): update readme file --- README.md | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index 0223a7c..1cfdf6b 100644 --- a/README.md +++ b/README.md @@ -227,20 +227,17 @@ http_server: # Display version ./build/axon_recorder/axon_recorder --version -# Run with default configuration +# Run with default configuration (HTTP RPC mode) ./build/axon_recorder/axon_recorder # Run with custom configuration ./build/axon_recorder/axon_recorder --config /path/to/config.yaml -# Run with plugin -./build/axon_recorder/axon_recorder --plugin /path/to/libaxon_ros2.so +# Simple mode: start recording immediately without HTTP RPC +./build/axon_recorder/axon_recorder --simple --config /path/to/config.yaml -# Specify output directory -./build/axon_recorder/axon_recorder --path /data/recordings - -# Subscribe to specific topics -./build/axon_recorder/axon_recorder --topic /camera/image --type sensor_msgs/msg/Image +# Simple mode: custom output file +./build/axon_recorder/axon_recorder --simple --output /tmp/recording.mcap --config /path/to/config.yaml ``` ### HTTP RPC API From 8bcfaefae02bf25beef6a4f5391d4f9675efc1d5 Mon Sep 17 00:00:00 2001 From: Liangwei XU Date: Mon, 2 Feb 2026 11:54:45 +0800 Subject: [PATCH 3/6] fix(format): format code format --- apps/axon_recorder/axon_recorder.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/apps/axon_recorder/axon_recorder.cpp b/apps/axon_recorder/axon_recorder.cpp index 44b8fb3..cb94ee9 100644 --- a/apps/axon_recorder/axon_recorder.cpp +++ b/apps/axon_recorder/axon_recorder.cpp @@ -72,7 +72,8 @@ void print_usage(const char* program_name) { << " or CLI parameters. No HTTP RPC server is started.\n" << "\n" << "HTTP RPC Server:\n" - << " Without --simple, the recorder starts an HTTP RPC server on port 8080 for remote control.\n" + << " Without --simple, the recorder starts an HTTP RPC server on port 8080 for remote " + "control.\n" << " The recorder starts in IDLE state and waits for RPC commands.\n" << " Available endpoints:\n" << " POST /rpc/config - Set task configuration (IDLE->READY)\n" @@ -115,10 +116,12 @@ void print_usage(const char* program_name) { << "\n" << "Examples:\n" << " # Simple mode with auto-generated filename\n" - << " " << program_name << " --simple --plugin ./ros2_plugin.so --config config/default_config_ros2.yaml\n" + << " " << program_name + << " --simple --plugin ./ros2_plugin.so --config config/default_config_ros2.yaml\n" << "\n" << " # Simple mode with custom filename\n" - << " " << program_name << " --simple --output /data/my_recording.mcap --plugin ./ros2_plugin.so\n" + << " " << program_name + << " --simple --output /data/my_recording.mcap --plugin ./ros2_plugin.so\n" << "\n" << " # Use config file only\n" << " " << program_name << " --config config/default_config_ros2.yaml\n" From 4dc71283b81a8ef96d0a0a0b522b19fc02638018 Mon Sep 17 00:00:00 2001 From: Liangwei XU Date: Mon, 2 Feb 2026 12:27:34 +0800 Subject: [PATCH 4/6] fix(recorder): use thread-safe localtime alternatives in timestamp generation --- apps/axon_recorder/axon_recorder.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/apps/axon_recorder/axon_recorder.cpp b/apps/axon_recorder/axon_recorder.cpp index cb94ee9..8f5680f 100644 --- a/apps/axon_recorder/axon_recorder.cpp +++ b/apps/axon_recorder/axon_recorder.cpp @@ -149,8 +149,15 @@ std::string generate_timestamp_filename() { auto now = std::chrono::system_clock::now(); auto time_t_now = std::chrono::system_clock::to_time_t(now); + std::tm tm_buf; +#if defined(_WIN32) || defined(_WIN64) + localtime_s(&tm_buf, &time_t_now); +#else + localtime_r(&time_t_now, &tm_buf); +#endif + std::stringstream ss; - ss << std::put_time(std::localtime(&time_t_now), "%Y%m%d_%H%M%S"); + ss << std::put_time(&tm_buf, "%Y%m%d_%H%M%S"); return ss.str() + ".mcap"; } From 41801f0f630ef77a1af5f8aa469fad4c9242e9f9 Mon Sep 17 00:00:00 2001 From: Liangwei XU Date: Mon, 2 Feb 2026 12:33:44 +0800 Subject: [PATCH 5/6] feat(recorder): add output_file field to dataset configuration --- apps/axon_recorder/config_parser.cpp | 3 +++ apps/axon_recorder/recorder.hpp | 1 + 2 files changed, 4 insertions(+) diff --git a/apps/axon_recorder/config_parser.cpp b/apps/axon_recorder/config_parser.cpp index 28d087a..52d0d46 100644 --- a/apps/axon_recorder/config_parser.cpp +++ b/apps/axon_recorder/config_parser.cpp @@ -121,6 +121,9 @@ bool ConfigParser::parse_dataset(const YAML::Node& node, DatasetConfig& dataset) if (node["path"]) { dataset.path = node["path"].as(); } + if (node["output_file"]) { + dataset.output_file = node["output_file"].as(); + } if (node["mode"]) { dataset.mode = node["mode"].as(); } diff --git a/apps/axon_recorder/recorder.hpp b/apps/axon_recorder/recorder.hpp index 99bdaca..58bac99 100644 --- a/apps/axon_recorder/recorder.hpp +++ b/apps/axon_recorder/recorder.hpp @@ -70,6 +70,7 @@ struct SubscriptionConfig { */ struct DatasetConfig { std::string path; + std::string output_file = "output.mcap"; // Output filename std::string mode = "append"; // "create" or "append" std::string stats_file_path = "/data/recordings/recorder_stats.json"; // Stats output file }; From fc9eebf8d35c739812b71c13204dec116e56b89b Mon Sep 17 00:00:00 2001 From: Liangwei XU Date: Mon, 2 Feb 2026 12:42:26 +0800 Subject: [PATCH 6/6] refactor(recorder): use explicit flag instead of magic string comparison --- apps/axon_recorder/axon_recorder.cpp | 2 ++ apps/axon_recorder/config_parser.cpp | 8 +++++--- apps/axon_recorder/recorder.cpp | 4 ++-- apps/axon_recorder/recorder.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) diff --git a/apps/axon_recorder/axon_recorder.cpp b/apps/axon_recorder/axon_recorder.cpp index 8f5680f..c36ad88 100644 --- a/apps/axon_recorder/axon_recorder.cpp +++ b/apps/axon_recorder/axon_recorder.cpp @@ -293,9 +293,11 @@ int main(int argc, char* argv[]) { if (!cli_output_file.empty()) { // User specified output file config.output_file = cli_output_file; + config.output_file_is_explicit = true; } else { // Auto-generate timestamp-based filename config.output_file = generate_timestamp_filename(); + config.output_file_is_explicit = true; } } diff --git a/apps/axon_recorder/config_parser.cpp b/apps/axon_recorder/config_parser.cpp index 52d0d46..5c6e510 100644 --- a/apps/axon_recorder/config_parser.cpp +++ b/apps/axon_recorder/config_parser.cpp @@ -51,6 +51,11 @@ bool ConfigParser::load_from_string(const std::string& yaml_content, RecorderCon // Parse dataset config if (node["dataset"]) { parse_dataset(node["dataset"], config.dataset); + // Copy dataset.output_file to config.output_file for backward compatibility + if (node["dataset"]["output_file"]) { + config.output_file = node["dataset"]["output_file"].as(); + config.output_file_is_explicit = true; + } } // Parse subscriptions @@ -121,9 +126,6 @@ bool ConfigParser::parse_dataset(const YAML::Node& node, DatasetConfig& dataset) if (node["path"]) { dataset.path = node["path"].as(); } - if (node["output_file"]) { - dataset.output_file = node["output_file"].as(); - } if (node["mode"]) { dataset.mode = node["mode"].as(); } diff --git a/apps/axon_recorder/recorder.cpp b/apps/axon_recorder/recorder.cpp index db356db..43609ca 100644 --- a/apps/axon_recorder/recorder.cpp +++ b/apps/axon_recorder/recorder.cpp @@ -126,8 +126,8 @@ bool AxonRecorder::start() { // Construct output file path: dataset.path/task_id.mcap std::string output_file; - // If user specified a custom output file (via --output in simple mode), use it - if (!config_.output_file.empty() && config_.output_file != "output.mcap") { + // If user specified a custom output file (via --output or config file), use it + if (config_.output_file_is_explicit) { output_file = config_.output_file; } else if (!config_.dataset.path.empty()) { // Ensure path ends with / diff --git a/apps/axon_recorder/recorder.hpp b/apps/axon_recorder/recorder.hpp index 58bac99..980d2b9 100644 --- a/apps/axon_recorder/recorder.hpp +++ b/apps/axon_recorder/recorder.hpp @@ -70,7 +70,6 @@ struct SubscriptionConfig { */ struct DatasetConfig { std::string path; - std::string output_file = "output.mcap"; // Output filename std::string mode = "append"; // "create" or "append" std::string stats_file_path = "/data/recordings/recorder_stats.json"; // Stats output file }; @@ -154,6 +153,7 @@ struct HttpServerConfig { struct RecorderConfig { // Basic recorder settings std::string output_file = "output.mcap"; + bool output_file_is_explicit = false; // True if set via CLI or config file std::string plugin_path; std::vector subscriptions;