Skip to content
Open
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
21 changes: 13 additions & 8 deletions minimal_scheduling/minimal_scheduling_real_time_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "rcpputils/thread.hpp"
#include "std_msgs/msg/string.hpp"

#include "rusage_utils.hpp"
Expand Down Expand Up @@ -113,8 +114,14 @@ int main(int argc, char * argv[])
auto node_sub = std::make_shared<MinimalSubscriber>("minimal_sub1", "topic");
auto node_sub_rt = std::make_shared<MinimalSubscriber>("minimal_sub2", "topic_rt");

rclcpp::executors::StaticSingleThreadedExecutor default_executor;
rclcpp::executors::StaticSingleThreadedExecutor realtime_executor;

rcpputils::ThreadAttribute default_attr;
rcpputils::ThreadAttribute realtime_attr;
realtime_attr.set_sched_policy(rcpputils::SchedPolicy::fifo);
realtime_attr.set_priority(options.priority);

rclcpp::executors::SingleThreadedExecutor default_executor(rclcpp::ExecutorOptions(), default_attr);
rclcpp::executors::SingleThreadedExecutor realtime_executor(rclcpp::ExecutorOptions(), realtime_attr);

// the publisher and non real-time subscriber are processed by default_executor
default_executor.add_node(node_pub);
Expand All @@ -132,21 +139,19 @@ int main(int argc, char * argv[])
// of the thread, in which the Executor is spinning.

// spin non real-time tasks in a separate thread
auto default_thread = std::thread(
auto default_executor_thread = std::thread(
[&]() {
default_executor.spin();
});

// spin real-time tasks in a separate thread
auto realtime_thread = std::thread(
auto realtime_executor_thread = std::thread(
[&]() {
realtime_executor.spin();
});

set_thread_scheduling(realtime_thread.native_handle(), options.policy, options.priority);

default_thread.join();
realtime_thread.join();
default_executor_thread.join();
realtime_executor_thread.join();

rclcpp::shutdown();
return 0;
Expand Down
8 changes: 6 additions & 2 deletions minimal_scheduling/minimal_scheduling_spin_thread.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "rcpputils/thread.hpp"
#include "std_msgs/msg/string.hpp"

#include "rusage_utils.hpp"
Expand Down Expand Up @@ -85,12 +86,15 @@ int main(int argc, char * argv[])
rclcpp::init(argc, argv);

auto node = std::make_shared<MinimalPublisher>();
auto spin_thread = std::thread(
rcpputils::ThreadAttribute attr;
attr.set_sched_policy(rcpputils::SchedPolicy::fifo);
attr.set_priority(options.priority);
auto spin_thread = rcpputils::Thread(
attr,
[&]() {
rclcpp::spin(node);
});

set_thread_scheduling(spin_thread.native_handle(), options.policy, options.priority);

spin_thread.join();
rclcpp::shutdown();
Expand Down
2 changes: 2 additions & 0 deletions minimal_scheduling/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,11 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>rclcpp</build_depend>
<build_depend>rcpputils</build_depend>
<build_depend>std_msgs</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>rcpputils</exec_depend>
<exec_depend>std_msgs</exec_depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down