Skip to content

Commit

Permalink
c++ action and node fixed
Browse files Browse the repository at this point in the history
  • Loading branch information
mgonzs13 committed Apr 17, 2024
1 parent 69fc142 commit e6d9bb2
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 9 deletions.
4 changes: 4 additions & 0 deletions simple_node/include/simple_node/actions/action_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,10 @@ class ActionClient : public rclcpp_action::Client<ActionT> {
void result_callback(const typename GoalHandle::WrappedResult &result) {
this->result = result.result;
this->set_status(result.code);

std::lock_guard<std::mutex> lock(this->goal_handle_mutex);
this->goal_handle = nullptr;

this->action_done_cond.notify_one();
}

Expand Down
9 changes: 3 additions & 6 deletions simple_node/include/simple_node/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,10 @@ class Node : public rclcpp::Node {
public:
Node(const std::string &name,
const rclcpp::NodeOptions &options = rclcpp::NodeOptions(),
rclcpp::Executor::SharedPtr executor =
std::make_shared<rclcpp::executors::MultiThreadedExecutor>());
rclcpp::Executor::SharedPtr executor = nullptr);
Node(const std::string &name, const std::string &namespace_,
const rclcpp::NodeOptions &options = rclcpp::NodeOptions(),
rclcpp::Executor::SharedPtr executor =
std::make_shared<rclcpp::executors::MultiThreadedExecutor>());
~Node();
rclcpp::Executor::SharedPtr executor = nullptr);

void join_spin();

Expand Down Expand Up @@ -123,7 +120,7 @@ class Node : public rclcpp::Node {
private:
rclcpp::CallbackGroup::SharedPtr group;
rclcpp::Executor::SharedPtr executor;
std::thread *spin_thread;
std::unique_ptr<std::thread> spin_thread;

void run_executor();

Expand Down
9 changes: 6 additions & 3 deletions simple_node/src/simple_node/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,14 +26,17 @@ Node::Node(const std::string &name, const std::string &namespace_,
rclcpp::Executor::SharedPtr executor)
: rclcpp::Node(name, namespace_, options), executor(executor) {

if (this->executor == nullptr) {
this->executor =
std::make_shared<rclcpp::executors::MultiThreadedExecutor>();
}

rclcpp::CallbackGroup::SharedPtr group =
this->create_callback_group(rclcpp::CallbackGroupType::Reentrant);

this->spin_thread = new std::thread(&Node::run_executor, this);
this->spin_thread = std::make_unique<std::thread>(&Node::run_executor, this);
}

Node::~Node() { delete this->spin_thread; }

void Node::join_spin() {
this->spin_thread->join();
RCLCPP_INFO(this->get_logger(), "Destroying node %s", this->get_name());
Expand Down

0 comments on commit e6d9bb2

Please sign in to comment.