-
Notifications
You must be signed in to change notification settings - Fork 1.8k
Expand file tree
/
Copy pathpipeline_sequence.cpp
More file actions
89 lines (80 loc) · 2.57 KB
/
pipeline_sequence.cpp
File metadata and controls
89 lines (80 loc) · 2.57 KB
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
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
// 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 <stdexcept>
#include <sstream>
#include <string>
#include "nav2_behavior_tree/plugins/control/pipeline_sequence.hpp"
namespace nav2_behavior_tree
{
PipelineSequence::PipelineSequence(const std::string & name)
: BT::ControlNode(name, {})
{
}
PipelineSequence::PipelineSequence(
const std::string & name,
const BT::NodeConfiguration & config)
: BT::ControlNode(name, config)
{
}
BT::NodeStatus PipelineSequence::tick()
{
unsigned skipped_count = 0;
for (std::size_t i = 0; i < children_nodes_.size(); ++i) {
auto status = children_nodes_[i]->executeTick();
switch (status) {
case BT::NodeStatus::FAILURE:
ControlNode::haltChildren();
last_child_ticked_ = 0; // reset
return status;
case BT::NodeStatus::SKIPPED:
skipped_count++;
// do nothing and continue on to the next child.
break;
case BT::NodeStatus::SUCCESS:
// do nothing and continue on to the next child. If it is the last child
// we'll exit the loop and hit the wrap-up code at the end of the method.
break;
case BT::NodeStatus::RUNNING:
if (i >= last_child_ticked_) {
last_child_ticked_ = i;
return status;
}
// else do nothing and continue on to the next child
break;
default:
std::stringstream error_msg;
error_msg << "Invalid node status. Received status " << status <<
"from child " << children_nodes_[i]->name();
throw std::runtime_error(error_msg.str());
}
}
// Wrap up.
ControlNode::haltChildren();
last_child_ticked_ = 0; // reset
if (skipped_count == children_nodes_.size()) {
// All the children were skipped
return BT::NodeStatus::SKIPPED;
}
return BT::NodeStatus::SUCCESS;
}
void PipelineSequence::halt()
{
BT::ControlNode::halt();
last_child_ticked_ = 0;
}
} // namespace nav2_behavior_tree
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<nav2_behavior_tree::PipelineSequence>("PipelineSequence");
}