Skip to content

Commit

Permalink
improve and refactor locking mechanism
Browse files Browse the repository at this point in the history
Signed-off-by: M. Fatih Cırıt <[email protected]>
  • Loading branch information
M. Fatih Cırıt committed May 17, 2024
1 parent ad99c35 commit 6886a53
Showing 1 changed file with 32 additions and 17 deletions.
49 changes: 32 additions & 17 deletions common/autoware_control_center/src/control_center_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,63 +17,77 @@
#include <rclcpp/rclcpp.hpp>

#include <fcntl.h>
#include <sys/file.h>
#include <unistd.h>

#include <algorithm>
#include <memory>
#include <string>

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());
Expand All @@ -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;
Expand Down

0 comments on commit 6886a53

Please sign in to comment.