Skip to content

Commit e6d9bb2

Browse files
committed
c++ action and node fixed
1 parent 69fc142 commit e6d9bb2

File tree

3 files changed

+13
-9
lines changed

3 files changed

+13
-9
lines changed

simple_node/include/simple_node/actions/action_client.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -161,6 +161,10 @@ class ActionClient : public rclcpp_action::Client<ActionT> {
161161
void result_callback(const typename GoalHandle::WrappedResult &result) {
162162
this->result = result.result;
163163
this->set_status(result.code);
164+
165+
std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
166+
this->goal_handle = nullptr;
167+
164168
this->action_done_cond.notify_one();
165169
}
166170

simple_node/include/simple_node/node.hpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -36,13 +36,10 @@ class Node : public rclcpp::Node {
3636
public:
3737
Node(const std::string &name,
3838
const rclcpp::NodeOptions &options = rclcpp::NodeOptions(),
39-
rclcpp::Executor::SharedPtr executor =
40-
std::make_shared<rclcpp::executors::MultiThreadedExecutor>());
39+
rclcpp::Executor::SharedPtr executor = nullptr);
4140
Node(const std::string &name, const std::string &namespace_,
4241
const rclcpp::NodeOptions &options = rclcpp::NodeOptions(),
43-
rclcpp::Executor::SharedPtr executor =
44-
std::make_shared<rclcpp::executors::MultiThreadedExecutor>());
45-
~Node();
42+
rclcpp::Executor::SharedPtr executor = nullptr);
4643

4744
void join_spin();
4845

@@ -123,7 +120,7 @@ class Node : public rclcpp::Node {
123120
private:
124121
rclcpp::CallbackGroup::SharedPtr group;
125122
rclcpp::Executor::SharedPtr executor;
126-
std::thread *spin_thread;
123+
std::unique_ptr<std::thread> spin_thread;
127124

128125
void run_executor();
129126

simple_node/src/simple_node/node.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -26,14 +26,17 @@ Node::Node(const std::string &name, const std::string &namespace_,
2626
rclcpp::Executor::SharedPtr executor)
2727
: rclcpp::Node(name, namespace_, options), executor(executor) {
2828

29+
if (this->executor == nullptr) {
30+
this->executor =
31+
std::make_shared<rclcpp::executors::MultiThreadedExecutor>();
32+
}
33+
2934
rclcpp::CallbackGroup::SharedPtr group =
3035
this->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
3136

32-
this->spin_thread = new std::thread(&Node::run_executor, this);
37+
this->spin_thread = std::make_unique<std::thread>(&Node::run_executor, this);
3338
}
3439

35-
Node::~Node() { delete this->spin_thread; }
36-
3740
void Node::join_spin() {
3841
this->spin_thread->join();
3942
RCLCPP_INFO(this->get_logger(), "Destroying node %s", this->get_name());

0 commit comments

Comments
 (0)