/
/
/
1#include <signal.h>
2
3#include <memory>
4#include <rclcpp/rclcpp.hpp>
5
6#include "bag_recorder_backend/bag_recorder_node.hpp"
7#include "bag_recorder_backend/crow_server.hpp"
8
9// Global variables for signal handling
10std::shared_ptr<bag_recorder_backend::BagRecorderNode> g_recorder_node;
11std::shared_ptr<bag_recorder_backend::CrowServer> g_crow_server;
12
13void signal_handler(int signum) {
14 RCLCPP_INFO(rclcpp::get_logger("main"), "Received signal %d, shutting down gracefully...", signum);
15
16 if (g_crow_server) {
17 g_crow_server->stop();
18 }
19
20 if (g_recorder_node) {
21 g_recorder_node->stop_recording();
22 }
23
24 rclcpp::shutdown();
25}
26
27int main(int argc, char** argv) {
28 // Initialize ROS2
29 rclcpp::init(argc, argv);
30
31 // Set up signal handlers for graceful shutdown
32 signal(SIGINT, signal_handler);
33 signal(SIGTERM, signal_handler);
34
35 try {
36 // Create recorder node
37 g_recorder_node = std::make_shared<bag_recorder_backend::BagRecorderNode>();
38
39 // Get server configuration from parameters
40 int server_port = g_recorder_node->declare_parameter("server_port", 8080);
41 bool enable_cors = g_recorder_node->declare_parameter("enable_cors", true);
42
43 // Create and configure Crow server
44 g_crow_server = std::make_shared<bag_recorder_backend::CrowServer>(g_recorder_node, server_port);
45 g_crow_server->enable_cors(enable_cors);
46
47 // Start the web server in a separate thread
48 std::thread server_thread([&]() {
49 try {
50 g_crow_server->start();
51 } catch (const std::exception& e) {
52 RCLCPP_ERROR(g_recorder_node->get_logger(), "Server error: %s", e.what());
53 }
54 });
55
56 RCLCPP_INFO(g_recorder_node->get_logger(), "Bag Recorder Backend started on port %d", server_port);
57
58 // Spin the ROS2 node
59 rclcpp::spin(g_recorder_node);
60
61 // Clean shutdown
62 if (g_crow_server) {
63 g_crow_server->stop();
64 }
65
66 if (server_thread.joinable()) {
67 server_thread.join();
68 }
69
70 } catch (const std::exception& e) {
71 RCLCPP_ERROR(rclcpp::get_logger("main"), "Fatal error: %s", e.what());
72 return 1;
73 }
74
75 RCLCPP_INFO(rclcpp::get_logger("main"), "Bag Recorder Backend shutdown complete");
76 return 0;
77}
78