-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
node_thread.cpp
50 lines (44 loc) · 1.3 KB
/
node_thread.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
// Copyright (c) 2019 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <memory>
#include "nav2_util/node_thread.hpp"
namespace nav2_util
{
NodeThread::NodeThread(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base)
: node_(node_base)
{
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
thread_ = std::make_unique<std::thread>(
[&]()
{
executor_->add_node(node_);
executor_->spin();
executor_->remove_node(node_);
});
}
NodeThread::NodeThread(rclcpp::executors::SingleThreadedExecutor::SharedPtr executor)
: executor_(executor)
{
thread_ = std::make_unique<std::thread>(
[&]() {
executor_->spin();
});
}
NodeThread::~NodeThread()
{
executor_->cancel();
thread_->join();
}
} // namespace nav2_util