Skip to content

Commit

Permalink
Merge pull request #10 from JanStaschulat/feature/real-time-tutorial
Browse files Browse the repository at this point in the history
added minimal_scheduling_real_time_tutorial.cpp
  • Loading branch information
carlossvg authored Jun 5, 2023
2 parents 23e3891 + 4a8fb1b commit f61f93f
Show file tree
Hide file tree
Showing 4 changed files with 199 additions and 9 deletions.
4 changes: 4 additions & 0 deletions minimal_scheduling/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,15 @@ ament_target_dependencies(minimal_scheduling_spin_thread rclcpp std_msgs)
add_executable(minimal_scheduling_callback_group minimal_scheduling_callback_group.cpp)
ament_target_dependencies(minimal_scheduling_callback_group rclcpp std_msgs)

add_executable(minimal_scheduling_real_time_executor minimal_scheduling_real_time_executor.cpp)
ament_target_dependencies(minimal_scheduling_real_time_executor rclcpp std_msgs)

install(TARGETS
minimal_scheduling_main_thread
minimal_scheduling_middleware_threads
minimal_scheduling_spin_thread
minimal_scheduling_callback_group
minimal_scheduling_real_time_executor
DESTINATION lib/${PROJECT_NAME}
)

Expand Down
50 changes: 41 additions & 9 deletions minimal_scheduling/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -202,14 +202,46 @@ $ ps -C minimal_schedul -L -o tid,comm,rtprio,cls,psr

<script id="asciicast-FncZQ5gSgp6sNIxHj4weDra3n" src="https://asciinema.org/a/FncZQ5gSgp6sNIxHj4weDra3n.js" async></script>


### minimal_scheduling_real_time_executor

Example to demonstrate mixed system, with a real-time thread and non real-time thread. Two publisher callbacks are created. The first one is executed in the real-time thread, the other one is executed in a non real-time thread. Output: No preemptions of the real-time publisher and multiple preemptions of the non real-time publisher.

```bash
$ ros2 run minimal_scheduling minimal_scheduling_real_time_executor
```

Output: real-time subscriber is not preempted by other kernel processes, but normal subscriber is.
```bash
ros2 run minimal_scheduling minimal_scheduling_real_time_executor
[WARN] [1680948979.971439054] [minimal_sub1]: [sub] Involuntary context switches: '25'
[WARN] [1680948979.971483357] [minimal_sub2]: [sub] Involuntary context switches: '20'
[WARN] [1680948980.473828433] [minimal_sub1]: [sub] Involuntary context switches: '23'
[WARN] [1680948980.473872245] [minimal_sub2]: [sub] Involuntary context switches: '21'
[WARN] [1680948980.972909968] [minimal_sub1]: [sub] Involuntary context switches: '26'
[WARN] [1680948980.973096277] [minimal_sub2]: [sub] Involuntary context switches: '15'

ros2 run minimal_scheduling minimal_scheduling_real_time_executor --sched SCHED_FIFO --priority 80
[WARN] [1680947876.099416572] [minimal_sub1]: [sub] Involuntary context switches: '8'
[INFO] [1680947876.099471567] [minimal_sub2]: [sub] Involuntary context switches: '0'
[WARN] [1680947876.599197932] [minimal_sub1]: [sub] Involuntary context switches: '49'
[INFO] [1680947876.599202498] [minimal_sub2]: [sub] Involuntary context switches: '0'
[WARN] [1680947877.101378852] [minimal_sub1]: [sub] Involuntary context switches: '25'
[INFO] [1680947877.101372018] [minimal_sub2]: [sub] Involuntary context switches: '0'
```

## Resources

- [https://www.man7.org/linux/man-pages/man7/sched.7.html](https://www.man7.org/linux/man-pages/man7/sched.7.html)
- [https://wiki.linuxfoundation.org/realtime/documentation/technical_basics/sched_policy_prio/start](https://wiki.linuxfoundation.org/realtime/documentation/technical_basics/sched_policy_prio/start)
- [https://wiki.linuxfoundation.org/realtime/documentation/howto/applications/application_base](https://wiki.linuxfoundation.org/realtime/documentation/howto/applications/application_base)
- [https://linux.die.net/man/3/pthread_setschedparam](https://linux.die.net/man/3/pthread_setschedparam)
- [https://linux.die.net/man/3/pthread_create](https://linux.die.net/man/3/pthread_create)
- [https://access.redhat.com/documentation/en-us/red_hat_enterprise_linux/6/html/performance_tuning_guide/s-cpu-scheduler](https://access.redhat.com/documentation/en-us/red_hat_enterprise_linux/6/html/performance_tuning_guide/s-cpu-scheduler)
- Callback groups executor - Ralph Lange [video](https://www.youtube.com/watch?v=5Sd5bvvZeb0), [slides](https://www.apex.ai/_files/ugd/984e93_f3791ae0711042a883bfc40f827d6268.pdf)
- [https://github.com/ros2/examples/tree/master/rclcpp/executors/cbg_executor](https://github.com/ros2/examples/tree/master/rclcpp/executors/cbg_executor)
- [Basic investigation of priority of DDS-generated threads.](https://discourse.ros.org/uploads/short-url/p2fAAbrKHkrSqZ9oJkZNwOOf2Hi.pdf)
- Linux scheduling and multi-threading
- [https://www.man7.org/linux/man-pages/man7/sched.7.html](https://www.man7.org/linux/man-pages/man7/sched.7.html)
- [https://wiki.linuxfoundation.org/realtime/documentation/technical_basics/sched_policy_prio/start](https://wiki.linuxfoundation.org/realtime/documentation/technical_basics/sched_policy_prio/start)
- [https://wiki.linuxfoundation.org/realtime/documentation/howto/applications/application_base](https://wiki.linuxfoundation.org/realtime/documentation/howto/applications/application_base)
- [https://linux.die.net/man/3/pthread_setschedparam](https://linux.die.net/man/3/pthread_setschedparam)
- [https://linux.die.net/man/3/pthread_create](https://linux.die.net/man/3/pthread_create)
- [https://access.redhat.com/documentation/en-us/red_hat_enterprise_linux/6/html/performance_tuning_guide/s-cpu-scheduler](https://access.redhat.com/documentation/en-us/red_hat_enterprise_linux/6/html/performance_tuning_guide/s-cpu-scheduler)
- ROS 2 Execution Management
- ROS 2 documentation [About-Executors](https://docs.ros.org/en/humble/Concepts/About-Executors.html)
- ROS 2 documentation [Using-callback-groups](https://docs.ros.org/en/humble/How-To-Guides/Using-callback-groups.html)
- Talk "Callback group level executor", Ralph Lange, ROS 2 Executor Workshop, 2021. [video](https://www.youtube.com/watch?v=5Sd5bvvZeb0), [slides](https://www.apex.ai/_files/ugd/984e93_f3791ae0711042a883bfc40f827d6268.pdf)
- Code example with callback group level executor [https://github.com/ros2/examples/tree/master/rclcpp/executors/cbg_executor](https://github.com/ros2/examples/tree/master/rclcpp/executors/cbg_executor)
- [Basic investigation of priority of DDS-generated threads.](https://discourse.ros.org/uploads/short-url/p2fAAbrKHkrSqZ9oJkZNwOOf2Hi.pdf)
153 changes: 153 additions & 0 deletions minimal_scheduling/minimal_scheduling_real_time_executor.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,153 @@
// Copyright 2023
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <chrono>
#include <memory>
#include <string>

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

#include "rusage_utils.hpp"
#include "sched_utils.hpp"
#include "command_line_options.hpp"
#include "burn_cpu_cycles.hpp"

/* For this example, we will be using two Executors running in different threads to separate
* callback processing, so it is possible to spin them in threads with different scheduling
* priorities.
*/

using namespace std::chrono_literals;

static ContextSwitchesCounter context_switches_counter(RUSAGE_THREAD);
static ContextSwitchesCounter context_switches_counter_rt(RUSAGE_THREAD);

class MinimalPublisher : public rclcpp::Node
{
public:
MinimalPublisher()
: Node("minimal_pub"), count1_(0), count2_(0)
{
publisher1_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
auto timer_callback1 =
[this]() -> void {
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(this->count1_++);
this->publisher1_->publish(message);
};
timer1_ = this->create_wall_timer(500ms, timer_callback1);

publisher2_ = this->create_publisher<std_msgs::msg::String>("topic_rt", 10);
auto timer_callback2 =
[this]() -> void {
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(this->count2_++);
this->publisher2_->publish(message);
};
timer2_ = this->create_wall_timer(500ms, timer_callback2);
}

private:
rclcpp::TimerBase::SharedPtr timer1_, timer2_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher1_, publisher2_;
size_t count1_, count2_;
};

class MinimalSubscriber : public rclcpp::Node
{
public:
MinimalSubscriber(const std::string & node_name, const std::string & topic_name)
: Node(node_name), context_switches_counter_(RUSAGE_THREAD)
{
subscription1_ = this->create_subscription<std_msgs::msg::String>(
topic_name,
10,
[this](std_msgs::msg::String::UniquePtr) {
auto context_switches = context_switches_counter_.get();
if (context_switches > 0L) {
RCLCPP_WARN(
this->get_logger(), "[sub] Involuntary context switches: '%lu'",
context_switches);
} else {
RCLCPP_INFO(
this->get_logger(), "[sub] Involuntary context switches: '%lu'",
context_switches);
}
burn_cpu_cycles(200ms);
});
}

private:
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription1_;
ContextSwitchesCounter context_switches_counter_;
};


int main(int argc, char * argv[])
{
// Force flush of the stdout buffer.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);

auto options_reader = SchedOptionsReader();
if (!options_reader.read_options(argc, argv)) {
options_reader.print_usage();
return 0;
}
auto options = options_reader.get_options();

rclcpp::init(argc, argv);

auto node_pub = std::make_shared<MinimalPublisher>();
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;

// the publisher and non real-time subscriber are processed by default_executor
default_executor.add_node(node_pub);
default_executor.add_node(node_sub);

// real-time subscriber is processed by realtime_executor.
realtime_executor.add_node(node_sub_rt);

// middleware threads are not configured with real-time priority
// because scheduling configuration of main thread is not real-time.

// Note: you can only add complete nodes to an Executor. That is:
// If a node has multiple entities (e.g. subscribers) then the corresponding
// callbacks are all entities processed with the same scheduling configuration
// of the thread, in which the Executor is spinning.

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

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

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

default_thread.join();
realtime_thread.join();

rclcpp::shutdown();
return 0;
}
1 change: 1 addition & 0 deletions minimal_scheduling/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<maintainer email="[email protected]">Carlos San Vicente</maintainer>
<license>Apache License 2.0</license>
<author>Carlos San Vicente</author>
<author>Jan Staschulat</author>

<buildtool_depend>ament_cmake</buildtool_depend>

Expand Down

0 comments on commit f61f93f

Please sign in to comment.