Skip to content

Commit 5e8e2da

Browse files
committed
fix compilation and unit tests
1 parent 02330ac commit 5e8e2da

File tree

4 files changed

+20
-11
lines changed

4 files changed

+20
-11
lines changed

CMakeLists.txt

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,18 +18,19 @@ if(Boost_FOUND)
1818
include_directories(${Boost_INCLUDE_DIRS})
1919
message(STATUS "Found boost::coroutine2.")
2020
add_definitions(-DBT_BOOST_COROUTINE2)
21+
set(BT_COROUTINES true)
2122
else()
2223
find_package(Boost COMPONENTS coroutine QUIET)
2324
if(Boost_FOUND)
2425
message(STATUS "Found boost::coroutine.")
2526
include_directories(${Boost_INCLUDE_DIRS})
2627
add_definitions(-DBT_BOOST_COROUTINE)
28+
set(BT_COROUTINES true)
2729
else()
2830
add_definitions(-DBT_NO_COROUTINES)
2931
endif()
3032
endif()
3133

32-
3334
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
3435

3536
set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake")

examples/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ target_link_libraries(t07_wrap_legacy ${BEHAVIOR_TREE_LIBRARY} )
3535
add_executable(t08_additional_node_args t08_additional_node_args.cpp )
3636
target_link_libraries(t08_additional_node_args ${BEHAVIOR_TREE_LIBRARY} )
3737

38-
if (NOT MINGW)
38+
if (BT_COROUTINES)
3939
add_executable(t09_async_actions_coroutines t09_async_actions_coroutines.cpp )
4040
target_link_libraries(t09_async_actions_coroutines ${BEHAVIOR_TREE_LIBRARY} )
4141
endif()

tests/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ set(BT_TESTS
1919
gtest_switch.cpp
2020
)
2121

22-
if (NOT MINGW)
22+
if (BT_COROUTINES)
2323
list(APPEND BT_TESTS gtest_coroutines.cpp)
2424
endif()
2525

tests/navigation_test.cpp

Lines changed: 16 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -110,28 +110,36 @@ class ComputePathToPose: public SyncActionNode, public TestNode
110110
}
111111
};
112112

113-
class FollowPath: public CoroActionNode, public TestNode
113+
class FollowPath: public ActionNodeBase, public TestNode
114114
{
115+
std::chrono::high_resolution_clock::time_point _initial_time;
115116
public:
116-
FollowPath(const std::string& name): CoroActionNode(name, {}), TestNode(name), _halted(false){}
117+
FollowPath(const std::string& name): ActionNodeBase(name, {}), TestNode(name), _halted(false){}
117118

118119
NodeStatus tick() override
119120
{
120-
_halted = false;
121-
std::cout << "FollowPath::started" << std::endl;
122-
auto initial_time = Now();
121+
if( status() == NodeStatus::IDLE )
122+
{
123+
setStatus(NodeStatus::RUNNING);
124+
_halted = false;
125+
std::cout << "FollowPath::started" << std::endl;
126+
_initial_time = Now();
127+
}
123128

124129
// Yield for 1 second
125-
while( Now() < initial_time + Milliseconds(600) )
130+
while( Now() < _initial_time + Milliseconds(600) || _halted )
131+
{
132+
return NodeStatus::RUNNING;
133+
}
134+
if( _halted )
126135
{
127-
setStatusRunningAndYield();
136+
return NodeStatus::IDLE;
128137
}
129138
return tickImpl();
130139
}
131140
void halt() override {
132141
std::cout << "FollowPath::halt" << std::endl;
133142
_halted = true;
134-
CoroActionNode::halt();
135143
}
136144

137145
bool wasHalted() const { return _halted; }

0 commit comments

Comments
 (0)