Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Hide Ros2Adapter from threads #139

Merged
merged 1 commit into from
Sep 11, 2024
Merged
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
2 changes: 1 addition & 1 deletion docs/imgs/ROS2Ownership.svg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
4 changes: 2 additions & 2 deletions examples/ros2/publisher/complex_data.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<RealtimeType, RosType>("/cactus_rt/complex", rclcpp::QoS(100));
void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override {
publisher_ = ros2_adapter.CreatePublisher<RealtimeType, RosType>("/cactus_rt/complex", rclcpp::QoS(100));
}

protected:
Expand Down
4 changes: 2 additions & 2 deletions examples/ros2/publisher/simple_data.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<RealtimeType, RosType, false>("/cactus_rt/simple", rclcpp::QoS(100));
void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override {
publisher_ = ros2_adapter.CreatePublisher<RealtimeType, RosType, false>("/cactus_rt/simple", rclcpp::QoS(100));
}

protected:
Expand Down
4 changes: 2 additions & 2 deletions examples/ros2/subscriber/complex_data.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<RealtimeType, RosType>("/cactus_rt/complex", rclcpp::QoS(100));
void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override {
subscription_ = ros2_adapter.CreateSubscriptionForLatestValue<RealtimeType, RosType>("/cactus_rt/complex", rclcpp::QoS(100));
}

protected:
Expand Down
4 changes: 2 additions & 2 deletions examples/ros2/subscriber/queued_data.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<RealtimeType, RosType, false>("/cactus_rt/simple", rclcpp::QoS(100));
void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override {
subscription_ = ros2_adapter.CreateSubscriptionQueued<RealtimeType, RosType, false>("/cactus_rt/simple", rclcpp::QoS(100));
}

protected:
Expand Down
4 changes: 2 additions & 2 deletions examples/ros2/subscriber/simple_data.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<RealtimeType, RosType, false>("/cactus_rt/simple", rclcpp::QoS(100));
void InitializeForRos2(cactus_rt::ros2::Ros2Adapter& ros2_adapter) override {
subscription_ = ros2_adapter.CreateSubscriptionForLatestValue<RealtimeType, RosType, false>("/cactus_rt/simple", rclcpp::QoS(100));
}

protected:
Expand Down
20 changes: 5 additions & 15 deletions include/cactus_rt/ros2/app.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,32 +12,23 @@ namespace cactus_rt::ros2 {
class App;

class Ros2ThreadMixin {
friend class App;

protected:
std::shared_ptr<Ros2Adapter> ros2_adapter_;

private:
void SetRos2Adapter(std::shared_ptr<Ros2Adapter> 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<Ros2Adapter> ros2_adapter_;
std::optional<rclcpp::executors::SingleThreadedExecutor> executor_;

static cactus_rt::ThreadConfig CreateThreadConfig();

public:
Ros2ExecutorThread();
explicit Ros2ExecutorThread(std::shared_ptr<Ros2Adapter> ros2_adapter);

void Run() override;

void InitializeForRos2() override {}
void InitializeForRos2(Ros2Adapter& /*ros2_adapter*/) override {}
};

class App : public cactus_rt::App {
Expand All @@ -63,8 +54,7 @@ class App : public cactus_rt::App {
static_assert(std::is_base_of_v<Ros2ThreadMixin, ThreadT>, "Must derive ROS2 thread from Ros2ThreadMixin");
std::shared_ptr<ThreadT> thread = CreateThread<ThreadT>(std::forward<Args>(args)...);

thread->SetRos2Adapter(ros2_adapter_);
thread->InitializeForRos2();
thread->InitializeForRos2(*ros2_adapter_);

return thread;
}
Expand Down
6 changes: 4 additions & 2 deletions src/cactus_rt/ros2/app.cc
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,9 @@ cactus_rt::ThreadConfig Ros2ExecutorThread::CreateThreadConfig() {
return thread_config;
}

Ros2ExecutorThread::Ros2ExecutorThread() : Thread("ROS2ExecutorThread", CreateThreadConfig()) {}
Ros2ExecutorThread::Ros2ExecutorThread(std::shared_ptr<Ros2Adapter> ros2_adapter)
: Thread("ROS2ExecutorThread", CreateThreadConfig()),
ros2_adapter_(ros2_adapter) {}

void Ros2ExecutorThread::Run() {
rclcpp::ExecutorOptions options;
Expand Down Expand Up @@ -52,7 +54,7 @@ App::App(

// Must initialize rclcpp before making the Ros2Adapter;
ros2_adapter_ = std::make_shared<Ros2Adapter>(name, ros2_adapter_config);
ros2_executor_thread_ = CreateROS2EnabledThread<Ros2ExecutorThread>();
ros2_executor_thread_ = CreateROS2EnabledThread<Ros2ExecutorThread>(ros2_adapter_);
}

App::~App() {
Expand Down
Loading