Skip to content

Commit

Permalink
Create app and thread configuration struct
Browse files Browse the repository at this point in the history
  • Loading branch information
stephanie-eng committed Jul 27, 2023
1 parent 97c3bba commit ba09fad
Show file tree
Hide file tree
Showing 20 changed files with 369 additions and 303 deletions.
69 changes: 67 additions & 2 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -1,5 +1,70 @@
{
"files.associations": {
"iosfwd": "cpp"
"iosfwd": "cpp",
"cctype": "cpp",
"clocale": "cpp",
"cmath": "cpp",
"csignal": "cpp",
"cstdarg": "cpp",
"cstddef": "cpp",
"cstdio": "cpp",
"cstdlib": "cpp",
"cstring": "cpp",
"ctime": "cpp",
"cwchar": "cpp",
"cwctype": "cpp",
"array": "cpp",
"atomic": "cpp",
"bit": "cpp",
"*.tcc": "cpp",
"bitset": "cpp",
"chrono": "cpp",
"codecvt": "cpp",
"compare": "cpp",
"concepts": "cpp",
"condition_variable": "cpp",
"cstdint": "cpp",
"deque": "cpp",
"map": "cpp",
"set": "cpp",
"string": "cpp",
"unordered_map": "cpp",
"unordered_set": "cpp",
"vector": "cpp",
"exception": "cpp",
"algorithm": "cpp",
"functional": "cpp",
"iterator": "cpp",
"memory": "cpp",
"memory_resource": "cpp",
"numeric": "cpp",
"optional": "cpp",
"random": "cpp",
"ratio": "cpp",
"regex": "cpp",
"string_view": "cpp",
"system_error": "cpp",
"tuple": "cpp",
"type_traits": "cpp",
"utility": "cpp",
"fstream": "cpp",
"initializer_list": "cpp",
"iomanip": "cpp",
"iostream": "cpp",
"istream": "cpp",
"limits": "cpp",
"mutex": "cpp",
"new": "cpp",
"numbers": "cpp",
"ostream": "cpp",
"semaphore": "cpp",
"sstream": "cpp",
"stdexcept": "cpp",
"stop_token": "cpp",
"streambuf": "cpp",
"thread": "cpp",
"cinttypes": "cpp",
"typeinfo": "cpp",
"variant": "cpp"
}
}
}
38 changes: 22 additions & 16 deletions examples/logging_example/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,24 +4,17 @@

using cactus_rt::App;
using cactus_rt::CyclicThread;
using cactus_rt::schedulers::Fifo;

/**
* This is a no-op thread that does nothing at 1 kHz.
*
*/
class ExampleRTThread : public CyclicThread<> {
class ExampleRTThread : public CyclicThread {
int64_t loop_counter_ = 0;

public:
ExampleRTThread() : CyclicThread<>(
"ExampleRTThread",
1'000'000, // Period in ns
Fifo::Config{
80 /* Priority */,
},
std::vector<size_t>{2} /* CPU affinity */
) {}
ExampleRTThread(cactus_rt::CyclicThreadConfig config) : CyclicThread(config
) {}

int64_t GetLoopCounter() const {
return loop_counter_;
Expand All @@ -38,18 +31,31 @@ class ExampleRTThread : public CyclicThread<> {
};

int main() {
auto thread = std::make_shared<ExampleRTThread>();
cactus_rt::FifoThreadConfig fifo_config;
fifo_config.priority = 80;

// Create a Quill logging config
quill::Config cfg;
cactus_rt::CyclicThreadConfig config;
config.name = "ExampleRTThread";
config.period_ns = 1'000'000;
config.cpu_affinity = std::vector<size_t>{2};
config.scheduler_config = fifo_config;

auto thread = std::make_shared<ExampleRTThread>(config);

// Create a cactus_rt app configuration
cactus_rt::AppConfig app_config;

// Create a Quill logging config to configure logging
quill::Config logging_config;

// Disable strict timestamp order - this will be faster, but logs may appear out of order
cfg.backend_thread_strict_log_timestamp_order = false;
logging_config.backend_thread_strict_log_timestamp_order = false;

// Set the background logging thread CPU affinity
cfg.backend_thread_cpu_affinity = 1; // Different CPU than the CyclicThread CPU!
logging_config.backend_thread_cpu_affinity = 1; // Different CPU than the CyclicThread CPU!

App app(cfg);
app_config.logger_config = logging_config;
App app(app_config);

app.RegisterThread(thread);
constexpr unsigned int time = 5;
Expand Down
10 changes: 9 additions & 1 deletion examples/message_passing_example/data_logger_thread.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,19 @@

#include <chrono>

namespace {
cactus_rt::ThreadConfig MakeDataLoggerThreadConfig() {
cactus_rt::ThreadConfig config;
config.name = "DataLogger";
return config;
}
} // namespace

DataLogger::DataLogger(
const std::string& data_file_path,
int64_t period_ns,
int64_t write_data_interval_ns
) : Thread<Other>("DataLogger"),
) : Thread(MakeDataLoggerThreadConfig()),
period_ns_(period_ns),
write_data_interval_ns_(write_data_interval_ns),
queue_(kQueueCapacity),
Expand Down
3 changes: 1 addition & 2 deletions examples/message_passing_example/data_logger_thread.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
using moodycamel::ReaderWriterQueue;

using cactus_rt::Thread;
using cactus_rt::schedulers::Other;

struct OutputData {
double timestamp = 0;
Expand All @@ -23,7 +22,7 @@ struct OutputData {
OutputData(double t, double o) : timestamp(t), output_value(o) {}
};

class DataLogger : public Thread<Other> {
class DataLogger : public Thread {
constexpr static int kQueueCapacity = 8 * 1024; // This is over 8 seconds of data while we write every 1 second. Should never be full.

int64_t period_ns_;
Expand Down
2 changes: 1 addition & 1 deletion examples/message_passing_example/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ using cactus_rt::App;

int main() {
auto data_logger = std::make_shared<DataLogger>("build/data.csv");
auto rt_thread = std::make_shared<RtThread>(data_logger, 1'000'000);
auto rt_thread = std::make_shared<RtThread>(data_logger);

App app;
app.RegisterThread(data_logger);
Expand Down
22 changes: 18 additions & 4 deletions examples/message_passing_example/rt_thread.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,16 +8,30 @@
#include "data_logger_thread.h"

using cactus_rt::CyclicThread;
using cactus_rt::schedulers::Fifo;
// "RtThread", 1'000'000, Fifo::Config{80 /* priority */}

class RtThread : public CyclicThread<> {
namespace {
cactus_rt::CyclicThreadConfig MakeRealTimeThreadConfig() {
cactus_rt::FifoThreadConfig fifo_config;
fifo_config.priority = 80;

cactus_rt::CyclicThreadConfig config;
config.name = "RtThread";
config.period_ns = 1'000'000;
config.scheduler_config = fifo_config;

return config;
}
} // namespace

class RtThread : public CyclicThread {
std::shared_ptr<DataLogger> data_logger_;
size_t max_iterations_;
size_t iterations_ = 0;

public:
RtThread(std::shared_ptr<DataLogger> data_logger, int period_ns, size_t max_iterations = 30000)
: CyclicThread<>("RtThread", period_ns, Fifo::Config{80 /* priority */}),
RtThread(std::shared_ptr<DataLogger> data_logger, size_t max_iterations = 30000)
: CyclicThread(MakeRealTimeThreadConfig()),
data_logger_(data_logger),
max_iterations_(max_iterations) {
}
Expand Down
38 changes: 25 additions & 13 deletions examples/mutex_example/main.cc
Original file line number Diff line number Diff line change
@@ -1,14 +1,13 @@
#include <cactus_rt/rt.h>

#include <cmath>
#include <iostream>

#include "double_buffer.h"

using cactus_rt::App;
using cactus_rt::CyclicThread;
using cactus_rt::Thread;
using cactus_rt::schedulers::Fifo;
using cactus_rt::schedulers::Other;

struct Data {
double v1 = 0.0;
Expand All @@ -17,16 +16,14 @@ struct Data {
double v4 = 0.0;
};

class RTThread : public CyclicThread<> {
class RTThread : public CyclicThread {
NaiveDoubleBuffer<Data>& buf_;

public:
explicit RTThread(NaiveDoubleBuffer<Data>& buf) : CyclicThread<>(
"RTThread",
1'000'000, // Period in ns
Fifo::Config{80 /* Priority */}
),
buf_(buf) {}
explicit RTThread(cactus_rt::CyclicThreadConfig config, NaiveDoubleBuffer<Data>& buf)
: CyclicThread(config
),
buf_(buf) {}

protected:
bool Loop(int64_t ellapsed_ns) noexcept final {
Expand All @@ -45,11 +42,11 @@ class RTThread : public CyclicThread<> {
}
};

class NonRTThread : public Thread<Other> {
class NonRTThread : public Thread {
NaiveDoubleBuffer<Data>& buf_;

public:
explicit NonRTThread(NaiveDoubleBuffer<Data>& buf) : Thread<Other>("NonRTThread"), buf_(buf) {}
explicit NonRTThread(cactus_rt::CyclicThreadConfig config, NaiveDoubleBuffer<Data>& buf) : Thread(config), buf_(buf) {}

protected:
void Run() final {
Expand All @@ -71,12 +68,27 @@ void TrivialDemo() {
}

void ThreadedDemo() {
cactus_rt::FifoThreadConfig fifo_config;
fifo_config.priority = 80;

cactus_rt::CyclicThreadConfig rt_thread_config;
rt_thread_config.name = "RTThread";
rt_thread_config.period_ns = 1'000'000;
rt_thread_config.scheduler_config = fifo_config;

cactus_rt::OtherThreadConfig other_config;
fifo_config.priority = 80;

cactus_rt::CyclicThreadConfig non_rt_thread_config;
non_rt_thread_config.name = "NonRTThread";
non_rt_thread_config.scheduler_config = other_config;

// The double buffer is shared between the two threads, so we pass a reference
// into the thread and maintain the object lifetime to this function.
NaiveDoubleBuffer<Data> buf;

auto rt_thread = std::make_shared<RTThread>(buf);
auto non_rt_thread = std::make_shared<NonRTThread>(buf);
auto rt_thread = std::make_shared<RTThread>(rt_thread_config, buf);
auto non_rt_thread = std::make_shared<NonRTThread>(non_rt_thread_config, buf);
App app;

app.RegisterThread(non_rt_thread);
Expand Down
21 changes: 12 additions & 9 deletions examples/signal_handling_example/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,21 +4,15 @@

using cactus_rt::App;
using cactus_rt::CyclicThread;
using cactus_rt::schedulers::Fifo;

/**
* This is a no-op thread that does nothing at 1 kHz.
*/
class ExampleRTThread : public CyclicThread<> {
class ExampleRTThread : public CyclicThread {
int64_t loop_counter_ = 0;

public:
ExampleRTThread() : CyclicThread<>(
"ExampleRTThread",
1'000'000, // Period in ns
Fifo::Config{80 /* Priority */},
std::vector<size_t>{2}
) {}
ExampleRTThread(cactus_rt::CyclicThreadConfig config) : CyclicThread(config) {}

int64_t GetLoopCounter() const {
return loop_counter_;
Expand All @@ -32,7 +26,16 @@ class ExampleRTThread : public CyclicThread<> {
};

int main() {
auto thread = std::make_shared<ExampleRTThread>();
cactus_rt::FifoThreadConfig fifo_config;
fifo_config.priority = 80;

cactus_rt::CyclicThreadConfig config;
config.name = "ExampleRTThread";
config.period_ns = 1'000'000;
config.cpu_affinity = std::vector<size_t>{2};
config.scheduler_config = fifo_config;

auto thread = std::make_shared<ExampleRTThread>(config);
App app;

app.RegisterThread(thread);
Expand Down
26 changes: 15 additions & 11 deletions examples/simple_deadline_example/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,26 +4,19 @@

using cactus_rt::App;
using cactus_rt::CyclicThread;
using cactus_rt::schedulers::Deadline;

/**
* This is a no-op thread that does nothing at 1 kHz.
*
* Note that we are using the Deadline scheduler as opposed to leaving the
* template argument blank (which defaults to real-time).
*/
class ExampleDeadlineThread : public CyclicThread<Deadline> {
class ExampleDeadlineThread : public CyclicThread {
int64_t loop_counter_ = 0;

public:
ExampleDeadlineThread() : CyclicThread<Deadline>(
"ExampleRTThread",
1'000'000, // Period in ns
Deadline::Config{
500'000, /* Run time in ns */
1'000'000 /* Deadline in ns */
}
) {}
ExampleDeadlineThread(cactus_rt::CyclicThreadConfig config) : CyclicThread(config
) {}

int64_t GetLoopCounter() const {
return loop_counter_;
Expand All @@ -37,7 +30,18 @@ class ExampleDeadlineThread : public CyclicThread<Deadline> {
};

int main() {
auto thread = std::make_shared<ExampleDeadlineThread>();
cactus_rt::DeadlineThreadConfig deadline_config;
deadline_config.sched_deadline_ns = 1'000'000;
deadline_config.sched_runtime_ns = 500'000;
deadline_config.sched_period_ns = 1'000'000;

cactus_rt::CyclicThreadConfig config;
config.name = "ExampleRTThread";

// config.cpu_affinity = std::vector<size_t>{2};

config.scheduler_config = deadline_config;
auto thread = std::make_shared<ExampleDeadlineThread>(config);
App app;

app.RegisterThread(thread);
Expand Down
Loading

0 comments on commit ba09fad

Please sign in to comment.