diff --git a/README.md b/README.md index c45aeee..657a90a 100644 --- a/README.md +++ b/README.md @@ -29,6 +29,8 @@ writing a real-time Linux application. Some key features are: Examples -------- +Core examples that show you how to use all the facilities of cactus-rt: + * [`simple_example`](examples/simple_example/): The most basic example showing a single real-time looping thread running at 1000 Hz. * [`tracing_example`](examples/tracing_example/): This demonstrates how to use @@ -38,14 +40,26 @@ Examples priority-inheritence mutex (`cactus_rt::mutex`) to pass data between real-time and non-real-time threads via the implementation of a mutex-based double buffer. +* [`lockless_examples`](examples/lockless_examples/): Demonstrates the usage of + lockless data structures built into cactus-rt to safely pass data to and from + the real-time thread. * [`logging_example`](examples/logging_example/): Demonstrates setting up custom logging configuration via `cactus_rt::App`. +* [`message_passing_example`](examples/message_passing_example/): A simplified + example of a real robotics application consists of two threads: a real-time + thread that is generating metrics and a non-real-time data logger that logs + the metrics to disk. +* [`ros2`](examples/ros2/): Shows how to use cactus-rt with ROS2. + +Some examples showing optional/advanced features/usage patterns of cactus-rt. * [`simple_deadline_example`](examples/simple_deadline_example/): Same as `simple_example`, except it uses `SCHED_DEADLINE` as opposed to `SCHED_FIFO`. This is for a more advanced use case. - -* [`tracing_example_no_rt`](examples/tracing_example_no_rt/): Shows how to using the tracing library in `cactus_rt` without using `cactus_rt::App`. +* [`random_example`](examples/random_example/): Shows you how to use cactus-rt's + real-time-safe random number generator. +* [`tracing_example_no_rt`](examples/tracing_example_no_rt/): Shows how to using + the tracing library in `cactus_rt` without using `cactus_rt::App`. Installation instructions diff --git a/examples/lockless_examples/README.md b/examples/lockless_examples/README.md index d6a9438..8887148 100644 --- a/examples/lockless_examples/README.md +++ b/examples/lockless_examples/README.md @@ -1,3 +1,10 @@ Lockless examples ================= +`realtime_read` +--------------- + +This example shows you how to use the `RealtimeReadableValue` lockless data +structure. This data structure allows you to read a struct from a single +real-time thread in a wait-free manner O(1). The writer has to be a single +thread is non-real-time as the write algorithm is lock-free but not wait-free. diff --git a/examples/lockless_examples/realtime_read.cc b/examples/lockless_examples/realtime_read.cc index e22e8b7..4381cd1 100644 --- a/examples/lockless_examples/realtime_read.cc +++ b/examples/lockless_examples/realtime_read.cc @@ -60,7 +60,7 @@ class RTThread : public CyclicThread { Context& ctx_; Pose current_target_pose_; - static cactus_rt::CyclicThreadConfig CreateThreadConfig() { + static cactus_rt::CyclicThreadConfig MakeConfig() { cactus_rt::CyclicThreadConfig thread_config; thread_config.period_ns = 1'000'000; thread_config.cpu_affinity = std::vector{2}; @@ -70,7 +70,7 @@ class RTThread : public CyclicThread { } public: - RTThread(Context& ctx) : CyclicThread("RTThread", CreateThreadConfig()), ctx_(ctx) {} + RTThread(Context& ctx) : CyclicThread("RTThread", MakeConfig()), ctx_(ctx) {} protected: LoopControl Loop(int64_t /*now*/) noexcept final { @@ -104,14 +104,14 @@ class RTThread : public CyclicThread { class NonRTThread : public Thread { Context& ctx_; - static cactus_rt::ThreadConfig CreateThreadConfig() { + static cactus_rt::ThreadConfig MakeConfig() { cactus_rt::ThreadConfig thread_config; thread_config.SetOtherScheduler(); return thread_config; } public: - NonRTThread(Context& ctx) : Thread("NonRTThread", CreateThreadConfig()), ctx_(ctx) {} + NonRTThread(Context& ctx) : Thread("NonRTThread", MakeConfig()), ctx_(ctx) {} void Run() final { ctx_.target_pose.Write(Pose(1.5, 2.5, 3.5, 4.5, 5.5, 6.5)); diff --git a/examples/logging_example/main.cc b/examples/logging_example/main.cc index 89c8b6d..d6e7c23 100644 --- a/examples/logging_example/main.cc +++ b/examples/logging_example/main.cc @@ -13,8 +13,16 @@ using cactus_rt::CyclicThread; class ExampleRTThread : public CyclicThread { int64_t loop_counter_ = 0; + static cactus_rt::CyclicThreadConfig MakeConfig() { + cactus_rt::CyclicThreadConfig thread_config; + thread_config.period_ns = 1'000'000; + thread_config.cpu_affinity = std::vector{2}; + thread_config.SetFifoScheduler(80); + return thread_config; + } + public: - ExampleRTThread(const char* name, cactus_rt::CyclicThreadConfig config) : CyclicThread(name, config) {} + ExampleRTThread() : CyclicThread("ExampleRTThread", MakeConfig()) {} int64_t GetLoopCounter() const { return loop_counter_; @@ -26,33 +34,26 @@ class ExampleRTThread : public CyclicThread { if (loop_counter_ % 1000 == 0) { LOG_INFO(Logger(), "Loop {}", loop_counter_); } + LOG_INFO_LIMIT(std::chrono::milliseconds{1500}, Logger(), "Log limit: Loop {}", loop_counter_); return LoopControl::Continue; } }; int main() { - cactus_rt::CyclicThreadConfig thread_config; - thread_config.period_ns = 1'000'000; - thread_config.cpu_affinity = std::vector{2}; - thread_config.SetFifoScheduler(80); - // 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 - logging_config.backend_thread_strict_log_timestamp_order = false; + app_config.logger_config.backend_thread_strict_log_timestamp_order = false; // Set the background logging thread CPU affinity - logging_config.backend_thread_cpu_affinity = 1; // Different CPU than the CyclicThread CPU! + app_config.logger_config.backend_thread_cpu_affinity = 1; // Different CPU than the CyclicThread CPU! - app_config.logger_config = logging_config; App app("LoggingExampleApp", app_config); - auto thread = app.CreateThread("ExampleRTThread", thread_config); + auto thread = app.CreateThread(); + constexpr unsigned int time = 5; std::cout << "Testing RT loop for " << time << " seconds.\n"; diff --git a/examples/message_passing_example/data_logger_thread.cc b/examples/message_passing_example/data_logger_thread.cc index c83f4b6..97290da 100644 --- a/examples/message_passing_example/data_logger_thread.cc +++ b/examples/message_passing_example/data_logger_thread.cc @@ -10,7 +10,7 @@ DataLogger::DataLogger( period_ns_(period_ns), write_data_interval_ns_(write_data_interval_ns), queue_(kQueueCapacity), - message_count_({0, 0}) { + message_count_(CountData{0, 0}) { file_.open(data_file_path); if (!file_.is_open()) { throw std::runtime_error{"failed to open data file"}; @@ -61,10 +61,6 @@ void DataLogger::Run() { break; } - // TODO: looking at the code for this, it seems safe as it just calls - // nanosleep. That said, to make it explicit that we're not using the c++ - // thread library, should just refactor that code out in to Thread::sleep - // here. std::this_thread::sleep_for(std::chrono::nanoseconds(period_ns_)); } } @@ -87,22 +83,17 @@ void DataLogger::WriteAndEmptyDataFromBuffer() noexcept { } void DataLogger::ReadAndLogMessageCount() noexcept { - const auto current_count = message_count_.load(); + const auto current_count = message_count_.Read(); LOG_INFO(Logger(), "received {} messages and dropped {}", current_count.total_messages, current_count.total_messages - current_count.successful_messages); } // A demonstration of how to pass a small amount of data via std::atomic if it can be done in a lock free manner. -// This is called from the real-time thread. The loop is probably unnecessary -// because it must be the only thread that reads and writes to this variable.. -// successful_message_count should be either 0 or 1... +// This is called from the real-time thread. void DataLogger::IncrementMessageCount(uint32_t successful_message_count) noexcept { - auto old_count = message_count_.load(); - decltype(old_count) new_count; - - do { - new_count = old_count; - new_count.successful_messages += successful_message_count; - new_count.total_messages += 1; - } while (!message_count_.compare_exchange_weak(old_count, new_count)); + message_count_.Modify([successful_message_count](CountData old_value) noexcept { + old_value.successful_messages += successful_message_count; + old_value.total_messages += 1; + return old_value; + }); } diff --git a/examples/message_passing_example/data_logger_thread.h b/examples/message_passing_example/data_logger_thread.h index d40648b..3a3b2f7 100644 --- a/examples/message_passing_example/data_logger_thread.h +++ b/examples/message_passing_example/data_logger_thread.h @@ -1,10 +1,10 @@ #ifndef CACTUS_RT_EXAMPLES_MESSAGE_PASSING_EXAMPLE_DATA_LOGGER_H_ #define CACTUS_RT_EXAMPLES_MESSAGE_PASSING_EXAMPLE_DATA_LOGGER_H_ +#include #include #include -#include #include #include #include @@ -38,9 +38,8 @@ class DataLogger : public Thread { uint32_t total_messages; }; - using AtomicMessageCount = std::atomic; + using AtomicMessageCount = cactus_rt::experimental::lockless::AtomicMessage; AtomicMessageCount message_count_; - static_assert(AtomicMessageCount::is_always_lock_free); std::vector data_buffer_; // A simple buffer to hold the data in non-realtime thread so batch writing can occur diff --git a/examples/message_passing_example/rt_thread.h b/examples/message_passing_example/rt_thread.h index c9368b8..347cc02 100644 --- a/examples/message_passing_example/rt_thread.h +++ b/examples/message_passing_example/rt_thread.h @@ -14,7 +14,7 @@ class RtThread : public CyclicThread { size_t max_iterations_; size_t iterations_ = 0; - static cactus_rt::CyclicThreadConfig MakeRealTimeThreadConfig() { + static cactus_rt::CyclicThreadConfig MakeConfig() { cactus_rt::CyclicThreadConfig config; config.period_ns = 1'000'000; config.cpu_affinity = std::vector{2}; @@ -25,7 +25,7 @@ class RtThread : public CyclicThread { public: RtThread(std::shared_ptr data_logger, size_t max_iterations = 30000) - : CyclicThread("RtThread", MakeRealTimeThreadConfig()), + : CyclicThread("RtThread", MakeConfig()), data_logger_(data_logger), max_iterations_(max_iterations) { } diff --git a/examples/mutex_example/README.md b/examples/mutex_example/README.md index d77cd7e..3e63349 100644 --- a/examples/mutex_example/README.md +++ b/examples/mutex_example/README.md @@ -13,7 +13,10 @@ thread writes to the double buffer at 1 kHz and the non-RT thread reads it every half second. Once it is read, it is logged via the `cactus_rt` logging capability. -_Note: a lockless version of this double buffer is implemented by the cactus-rt framework under `cactus_rt::experimental::lockless::spsc::AtomicWritableValue` which doesn't require a lock. That serves as an alternative to this code without the usage of a mutex._ +_Note: a lockless version of this double buffer is implemented by the cactus-rt +framework under `cactus_rt::experimental::lockless::spsc::RealtimeWritableValue` +which doesn't require a lock. That serves as an alternative to this code without +the usage of a mutex._ To run: diff --git a/examples/mutex_example/main.cc b/examples/mutex_example/main.cc index 31945f2..f58f769 100644 --- a/examples/mutex_example/main.cc +++ b/examples/mutex_example/main.cc @@ -13,6 +13,8 @@ using cactus_rt::Thread; // This is the data structure we are passing between the RT and non-RT thread. // It is big enough such that it cannot be atomically changed with a single // instruction to necessitate a mutex. +// +// Alternatively, you can also use RealtimeWritableValue instead of a mutex. struct Data { double v1 = 0.0; double v2 = 0.0; @@ -25,7 +27,7 @@ class RTThread : public CyclicThread { public: explicit RTThread(NaiveDoubleBuffer& buf) - : CyclicThread("RTThread", CreateConfig()), + : CyclicThread("RTThread", MakeConfig()), buf_(buf) {} protected: @@ -45,7 +47,7 @@ class RTThread : public CyclicThread { } private: - static cactus_rt::CyclicThreadConfig CreateConfig() { + static cactus_rt::CyclicThreadConfig MakeConfig() { cactus_rt::CyclicThreadConfig thread_config; thread_config.period_ns = 1'000'000; thread_config.SetFifoScheduler(80); @@ -59,7 +61,7 @@ class NonRTThread : public Thread { public: explicit NonRTThread(NaiveDoubleBuffer& buf) - : Thread("NonRTThread", CreateConfig()), + : Thread("NonRTThread", MakeConfig()), buf_(buf) {} protected: @@ -73,7 +75,7 @@ class NonRTThread : public Thread { } private: - static cactus_rt::ThreadConfig CreateConfig() { + static cactus_rt::ThreadConfig MakeConfig() { cactus_rt::CyclicThreadConfig rt_thread_config; rt_thread_config.SetOtherScheduler(0 /* niceness */); return rt_thread_config; diff --git a/examples/random_example/README.md b/examples/random_example/README.md new file mode 100644 index 0000000..9233409 --- /dev/null +++ b/examples/random_example/README.md @@ -0,0 +1,13 @@ +`random_example` +================ + +Technically, [none of the random number generators in C++ are O(1)][1]. This +means there is a small (infinitesimal?) probability that it may cause real-time +problems (for some of the implementation it may be near impossible). To ensure +absolute safety at the cost of slightly non-uniform random number generation, +cactus-rt implements a O(1) random number generator with the Xorshift algorithm. +This example shows how to use it. + +**WARNING: DO NOT USE THIS RNG IN SECURE CRYPTOGRAPHIC CONTEXT AS IT IS NOT PERFECTLY RANDOM**. + +[1]: https://youtu.be/Tof5pRedskI?t=2514 diff --git a/examples/random_example/main.cc b/examples/random_example/main.cc index f4b9256..198e62b 100644 --- a/examples/random_example/main.cc +++ b/examples/random_example/main.cc @@ -28,15 +28,18 @@ class Histogram { }; int main() { + // Generate the seed once in non-real-time code. const uint64_t seed = std::random_device{}(); std::cout << "Seed: " << seed << "\n"; Histogram<20> hist; - cactus_rt::experimental::Xorshift64Rand rng(seed); + // Initialize the RNG state in non-real-time code. + cactus_rt::experimental::random::Xorshift64Rand rng(seed); for (int i = 0; i < 1'000'000; i++) { - const float num = cactus_rt::experimental::RandomRealNumber(rng); + // RealNumber(rng) is always O(1). + const float num = cactus_rt::experimental::random::RealNumber(rng); if (num >= 1.0F || num < 0.0F) { std::cerr << "ERROR: seed = " << seed << " i = " << i << " num = " << num << " is out of range \n"; return 1; diff --git a/examples/ros2/README.md b/examples/ros2/README.md new file mode 100644 index 0000000..5993367 --- /dev/null +++ b/examples/ros2/README.md @@ -0,0 +1,77 @@ +`ros2` examples +=============== + +This directory contains many examples showing how to use the various ROS2 +integration feature of cactus-rt. The most important is the ability to receive +and publish ROS2 messages. + +In general, ROS 2 data structure are not safe to construct and copy in +real-time due to the internal usage of data structures like `std::vector` which +can result in memory allocation in the constructors. As a result, [ROS2 type +adaptation](https://ros.org/reps/rep-2007.html) is used to adapt the ROS types +into real-time-safe versions that you must define for your application. These +are shown in the `complex_data.cc` examples for the +[publisher](publisher/complex_data.cc) and +[subscriber](subscriber/complex_data.cc). However, these type adaptaion triggers +an extra copy in the non-real-time thread which can limit throughput. + +In some situation, the ROS type is actually real-time-safe. In these situations, +type adaptation can be turned off via an extra template argument (required as +ROS-generated types typically create non-trivial constructors which makes it +difficult for us to detect the type is a +[POD](https://en.cppreference.com/w/cpp/types/is_pod)). Turning off type +adaptation results in one less copy in the non-real-time thread, potentially +increasing throughput. These are shown in the `simple_data.cc` examples for the +[publisher](publisher/simple_data.cc) and +[subscriber](subscriber/simple_data.cc). **This should be used sparingly as most +ROS types are not real-time safe. If you turn off type adaptation and the +underlying ROS data incurs memory allocation on construction/copy, the cactus-rt +code path will not be real-time-safe.** + +Differences from ROS +-------------------- + +ROS subscribers are callbacks that executes on message arrival. ROS publishers +are simple function calls that writes the data directly to the middleware (which +internally may have buffering and async behaviors). The ROS integration for +cactus-rt does not work like this. Instead: + +- Subscription messages must be polled on each iteration of the real-time loop. +- Messages published from the real-time thread is queued and sent to ROS in + batches by a non-real-time thread. + +This means messages received by the real-time thread will be slightly delayed +according to the real-time loop frequency. Published messages are also slightly +delayed as it is processed in the background. These trade offs are made to keep +the real-time loop within hard deadlines, instead of ensuring messages are +delivered as fast as possible. + +Subscriber +---------- + +There are two ways to subscribe data from a real-time thread: + +- `CreateSubscriptionForLatestValue`: this will only allow the real-time thread + to read the latest message from the subscription. If multiple messages are + received between consecutive reads by the real-time thread, the latest value + is the only one that is available. This is shown in + [`simple_data.cc`](subscriber/simple_data.cc) and + [`complex_data.cc`](subscriber/complex_data.cc). +- `CreateSubscriptionQueued`: this will allow the real-time thread to read all + messages from the subscription, up to the queue size limit. The real-time + thread will also get these messages in a FIFO order. If the queue size limits + are reached, messages will be dropped when being received. + +Conceptually, the LatestValue variant is a queue with a size of 1. Many robotics +applications should work with this, as many applications simply require the +latest value. An example is a goal pose. The real-time thread is almost always +only interested in the latest goal pose. + +Publisher +--------- + +Messages published from the real-time thread are batch processed in a +non-real-time thread (`Ros2Adapter::TimerCallback`). This means data might be +slightly delayed. Depending on the QoS setting of the receive side, there could +also be message drops at the receive side if messages are published at high +frequencies (~1000 Hz). diff --git a/examples/ros2/publisher/complex_data.cc b/examples/ros2/publisher/complex_data.cc index 31740c4..0a90790 100644 --- a/examples/ros2/publisher/complex_data.cc +++ b/examples/ros2/publisher/complex_data.cc @@ -43,7 +43,7 @@ class RTROS2PublisherThread : public cactus_rt::CyclicThread, public cactus_rt:: std::shared_ptr> publisher_; - static cactus_rt::CyclicThreadConfig CreateThreadConfig() { + static cactus_rt::CyclicThreadConfig MakeConfig() { cactus_rt::CyclicThreadConfig thread_config; thread_config.period_ns = 1'000'000; thread_config.cpu_affinity = std::vector{2}; @@ -54,7 +54,7 @@ class RTROS2PublisherThread : public cactus_rt::CyclicThread, public cactus_rt:: public: explicit RTROS2PublisherThread(std::chrono::nanoseconds run_duration = std::chrono::seconds(30)) - : cactus_rt::CyclicThread("RTROS2Publisher", CreateThreadConfig()), + : cactus_rt::CyclicThread("RTROS2Publisher", MakeConfig()), run_duration_(run_duration.count()) {} void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { diff --git a/examples/ros2/publisher/simple_data.cc b/examples/ros2/publisher/simple_data.cc index c998b66..54c126c 100644 --- a/examples/ros2/publisher/simple_data.cc +++ b/examples/ros2/publisher/simple_data.cc @@ -18,7 +18,7 @@ class RTROS2PublisherThread : public cactus_rt::CyclicThread, public cactus_rt:: // type check manually. std::shared_ptr> publisher_; - static cactus_rt::CyclicThreadConfig CreateThreadConfig() { + static cactus_rt::CyclicThreadConfig MakeConfig() { cactus_rt::CyclicThreadConfig thread_config; thread_config.period_ns = 1'000'000; thread_config.cpu_affinity = std::vector{2}; @@ -29,7 +29,7 @@ class RTROS2PublisherThread : public cactus_rt::CyclicThread, public cactus_rt:: public: explicit RTROS2PublisherThread(std::chrono::nanoseconds run_duration = std::chrono::seconds(30)) - : cactus_rt::CyclicThread("RTROS2Publisher", CreateThreadConfig()), + : cactus_rt::CyclicThread("RTROS2Publisher", MakeConfig()), run_duration_(run_duration.count()) {} void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { diff --git a/examples/ros2/subscriber/complex_data.cc b/examples/ros2/subscriber/complex_data.cc index a4ce826..7c1ce2f 100644 --- a/examples/ros2/subscriber/complex_data.cc +++ b/examples/ros2/subscriber/complex_data.cc @@ -43,7 +43,7 @@ class RTROS2SubscriberThread : public cactus_rt::CyclicThread, public cactus_rt: std::shared_ptr> subscription_; - static cactus_rt::CyclicThreadConfig CreateThreadConfig() { + static cactus_rt::CyclicThreadConfig MakeConfig() { cactus_rt::CyclicThreadConfig thread_config; thread_config.period_ns = 1'000'000; thread_config.cpu_affinity = std::vector{2}; @@ -54,7 +54,7 @@ class RTROS2SubscriberThread : public cactus_rt::CyclicThread, public cactus_rt: public: explicit RTROS2SubscriberThread(std::chrono::nanoseconds run_duration = std::chrono::seconds(30)) - : cactus_rt::CyclicThread("RTROS2Subscriber", CreateThreadConfig()), + : cactus_rt::CyclicThread("RTROS2Subscriber", MakeConfig()), run_duration_(run_duration.count()) {} void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { diff --git a/examples/ros2/subscriber/queued_data.cc b/examples/ros2/subscriber/queued_data.cc index 6825323..baa9d59 100644 --- a/examples/ros2/subscriber/queued_data.cc +++ b/examples/ros2/subscriber/queued_data.cc @@ -17,7 +17,7 @@ class RTROS2SubscriberThread : public cactus_rt::CyclicThread, public cactus_rt: // type check manually. std::shared_ptr> subscription_; - static cactus_rt::CyclicThreadConfig CreateThreadConfig() { + static cactus_rt::CyclicThreadConfig MakeConfig() { cactus_rt::CyclicThreadConfig thread_config; thread_config.period_ns = 1'000'000; thread_config.cpu_affinity = std::vector{2}; @@ -28,7 +28,7 @@ class RTROS2SubscriberThread : public cactus_rt::CyclicThread, public cactus_rt: public: explicit RTROS2SubscriberThread(std::chrono::nanoseconds run_duration = std::chrono::seconds(30)) - : cactus_rt::CyclicThread("RTROS2Subscriber", CreateThreadConfig()), + : cactus_rt::CyclicThread("RTROS2Subscriber", MakeConfig()), run_duration_(run_duration.count()) {} void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { diff --git a/examples/ros2/subscriber/simple_data.cc b/examples/ros2/subscriber/simple_data.cc index eeb5a03..e8d915f 100644 --- a/examples/ros2/subscriber/simple_data.cc +++ b/examples/ros2/subscriber/simple_data.cc @@ -18,7 +18,7 @@ class RTROS2SubscriberThread : public cactus_rt::CyclicThread, public cactus_rt: // type check manually. std::shared_ptr> subscription_; - static cactus_rt::CyclicThreadConfig CreateThreadConfig() { + static cactus_rt::CyclicThreadConfig MakeConfig() { cactus_rt::CyclicThreadConfig thread_config; thread_config.period_ns = 1'000'000; thread_config.cpu_affinity = std::vector{2}; @@ -29,7 +29,7 @@ class RTROS2SubscriberThread : public cactus_rt::CyclicThread, public cactus_rt: public: explicit RTROS2SubscriberThread(std::chrono::nanoseconds run_duration = std::chrono::seconds(30)) - : cactus_rt::CyclicThread("RTROS2Subscriber", CreateThreadConfig()), + : cactus_rt::CyclicThread("RTROS2Subscriber", MakeConfig()), run_duration_(run_duration.count()) {} void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { diff --git a/include/cactus_rt/experimental/lockless/atomic_message.h b/include/cactus_rt/experimental/lockless/atomic_message.h index d3a6f09..92eec4e 100644 --- a/include/cactus_rt/experimental/lockless/atomic_message.h +++ b/include/cactus_rt/experimental/lockless/atomic_message.h @@ -56,7 +56,7 @@ class AtomicMessage { "Argument f to AtomicMessage::Modify requires an invocable signature T(T) noexcept" ); - auto old_value = Read(); + T old_value = Read(); while (true) { T new_value = f(old_value); diff --git a/include/cactus_rt/experimental/random.h b/include/cactus_rt/experimental/random.h index 849bed7..ee874d3 100644 --- a/include/cactus_rt/experimental/random.h +++ b/include/cactus_rt/experimental/random.h @@ -21,7 +21,7 @@ * [3]: https://doi.org/10.18637/jss.v008.i14 */ -namespace cactus_rt::experimental { +namespace cactus_rt::experimental::random { class Xorshift64Rand { uint64_t x_; @@ -62,7 +62,7 @@ class Xorshift64Rand { * @return T A random number between [0, 1) */ template -T RandomRealNumber(Generator& rng) { +T RealNumber(Generator& rng) { T v = static_cast(rng() - Generator::min()) / static_cast(Generator::max() - Generator::min()); if (v == static_cast(1.0)) { // Random numbers are supposed to be [0, 1). This is a hack to make sure we never land on 1. @@ -72,6 +72,6 @@ T RandomRealNumber(Generator& rng) { return v; } -} // namespace cactus_rt::experimental +} // namespace cactus_rt::experimental::random #endif diff --git a/tests/experimental/random_test.cc b/tests/experimental/random_test.cc index 3558498..6c5221f 100644 --- a/tests/experimental/random_test.cc +++ b/tests/experimental/random_test.cc @@ -4,22 +4,22 @@ #include -using cactus_rt::experimental::RandomRealNumber; -using cactus_rt::experimental::Xorshift64Rand; +using cactus_rt::experimental::random::RealNumber; +using cactus_rt::experimental::random::Xorshift64Rand; TEST(RandomRealNumber, Generate) { const uint64_t seed = std::random_device{}(); Xorshift64Rand rng(seed); for (int i = 0; i < 1'000'000; i++) { - const float current = RandomRealNumber(rng); + const float current = RealNumber(rng); if (current < 0.0F || current >= 1.0F) { ADD_FAILURE() << "number generated out of range: " << current << " (seed = " << seed << ", i = " << i << ")"; } } for (int i = 0; i < 1'000'000; i++) { - const auto current = RandomRealNumber(rng); + const auto current = RealNumber(rng); if (current < 0.0 || current >= 1.0) { ADD_FAILURE() << "number generated out of range: " << current << " (seed = " << seed << ", i = " << i << ")"; } @@ -30,14 +30,14 @@ TEST(RandomRealNumber, GenerateZeroSeed) { Xorshift64Rand rng(0); for (int i = 0; i < 1'000'000; i++) { - const float current = RandomRealNumber(rng); + const float current = RealNumber(rng); if (current < 0.0F || current >= 1.0F) { ADD_FAILURE() << "number generated out of range: " << current << " (seed = " << 0 << ", i = " << i << ")"; } } for (int i = 0; i < 1'000'000; i++) { - const auto current = RandomRealNumber(rng); + const auto current = RealNumber(rng); if (current < 0.0 || current >= 1.0) { ADD_FAILURE() << "number generated out of range: " << current << " (seed = " << 0 << ", i = " << i << ")"; } @@ -62,5 +62,5 @@ TEST(RandomRealNumber, DoesNotGenerate1) { }; MaxGenerator rng; - EXPECT_EQ(RandomRealNumber(rng), 0.0F); + EXPECT_EQ(RealNumber(rng), 0.0F); }