From 6886a539b1063a304e35b65dbda977933d206d2d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 17 May 2024 19:26:44 +0300 Subject: [PATCH] improve and refactor locking mechanism MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../src/control_center_main.cpp | 49 ++++++++++++------- 1 file changed, 32 insertions(+), 17 deletions(-) diff --git a/common/autoware_control_center/src/control_center_main.cpp b/common/autoware_control_center/src/control_center_main.cpp index 7eb809c2d8..244b0986aa 100644 --- a/common/autoware_control_center/src/control_center_main.cpp +++ b/common/autoware_control_center/src/control_center_main.cpp @@ -17,63 +17,77 @@ #include #include -#include #include +#include #include +#include const char * lock_file_path = "/tmp/autoware_control_center_node.lock"; -bool lock_file() +int open_lock_file() { + // Open or create the lock file with read/write permissions int fd = open(lock_file_path, O_CREAT | O_RDWR, 0666); + + // Check if the file descriptor is valid if (fd == -1) { RCLCPP_FATAL(rclcpp::get_logger(""), "Failed to open lock file"); - return false; } + return fd; +} - if (flock(fd, LOCK_EX | LOCK_NB) == -1) { +bool lock_file(int fd) +{ + struct flock fl = {F_WRLCK, SEEK_SET, 0, 0, 0}; + // F_WRLCK: Write lock + // SEEK_SET: Base the lock offset from the beginning of the file + // 0, 0: Lock the entire file (start offset, length) + + // Attempt to set the file lock using fcntl + if (fcntl(fd, F_SETLK, &fl) == -1) { + // Check if the file is already locked by another process if (errno == EWOULDBLOCK) { RCLCPP_FATAL(rclcpp::get_logger(""), "Another instance is already running"); } else { + // Handle other locking errors RCLCPP_FATAL(rclcpp::get_logger(""), "Failed to lock file"); } + // Close the file descriptor on failure close(fd); return false; } - - // Keep the file descriptor open to maintain the lock return true; } void unlock_file(int fd) { + // Ensure the file descriptor is valid before closing if (fd != -1) { - flock(fd, LOCK_UN); close(fd); } } +bool node_already_exists(const std::string & node_name) +{ + auto temp_node = rclcpp::Node::make_shared("temp_node"); + auto all_nodes = temp_node->get_node_names(); + return std::find(all_nodes.begin(), all_nodes.end(), node_name) != all_nodes.end(); +} + int main(int argc, char * argv[]) { rclcpp::init(argc, argv); // Lock file to prevent multiple instances on the same machine - int lock_fd = open(lock_file_path, O_CREAT | O_RDWR, 0666); - if (!lock_file()) { + int lock_fd = open_lock_file(); + if (lock_fd == -1 || !lock_file(lock_fd)) { return 1; } // Check if node already exists to prevent multiple instances across the network // It's a bit slow but better than nothing - const auto node_name_with_namespace = std::string("/autoware/control_center"); - - auto node_already_exists = [](const std::string & node_name) { - auto temp_node = rclcpp::Node::make_shared("temp_node"); - auto all_nodes = temp_node->get_node_names(); - return std::find(all_nodes.begin(), all_nodes.end(), node_name) != all_nodes.end(); - }; - + const std::string node_name_with_namespace = "/autoware/control_center"; if (node_already_exists(node_name_with_namespace)) { RCLCPP_FATAL( rclcpp::get_logger(""), "Node %s already exists", node_name_with_namespace.c_str()); @@ -87,6 +101,7 @@ int main(int argc, char * argv[]) rclcpp::executors::MultiThreadedExecutor exec; exec.add_node(control_center->get_node_base_interface()); exec.spin(); + unlock_file(lock_fd); rclcpp::shutdown(); return 0;