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

Skip to content

Commit 4bfd6da

Browse files
author
Davide Faconti
committed
[COSMETIC]: non functional change in the code
1 parent f574155 commit 4bfd6da

File tree

5 files changed

+69
-72
lines changed

5 files changed

+69
-72
lines changed

src/controls/fallback_node.cpp

Lines changed: 25 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -22,47 +22,45 @@ FallbackNode::FallbackNode(const std::string& name) : ControlNode::ControlNode(n
2222
NodeStatus FallbackNode::tick()
2323
{
2424
// gets the number of children. The number could change if, at runtime, one edits the tree.
25-
const unsigned N_of_children = children_nodes_.size();
25+
const unsigned children_count = children_nodes_.size();
2626

2727
// Routing the ticks according to the fallback node's logic:
2828

2929
setStatus(NodeStatus::RUNNING);
3030

31-
for (unsigned i = 0; i < N_of_children; i++)
31+
for (unsigned index = 0; index < children_count; index++)
3232
{
33-
TreeNode* child_node = children_nodes_[i];
34-
33+
TreeNode* child_node = children_nodes_[index];
3534
const NodeStatus child_status = child_node->executeTick();
3635

37-
// Ponderate on which status to send to the parent
38-
if (child_status != NodeStatus::FAILURE)
36+
switch( child_status )
3937
{
40-
if (child_status == NodeStatus::SUCCESS)
41-
{
42-
for (unsigned t = 0; t <= i; t++)
43-
{
44-
children_nodes_[t]->setStatus(NodeStatus::IDLE);
45-
}
46-
}
47-
// If the child status is not failure, halt the next children and return the status to your parent.
48-
haltChildren(i + 1);
38+
case NodeStatus::RUNNING:{
4939
return child_status;
5040
}
51-
else
52-
{
53-
// the child returned failure.
54-
if (i == N_of_children - 1)
41+
case NodeStatus::SUCCESS:{
42+
for (unsigned t = 0; t <= index; t++)
5543
{
56-
// If the child status is failure, and it is the last child to be ticked,
57-
// then the sequence has failed.
58-
for (unsigned t = 0; t <= i; t++)
59-
{
60-
children_nodes_[t]->setStatus(NodeStatus::IDLE);
61-
}
62-
return NodeStatus::FAILURE;
44+
children_nodes_[t]->setStatus(NodeStatus::IDLE);
6345
}
46+
haltChildren(index + 1);
47+
return child_status;
6448
}
49+
case NodeStatus::FAILURE: {
50+
// continue;
51+
}break;
52+
53+
case NodeStatus::IDLE:{
54+
throw std::runtime_error("This is not supposed to happen");
55+
}
56+
} // end switch
57+
}// end for loop
58+
59+
for (auto& ch : children_nodes_)
60+
{
61+
ch->setStatus(NodeStatus::IDLE);
6562
}
66-
throw std::runtime_error("This is not supposed to happen");
63+
return NodeStatus::FAILURE;
6764
}
65+
6866
}

src/controls/fallback_star_node.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -24,12 +24,12 @@ FallbackStarNode::FallbackStarNode(const std::string& name)
2424

2525
NodeStatus FallbackStarNode::tick()
2626
{
27-
// Vector size initialization. N_of_children_ could change at runtime if you edit the tree
28-
const unsigned N_of_children = children_nodes_.size();
27+
// Vector size initialization. children_count_ could change at runtime if you edit the tree
28+
const unsigned children_count = children_nodes_.size();
2929

3030
setStatus(NodeStatus::RUNNING);
3131

32-
while (current_child_idx_ < N_of_children)
32+
while (current_child_idx_ < children_count)
3333
{
3434
TreeNode* current_child_node = children_nodes_[current_child_idx_];
3535
const NodeStatus child_status = current_child_node->executeTick();
@@ -61,9 +61,9 @@ NodeStatus FallbackStarNode::tick()
6161
}// end while loop
6262

6363
// The entire while loop completed. This means that all the children returned FAILURE.
64-
if (current_child_idx_ == N_of_children)
64+
if (current_child_idx_ == children_count)
6565
{
66-
for (unsigned t = 0; t < N_of_children; t++)
66+
for (unsigned t = 0; t < children_count; t++)
6767
{
6868
children_nodes_[t]->setStatus(NodeStatus::IDLE);
6969
}

src/controls/parallel_node.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -22,11 +22,11 @@ BT::NodeStatus BT::ParallelNode::tick()
2222
{
2323
success_childred_num_ = 0;
2424
failure_childred_num_ = 0;
25-
// Vector size initialization. N_of_children_ could change at runtime if you edit the tree
26-
const unsigned N_of_children = children_nodes_.size();
25+
// Vector size initialization. children_count_ could change at runtime if you edit the tree
26+
const unsigned children_count = children_nodes_.size();
2727

2828
// Routing the tree according to the sequence node's logic:
29-
for (unsigned int i = 0; i < N_of_children; i++)
29+
for (unsigned int i = 0; i < children_count; i++)
3030
{
3131
TreeNode* child_node = children_nodes_[i];
3232

@@ -46,7 +46,7 @@ BT::NodeStatus BT::ParallelNode::tick()
4646
break;
4747
case NodeStatus::FAILURE:
4848
child_node->setStatus(NodeStatus::IDLE); // the child goes in idle if it has returned failure.
49-
if (++failure_childred_num_ > N_of_children - threshold_M_)
49+
if (++failure_childred_num_ > children_count - threshold_M_)
5050
{
5151
success_childred_num_ = 0;
5252
failure_childred_num_ = 0;

src/controls/sequence_node.cpp

Lines changed: 30 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -13,53 +13,52 @@
1313

1414
#include "behavior_tree_core/controls/sequence_node.h"
1515

16-
BT::SequenceNode::SequenceNode(const std::string& name) : ControlNode::ControlNode(name, NodeParameters())
16+
namespace BT
1717
{
18-
}
1918

20-
BT::NodeStatus BT::SequenceNode::tick()
19+
SequenceNode::SequenceNode(const std::string& name) : ControlNode::ControlNode(name, NodeParameters())
2120
{
22-
// gets the number of children. The number could change if, at runtime, one edits the tree.
23-
const unsigned N_of_children = children_nodes_.size();
21+
}
2422

25-
// Routing the ticks according to the sequence node's logic:
23+
NodeStatus SequenceNode::tick()
24+
{
25+
const unsigned children_count = children_nodes_.size();
2626

2727
setStatus(NodeStatus::RUNNING);
2828

29-
for (unsigned int i = 0; i < N_of_children; i++)
29+
for (unsigned int index = 0; index < children_count; index++)
3030
{
31-
TreeNode* child_node = children_nodes_[i];
32-
31+
TreeNode* child_node = children_nodes_[index];
3332
const NodeStatus child_status = child_node->executeTick();
3433

35-
// Ponderate on which status to send to the parent
36-
if (child_status != NodeStatus::SUCCESS)
34+
switch( child_status )
3735
{
38-
// If the child status is not success, halt the next children and return the status to your parent.
39-
if (child_status == NodeStatus::FAILURE)
40-
{
41-
for (unsigned t = 0; t <= i; t++)
36+
case NodeStatus::RUNNING:{
37+
return child_status;
38+
}
39+
case NodeStatus::FAILURE:{
40+
for (unsigned t = 0; t <= index; t++)
4241
{
4342
children_nodes_[t]->setStatus(NodeStatus::IDLE);
4443
}
44+
haltChildren(index + 1);
45+
return child_status;
4546
}
47+
case NodeStatus::SUCCESS: {
48+
// continue;
49+
}break;
4650

47-
haltChildren(i + 1);
48-
return child_status;
49-
}
50-
else
51-
{
52-
if (i == N_of_children - 1)
53-
{
54-
// If the child status is success, and it is the last child to be ticked,
55-
// then the sequence has succeeded.
56-
for (auto& ch : children_nodes_)
57-
{
58-
ch->setStatus(NodeStatus::IDLE);
59-
}
60-
return NodeStatus::SUCCESS;
51+
case NodeStatus::IDLE:{
52+
throw std::runtime_error("This is not supposed to happen");
6153
}
62-
}
54+
} // end switch
55+
}// end for loop
56+
57+
for (auto& ch : children_nodes_)
58+
{
59+
ch->setStatus(NodeStatus::IDLE);
6360
}
64-
throw std::runtime_error("This is not supposed to happen");
61+
return NodeStatus::SUCCESS;
62+
}
63+
6564
}

src/controls/sequence_star_node.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -33,12 +33,12 @@ SequenceStarNode::SequenceStarNode(const std::string& name, const NodeParameters
3333

3434
NodeStatus SequenceStarNode::tick()
3535
{
36-
// Vector size initialization. N_of_children_ could change at runtime if you edit the tree
37-
const unsigned N_of_children = children_nodes_.size();
36+
// Vector size initialization. children_count_ could change at runtime if you edit the tree
37+
const unsigned children_count = children_nodes_.size();
3838

3939
setStatus(NodeStatus::RUNNING);
4040

41-
while (current_child_idx_ < N_of_children)
41+
while (current_child_idx_ < children_count)
4242
{
4343
TreeNode* current_child_node = children_nodes_[current_child_idx_];
4444
const NodeStatus child_status = current_child_node->executeTick();
@@ -77,9 +77,9 @@ NodeStatus SequenceStarNode::tick()
7777

7878

7979
// The entire while loop completed. This means that all the children returned SUCCESS.
80-
if (current_child_idx_ == N_of_children)
80+
if (current_child_idx_ == children_count)
8181
{
82-
for (unsigned t = 0; t < N_of_children; t++)
82+
for (unsigned t = 0; t < children_count; t++)
8383
{
8484
children_nodes_[t]->setStatus(NodeStatus::IDLE);
8585
}

0 commit comments

Comments
 (0)