Skip to content

Commit

Permalink
Add joinable
Browse files Browse the repository at this point in the history
Signed-off-by: Carlos San Vicente <carlos.svic@gmail.com>
  • Loading branch information
carlossvg committed Jul 9, 2021
1 parent 4828f40 commit df87d38
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 4 deletions.
4 changes: 3 additions & 1 deletion rclcpp/minimal_subscriber/static_wait_set.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,9 @@ class MinimalSubscriber : public rclcpp::Node

~MinimalSubscriber()
{
thread_.join();
if (thread_.joinable()) {
thread_.join();
}
}

void spin_wait_set()
Expand Down
4 changes: 3 additions & 1 deletion rclcpp/minimal_subscriber/wait_set.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,9 @@ class MinimalSubscriber : public rclcpp::Node

~MinimalSubscriber()
{
thread_.join();
if (thread_.joinable()) {
thread_.join();
}
}

void spin_wait_set()
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/wait_set/include/wait_set/listener.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class Listener : public rclcpp::Node
{
public:
WAIT_SET_PUBLIC explicit Listener(rclcpp::NodeOptions options);
WAIT_SET_PUBLIC ~Listener();
WAIT_SET_PUBLIC ~Listener() override;

private:
void spin_wait_set();
Expand Down
4 changes: 3 additions & 1 deletion rclcpp/wait_set/src/listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,9 @@ Listener::Listener(rclcpp::NodeOptions options)

Listener::~Listener()
{
thread_.join();
if (thread_.joinable()) {
thread_.join();
}
}

void Listener::spin_wait_set()
Expand Down

0 comments on commit df87d38

Please sign in to comment.