Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
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
16 changes: 13 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,12 @@ After launching the `prerun` node, launch your ROS 2 application.

To launch the `prerun` node, type the command below.
```bash
$ ros2 run cie_thread_configurator thread_configurator_node --prerun
$ ros2 run cie_thread_configurator prerun_node
```

Alternatively, you can use the provided launch file:
```bash
$ ros2 launch cie_thread_configurator thread_configurator.launch.xml prerun:=true
```

Then launch your ROS 2 application in another terminal window, after which you can see log messages like shown below in the `prerun` node window.
Expand Down Expand Up @@ -220,15 +225,20 @@ For the detailed specifications of the configuration file, please refer to https
To launch the target ROS 2 application with the scheduler settings applied from the your_config.yaml you created, first start the configurator node with the following command.

```bash
$ ros2 run cie_thread_configurator thread_configurator_node --config-file your_config.yaml
$ ros2 run cie_thread_configurator thread_configurator_node --ros-args -p config_file:=your_config.yaml
```

Alternatively, you can use the provided launch file:
```bash
$ ros2 launch cie_thread_configurator thread_configurator.launch.xml config_file:=your_config.yaml
```

If there is a callback group with the `SCHED_DEADLINE` scheduling policy specified, running the configurator node requires root privileges.
This is because it is not possible to set threads to SCHED_DEADLINE within the permissions that can be granted through capability.
Note that if the target ROS 2 application is operating with a specific ROS_DOMAIN_ID, the configurator node must also be operated with the same ROS_DOMAIN_ID.

```bash
$ sudo bash -c "export ROS_DOMAIN_ID=[app domain id]; source /path/to/callback_isolated_executor/install/setup.bash; ros2 run cie_thread_configurator thread_configurator_node --config-file your_config.yaml"
$ sudo bash -c "export ROS_DOMAIN_ID=[app domain id]; source /path/to/callback_isolated_executor/install/setup.bash; ros2 run cie_thread_configurator thread_configurator_node --ros-args -p config_file:=your_config.yaml"
```

Immediately after launching the configurator node, it will validate the hardware configuration. The configurator compares the hardware information stored in the configuration file against the current system's hardware details. If there are any mismatches (such as different CPU family or model), the configurator will report an error like:
Expand Down
14 changes: 12 additions & 2 deletions cie_thread_configurator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,22 @@ endif()
add_library(thread_configurator SHARED src/util.cpp)
ament_target_dependencies(thread_configurator rclcpp cie_config_msgs)

add_executable(thread_configurator_node src/main.cpp src/thread_configurator_node.cpp src/prerun_node.cpp)
add_executable(thread_configurator_node src/thread_configurator_node_main.cpp src/thread_configurator_node.cpp)
ament_target_dependencies(thread_configurator_node rclcpp cie_config_msgs)
target_link_libraries(thread_configurator_node yaml-cpp thread_configurator)

target_include_directories(thread_configurator_node PRIVATE
${CMAKE_CURRENT_SOURCE_DIR}/include
)

add_executable(prerun_node src/prerun_node_main.cpp src/prerun_node.cpp)
ament_target_dependencies(prerun_node rclcpp cie_config_msgs)
target_link_libraries(prerun_node yaml-cpp thread_configurator)

target_include_directories(prerun_node PRIVATE
${CMAKE_CURRENT_SOURCE_DIR}/include
)

target_include_directories(thread_configurator PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
Expand All @@ -51,7 +59,9 @@ install(
DESTINATION include
)

install(TARGETS thread_configurator_node DESTINATION lib/${PROJECT_NAME})
install(TARGETS thread_configurator_node prerun_node DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch)

ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
ament_export_include_directories(include)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,8 @@

class PrerunNode : public rclcpp::Node {
public:
PrerunNode();
explicit PrerunNode(
const rclcpp::NodeOptions &options = rclcpp::NodeOptions());
void dump_yaml_config(std::filesystem::path path);

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,14 @@ class ThreadConfiguratorNode : public rclcpp::Node {
};

public:
ThreadConfiguratorNode(const YAML::Node &yaml);
/// Construct the node. Reads the 'config_file' ROS parameter, loads the
/// YAML, and performs hardware validation when a 'hardware_info' section
/// is present in the configuration.
/// @throws std::runtime_error if the 'config_file' parameter is empty, the
/// YAML file cannot be loaded, or a present hardware_info section
/// does not match the current system.
explicit ThreadConfiguratorNode(
const rclcpp::NodeOptions &options = rclcpp::NodeOptions());
~ThreadConfiguratorNode();
bool all_applied();
void print_all_unapplied();
Expand All @@ -35,6 +42,7 @@ class ThreadConfiguratorNode : public rclcpp::Node {
bool apply_deadline_configs();

private:
void validate_hardware_info(const YAML::Node &yaml);
bool set_affinity_by_cgroup(int64_t thread_id, const std::vector<int> &cpus);
bool issue_syscalls(const ThreadConfig &config);
void callback_group_callback(
Expand Down
11 changes: 11 additions & 0 deletions cie_thread_configurator/launch/thread_configurator.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0"?>
<launch>
<arg name="prerun" default="false" description="Run prerun_node to generate a YAML template instead of applying a config."/>
<arg name="config_file" default="" description="Path to the YAML configuration file. Required when 'prerun' is false; the node will abort with an error if left empty."/>

<node pkg="cie_thread_configurator" exec="prerun_node" name="prerun_node" output="screen" if="$(var prerun)"/>

<node pkg="cie_thread_configurator" exec="thread_configurator_node" name="thread_configurator_node" output="screen" unless="$(var prerun)">
<param name="config_file" value="$(var config_file)"/>
</node>
</launch>
150 changes: 0 additions & 150 deletions cie_thread_configurator/src/main.cpp

This file was deleted.

3 changes: 2 additions & 1 deletion cie_thread_configurator/src/prerun_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,8 @@
#include "cie_thread_configurator/cie_thread_configurator.hpp"
#include "cie_thread_configurator/prerun_node.hpp"

PrerunNode::PrerunNode() : Node("prerun_node") {
PrerunNode::PrerunNode(const rclcpp::NodeOptions &options)
: Node("prerun_node", options) {
auto cbg_qos = rclcpp::QoS(rclcpp::KeepAll()).reliable().transient_local();
subscription_ =
this->create_subscription<cie_config_msgs::msg::CallbackGroupInfo>(
Expand Down
30 changes: 30 additions & 0 deletions cie_thread_configurator/src/prerun_node_main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include <exception>
#include <filesystem>
#include <iostream>
#include <memory>

#include "rclcpp/rclcpp.hpp"

#include "cie_thread_configurator/prerun_node.hpp"

int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);

try {
auto node = std::make_shared<PrerunNode>();
auto executor =
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

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

node->dump_yaml_config(std::filesystem::current_path());
} catch (const std::exception &e) {
std::cerr << "[ERROR] " << e.what() << std::endl;
rclcpp::shutdown();
return 1;
}

rclcpp::shutdown();
return 0;
}
Loading
Loading