Skip to content

Commit 547052f

Browse files
committed
cleanup
1 parent 177fff0 commit 547052f

File tree

6 files changed

+58
-105
lines changed

6 files changed

+58
-105
lines changed

src/controls/reactive_fallback.cpp

Lines changed: 4 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/* Copyright (C) 2019 Davide Faconti, Eurecat - All Rights Reserved
2-
*
2+
* Copyright (C) 2019 Michele Colledanchise - All Rights Reserved
33
* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
44
* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
55
* and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
@@ -33,24 +33,15 @@ NodeStatus ReactiveFallback::tick()
3333
{
3434
if (current_child_node->status() != NodeStatus::RUNNING)
3535
{
36-
// if not running already, tick it
37-
38-
if (parent_prt_ == nullptr)
39-
{
40-
// std::cout << name() << " is root" << std::endl;
36+
/* if not running already, tick it. I assume that ACTION_ASYNC returns running for (at least the first tick),
37+
hence the halt of possibly other async actions should be sent before ticking current_child_node */
4138

42-
}
43-
else
39+
if (parent_prt_ != nullptr)
4440
{
4541

46-
// std::cout << name() << " is propagating halt to" << ((ControlNode*)parent_prt_)->name() << std::endl;
47-
48-
4942
parent_prt_->propagateHalt(child_index_);
5043
}
5144

52-
53-
5445
current_child_node->executeTick();
5546
do
5647
{

src/controls/reactive_sequence.cpp

Lines changed: 4 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/* Copyright (C) 2019 Davide Faconti, Eurecat - All Rights Reserved
2-
*
2+
* Copyright (C) 2019 Michele Colledanchise - All Rights Reserved
33
* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
44
* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
55
* and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
@@ -36,20 +36,12 @@ NodeStatus ReactiveSequence::tick()
3636
{
3737
if (current_child_node->status() != NodeStatus::RUNNING)
3838
{
39-
// if not running already, tick it
40-
//before ticking it, make sure to halt the other running child.
41-
42-
if (parent_prt_ == nullptr)
43-
{
44-
// std::cout << name() << " is root" << std::endl;
39+
/* if not running already, tick it. I assume that ACTION_ASYNC returns running for (at least the first tick),
40+
hence the halt of possibly other async actions should be sent before ticking current_child_node */
4541

46-
}
47-
else
42+
if (parent_prt_ != nullptr)
4843
{
4944

50-
// std::cout << name() << " is propagating halt to" << ((ControlNode*)parent_prt_)->name() << std::endl;
51-
52-
5345
parent_prt_->propagateHalt(child_index_);
5446
}
5547

tests/CMakeLists.txt

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -6,18 +6,18 @@ include_directories(include)
66
set(BT_TESTS
77
src/action_test_node.cpp
88
src/condition_test_node.cpp
9-
# gtest_tree.cpp
10-
# gtest_sequence.cpp
11-
# gtest_parallel.cpp
12-
# gtest_fallback.cpp
13-
# gtest_factory.cpp
14-
# gtest_decorator.cpp
15-
# gtest_blackboard.cpp
16-
# gtest_coroutines.cpp
17-
# navigation_test.cpp
18-
# gtest_subtree.cpp
19-
#gtest_reactive_sequence.cpp
20-
gtest_reactive_tree.cpp
9+
gtest_tree.cpp
10+
gtest_sequence.cpp
11+
gtest_parallel.cpp
12+
gtest_fallback.cpp
13+
gtest_factory.cpp
14+
gtest_decorator.cpp
15+
gtest_blackboard.cpp
16+
gtest_coroutines.cpp
17+
navigation_test.cpp
18+
gtest_subtree.cpp
19+
gtest_reactive_sequence.cpp
20+
gtest_reactive_tree.cpp
2121

2222
)
2323

tests/gtest_reactive_tree.cpp

Lines changed: 2 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -64,29 +64,6 @@ struct ComplexReactiveTree : testing::Test
6464
TEST_F(ComplexReactiveTree, ConditionsFalse)
6565
{
6666

67-
68-
// std::cout << fal_1.name() << " is the child of " << fal_1.parent_prt_->name() << std::endl;
69-
// std::cout << fal_2.name() << " is the child of " << fal_2.parent_prt_->name() << std::endl;
70-
71-
// std::cout << action_1.name() << " is the child of " << action_1.parent_prt_->name() << std::endl;
72-
// std::cout << action_2.name() << " is the child of " << action_2.parent_prt_->name() << std::endl;
73-
74-
// std::cout << condition_1.name() << " is the child of " << condition_1.parent_prt_->name() << std::endl;
75-
// std::cout << condition_2.name() << " is the child of " << condition_2.parent_prt_->name() << std::endl;
76-
77-
78-
if (root.parent_prt() == nullptr)
79-
{
80-
std::cout << root.name() << " is root" << std::endl;
81-
82-
}
83-
else
84-
{
85-
std::cout << root.name() << " is the child of " << root.parent_prt()->name() << std::endl;
86-
}
87-
88-
89-
9067
auto t0 = std::chrono::high_resolution_clock::now();
9168

9269

@@ -105,9 +82,7 @@ TEST_F(ComplexReactiveTree, ConditionsFalse)
10582

10683
std::this_thread::sleep_for(milliseconds(300));
10784

108-
std::cout << "condition 1 set to true" << std::endl;
109-
110-
condition_1.setBoolean(true);
85+
condition_1.setBoolean(true); // condition 1 set to true"
11186

11287
state = root.executeTick();
11388

@@ -122,22 +97,13 @@ TEST_F(ComplexReactiveTree, ConditionsFalse)
12297

12398

12499
std::this_thread::sleep_for(milliseconds(300));
125-
condition_1.setBoolean(false);
100+
condition_1.setBoolean(false); // condition 1 set to false"
126101

127-
std::cout << "condition 1 set to false" << std::endl;
128-
129-
130-
// std::cout << "Ticking..." << std::endl;
131102
state = root.executeTick();
132-
// std::cout << "...done" << std::endl;
133-
134103

135104

136105
std::this_thread::sleep_for(milliseconds(300));
137106

138-
// std::cout << action_1.startTimePoint().time_since_epoch().count() << std::endl;
139-
// std::cout << action_2.stopTimePoint().time_since_epoch().count() << std::endl;
140-
141107
ASSERT_TRUE(action_1.startTimePoint().time_since_epoch().count() >
142108
action_2.stopTimePoint().time_since_epoch().count() );
143109

tests/include/action_test_node.h

Lines changed: 5 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -59,38 +59,11 @@ class AsyncActionTest : public AsyncActionNode
5959
tick_count_ = 0;
6060
}
6161

62-
void setStartTimePoint(std::chrono::high_resolution_clock::time_point now)
63-
{
64-
std::lock_guard<std::mutex> lock(start_time_mutex_);
65-
// std::cout << this->name() << " Setting Start Time: " << now.time_since_epoch().count() << std::endl;
66-
67-
start_time_ = now;
68-
}
69-
70-
std::chrono::high_resolution_clock::time_point startTimePoint()
71-
{
72-
std::lock_guard<std::mutex> lock(start_time_mutex_);
73-
74-
return start_time_;
75-
}
76-
77-
78-
void setStopTimePoint(std::chrono::high_resolution_clock::time_point now)
79-
{
80-
std::lock_guard<std::mutex> lock(stop_time_mutex_);
81-
82-
// std::cout << this->name() << " Setting Stop Time: " << now.time_since_epoch().count() << std::endl;
83-
84-
stop_time_ = now;
85-
}
86-
87-
std::chrono::high_resolution_clock::time_point stopTimePoint()
88-
{
89-
std::lock_guard<std::mutex> lock(stop_time_mutex_);
90-
91-
return stop_time_;
92-
}
9362

63+
void setStartTimePoint(std::chrono::high_resolution_clock::time_point now);
64+
std::chrono::high_resolution_clock::time_point startTimePoint() const;
65+
void setStopTimePoint(std::chrono::high_resolution_clock::time_point now);
66+
std::chrono::high_resolution_clock::time_point stopTimePoint() const;
9467

9568
private:
9669
// using atomic because these variables might be accessed from different threads
@@ -100,7 +73,7 @@ class AsyncActionTest : public AsyncActionNode
10073
std::atomic_bool stop_loop_;
10174
std::chrono::high_resolution_clock::time_point start_time_, stop_time_;
10275

103-
std::mutex start_time_mutex_, stop_time_mutex_;
76+
mutable std::mutex start_time_mutex_, stop_time_mutex_;
10477

10578
};
10679
}

tests/src/action_test_node.cpp

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -98,6 +98,37 @@ void BT::AsyncActionTest::setBoolean(bool boolean_value)
9898
boolean_value_ = boolean_value;
9999
}
100100

101+
102+
void BT::AsyncActionTest::setStartTimePoint(std::chrono::high_resolution_clock::time_point now)
103+
{
104+
std::lock_guard<std::mutex> lock(start_time_mutex_);
105+
106+
start_time_ = now;
107+
}
108+
109+
std::chrono::high_resolution_clock::time_point BT::AsyncActionTest::startTimePoint() const
110+
{
111+
std::lock_guard<std::mutex> lock(start_time_mutex_);
112+
113+
return start_time_;
114+
}
115+
116+
117+
void BT::AsyncActionTest::setStopTimePoint(std::chrono::high_resolution_clock::time_point now)
118+
{
119+
std::lock_guard<std::mutex> lock(stop_time_mutex_);
120+
121+
stop_time_ = now;
122+
}
123+
124+
std::chrono::high_resolution_clock::time_point BT::AsyncActionTest::stopTimePoint() const
125+
{
126+
std::lock_guard<std::mutex> lock(stop_time_mutex_);
127+
128+
return stop_time_;
129+
}
130+
131+
101132
//----------------------------------------------
102133

103134
BT::SyncActionTest::SyncActionTest(const std::string& name) :

0 commit comments

Comments
 (0)