Thanks to visit codestin.com
Credit goes to github.com

Skip to content

Commit 295eb1f

Browse files
author
Davide Faconti
committed
simplified policy of nodes with memory
1 parent ec3d37c commit 295eb1f

File tree

8 files changed

+143
-185
lines changed

8 files changed

+143
-185
lines changed

include/behavior_tree_core/basic_types.h

Lines changed: 1 addition & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -48,12 +48,7 @@ enum FailurePolicy
4848
FAIL_ON_ONE,
4949
FAIL_ON_ALL
5050
};
51-
enum ResetPolicy
52-
{
53-
ON_SUCCESS_OR_FAILURE,
54-
ON_SUCCESS,
55-
ON_FAILURE
56-
};
51+
5752

5853
// Enumerates the options for when a parallel node is considered to have succeeded:
5954
// - "SUCCEED_ON_ONE" indicates that the node will return success as soon as one
@@ -85,13 +80,6 @@ const char* toStr(const BT::NodeType& type);
8580

8681
std::ostream& operator<<(std::ostream& os, const BT::NodeType& type);
8782

88-
/**
89-
* @brief toStr converts ResetPolicy to string.
90-
*/
91-
const char* toStr(const BT::ResetPolicy& policy);
92-
93-
std::ostream& operator<<(std::ostream& os, const BT::ResetPolicy& type);
94-
9583
// small utility, unless you want to use <boost/algorithm/string.hpp>
9684
std::vector<std::string> splitString(const std::string& strToSplit, char delimeter);
9785

include/behavior_tree_core/controls/fallback_node.h

Lines changed: 8 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -20,20 +20,17 @@ namespace BT
2020
{
2121

2222
/**
23-
* @brief The FallbackNode is used when you want to evaluate different "strategies".
23+
* @brief The FallbackNode is used to try different strategies,
24+
* until one succeed.
25+
* If any child returns RUNNING, previous children will be ticked again.
2426
*
25-
* This control node ticks its children UNTIL one of them returns SUCCESS.
27+
* - If all the children return FAILURE, this node returns FAILURE.
2628
*
27-
* In that case it return SUCCESS, otherwise it return FAILURE.
28-
* If it finds a child returning RUNNING, it returns RUNNING and it restarts from the first child.
29+
* - If a child returns RUNNING, this node returns RUNNING.
30+
* The loop is restarted, but already completed children are not halted.
31+
* This generally implies that ConditionNode are ticked again.
2932
*
30-
* If you don't want to restart from the first child, use FallbackNodeWithMemory instead.
31-
*
32-
* Example: three children, A, B and C
33-
*
34-
* 1) A returns FAILURE. Continue.
35-
* 2) B returns RUNNING, Restart from A
36-
* 3) A returns FAILURE again but B return SUCCESS. Stop and return SUCCESS.
33+
* - If a child returns SUCCESS, stop the loop and returns SUCCESS.
3734
*
3835
*/
3936
class FallbackNode : public ControlNode

include/behavior_tree_core/controls/fallback_node_with_memory.h

Lines changed: 8 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -20,46 +20,28 @@ namespace BT
2020
{
2121

2222
/**
23-
* @brief The FallbackNodeWithMemory is used when you want to evaluate different "strategies".
23+
* @brief The FallbackNodeWithMemory is used to try different strategies,
24+
* until one succeed.
25+
* If any child returns RUNNING, previous children will NOT be ticked again.
2426
*
25-
* This control node ticks its children UNTIL one of them returns SUCCESS.
27+
* - If all the children return FAILURE, this node returns FAILURE.
2628
*
27-
* In that case it returns SUCCESS, otherwise it returns FAILURE.
28-
* If a child return RUNNING, this node returns RUNNING and at the next tick it will continue
29-
* from the same index.
30-
* It is recommended for asynchronous children which may return RUNNING.
31-
*
32-
* Example: three children, A, B and C
33-
*
34-
* 1) A returns FAILURE. Continue.
35-
* 2) B returns RUNNING. Stop and return RUNNING.
36-
* 3) B is ticked again but it returns SUCCESS. Stop and return SUCCESS.
29+
* - If a child returns RUNNING, this node returns RUNNING.
30+
* Loop is NOT restarted, the same running child will be ticked again.
3731
*
32+
* - If a child returns SUCCESS, stop the loop and returns SUCCESS.
3833
*/
3934

4035
class FallbackNodeWithMemory : public ControlNode
4136
{
4237
public:
43-
FallbackNodeWithMemory(const std::string& name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE);
44-
45-
// Reset policy passed by parameter [reset_policy]
46-
FallbackNodeWithMemory(const std::string&, const NodeParameters& params);
47-
48-
virtual ~FallbackNodeWithMemory() override = default;
38+
FallbackNodeWithMemory(const std::string& name);
4939

5040
virtual void halt() override;
5141

52-
static const NodeParameters& requiredNodeParameters()
53-
{
54-
static NodeParameters params = {{RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)}};
55-
return params;
56-
}
57-
5842
private:
5943
unsigned int current_child_idx_;
60-
ResetPolicy reset_policy_;
6144

62-
constexpr static const char* RESET_POLICY = "reset_policy";
6345
virtual BT::NodeStatus tick() override;
6446
};
6547
}

include/behavior_tree_core/controls/sequence_node.h

Lines changed: 7 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -19,22 +19,17 @@
1919
namespace BT
2020
{
2121
/**
22-
* @brief The SequenceNode is used to execute a sequence of synchronous children.
22+
* @brief The SequenceNode is used to execute a sequence of children.
23+
* If any child returns RUNNING, previous children will be ticked again.
2324
*
24-
* This control node ticks its children AS LONG AS they returns SUCCESS.
25+
* - If all the children return SUCCESS, this node returns SUCCESS.
2526
*
26-
* If all the children return SUCCESS, the sequence is SUCCESS.
27-
* If any return FAILURE, the sequence returns FAILURE and it starts from the beginning.
28-
* If a child returns RUNNING, this node returns RUNNING and at the next tick it will continue
29-
* from the same index.
30-
* It is recommended for asynchronous children which may return RUNNING.
27+
* - If a child returns RUNNING, this node returns RUNNING.
28+
* The loop is restarted, but already completed children are not halted.
29+
* This generally implies that ConditionNode are ticked again.
3130
*
32-
* Example: three children, A , B and C
31+
* - If a child returns FAILURE, stop the loop and returns FAILURE.
3332
*
34-
* 1) A returns SUCCESS. Continue.
35-
* 2) B returns RUNNING. Stop and return RUNNING.
36-
* 3) A is ticked again and return SUCCESS. B is ticked and retuns SUCCESS. Continue.
37-
* 4) C returns SUCCESS. The entire sequence returns SUCCESS.
3833
*/
3934
class SequenceNode : public ControlNode
4035
{

include/behavior_tree_core/controls/sequence_node_with_memory.h

Lines changed: 11 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -20,24 +20,23 @@ namespace BT
2020
{
2121

2222
/**
23-
* @brief The SequenceNode is used to execute a sequence of asynchronous children.
23+
* @brief The SequenceNodeWithMemory is used to execute a sequence of children.
24+
* If any child returns RUNNING, previous children are not ticked again.
2425
*
25-
* Tick all the children as long as they return SUCCESS.
26-
* If any child return FAILURE, stop the sequence and return FAILURE.
27-
* If any child return RUNNING, stop the sequence, return RUNNING. Restart from the same child
26+
* - If all the children return SUCCESS, this node returns SUCCESS.
2827
*
29-
* Example: three children, A , B and C
28+
* - If a child returns RUNNING, this node returns RUNNING.
29+
* Loop is NOT restarted, the same running child will be ticked again.
30+
*
31+
* - If a child returns FAILURE, stop the loop and returns FAILURE.
32+
* Restart the loop only if (reset_on_failure == true)
3033
*
31-
* 1) A returns SUCCESS. Continue.
32-
* 2) B returns RUNNING. Stop and return RUNNING.
33-
* 3) B is ticked and retuns SUCCESS. Continue.
34-
* 4) C returns SUCCESS. The entire sequence returns SUCCESS.
3534
*/
3635

3736
class SequenceNodeWithMemory : public ControlNode
3837
{
3938
public:
40-
SequenceNodeWithMemory(const std::string& name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE);
39+
SequenceNodeWithMemory(const std::string& name, bool reset_on_failure = true);
4140

4241
// Reset policy passed by parameter [reset_policy]
4342
SequenceNodeWithMemory(const std::string& name, const NodeParameters& params);
@@ -48,15 +47,14 @@ class SequenceNodeWithMemory : public ControlNode
4847

4948
static const NodeParameters& requiredNodeParameters()
5049
{
51-
static NodeParameters params = {{RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)}};
50+
static NodeParameters params = {{"reset_on_failure", "true"}};
5251
return params;
5352
}
5453

5554
private:
5655
unsigned int current_child_idx_;
57-
ResetPolicy reset_policy_;
56+
bool reset_on_failure_;
5857

59-
static constexpr const char* RESET_POLICY = "reset_policy";
6058
virtual BT::NodeStatus tick() override;
6159
};
6260
}

src/basic_types.cpp

Lines changed: 40 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -63,21 +63,6 @@ const char* toStr(const NodeType& type)
6363
}
6464
}
6565

66-
const char* toStr(const ResetPolicy& policy)
67-
{
68-
switch (policy)
69-
{
70-
case ResetPolicy::ON_FAILURE:
71-
return "ON_FAILURE";
72-
case ResetPolicy::ON_SUCCESS:
73-
return "ON_SUCCESS";
74-
case ResetPolicy::ON_SUCCESS_OR_FAILURE:
75-
return "ON_SUCCESS_OR_FAILURE";
76-
default:
77-
return "Undefined";
78-
}
79-
}
80-
8166
template <>
8267
std::string convertFromString<std::string>(const std::string& str)
8368
{
@@ -110,45 +95,73 @@ double convertFromString<double>(const std::string& str)
11095
}
11196

11297
template <>
113-
NodeStatus convertFromString<NodeStatus>(const std::string& str)
98+
bool convertFromString<bool>(const std::string& str)
11499
{
115-
for (auto status : {NodeStatus::IDLE, NodeStatus::RUNNING, NodeStatus::SUCCESS, NodeStatus::FAILURE})
100+
if( str.size() == 1)
116101
{
117-
if (std::strcmp(toStr(status), str.c_str()) == 0)
102+
if ( str[0] == '0'){
103+
return false;
104+
}
105+
else if( str[0] == '1'){
106+
return true;
107+
}
108+
else{
109+
std::runtime_error("invalid bool conversion");
110+
}
111+
}
112+
else if( str.size() == 4)
113+
{
114+
if( str == "true" || str == "TRUE" || str == "True")
118115
{
119-
return status;
116+
return true;
117+
}
118+
else{
119+
std::runtime_error("invalid bool conversion");
120120
}
121121
}
122-
throw std::invalid_argument(std::string("Cannot convert this to NodeStatus: ") + str);
122+
else if( str.size() == 5)
123+
{
124+
if( str == "false" || str == "FALSE" || str == "False")
125+
{
126+
return false;
127+
}
128+
else{
129+
std::runtime_error("invalid bool conversion");
130+
}
131+
}
132+
133+
std::runtime_error("invalid bool conversion");
134+
return false;
123135
}
124136

125137
template <>
126-
NodeType convertFromString<NodeType>(const std::string& str)
138+
NodeStatus convertFromString<NodeStatus>(const std::string& str)
127139
{
128-
for (auto status : {NodeType::ACTION, NodeType::CONDITION, NodeType::CONTROL, NodeType::DECORATOR,
129-
NodeType::SUBTREE, NodeType::UNDEFINED})
140+
for (auto status : {NodeStatus::IDLE, NodeStatus::RUNNING, NodeStatus::SUCCESS, NodeStatus::FAILURE})
130141
{
131142
if (std::strcmp(toStr(status), str.c_str()) == 0)
132143
{
133144
return status;
134145
}
135146
}
136-
throw std::invalid_argument(std::string("Cannot convert this to NodeType: ") + str);
147+
throw std::invalid_argument(std::string("Cannot convert this to NodeStatus: ") + str);
137148
}
138149

139150
template <>
140-
ResetPolicy convertFromString<ResetPolicy>(const std::string& str)
151+
NodeType convertFromString<NodeType>(const std::string& str)
141152
{
142-
for (auto status : {ResetPolicy::ON_SUCCESS, ResetPolicy::ON_SUCCESS_OR_FAILURE, ResetPolicy::ON_FAILURE})
153+
for (auto status : {NodeType::ACTION, NodeType::CONDITION, NodeType::CONTROL, NodeType::DECORATOR,
154+
NodeType::SUBTREE, NodeType::UNDEFINED})
143155
{
144156
if (std::strcmp(toStr(status), str.c_str()) == 0)
145157
{
146158
return status;
147159
}
148160
}
149-
throw std::invalid_argument(std::string("Cannot convert this to ResetPolicy: ") + str);
161+
throw std::invalid_argument(std::string("Cannot convert this to NodeType: ") + str);
150162
}
151163

164+
152165
std::ostream &operator<<(std::ostream &os, const NodeType &type)
153166
{
154167
os << toStr(type);
@@ -161,11 +174,6 @@ std::ostream &operator<<(std::ostream &os, const NodeStatus &status)
161174
return os;
162175
}
163176

164-
std::ostream &operator<<(std::ostream &os, const ResetPolicy &type)
165-
{
166-
os << toStr(type);
167-
return os;
168-
}
169177

170178
std::vector<std::string> splitString(const std::string &strToSplit, char delimeter)
171179
{

0 commit comments

Comments
 (0)