Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 4 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -253,12 +253,11 @@ After successful validation, the configurator will print the settings and then w
<img width="1292" height="366" alt="cie_image1" src="https://github.com/user-attachments/assets/537034e0-167d-40dd-83ad-72c6efba7af8" />

In this state, when you launch the target ROS 2 application, the configurator node will receive callback group information from the application.
The entries in the configurator window show the callback group ID and OS thread ID information received from the ROS 2 application, and all configured policies are applied immediately upon receipt.
The entries in the configurator window show the callback group ID and OS thread ID information received from the ROS 2 application, and all configured policies are applied immediately upon receipt, including `SCHED_DEADLINE` (which uses `SCHED_FLAG_RESET_ON_FORK` so that forked children reset to `SCHED_OTHER`).

While the target ROS 2 application is running, the configurator node's window should not be closed and must remain open.
If your configuration includes `SCHED_DEADLINE` threads with CPU affinity (configured via cgroup), after all configurations are applied the configurator will display `Press enter to exit and remove cgroups...`.
Press enter to terminate the configurator and clean up the cgroup directories.
If no cgroup-based affinity was used, the configurator exits automatically once all configurations have been applied (that is, after it receives the required thread information from the target application).
The configurator node keeps running after all configurations have been applied.
This allows it to re-apply configurations automatically when a target application restarts (the OS may reuse thread IDs, so thread ID equality cannot be used to skip reconfiguration).
If your configuration includes `SCHED_DEADLINE` threads with CPU affinity (configured via cgroup), the cgroup directories are cleaned up when the configurator node is terminated.

## Notes on Adoption

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@ class ThreadConfiguratorNode : public rclcpp::Node {
explicit ThreadConfiguratorNode(
const rclcpp::NodeOptions &options = rclcpp::NodeOptions());
~ThreadConfiguratorNode();
bool all_applied();
void print_all_unapplied();
bool has_configured_once() const;

bool has_cgroup() const;

Expand All @@ -48,6 +48,7 @@ class ThreadConfiguratorNode : public rclcpp::Node {
const cie_config_msgs::msg::CallbackGroupInfo::SharedPtr msg);
void non_ros_thread_callback(
const cie_config_msgs::msg::NonRosThreadInfo::SharedPtr msg);
void on_all_configured();

rclcpp::Subscription<cie_config_msgs::msg::CallbackGroupInfo>::SharedPtr
subscription_;
Expand All @@ -58,4 +59,5 @@ class ThreadConfiguratorNode : public rclcpp::Node {
std::unordered_map<std::string, ThreadConfig *> id_to_thread_config_;
int unapplied_num_;
int cgroup_num_;
bool configured_at_least_once_ = false;
};
48 changes: 38 additions & 10 deletions cie_thread_configurator/src/thread_configurator_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,8 +170,6 @@ ThreadConfiguratorNode::~ThreadConfiguratorNode() {
}
}

bool ThreadConfiguratorNode::all_applied() { return unapplied_num_ == 0; }

void ThreadConfiguratorNode::print_all_unapplied() {
RCLCPP_WARN(this->get_logger(), "Following threads are not yet configured");

Expand Down Expand Up @@ -325,11 +323,14 @@ void ThreadConfiguratorNode::callback_group_callback(

ThreadConfig *config = it->second;
if (config->applied) {
// Always re-apply: the OS may reuse the same thread IDs after an
// application restarts, so we cannot use thread_id equality to skip
// reconfiguration.
RCLCPP_INFO(
this->get_logger(),
"This callback group is already configured. skip (id=%s, tid=%ld)",
"Re-applying configuration for already configured callback group "
"(id=%s, tid=%ld)",
msg->callback_group_id.c_str(), msg->thread_id);
return;
}
Comment thread
atsushi421 marked this conversation as resolved.

RCLCPP_INFO(this->get_logger(), "Received CallbackGroupInfo: tid=%ld | %s",
Expand All @@ -344,8 +345,14 @@ void ThreadConfiguratorNode::callback_group_callback(
return;
}

if (!config->applied) {
unapplied_num_--;
}
config->applied = true;
unapplied_num_--;

if (unapplied_num_ == 0) {
on_all_configured();
}
Comment thread
atsushi421 marked this conversation as resolved.
Outdated
}

void ThreadConfiguratorNode::non_ros_thread_callback(
Expand All @@ -361,10 +368,14 @@ void ThreadConfiguratorNode::non_ros_thread_callback(

ThreadConfig *config = it->second;
if (config->applied) {
RCLCPP_INFO(this->get_logger(),
"This thread is already configured. skip (name=%s, tid=%ld)",
msg->thread_name.c_str(), msg->thread_id);
return;
// Always re-apply: the OS may reuse the same thread IDs after an
// application restarts, so we cannot use thread_id equality to skip
// reconfiguration.
RCLCPP_INFO(
this->get_logger(),
"Re-applying configuration for already configured non-ROS thread "
"(name=%s, tid=%ld)",
msg->thread_name.c_str(), msg->thread_id);
}

RCLCPP_INFO(this->get_logger(), "Received NonRosThreadInfo: tid=%ld | %s",
Expand All @@ -379,8 +390,25 @@ void ThreadConfiguratorNode::non_ros_thread_callback(
return;
}

if (!config->applied) {
unapplied_num_--;
}
config->applied = true;
unapplied_num_--;

if (unapplied_num_ == 0) {
on_all_configured();
}
}

void ThreadConfiguratorNode::on_all_configured() {
RCLCPP_INFO(this->get_logger(),
"Success: All of the configurations are applied.");

configured_at_least_once_ = true;
}

bool ThreadConfiguratorNode::has_configured_once() const {
return configured_at_least_once_;
}

bool ThreadConfiguratorNode::has_cgroup() const { return cgroup_num_ > 0; }
16 changes: 2 additions & 14 deletions cie_thread_configurator/src/thread_configurator_node_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,21 +15,9 @@ int main(int argc, char *argv[]) {
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

executor->add_node(node);
executor->spin();

while (rclcpp::ok() && !node->all_applied()) {
executor->spin_once();
}

if (node->all_applied()) {
RCLCPP_INFO(node->get_logger(),
"Success: All of the configurations are applied.");
if (node->has_cgroup()) {
RCLCPP_INFO(node->get_logger(),
"Press enter to exit and remove the cgroups created for "
"thread affinity:");
std::cin.get();
}
} else {
if (!node->has_configured_once()) {
node->print_all_unapplied();
}
Comment thread
atsushi421 marked this conversation as resolved.
Outdated
} catch (const std::exception &e) {
Expand Down
Loading