diff --git a/docs/imgs/ROS2Ownership.svg b/docs/imgs/ROS2Ownership.svg index 31c3c7a..a905e5d 100644 --- a/docs/imgs/ROS2Ownership.svg +++ b/docs/imgs/ROS2Ownership.svg @@ -1,4 +1,4 @@ -cactus_rt::ros2::Appcactus_rt::ros2::Ros2ExecutorThreadrclcpp::SingleThreadedExecutorcactus_rt::ros2::Ros2Adapterrclcpp::Node...Publish<RealtimeT>(...)MyThread : cactus_rt::ThreadCreatePublisher(...)CreateSubscription(...)User accessiblecactus-rt internalsLegendcactus-rt ROS2 ownershipcactus_rt::ros2::Publisher<RealtimeT>rclcpp::Publisher<RosT>RealtimeToRos2Converter<RealtimeT, RosT>Lockless SPSC Queue \ No newline at end of file +cactus_rt::ros2::Appcactus_rt::ros2::Ros2ExecutorThreadrclcpp::SingleThreadedExecutorcactus_rt::ros2::Ros2Adapterrclcpp::Nodeclass RT1000 : public cactus_rt::CyclicThreadCreatePublisher(...)CreateSubscription(...)User accessiblecactus-rt internalsLegendROS publisher/subscription/servicescactus_rt::ros2::Publisher<RealtimeT,RosT>rclcpp::Publisher<RosT>Lockless SPSC Queuecactus_rt::ros2::SubscriptionLatest<RealtimeT,RosT>rclcpp::Subscription<RosT>cactus_rt::{...}::AtomicReadableValuecactus_rt::ros2::SubscriptionQueued<RealtimeT,RosT>rclcpp::Subscription<RosT>Lockless SPSC Queuepublisher->Publish(...)subscription->ReadLatest(...)Ros2Adapter only accessible during InitializeForRos2 \ No newline at end of file diff --git a/examples/ros2/publisher/complex_data.cc b/examples/ros2/publisher/complex_data.cc index 85bbd4a..31740c4 100644 --- a/examples/ros2/publisher/complex_data.cc +++ b/examples/ros2/publisher/complex_data.cc @@ -57,8 +57,8 @@ class RTROS2PublisherThread : public cactus_rt::CyclicThread, public cactus_rt:: : cactus_rt::CyclicThread("RTROS2Publisher", CreateThreadConfig()), run_duration_(run_duration.count()) {} - void InitializeForRos2() override { - publisher_ = ros2_adapter_->CreatePublisher("/cactus_rt/complex", rclcpp::QoS(100)); + void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { + publisher_ = ros2_adapter.CreatePublisher("/cactus_rt/complex", rclcpp::QoS(100)); } protected: diff --git a/examples/ros2/publisher/simple_data.cc b/examples/ros2/publisher/simple_data.cc index 4d02267..c998b66 100644 --- a/examples/ros2/publisher/simple_data.cc +++ b/examples/ros2/publisher/simple_data.cc @@ -32,8 +32,8 @@ class RTROS2PublisherThread : public cactus_rt::CyclicThread, public cactus_rt:: : cactus_rt::CyclicThread("RTROS2Publisher", CreateThreadConfig()), run_duration_(run_duration.count()) {} - void InitializeForRos2() override { - publisher_ = ros2_adapter_->CreatePublisher("/cactus_rt/simple", rclcpp::QoS(100)); + void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { + publisher_ = ros2_adapter.CreatePublisher("/cactus_rt/simple", rclcpp::QoS(100)); } protected: diff --git a/examples/ros2/subscriber/complex_data.cc b/examples/ros2/subscriber/complex_data.cc index 9f31ac9..a4ce826 100644 --- a/examples/ros2/subscriber/complex_data.cc +++ b/examples/ros2/subscriber/complex_data.cc @@ -57,8 +57,8 @@ class RTROS2SubscriberThread : public cactus_rt::CyclicThread, public cactus_rt: : cactus_rt::CyclicThread("RTROS2Subscriber", CreateThreadConfig()), run_duration_(run_duration.count()) {} - void InitializeForRos2() override { - subscription_ = ros2_adapter_->CreateSubscriptionForLatestValue("/cactus_rt/complex", rclcpp::QoS(100)); + void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { + subscription_ = ros2_adapter.CreateSubscriptionForLatestValue("/cactus_rt/complex", rclcpp::QoS(100)); } protected: diff --git a/examples/ros2/subscriber/queued_data.cc b/examples/ros2/subscriber/queued_data.cc index ff450dc..6825323 100644 --- a/examples/ros2/subscriber/queued_data.cc +++ b/examples/ros2/subscriber/queued_data.cc @@ -31,8 +31,8 @@ class RTROS2SubscriberThread : public cactus_rt::CyclicThread, public cactus_rt: : cactus_rt::CyclicThread("RTROS2Subscriber", CreateThreadConfig()), run_duration_(run_duration.count()) {} - void InitializeForRos2() override { - subscription_ = ros2_adapter_->CreateSubscriptionQueued("/cactus_rt/simple", rclcpp::QoS(100)); + void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { + subscription_ = ros2_adapter.CreateSubscriptionQueued("/cactus_rt/simple", rclcpp::QoS(100)); } protected: diff --git a/examples/ros2/subscriber/simple_data.cc b/examples/ros2/subscriber/simple_data.cc index 3363f47..eeb5a03 100644 --- a/examples/ros2/subscriber/simple_data.cc +++ b/examples/ros2/subscriber/simple_data.cc @@ -32,8 +32,8 @@ class RTROS2SubscriberThread : public cactus_rt::CyclicThread, public cactus_rt: : cactus_rt::CyclicThread("RTROS2Subscriber", CreateThreadConfig()), run_duration_(run_duration.count()) {} - void InitializeForRos2() override { - subscription_ = ros2_adapter_->CreateSubscriptionForLatestValue("/cactus_rt/simple", rclcpp::QoS(100)); + void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override { + subscription_ = ros2_adapter.CreateSubscriptionForLatestValue("/cactus_rt/simple", rclcpp::QoS(100)); } protected: diff --git a/include/cactus_rt/ros2/app.h b/include/cactus_rt/ros2/app.h index 2641d12..528a4c5 100644 --- a/include/cactus_rt/ros2/app.h +++ b/include/cactus_rt/ros2/app.h @@ -12,32 +12,23 @@ namespace cactus_rt::ros2 { class App; class Ros2ThreadMixin { - friend class App; - - protected: - std::shared_ptr ros2_adapter_; - - private: - void SetRos2Adapter(std::shared_ptr ros2_adapter) { - ros2_adapter_ = ros2_adapter; - } - public: - virtual void InitializeForRos2() = 0; + virtual void InitializeForRos2(Ros2Adapter& ros2_adapter) = 0; virtual ~Ros2ThreadMixin() = 0; }; class Ros2ExecutorThread : public cactus_rt::Thread, public cactus_rt::ros2::Ros2ThreadMixin { + std::shared_ptr ros2_adapter_; std::optional executor_; static cactus_rt::ThreadConfig CreateThreadConfig(); public: - Ros2ExecutorThread(); + explicit Ros2ExecutorThread(std::shared_ptr ros2_adapter); void Run() override; - void InitializeForRos2() override {} + void InitializeForRos2(Ros2Adapter& /*ros2_adapter*/) override {} }; class App : public cactus_rt::App { @@ -63,8 +54,7 @@ class App : public cactus_rt::App { static_assert(std::is_base_of_v, "Must derive ROS2 thread from Ros2ThreadMixin"); std::shared_ptr thread = CreateThread(std::forward(args)...); - thread->SetRos2Adapter(ros2_adapter_); - thread->InitializeForRos2(); + thread->InitializeForRos2(*ros2_adapter_); return thread; } diff --git a/src/cactus_rt/ros2/app.cc b/src/cactus_rt/ros2/app.cc index fc0e938..e6e1699 100644 --- a/src/cactus_rt/ros2/app.cc +++ b/src/cactus_rt/ros2/app.cc @@ -12,7 +12,9 @@ cactus_rt::ThreadConfig Ros2ExecutorThread::CreateThreadConfig() { return thread_config; } -Ros2ExecutorThread::Ros2ExecutorThread() : Thread("ROS2ExecutorThread", CreateThreadConfig()) {} +Ros2ExecutorThread::Ros2ExecutorThread(std::shared_ptr ros2_adapter) + : Thread("ROS2ExecutorThread", CreateThreadConfig()), + ros2_adapter_(ros2_adapter) {} void Ros2ExecutorThread::Run() { rclcpp::ExecutorOptions options; @@ -52,7 +54,7 @@ App::App( // Must initialize rclcpp before making the Ros2Adapter; ros2_adapter_ = std::make_shared(name, ros2_adapter_config); - ros2_executor_thread_ = CreateROS2EnabledThread(); + ros2_executor_thread_ = CreateROS2EnabledThread(ros2_adapter_); } App::~App() {