/
/
/
1#include <rclcpp/rclcpp.hpp>
2#include <memory>
3#include <signal.h>
4
5#include "bag_recorder_backend/bag_recorder_node.hpp"
6#include "bag_recorder_backend/crow_server.hpp"
7
8// Global variables for signal handling
9std::shared_ptr<bag_recorder_backend::BagRecorderNode> g_recorder_node;
10std::shared_ptr<bag_recorder_backend::CrowServer> g_crow_server;
11
12void signal_handler(int signum)
13{
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{
29 // Initialize ROS2
30 rclcpp::init(argc, argv);
31
32 // Set up signal handlers for graceful shutdown
33 signal(SIGINT, signal_handler);
34 signal(SIGTERM, signal_handler);
35
36 try {
37 // Create recorder node
38 g_recorder_node = std::make_shared<bag_recorder_backend::BagRecorderNode>();
39
40 // Get server configuration from parameters
41 int server_port = g_recorder_node->declare_parameter("server_port", 8080);
42 std::string cert_file = g_recorder_node->declare_parameter("ssl_cert_file", "");
43 std::string key_file = g_recorder_node->declare_parameter("ssl_key_file", "");
44 bool enable_cors = g_recorder_node->declare_parameter("enable_cors", true);
45
46 // Create and configure Crow server
47 g_crow_server = std::make_shared<bag_recorder_backend::CrowServer>(g_recorder_node, server_port);
48
49 if (!cert_file.empty() && !key_file.empty()) {
50 g_crow_server->set_ssl_config(cert_file, key_file);
51 RCLCPP_INFO(g_recorder_node->get_logger(), "SSL enabled with cert: %s", cert_file.c_str());
52 }
53
54 g_crow_server->enable_cors(enable_cors);
55
56 // Start the web server in a separate thread
57 std::thread server_thread([&]() {
58 try {
59 g_crow_server->start();
60 } catch (const std::exception & e) {
61 RCLCPP_ERROR(g_recorder_node->get_logger(), "Server error: %s", e.what());
62 }
63 });
64
65 RCLCPP_INFO(g_recorder_node->get_logger(),
66 "Bag Recorder Backend started on port %d", server_port);
67
68 // Spin the ROS2 node
69 rclcpp::spin(g_recorder_node);
70
71 // Clean shutdown
72 if (g_crow_server) {
73 g_crow_server->stop();
74 }
75
76 if (server_thread.joinable()) {
77 server_thread.join();
78 }
79
80 } catch (const std::exception & e) {
81 RCLCPP_ERROR(rclcpp::get_logger("main"), "Fatal error: %s", e.what());
82 return 1;
83 }
84
85 RCLCPP_INFO(rclcpp::get_logger("main"), "Bag Recorder Backend shutdown complete");
86 return 0;
87}