From aaf764aea1527ddf4536ffcd6711948c74cd0a7c Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Apr 2018 21:59:55 +0200 Subject: [PATCH 001/125] Cattkinize (optional) and remove openGL from cmake --- .travis.yml | 28 +- CMakeLists.txt | 234 +++----- gtest/gtest_tree.cpp | 6 +- gtest/include/action_test_node.h | 2 +- gtest/include/condition_test_node.h | 2 +- gtest/src/action_test_node.cpp | 2 +- gtest/src/condition_test_node.cpp | 2 +- include/behavior_tree.h | 38 -- include/{ => behavior_tree}/action_node.h | 0 include/behavior_tree/behavior_tree.h | 20 + include/{ => behavior_tree}/condition_node.h | 0 include/{ => behavior_tree}/control_node.h | 2 +- .../decorator_negation_node.h | 2 +- .../decorator_retry_node.h | 2 +- include/{ => behavior_tree}/exceptions.h | 0 include/{ => behavior_tree}/fallback_node.h | 2 +- .../fallback_node_with_memory.h | 2 +- include/{ => behavior_tree}/leaf_node.h | 2 +- include/{ => behavior_tree}/parallel_node.h | 2 +- include/{ => behavior_tree}/sequence_node.h | 2 +- .../sequence_node_with_memory.h | 2 +- include/{ => behavior_tree}/tick_engine.h | 0 include/{ => behavior_tree}/tree_node.h | 4 +- include/draw.h | 44 -- package.xml | 17 + src/action_node.cpp | 2 +- src/behavior_tree.cpp | 41 -- src/condition_node.cpp | 2 +- src/control_node.cpp | 2 +- src/draw.cpp | 525 ------------------ src/exceptions.cpp | 2 +- src/fallback_node.cpp | 2 +- src/fallback_node_with_memory.cpp | 2 +- src/leaf_node.cpp | 2 +- src/parallel_node.cpp | 2 +- src/sequence_node.cpp | 2 +- src/sequence_node_with_memory.cpp | 2 +- src/tick_engine.cpp | 2 +- src/tree_node.cpp | 2 +- 39 files changed, 168 insertions(+), 839 deletions(-) delete mode 100644 include/behavior_tree.h rename include/{ => behavior_tree}/action_node.h (100%) create mode 100644 include/behavior_tree/behavior_tree.h rename include/{ => behavior_tree}/condition_node.h (100%) rename include/{ => behavior_tree}/control_node.h (96%) rename include/{ => behavior_tree}/decorator_negation_node.h (91%) rename include/{ => behavior_tree}/decorator_retry_node.h (91%) rename include/{ => behavior_tree}/exceptions.h (100%) rename include/{ => behavior_tree}/fallback_node.h (89%) rename include/{ => behavior_tree}/fallback_node_with_memory.h (93%) rename include/{ => behavior_tree}/leaf_node.h (87%) rename include/{ => behavior_tree}/parallel_node.h (93%) rename include/{ => behavior_tree}/sequence_node.h (88%) rename include/{ => behavior_tree}/sequence_node_with_memory.h (93%) rename include/{ => behavior_tree}/tick_engine.h (100%) rename include/{ => behavior_tree}/tree_node.h (98%) delete mode 100644 include/draw.h create mode 100644 package.xml delete mode 100644 src/behavior_tree.cpp delete mode 100644 src/draw.cpp diff --git a/.travis.yml b/.travis.yml index 3b630cc43..eadd19180 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,3 +1,6 @@ +# This config file for Travis CI utilizes ros-industrial/industrial_ci package. +# For more info for the package, see https://github.com/ros-industrial/industrial_ci/blob/master/README.rst + sudo: required dist: trusty language: cpp @@ -7,18 +10,29 @@ os: compiler: - gcc - - clang - + +matrix: + include: + - bare_linux: + env: ROS_DISTRO="none" + - ros_indigo: + env: ROS_DISTRO="indigo" + - ros_kinetic: + env: ROS_DISTRO="kinetic" + fast_finish: true + before_install: - - sudo apt-get update && sudo apt-get --reinstall install -qq build-essential freeglut3-dev libxmu-dev libxi-dev + - sudo apt-get update && sudo apt-get --reinstall install -qq build-essential + +install: + - if [ "$ROS_DISTRO" != "none" ]; then git clone https://github.com/ros-industrial/industrial_ci.git .ci_config; fi before_script: # Prepare build directory - mkdir -p build script: - # Build BTpp - - (cd build; cmake .. ;cmake --build . ) - #Install BTpp - - (cd build; sudo make install) + - if [ "$ROS_DISTRO" = "none" ]; then (cd build; cmake .. ;cmake --build . ); fi + - if [ "$ROS_DISTRO" != "none" ]; then (.ci_config/travis.sh); fi + diff --git a/CMakeLists.txt b/CMakeLists.txt index 4fde9f02f..2c9c51529 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,177 +1,103 @@ -cmake_minimum_required(VERSION 3.0) -project(BTpp) +cmake_minimum_required(VERSION 2.8) +project(behavior_tree_core) set(CMAKE_BUILD_TYPE Release) -add_definitions(-lX11 -Wall -lglut -lGL -lgtest -std=c++11 -lrt ) -# Needed for using threads -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pthread") - -######################################################### -# FIND X11 -######################################################### -find_package(X11 REQUIRED) -include_directories(${X11_INCLUDE_DIR}) -link_directories(${X11_LIBRARIES}) - -######################################################### -# FIND GTest -######################################################### -find_package(GTest) -include_directories(${GTEST_INCLUDE_DIRS}) -if(NOT GTEST_FOUND) - message(WARINING " GTest not found!") -endif(NOT GTEST_FOUND) - -######################################################### -# FIND GLUT -######################################################### -find_package(GLUT REQUIRED) -include_directories(${GLUT_INCLUDE_DIRS}) -link_directories(${GLUT_LIBRARY_DIRS}) -add_definitions(${GLUT_DEFINITIONS}) -if(NOT GLUT_FOUND) - message(ERROR " GLUT not found!") -endif(NOT GLUT_FOUND) - -######################################################### -# FIND OPENGL -######################################################### -find_package(OpenGL REQUIRED) -include_directories(${OpenGL_INCLUDE_DIRS}) -link_directories(${OpenGL_LIBRARY_DIRS}) -add_definitions(${OpenGL_DEFINITIONS}) -if(NOT OPENGL_FOUND) - message(ERROR " OPENGL not found!") -endif(NOT OPENGL_FOUND) - - -INCLUDE_DIRECTORIES(${PROJECT_SOURCE_DIR}/include/) -INCLUDE_DIRECTORIES(${PROJECT_SOURCE_DIR}/gtest/include/) - -if(APPLE) - include_directories(AFTER "/opt/X11/include") - set(CMAKE_OSX_ARCHITECTURES "x86_64") - if(CMAKE_GENERATOR STREQUAL Xcode) - set(CMAKE_OSX_DEPLOYMENT_TARGET "10.8") - endif() -endif() - - -######################################################### -# Make relative paths absolute (needed later on) -######################################################### - -foreach(p LIB BIN INCLUDE CMAKE) - set(var INSTALL_${p}_DIR) - if(NOT IS_ABSOLUTE "${${var}}") - set(${var} "${CMAKE_INSTALL_PREFIX}/${${var}}") - endif() -endforeach() +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11 -Werror=return-type") +############################################################# +# http://answers.ros.org/question/230877/optionally-build-a-package-with-catkin/ +if( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) + set(catkin_FOUND 1) + add_definitions( -DUSING_ROS ) +endif() - -file(GLOB_RECURSE BTHeadLibrary include/*.h) - -set(BTSrcLibrary -src/action_node.cpp -src/behavior_tree.cpp -src/condition_node.cpp -src/control_node.cpp -src/draw.cpp -src/exceptions.cpp -src/leaf_node.cpp -src/tick_engine.cpp -src/parallel_node.cpp -src/fallback_node.cpp -src/sequence_node.cpp -src/fallback_node_with_memory.cpp -src/sequence_node_with_memory.cpp -src/tree_node.cpp - -gtest/src/action_test_node.cpp -gtest/src/condition_test_node.cpp +if(catkin_FOUND) + find_package(catkin REQUIRED COMPONENTS ) + + message(STATUS "------------------------------------------") + message(STATUS "BehaviourTree is being built using CATKIN.") + message(STATUS "------------------------------------------") + + catkin_package( + INCLUDE_DIRS include + LIBRARIES behavior_tree_core + ) +else(catkin_FOUND) + + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/sample) + set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) + + find_package(GTest) + include_directories(${GTEST_INCLUDE_DIRS}) + if(NOT GTEST_FOUND) + message(WARNING " GTest not found!") + endif(NOT GTEST_FOUND) + +endif(catkin_FOUND) + + +set(BT_Source + src/action_node.cpp + src/condition_node.cpp + src/control_node.cpp + src/exceptions.cpp + src/leaf_node.cpp + src/tick_engine.cpp + src/parallel_node.cpp + src/fallback_node.cpp + src/sequence_node.cpp + src/fallback_node_with_memory.cpp + src/sequence_node_with_memory.cpp + src/tree_node.cpp ) +include_directories(include) ###################################################### -# SETTING BINARIES AND LIBRARY OUTPUT LOCATIONS +# COMPILING LIBRARY ###################################################### -set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/sample) -set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) +add_library(behavior_tree_core STATIC ${BT_Source} ) -###################################################### -# COMPILING GTEST -###################################################### -if(GTEST_FOUND) - #add_executable(btpp_gtest gtest/gtest_tree.cpp ${BTSrcLibrary} ${BTHeadLibrary}) - #target_link_libraries(btpp_gtest ${OPENGL_LIBRARIES} ${GLUT_LIBRARY} ${GTEST_LIBRARIES} ${GTEST_MAIN_LIBRARIES} ${X11_LIBRARIES}) -endif(GTEST_FOUND) ###################################################### -# COMPILING SAMPLE EXAMPLE +# TESTS ###################################################### -add_executable(btpp_example src/example.cpp ${BTSrcLibrary} ${BTHeadLibrary}) -target_link_libraries(btpp_example ${OPENGL_LIBRARIES} ${GLUT_LIBRARY} ${X11_LIBRARIES}) +set(BT_Tests + gtest/src/action_test_node.cpp + gtest/src/condition_test_node.cpp + gtest/gtest_tree.cpp +) -###################################################### -# COMPILING LIBRARY -###################################################### -add_library(BTppLib STATIC ${BTSrcLibrary} ${BTHeadLibrary}) -target_link_libraries(BTppLib ${OPENGL_LIBRARIES} ${GLUT_LIBRARY} ${X11_LIBRARIES}) +if(catkin_FOUND AND CATKIN_ENABLE_TESTING) + include_directories(gtest/include) + + catkin_add_gtest(behavior_tree_core_test ${BT_Tests} ) + target_link_libraries(behavior_tree_core_test + behavior_tree_core + ${catkin_LIBRARIES} ) + +elseif(GTEST_FOUND) + include_directories(gtest/include) + + add_executable(behavior_tree_core_test ${BT_Tests} ) + target_link_libraries(btpp_test + behavior_tree_core + ${GTEST_LIBRARIES} + ${GTEST_MAIN_LIBRARIES} ) + +endif() ###################################################### -# INSTALLATION OF LIBRARY AND EXECUTABLE +# COMPILING EXAMPLES ###################################################### +#TODO -# Add all targets to the build-tree export set -export(TARGETS BTppLib - FILE "${PROJECT_BINARY_DIR}/BTppTargets.cmake") - -# Export the package for use from the build-tree -# (this registers the build-tree with a global CMake-registry) -export(PACKAGE BTpp) - - -install(FILES ${BTHeadLibrary} DESTINATION ${INSTALL_INCLUDE_DIR}/include/BTpp) - - -install(TARGETS BTppLib - # IMPORTANT: Add the library to the "export-set" - EXPORT BTppTargets - ARCHIVE DESTINATION "${INSTALL_CMAKE_DIR}/BTpp/lib" - RUNTIME DESTINATION "${PROJECT_BINARY_DIR}/bin" COMPONENT ${PROJECT_BINARY_DIR}/bin - LIBRARY DESTINATION "${PROJECT_BINARY_DIR}/lib" COMPONENT ${PROJECT_BINARY_DIR}/shlib - PUBLIC_HEADER DESTINATION "${INSTALL_INCLUDE_DIR}/include/BTpp" - COMPONENT ${INSTALL_CMAKE_DIR}"include/BTpp") - - -# Create the BTppConfig.cmake and BTppConfigVersion files -file(RELATIVE_PATH REL_INCLUDE_DIR "${INSTALL_CMAKE_DIR}" - "${INSTALL_INCLUDE_DIR}") -# ... for the build tree - - -set(CONF_INCLUDE_DIRS "${INSTALL_INCLUDE_DIR}include/BTpp") -configure_file(conf/BTppConfig.cmake.in - "${PROJECT_BINARY_DIR}/BTppConfig.cmake" @ONLY) - -# ... for the install tree -#set(CONF_INCLUDE_DIRS "\${BTpp_CMAKE_DIR}/${REL_INCLUDE_DIR}") -configure_file(conf/BTppConfig.cmake.in - "${PROJECT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/BTppConfig.cmake" @ONLY) -# ... for both -configure_file(conf/BTppConfigVersion.cmake.in - "${PROJECT_BINARY_DIR}/BTppConfigVersion.cmake" @ONLY) +###################################################### +# INSTALLATION OF LIBRARY AND EXECUTABLE +###################################################### -# Install the BTppConfig.cmake and BTppConfigVersion.cmake -install(FILES - "${PROJECT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/BTppConfig.cmake" - "${PROJECT_BINARY_DIR}/BTppConfigVersion.cmake" - DESTINATION "${INSTALL_CMAKE_DIR}" COMPONENT dev) -# Install the export set for use with the install-tree -install(EXPORT BTppTargets DESTINATION - "${INSTALL_CMAKE_DIR}" COMPONENT dev) +#TODO diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 115f1e09c..c210a7fc5 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -12,9 +12,9 @@ #include -#include -#include -#include +#include "action_test_node.h" +#include "condition_test_node.h" +#include "behavior_tree/behavior_tree.h" diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index d3a7ac1ca..bb0ee1948 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -1,7 +1,7 @@ #ifndef ACTIONTEST_H #define ACTIONTEST_H -#include +#include "behavior_tree/action_node.h" namespace BT { diff --git a/gtest/include/condition_test_node.h b/gtest/include/condition_test_node.h index 98074c54c..35561f31d 100644 --- a/gtest/include/condition_test_node.h +++ b/gtest/include/condition_test_node.h @@ -1,7 +1,7 @@ #ifndef CONDITIONTEST_H #define CONDITIONTEST_H -#include +#include "behavior_tree/condition_node.h" namespace BT { diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 06b6f35ba..f96274f36 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -11,7 +11,7 @@ */ -#include +#include "action_test_node.h" #include diff --git a/gtest/src/condition_test_node.cpp b/gtest/src/condition_test_node.cpp index 34cfb244c..ddefd1807 100644 --- a/gtest/src/condition_test_node.cpp +++ b/gtest/src/condition_test_node.cpp @@ -11,7 +11,7 @@ */ -#include +#include "condition_test_node.h" #include BT::ConditionTestNode::ConditionTestNode(std::string name) : ConditionNode::ConditionNode(name) diff --git a/include/behavior_tree.h b/include/behavior_tree.h deleted file mode 100644 index 168b77c71..000000000 --- a/include/behavior_tree.h +++ /dev/null @@ -1,38 +0,0 @@ -#ifndef BEHAVIORTREE_H -#define BEHAVIORTREE_H - - - - - -#include - -#include -#include -#include - -#include -#include - - -#include -#include - -#include - -#include -#include - -#include -#include /* pow */ - - -#include -#include -#include - - -void Execute(BT::ControlNode* root,int TickPeriod_milliseconds); - - -#endif diff --git a/include/action_node.h b/include/behavior_tree/action_node.h similarity index 100% rename from include/action_node.h rename to include/behavior_tree/action_node.h diff --git a/include/behavior_tree/behavior_tree.h b/include/behavior_tree/behavior_tree.h new file mode 100644 index 000000000..f73f1fd08 --- /dev/null +++ b/include/behavior_tree/behavior_tree.h @@ -0,0 +1,20 @@ +#ifndef BEHAVIOR_TREE_H +#define BEHAVIOR_TREE_H + +#include "behavior_tree/parallel_node.h" +#include "behavior_tree/fallback_node.h" +#include "behavior_tree/sequence_node.h" + +#include "behavior_tree/sequence_node_with_memory.h" +#include "behavior_tree/fallback_node_with_memory.h" + +#include "behavior_tree/action_node.h" +#include "behavior_tree/condition_node.h" + +#include "behavior_tree/decorator_negation_node.h" +#include "behavior_tree/decorator_retry_node.h" + +#include "behavior_tree/exceptions.h" + + +#endif // BEHAVIOR_TREE_H diff --git a/include/condition_node.h b/include/behavior_tree/condition_node.h similarity index 100% rename from include/condition_node.h rename to include/behavior_tree/condition_node.h diff --git a/include/control_node.h b/include/behavior_tree/control_node.h similarity index 96% rename from include/control_node.h rename to include/behavior_tree/control_node.h index 2e9f77981..2d9db98c3 100644 --- a/include/control_node.h +++ b/include/behavior_tree/control_node.h @@ -3,7 +3,7 @@ #include -#include +#include "behavior_tree/tree_node.h" namespace BT { diff --git a/include/decorator_negation_node.h b/include/behavior_tree/decorator_negation_node.h similarity index 91% rename from include/decorator_negation_node.h rename to include/behavior_tree/decorator_negation_node.h index 01bae3b5f..6b759f1df 100644 --- a/include/decorator_negation_node.h +++ b/include/behavior_tree/decorator_negation_node.h @@ -1,7 +1,7 @@ #ifndef DECORATORNEGATIONNODE_H #define DECORATORNEGATIONNODE_H -#include +#include "behavior_tree/control_node.h" namespace BT { diff --git a/include/decorator_retry_node.h b/include/behavior_tree/decorator_retry_node.h similarity index 91% rename from include/decorator_retry_node.h rename to include/behavior_tree/decorator_retry_node.h index 3fcab306b..2700cbb49 100644 --- a/include/decorator_retry_node.h +++ b/include/behavior_tree/decorator_retry_node.h @@ -1,7 +1,7 @@ #ifndef DECORATORRETRYNODE_H #define DECORATORRETRYNODE_H -#include +#include "behavior_tree/control_node.h" namespace BT { diff --git a/include/exceptions.h b/include/behavior_tree/exceptions.h similarity index 100% rename from include/exceptions.h rename to include/behavior_tree/exceptions.h diff --git a/include/fallback_node.h b/include/behavior_tree/fallback_node.h similarity index 89% rename from include/fallback_node.h rename to include/behavior_tree/fallback_node.h index 54cebca8e..4fa630347 100644 --- a/include/fallback_node.h +++ b/include/behavior_tree/fallback_node.h @@ -1,7 +1,7 @@ #ifndef FALLBACKNODE_H #define FALLBACKNODE_H -#include +#include "behavior_tree/control_node.h" namespace BT { diff --git a/include/fallback_node_with_memory.h b/include/behavior_tree/fallback_node_with_memory.h similarity index 93% rename from include/fallback_node_with_memory.h rename to include/behavior_tree/fallback_node_with_memory.h index d85083ba0..2b2a260f3 100644 --- a/include/fallback_node_with_memory.h +++ b/include/behavior_tree/fallback_node_with_memory.h @@ -1,6 +1,6 @@ #ifndef FALLBACK_NODE_WITH_MEMORY_H #define FALLBACK_NODE_WITH_MEMORY_H -#include +#include "behavior_tree/control_node.h" namespace BT diff --git a/include/leaf_node.h b/include/behavior_tree/leaf_node.h similarity index 87% rename from include/leaf_node.h rename to include/behavior_tree/leaf_node.h index 72c0ac71a..0519e954b 100644 --- a/include/leaf_node.h +++ b/include/behavior_tree/leaf_node.h @@ -3,7 +3,7 @@ #include -#include +#include "behavior_tree/tree_node.h" namespace BT { diff --git a/include/parallel_node.h b/include/behavior_tree/parallel_node.h similarity index 93% rename from include/parallel_node.h rename to include/behavior_tree/parallel_node.h index ff1b08993..700c10dac 100644 --- a/include/parallel_node.h +++ b/include/behavior_tree/parallel_node.h @@ -1,7 +1,7 @@ #ifndef PARALLEL_NODE_H #define PARALLEL_NODE_H -#include +#include "behavior_tree/control_node.h" namespace BT { diff --git a/include/sequence_node.h b/include/behavior_tree/sequence_node.h similarity index 88% rename from include/sequence_node.h rename to include/behavior_tree/sequence_node.h index 7bd7afd8e..4dd59d7c4 100644 --- a/include/sequence_node.h +++ b/include/behavior_tree/sequence_node.h @@ -1,7 +1,7 @@ #ifndef SEQUENCENODE_H #define SEQUENCENODE_H -#include +#include "behavior_tree/control_node.h" namespace BT { diff --git a/include/sequence_node_with_memory.h b/include/behavior_tree/sequence_node_with_memory.h similarity index 93% rename from include/sequence_node_with_memory.h rename to include/behavior_tree/sequence_node_with_memory.h index 0d8488f3e..a9a649b50 100644 --- a/include/sequence_node_with_memory.h +++ b/include/behavior_tree/sequence_node_with_memory.h @@ -2,7 +2,7 @@ #define SEQUENCE_NODE_WITH_MEMORY_H -#include +#include "behavior_tree/control_node.h" diff --git a/include/tick_engine.h b/include/behavior_tree/tick_engine.h similarity index 100% rename from include/tick_engine.h rename to include/behavior_tree/tick_engine.h diff --git a/include/tree_node.h b/include/behavior_tree/tree_node.h similarity index 98% rename from include/tree_node.h rename to include/behavior_tree/tree_node.h index 77a641d35..8bbc2b96f 100644 --- a/include/tree_node.h +++ b/include/behavior_tree/tree_node.h @@ -50,8 +50,8 @@ #include -#include -#include +#include "behavior_tree/tick_engine.h" +#include "behavior_tree/exceptions.h" namespace BT { diff --git a/include/draw.h b/include/draw.h deleted file mode 100644 index 4f124e14b..000000000 --- a/include/draw.h +++ /dev/null @@ -1,44 +0,0 @@ -#ifndef DRAWTREE_H -#define DRAWTREE_H -#include - -#ifdef __APPLE__ -#include -#else -#include -#endif - -#include -#include -#include -#include - -//enum status {RUNNING,SUCCESS,FAILURE,IDLE, HALTED }; - -void drawEllipse(float xradius, float yradius); - -void drawTree(BT::ControlNode* tree_); - -void resize(int width, int height); - -void draw_status(float x, float y, int node_status); - -void drawString (void * font, char *string, float x, float y, float z); - -void renderBitmapString(float x, float y, void *font,const char *string); - -void draw_node(float x, float y, int node_type, const char *leafName, int status); - -void draw_edge(GLfloat parent_x, GLfloat parent_y, GLfloat parent_size, GLfloat child_x, GLfloat child_y, GLfloat child_size); - -void keyboard(unsigned char key, int x, int y); - -void drawCircle(float radius); - -int compute_node_lines(const char *string); - -int compute_max_width(const char *string); - -//void display(); - -#endif // DRAWTREE_H diff --git a/package.xml b/package.xml new file mode 100644 index 000000000..0137b6dcd --- /dev/null +++ b/package.xml @@ -0,0 +1,17 @@ + + behavior_tree_core + 0.1.0 + + This package provides a behavior trees core. + + + Michele Colledanchise + Davide Faconti + + MIT + + Michele Colledanchise + + catkin + + diff --git a/src/action_node.cpp b/src/action_node.cpp index 1dabb5a9a..e13ae99ff 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include +#include "behavior_tree/action_node.h" #include diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp deleted file mode 100644 index 5c53847cc..000000000 --- a/src/behavior_tree.cpp +++ /dev/null @@ -1,41 +0,0 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved -* -* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), -* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, -* 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: -* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. -* -* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, -* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. -*/ - - -#include - - - -void Execute(BT::ControlNode* root, int TickPeriod_milliseconds) -{ - std::cout << "Start Drawing!" << std::endl; - // Starts in another thread the drawing of the BT - std::thread t(&drawTree, root); - - root->ResetColorState(); - - while (true) - { - DEBUG_STDOUT("Ticking the root node !"); - - // Ticking the root node - root->Tick(); - // Printing its state - - if (root->get_status() != BT::RUNNING) - { - // when the root returns a status it resets the colors of the tree - root->ResetColorState(); - } - std::this_thread::sleep_for(std::chrono::milliseconds(TickPeriod_milliseconds)); - } -} diff --git a/src/condition_node.cpp b/src/condition_node.cpp index 352784294..f689b9587 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include +#include "behavior_tree/condition_node.h" #include BT::ConditionNode::ConditionNode(std::string name) : LeafNode::LeafNode(name) diff --git a/src/control_node.cpp b/src/control_node.cpp index 8e4ee59a1..6c8aa9123 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -11,7 +11,7 @@ */ -#include +#include "behavior_tree/control_node.h" #include #include diff --git a/src/draw.cpp b/src/draw.cpp deleted file mode 100644 index 7aa9d0d03..000000000 --- a/src/draw.cpp +++ /dev/null @@ -1,525 +0,0 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved -* -* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), -* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, -* 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: -* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. -* -* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, -* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. -*/ - - - -#include -#include -#include - -#include - -const float DEG2RAD = 3.14159/180.0; - - -BT::ControlNode* tree; -bool init = false; - - -void * font_array[3] = {GLUT_BITMAP_8_BY_13, GLUT_BITMAP_8_BY_13, GLUT_BITMAP_8_BY_13}; -void * font = font_array[0]; -float additional_spacing_array[10]; -bool is_number_pressed_array[10]; -unsigned char number_char[4] = {'0', '1', '2', '3'}; - - -float x = 0.0; -float y = 0.4; -float x_offset = 0.01; -float y_offset = 0.15; -float r_color = 1; -float g_color = 1; -float b_color = 1; -GLfloat x_space = 0.06; - -int depth; - -double zoom = 1.0f; - -float fraction = 0.1f; -float zoom_fraction = 0.1f; - - - - -void drawEllipse(float xpos, float ypos, float xradius, float yradius) -{ - glBegin(GL_LINE_LOOP); - - for (int i=0; i < 359; i++) - { - // convert degrees into radians - float degInRad = i*DEG2RAD; - glVertex2d(xpos+cos(degInRad)*xradius, ypos + sin(degInRad)*yradius); - } - glEnd(); -} - -void drawString(void * font, const char *string, float x, float y, float z) -{ - renderBitmapString(x, y, font, string); -} - -int compute_node_lines(const char *string) -{ - const char *c; - int i = 0; - int new_line_num = 1; - glRasterPos2f(x, y); - for (c=string; *c != '\0'; c++) - { - if ((*c == '\n') || ((*c == ' ' && i > 6) || i > 9)) - { - new_line_num++; - i = 0; - continue; - } - i++; - } - return new_line_num; -} - -int compute_max_width(const char *string) -{ - const char *current_char; - int current_line_width = 0; - int max_width = 0; - - glRasterPos2f(x, y); - for (current_char = string; *current_char != '\0'; current_char++) - { - if ((*current_char == '\n') || ((*current_char == ' ' && current_line_width > 6) || current_line_width > 9)) - { - if (current_line_width > max_width) - { - max_width = current_line_width; - } - current_line_width = 0; - continue; - } - current_line_width++; - } - - if (max_width == 0) // if the lable fits in a single line - { - max_width = current_line_width; - } - return max_width; -} - -void renderBitmapString(float x, float y, void *font, const char *string) -{ - const char *c; - int i = 0; - int new_line_num = 0; - glRasterPos2f(x, y); - for (c=string; *c != '\0'; c++) - { - if ((*c == '\n') || ((*c == ' ' && i > 6) || i > 9)) - { - new_line_num++; - glRasterPos2f(x, y - 0.025*(new_line_num)); - i = 0; - continue; - } - i++; - glutBitmapCharacter(font, *c); - } -} - - - -void draw_node(float x, float y, int node_type, const char *leafName, int status) -{ - float NODE_WIDTH = 0.04; - float NODE_HEIGHT = 0.02; - switch (node_type) - { - case BT::SELECTORSTAR: - drawString(font, "?*", (x + NODE_WIDTH/2 -0.005), (y - NODE_HEIGHT/2), 0); - break; - case BT::SEQUENCESTAR: - drawString(font, ">*", (x + NODE_WIDTH/2 -0.0051), (y - NODE_HEIGHT/2), 0); - break; - case BT::SELECTOR: - drawString(font, "?", (x + NODE_WIDTH/2 -0.005), (y - NODE_HEIGHT/2), 0); - break; - case BT::SEQUENCE: - drawString(font, ">", (x + NODE_WIDTH/2 -0.005), (y - NODE_HEIGHT/2), 0); - break; - case BT::PARALLEL: - drawString(font, "=", (x + NODE_WIDTH/2 -0.005), (y - NODE_HEIGHT/2), 0); - break; - case BT::DECORATOR: - drawString(font, "D", (x + NODE_WIDTH/2 -0.005), (y - NODE_HEIGHT/2), 0); - break; - case BT::ACTION: - { - NODE_HEIGHT = 0.02*(compute_node_lines(leafName)); - std::string st(leafName, 0, 15); - NODE_WIDTH = 0.02*compute_max_width(leafName); -// for (unsigned int i = 0; i < st.size(); i++) -// NODE_WIDTH += 0.01; - } - renderBitmapString((x + 0.015), (y - 0.01), font, leafName); - // glColor3f(0.2, 1.0, 0.2); - break; - case BT::CONDITION: - { - NODE_HEIGHT = 0.02*compute_node_lines(leafName); - std::string st(leafName, 0, 15); - NODE_WIDTH = 0.02*compute_max_width(leafName); - } - renderBitmapString((x + 2*0.015), (y - 0.01), font, leafName); - break; - default: - break; - } - - switch (status) - { - case BT::RUNNING: - glColor3f(0.8, 0.8, 0.8); - break; - case BT::SUCCESS: - glColor3f(0.0, 1.0, 0.0); - break; - case BT::FAILURE: - glColor3f(1.0, 0.0, 0.0); - break; - case BT::IDLE: - glColor3f(0.0, 0.0, 0.0); - break; - case BT::HALTED: - glColor3f(0.0, 0.0, 0.0); - break; - default: - break; - } - - switch (node_type) - { - case BT::CONDITION: - // drawEllipse(x,y,NODE_WIDTH,NODE_HEIGHT); - // drawEllipse(x,y,0.1,0.021); - glBegin(GL_LINE_LOOP); - glVertex2f((GLfloat) (x + NODE_WIDTH), (GLfloat) (y - NODE_HEIGHT - 0.015)); - glVertex2f((GLfloat) (x + NODE_WIDTH), (GLfloat) (y + 0.02)); - glVertex2f((GLfloat) (x), (GLfloat) (y + 0.02)); - glVertex2f((GLfloat) (x), (GLfloat) (y - NODE_HEIGHT - 0.015)); - glColor3f(0.0, 0.0, 0.0); - glEnd(); - break; - - break; - case BT::ACTION: - - glBegin(GL_LINE_LOOP); - glVertex2f((GLfloat) (x + NODE_WIDTH), (GLfloat) (y - NODE_HEIGHT - 0.015)); - glVertex2f((GLfloat) (x + NODE_WIDTH), (GLfloat) (y + 0.02)); - glVertex2f((GLfloat) (x), (GLfloat) (y + 0.02)); - glVertex2f((GLfloat) (x), (GLfloat) (y - NODE_HEIGHT - 0.015)); - glColor3f(0.0, 0.0, 0.0); - glEnd(); - break; - - default: - glBegin(GL_LINE_LOOP); - glVertex2f((GLfloat) (x + NODE_WIDTH), (GLfloat) (y - NODE_HEIGHT)); - glVertex2f((GLfloat) (x + NODE_WIDTH), (GLfloat) (y + NODE_HEIGHT)); - glVertex2f((GLfloat) (x), (GLfloat) (y + NODE_HEIGHT)); - glVertex2f((GLfloat) (x), (GLfloat) (y - NODE_HEIGHT)); - glColor3f(0.0, 0.0, 0.0); - glEnd(); - break; - } -} - -// draw the edge connecting one node to the other -void draw_edge(GLfloat parent_x, GLfloat parent_y, - GLfloat parent_size, GLfloat child_x, GLfloat child_y, GLfloat child_size) -{ - glLineWidth(1.5); - glColor3f(0.0, 0.0, 0.0); - // GLfloat bottom_spacing = 0.1; // commented-out as unused variable - GLfloat above_spacing = 0.04; - - glBegin(GL_LINES); - glVertex3f(parent_x, parent_y - parent_size, 0); - glVertex3f(parent_x, child_y + child_size + above_spacing, 0); - glEnd(); - - glBegin(GL_LINES); - glVertex3f(parent_x, child_y + child_size + above_spacing, 0); - glVertex3f(child_x, child_y + child_size + above_spacing, 0); - glEnd(); - - glBegin(GL_LINES); - glVertex3f(child_x, child_y + child_size + above_spacing, 0); - glVertex3f(child_x, child_y+child_size, 0); - glEnd(); -} - -// draw the edge connecting one node to the other -void draw_straight_edge(GLfloat parent_x, GLfloat parent_y, - GLfloat parent_size, GLfloat child_x, GLfloat child_y, GLfloat child_size) -{ - glLineWidth(1.5); - glColor3f(0.0, 0.0, 0.0); - - glBegin(GL_LINES); - glVertex3f(parent_x, parent_y-parent_size, 0.0); - glVertex3f(child_x, child_y+child_size, 0); - glEnd(); -} - -// Keyboard callback function ( called on keyboard event handling ) -void keyboard(unsigned char key, int x, int y) -{ - for (int i = 1; i < 4; i++) - { - if (key == number_char[i]) - { - is_number_pressed_array[i] = true; - } - else - { - is_number_pressed_array[i] = false; - } - } -} - -void keyboard_release(unsigned char key, int x, int y) -{ - for (int i = 1; i < 4; i++) - { - if (key == number_char[i]) - { - is_number_pressed_array[i] = false; - } - } -} - - -void drawCircle(float radius) -{ - glBegin(GL_LINE_LOOP); - - for (int i=0; i<= 360; i++) - { - float degInRad = i*3.14142/180; - glVertex2f(cos(degInRad)*radius, sin(degInRad)*radius); - } - glEnd(); -} - - -void updateTree(BT::TreeNode* tree, GLfloat x_pos, GLfloat y_pos, GLfloat y_offset, int depth ) -{ - BT::ControlNode* d = dynamic_cast (tree); - if (d == NULL) - { - // if it is a leaf node, draw it - draw_node(x_pos , (GLfloat) y_pos, tree->DrawType(), tree->get_name().c_str(), tree->get_color_status()); - } - else - { - // if it is a control flow node, draw it and its children - draw_node((GLfloat) x_pos, (GLfloat) y_pos, tree->DrawType(), - tree->get_name().c_str(), tree->get_color_status()); - std::vector children = d->GetChildren(); - int M = d->GetChildrenNumber(); - std::vector children_x_end; - std::vector children_x_middle_relative; - - GLfloat max_x_end = 0; - // GLfloat max_x_start = 0; // commented out as unused variable - GLfloat current_x_end = 0; - - for (int i = 0; i < M; i++) - { - if (children[i]->DrawType() != BT::ACTION && children[i]->DrawType() != BT::CONDITION) - { - current_x_end = 0.04; - children_x_middle_relative.push_back(0.02); - } - else - { - current_x_end = 0.02*compute_max_width(children[i]->get_name().c_str()); - children_x_middle_relative.push_back(current_x_end/2); - } - - if (i < M-1) - { - max_x_end = max_x_end + current_x_end + x_space + additional_spacing_array[depth]; - } - else - { - max_x_end = max_x_end + current_x_end; - } - children_x_end.push_back(max_x_end); - } - - // GLfloat x_min = 0.0; // commented-out as unused variable - // GLfloat x_max = 0.0; // commented-out as unused variable - GLfloat x_shift = x_pos - max_x_end/2; - // GLfloat x_shift_new = 0; // commented-out as unused variable - - for (int i = 0; i < M; i++) - { - if (i > 0) - { - updateTree(children[i], x_shift + children_x_end.at(i - 1) , y_pos - y_offset , y_offset, depth + 1); - draw_edge(x_pos + 0.015, y_pos, 0.02, - x_shift + children_x_end.at(i-1) + children_x_middle_relative.at(i), - y_pos - y_offset, 0.02); - } - else - { - updateTree(children[i], x_shift , y_pos - y_offset , y_offset, depth + 1); - draw_edge(x_pos + 0.015, y_pos, 0.02, - x_shift + children_x_middle_relative.at(i), y_pos - y_offset, 0.02); - } - } - } -} - - - - - -void display() -{ - glClearColor(r_color, g_color, b_color, 0.1); // clear the draw buffer . - glClear(GL_COLOR_BUFFER_BIT); // Erase everything - updateTree(tree, x , y, y_offset, 1); - glutSwapBuffers(); - glutPostRedisplay(); -} - - -void processSpecialKeys(int key, int xx, int yy) -{ - switch (key) - { - case GLUT_KEY_UP : - y += fraction; - break; - case GLUT_KEY_DOWN : - if (y >= 0) - { - y -= fraction; - } - break; - case GLUT_KEY_LEFT: - x -= fraction; - break; - case GLUT_KEY_RIGHT: - x += fraction; - break; - case GLUT_KEY_PAGE_UP: - for (int i = 1; i < 10; i++) - { - if (is_number_pressed_array[i]) - { - additional_spacing_array[i] += fraction; - } - } - break; - case GLUT_KEY_PAGE_DOWN: - for (int i = 1; i < 10; i++) - { - if (is_number_pressed_array[i] && additional_spacing_array[i] >= 0 ) - { - additional_spacing_array[i] -= fraction; - } - } - break; - case GLUT_KEY_F1: - if (r_color < 1) r_color += fraction; - break; - case GLUT_KEY_F2: - if (r_color > 0) r_color -= fraction; - break; - case GLUT_KEY_F3: - if (g_color < 1) g_color += fraction; - break; - case GLUT_KEY_F4: - if (g_color > 0) g_color -= fraction; - break; - case GLUT_KEY_F5: - if (b_color < 1) b_color += fraction; - break; - case GLUT_KEY_F6: - if (b_color > 0) b_color -= fraction; - break; - case GLUT_KEY_HOME: - if (zoom < 1.0f) - { - glScalef(1.0f + zoom_fraction, 1.0f + zoom_fraction, 1.0f); - zoom += zoom_fraction; - } - else - { - glScalef(1.0f, 1.0f, 1.0f); - } - break; - case GLUT_KEY_END: - glScalef(1.0f - zoom_fraction, 1.0f - zoom_fraction, 1.0f); - zoom -= zoom_fraction; - break; - } -} - -void drawTree(BT::ControlNode* tree_) -{ - /***************************BT VISUALIZATION****************************/ - int argc = 1; - char *argv[1] = {const_cast("")}; - - if (!init) - { - XInitThreads(); - glutInit(&argc, argv); - init = true; - glutInitDisplayMode(GLUT_DEPTH | GLUT_RGBA | GLUT_DOUBLE | GLUT_MULTISAMPLE ); // Antialiasing - glEnable(GL_MULTISAMPLE); - } - tree = tree_; - depth = tree->Depth(); - - glutInitWindowSize(1024, 860); - - glutCreateWindow("Behavior Tree"); // Create a window - - glClearColor(0, 0.71, 0.00, 0.1); - glutDisplayFunc(display); // Register display callback - - glutKeyboardFunc(keyboard); // Register keyboard presscallback - glutKeyboardUpFunc(keyboard_release); // Register keyboard release callback - - glutSpecialFunc(processSpecialKeys); // Register keyboard arrow callback - - glutMainLoop(); // Enter main event loop - - /***************************ENDOF BT VISUALIZATION ****************************/ -} - - - - - - - - - - diff --git a/src/exceptions.cpp b/src/exceptions.cpp index 2b19e15c8..3a5deb05a 100644 --- a/src/exceptions.cpp +++ b/src/exceptions.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include +#include "behavior_tree/exceptions.h" #include BT::BehaviorTreeException::BehaviorTreeException(const std::string Message) diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 34239177d..cf3fcc0fa 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include +#include "behavior_tree/fallback_node.h" #include BT::FallbackNode::FallbackNode(std::string name) : ControlNode::ControlNode(name) {} diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 83dae9396..c3abe8b68 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include +#include "behavior_tree/fallback_node_with_memory.h" #include BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name) : ControlNode::ControlNode(name) diff --git a/src/leaf_node.cpp b/src/leaf_node.cpp index 4399ce4d5..87b4c0a6f 100644 --- a/src/leaf_node.cpp +++ b/src/leaf_node.cpp @@ -11,7 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include +#include "behavior_tree/leaf_node.h" #include BT::LeafNode::LeafNode(std::string name) : TreeNode(name) {} diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 883dcbcff..9eaee92bd 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -12,7 +12,7 @@ */ -#include +#include "behavior_tree/parallel_node.h" #include BT::ParallelNode::ParallelNode(std::string name, int threshold_M) : ControlNode::ControlNode(name) diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index a7061b247..dd91059a6 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -12,7 +12,7 @@ */ -#include +#include "behavior_tree/sequence_node.h" #include diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 6cab9cdab..9609ede3b 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -12,7 +12,7 @@ */ -#include +#include "behavior_tree/sequence_node_with_memory.h" #include diff --git a/src/tick_engine.cpp b/src/tick_engine.cpp index 8f94ece07..ce68f9d17 100644 --- a/src/tick_engine.cpp +++ b/src/tick_engine.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include +#include "behavior_tree/tick_engine.h" TickEngine::TickEngine(int initial_value) { diff --git a/src/tree_node.cpp b/src/tree_node.cpp index ae8a89804..4afa724eb 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include +#include "behavior_tree/tree_node.h" #include From e07c5131e48ce2cc74192088f17a0a420ec11efe Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Apr 2018 22:34:16 +0200 Subject: [PATCH 002/125] more consistent naming of methods and removing the Drawing part of the API --- gtest/include/action_test_node.h | 6 +- gtest/include/condition_test_node.h | 2 +- gtest/src/action_test_node.cpp | 7 +- gtest/src/condition_test_node.cpp | 4 +- include/behavior_tree/action_node.h | 40 +++++---- include/behavior_tree/condition_node.h | 11 ++- include/behavior_tree/control_node.h | 10 +-- .../behavior_tree/decorator_negation_node.h | 4 +- include/behavior_tree/decorator_retry_node.h | 8 +- include/behavior_tree/fallback_node.h | 6 +- .../behavior_tree/fallback_node_with_memory.h | 8 +- include/behavior_tree/leaf_node.h | 5 +- include/behavior_tree/parallel_node.h | 8 +- include/behavior_tree/sequence_node.h | 6 +- .../behavior_tree/sequence_node_with_memory.h | 8 +- include/behavior_tree/tree_node.h | 86 ++----------------- src/action_node.cpp | 12 +-- src/condition_node.cpp | 11 +-- src/control_node.cpp | 50 ++--------- src/decorator_negation_node.cpp | 8 -- src/decorator_retry_node.cpp | 7 -- src/fallback_node.cpp | 23 ++--- src/fallback_node_with_memory.cpp | 22 ++--- src/leaf_node.cpp | 12 --- src/parallel_node.cpp | 23 ++--- src/sequence_node.cpp | 22 ++--- src/sequence_node_with_memory.cpp | 23 ++--- src/tree_node.cpp | 62 ++----------- 28 files changed, 133 insertions(+), 361 deletions(-) diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index bb0ee1948..cd5156653 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -11,14 +11,14 @@ namespace BT public: // Constructor ActionTestNode(std::string Name); - ~ActionTestNode(); + virtual ~ActionTestNode() = default; // The method that is going to be executed by the thread - BT::ReturnStatus Tick(); + virtual BT::ReturnStatus Tick() override; void set_time(int time); // The method used to interrupt the execution of the node - void Halt(); + virtual void Halt() override; void set_boolean_value(bool boolean_value); private: int time_; diff --git a/gtest/include/condition_test_node.h b/gtest/include/condition_test_node.h index 35561f31d..91472f081 100644 --- a/gtest/include/condition_test_node.h +++ b/gtest/include/condition_test_node.h @@ -14,7 +14,7 @@ namespace BT void set_boolean_value(bool boolean_value); // The method that is going to be executed by the thread - BT::ReturnStatus Tick(); + virtual BT::ReturnStatus Tick() override; private: bool boolean_value_; }; diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index f96274f36..7ab5718e4 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -21,18 +21,17 @@ BT::ActionTestNode::ActionTestNode(std::string name) : ActionNode::ActionNode(na time_ = 3; } -BT::ActionTestNode::~ActionTestNode() {} BT::ReturnStatus BT::ActionTestNode::Tick() { int i = 0; - while (get_status() != BT::HALTED && i++ < time_) + while (Status() != BT::HALTED && i++ < time_) { DEBUG_STDOUT(" Action " << get_name() << "running! Thread id:" << std::this_thread::get_id()); std::this_thread::sleep_for(std::chrono::seconds(1)); } - if (get_status() != BT::HALTED) + if (Status() != BT::HALTED) { if (boolean_value_) { @@ -53,7 +52,7 @@ BT::ReturnStatus BT::ActionTestNode::Tick() void BT::ActionTestNode::Halt() { - set_status(BT::HALTED); + SetStatus(BT::HALTED); DEBUG_STDOUT("HALTED state set!"); } diff --git a/gtest/src/condition_test_node.cpp b/gtest/src/condition_test_node.cpp index ddefd1807..92fe18a18 100644 --- a/gtest/src/condition_test_node.cpp +++ b/gtest/src/condition_test_node.cpp @@ -27,12 +27,12 @@ BT::ReturnStatus BT::ConditionTestNode::Tick() if (boolean_value_) { - set_status(BT::SUCCESS); + SetStatus(BT::SUCCESS); return BT::SUCCESS; } else { - set_status(BT::FAILURE); + SetStatus(BT::FAILURE); return BT::FAILURE; } } diff --git a/include/behavior_tree/action_node.h b/include/behavior_tree/action_node.h index 9954e4079..71ae7d014 100644 --- a/include/behavior_tree/action_node.h +++ b/include/behavior_tree/action_node.h @@ -6,25 +6,27 @@ namespace BT { - class ActionNode : public LeafNode - { - public: - // Constructor - ActionNode(std::string name); - ~ActionNode(); - - // The method that is going to be executed by the thread - void WaitForTick(); - virtual BT::ReturnStatus Tick() = 0; - - // The method used to interrupt the execution of the node - virtual void Halt() = 0; - - // Methods used to access the node state without the - // conditional waiting (only mutual access) - bool WriteState(ReturnStatus new_state); - int DrawType(); - }; +class ActionNode : public LeafNode +{ +public: + // Constructor + ActionNode(std::string name); + ~ActionNode() = default; + + // The method that is going to be executed by the thread + void WaitForTick(); + + // Methods used to access the node state without the + // conditional waiting (only mutual access) + bool WriteState(ReturnStatus new_state); + + virtual NodeType Type() const override { return ACTION_NODE; } + +protected: + // The thread that will execute the node + std::thread thread_; + +}; } #endif diff --git a/include/behavior_tree/condition_node.h b/include/behavior_tree/condition_node.h index 395486b8f..cf30f6899 100644 --- a/include/behavior_tree/condition_node.h +++ b/include/behavior_tree/condition_node.h @@ -10,18 +10,17 @@ namespace BT public: // Constructor ConditionNode(std::string name); - ~ConditionNode(); - - // The method that is going to be executed by the thread - virtual BT::ReturnStatus Tick() = 0; + ~ConditionNode() = default; // The method used to interrupt the execution of the node - void Halt(); + virtual void Halt() override; // Methods used to access the node state without the // conditional waiting (only mutual access) bool WriteState(ReturnStatus new_state); - int DrawType(); + + virtual NodeType Type() const override { return CONDITION_NODE; } + }; } diff --git a/include/behavior_tree/control_node.h b/include/behavior_tree/control_node.h index 2d9db98c3..1edfe6582 100644 --- a/include/behavior_tree/control_node.h +++ b/include/behavior_tree/control_node.h @@ -24,23 +24,23 @@ namespace BT public: // Constructor ControlNode(std::string name); - ~ControlNode(); + ~ControlNode() = default; // The method used to fill the child vector void AddChild(TreeNode* child); // The method used to know the number of children unsigned int GetChildrenNumber(); - std::vector GetChildren(); + std::vector GetChildren(); // The method used to interrupt the execution of the node - void Halt(); - void ResetColorState(); + virtual void Halt() override; void HaltChildren(int i); - int Depth(); // Methods used to access the node state without the // conditional waiting (only mutual access) bool WriteState(ReturnStatus new_state); + + virtual NodeType Type() const override { return CONTROL_NODE; } }; } diff --git a/include/behavior_tree/decorator_negation_node.h b/include/behavior_tree/decorator_negation_node.h index 6b759f1df..24e3d5dfe 100644 --- a/include/behavior_tree/decorator_negation_node.h +++ b/include/behavior_tree/decorator_negation_node.h @@ -10,8 +10,8 @@ namespace BT public: // Constructor DecoratorNegationNode(std::string name); - ~DecoratorNegationNode(); - int DrawType(); + ~DecoratorNegationNode() = default; + // The method that is going to be executed by the thread void Exec(); void AddChild(TreeNode* child); diff --git a/include/behavior_tree/decorator_retry_node.h b/include/behavior_tree/decorator_retry_node.h index 2700cbb49..733285f82 100644 --- a/include/behavior_tree/decorator_retry_node.h +++ b/include/behavior_tree/decorator_retry_node.h @@ -10,13 +10,13 @@ namespace BT public: // Constructor DecoratorRetryNode(std::string name, unsigned int NTries); - ~DecoratorRetryNode(); - int DrawType(); + ~DecoratorRetryNode() = default; + // The method that is going to be executed by the thread void Exec(); private: - unsigned int NTries_; - unsigned int TryIndx_; + unsigned int NTries_; + unsigned int TryIndx_; }; } diff --git a/include/behavior_tree/fallback_node.h b/include/behavior_tree/fallback_node.h index 4fa630347..61a297ede 100644 --- a/include/behavior_tree/fallback_node.h +++ b/include/behavior_tree/fallback_node.h @@ -10,10 +10,10 @@ namespace BT public: // Constructor FallbackNode(std::string name); - ~FallbackNode(); - int DrawType(); + ~FallbackNode() = default; + // The method that is going to be executed by the thread - BT::ReturnStatus Tick(); + virtual BT::ReturnStatus Tick() override; }; } diff --git a/include/behavior_tree/fallback_node_with_memory.h b/include/behavior_tree/fallback_node_with_memory.h index 2b2a260f3..f3ab1b7b9 100644 --- a/include/behavior_tree/fallback_node_with_memory.h +++ b/include/behavior_tree/fallback_node_with_memory.h @@ -11,11 +11,11 @@ class FallbackNodeWithMemory : public ControlNode // Constructor FallbackNodeWithMemory(std::string name); FallbackNodeWithMemory(std::string name, int reset_policy); - ~FallbackNodeWithMemory(); - int DrawType(); + ~FallbackNodeWithMemory() = default; + // The method that is going to be executed by the thread - BT::ReturnStatus Tick(); - void Halt(); + virtual BT::ReturnStatus Tick() override; + virtual void Halt() override; private: unsigned int current_child_idx_; unsigned int reset_policy_; diff --git a/include/behavior_tree/leaf_node.h b/include/behavior_tree/leaf_node.h index 0519e954b..52a3a9722 100644 --- a/include/behavior_tree/leaf_node.h +++ b/include/behavior_tree/leaf_node.h @@ -12,9 +12,8 @@ namespace BT protected: public: LeafNode(std::string name); - ~LeafNode(); - void ResetColorState(); - int Depth(); + ~LeafNode() = default; + }; } diff --git a/include/behavior_tree/parallel_node.h b/include/behavior_tree/parallel_node.h index 700c10dac..9bad36cc9 100644 --- a/include/behavior_tree/parallel_node.h +++ b/include/behavior_tree/parallel_node.h @@ -10,11 +10,11 @@ class ParallelNode : public ControlNode public: // Constructor ParallelNode(std::string name, int threshold_M); - ~ParallelNode(); - int DrawType(); + ~ParallelNode() = default; + // The method that is going to be executed by the thread - BT::ReturnStatus Tick(); - void Halt(); + virtual BT::ReturnStatus Tick() override; + virtual void Halt() override; unsigned int get_threshold_M(); void set_threshold_M(unsigned int threshold_M); diff --git a/include/behavior_tree/sequence_node.h b/include/behavior_tree/sequence_node.h index 4dd59d7c4..f4b4ecbfd 100644 --- a/include/behavior_tree/sequence_node.h +++ b/include/behavior_tree/sequence_node.h @@ -10,10 +10,10 @@ class SequenceNode : public ControlNode public: // Constructor SequenceNode(std::string name); - ~SequenceNode(); - int DrawType(); + ~SequenceNode() = default; + // The method that is going to be executed by the thread - BT::ReturnStatus Tick(); + virtual BT::ReturnStatus Tick() override; }; } diff --git a/include/behavior_tree/sequence_node_with_memory.h b/include/behavior_tree/sequence_node_with_memory.h index a9a649b50..f3dc68f42 100644 --- a/include/behavior_tree/sequence_node_with_memory.h +++ b/include/behavior_tree/sequence_node_with_memory.h @@ -15,11 +15,11 @@ class SequenceNodeWithMemory : public ControlNode // Constructor SequenceNodeWithMemory(std::string name); SequenceNodeWithMemory(std::string name, int reset_policy); - ~SequenceNodeWithMemory(); - int DrawType(); + ~SequenceNodeWithMemory() = default; + // The method that is going to be executed by the thread - BT::ReturnStatus Tick(); - void Halt(); + virtual BT::ReturnStatus Tick() override; + virtual void Halt() override; private: unsigned int current_child_idx_; unsigned int reset_policy_; diff --git a/include/behavior_tree/tree_node.h b/include/behavior_tree/tree_node.h index 8bbc2b96f..04f1f7497 100644 --- a/include/behavior_tree/tree_node.h +++ b/include/behavior_tree/tree_node.h @@ -2,34 +2,6 @@ #define BEHAVIORTREECORE_TREENODE_H -#ifndef _COLORS_ -#define _COLORS_ - -/* FOREGROUND */ -#define RST "\x1B[0m" -#define KRED "\x1B[31m" -#define KGRN "\x1B[32m" -#define KYEL "\x1B[33m" -#define KBLU "\x1B[34m" -#define KMAG "\x1B[35m" -#define KCYN "\x1B[36m" -#define KWHT "\x1B[37m" - -#define FRED(x) KRED x RST -#define FGRN(x) KGRN x RST -#define FYEL(x) KYEL x RST -#define FBLU(x) KBLU x RST -#define FMAG(x) KMAG x RST -#define FCYN(x) KCYN x RST -#define FWHT(x) KWHT x RST - -#define BOLD(x) "\x1B[1m" x RST -#define UNDL(x) "\x1B[4m" x RST - -#endif - - // #define DEBUG //uncomment this line if you want to print debug messages - #ifdef DEBUG // #define DEBUG_STDERR(x) (std::cerr << (x)) #define DEBUG_STDOUT(str) do { std::cout << str << std::endl; } while( false ) @@ -43,13 +15,11 @@ //#include #include - #include #include #include #include - #include "behavior_tree/tick_engine.h" #include "behavior_tree/exceptions.h" @@ -57,8 +27,8 @@ namespace BT { // Enumerates the possible types of a node, for drawinf we have do discriminate whoich control node it is: - enum NodeType {ACTION_NODE, CONDITION_NODE, CONTROL_NODE}; - enum DrawNodeType {PARALLEL, SELECTOR, SEQUENCE, SEQUENCESTAR, SELECTORSTAR, ACTION, CONDITION,DECORATOR}; + enum NodeType {ACTION_NODE, CONDITION_NODE, CONTROL_NODE, DECORATOR_NODE}; + // Enumerates the states every node can be in after execution during a particular // time step: // - "Success" indicates that the node has completed running during this time step; @@ -95,34 +65,20 @@ namespace BT // Node name std::string name_; - - protected: // The node state that must be treated in a thread-safe way bool is_state_updated_; ReturnStatus status_; - ReturnStatus color_status_; - - std::mutex state_mutex_; - std::mutex color_state_mutex_; + mutable std::mutex state_mutex_; std::condition_variable state_condition_variable_; - // Node type - NodeType type_; - //position and offset for horizontal positioning when drawing - float x_shift_, x_pose_; public: - // The thread that will execute the node - std::thread thread_; // Node semaphore to simulate the tick // (and to synchronize fathers and children) TickEngine tick_engine; - - - // The constructor and the distructor TreeNode(std::string name); ~TreeNode(); @@ -133,39 +89,15 @@ namespace BT // The method used to interrupt the execution of the node virtual void Halt() = 0; - // The method that retrive the state of the node - // (conditional waiting and mutual access) - // ReturnStatus GetNodeState(); - void SetNodeState(ReturnStatus new_state); - void set_color_status(ReturnStatus new_color_status); - - // Methods used to access the node state without the - // conditional waiting (only mutual access) - ReturnStatus ReadState(); - ReturnStatus get_color_status(); - virtual int DrawType() = 0; - virtual void ResetColorState() = 0; - virtual int Depth() = 0; - bool is_halted(); - - - //Getters and setters - void set_x_pose(float x_pose); - float get_x_pose(); - - void set_x_shift(float x_shift); - float get_x_shift(); - - - - ReturnStatus get_status(); - void set_status(ReturnStatus new_status); + bool IsHalted() const; + ReturnStatus Status() const; + void SetStatus(ReturnStatus new_status); - std::string get_name(); - void set_name(std::string new_name); + const std::string& Name() const; + void SetName(const std::string& new_name); - NodeType get_type(); + virtual NodeType Type() const = 0; }; } diff --git a/src/action_node.cpp b/src/action_node.cpp index e13ae99ff..b48de6cfd 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -16,12 +16,9 @@ BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name) { - type_ = BT::ACTION_NODE; thread_ = std::thread(&ActionNode::WaitForTick, this); } -BT::ActionNode::~ActionNode() {} - void BT::ActionNode::WaitForTick() { @@ -35,13 +32,8 @@ void BT::ActionNode::WaitForTick() DEBUG_STDOUT(get_name() << " TICK RECEIVED"); // Running state - set_status(BT::RUNNING); + SetStatus(BT::RUNNING); BT::ReturnStatus status = Tick(); - set_status(status); + SetStatus(status); } } - -int BT::ActionNode::DrawType() -{ - return BT::ACTION; -} diff --git a/src/condition_node.cpp b/src/condition_node.cpp index f689b9587..96460bafa 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -13,16 +13,11 @@ #include "behavior_tree/condition_node.h" #include -BT::ConditionNode::ConditionNode(std::string name) : LeafNode::LeafNode(name) +BT::ConditionNode::ConditionNode(std::string name) : + LeafNode::LeafNode(name) { - type_ = BT::CONDITION_NODE; -} -BT::ConditionNode::~ConditionNode() {} +} void BT::ConditionNode::Halt() {} -int BT::ConditionNode::DrawType() -{ - return BT::CONDITION; -} diff --git a/src/control_node.cpp b/src/control_node.cpp index 6c8aa9123..dac295ca1 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -17,15 +17,11 @@ BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) { - type_ = BT::CONTROL_NODE; - // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable // ReturnStatus child_i_status_ = BT::IDLE; // commented out as unused } -BT::ControlNode::~ControlNode() {} - void BT::ControlNode::AddChild(TreeNode* child) { // // Checking if the child is not already present @@ -50,7 +46,7 @@ void BT::ControlNode::Halt() { DEBUG_STDOUT("HALTING: "<< get_name()); HaltChildren(0); - set_status(BT::HALTED); + SetStatus(BT::HALTED); } std::vector BT::ControlNode::GetChildren() @@ -58,51 +54,19 @@ std::vector BT::ControlNode::GetChildren() return children_nodes_; } -void BT::ControlNode::ResetColorState() -{ - set_color_status(BT::IDLE); - for (unsigned int i = 0; i < children_nodes_.size(); i++) - { - children_nodes_[i]->ResetColorState(); - } -} - void BT::ControlNode::HaltChildren(int i) { for (unsigned int j=i; j < children_nodes_.size(); j++) { - if (children_nodes_[j]->get_type() == BT::CONDITION_NODE) + if (children_nodes_[j]->Status() == BT::RUNNING) { - children_nodes_[i]->ResetColorState(); + DEBUG_STDOUT("SENDING HALT TO CHILD " << children_nodes_[j]-> get_name()); + children_nodes_[j]->Halt(); } - else - { - if (children_nodes_[j]->get_status() == BT::RUNNING) - { - DEBUG_STDOUT("SENDING HALT TO CHILD " << children_nodes_[j]-> get_name()); - children_nodes_[j]->Halt(); - } - else - { - DEBUG_STDOUT("NO NEED TO HALT " << children_nodes_[j]-> get_name() - << "STATUS" << children_nodes_[j]->get_status()); - } - } - } -} - -int BT::ControlNode::Depth() -{ - int depMax = 0; - int dep = 0; - for (unsigned int i = 0; i < children_nodes_.size(); i++) - { - dep = (children_nodes_[i]->Depth()); - if (dep > depMax) - { - depMax = dep; + else{ + DEBUG_STDOUT("NO NEED TO HALT " << children_nodes_[j]-> get_name() + << "STATUS" << children_nodes_[j]->Status()); } } - return 1 + depMax; } diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index f2b8f5179..22c7c80f9 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -166,14 +166,6 @@ void BT::DecoratorNegationNode::Exec() } } -int BT::DecoratorNegationNode::DrawType() -{ - // Lock acquistion - - return BT::DECORATOR; -} - - void BT::DecoratorNegationNode::AddChild(BT::TreeNode* child) { // Checking if the child is not already present diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index da3fdbc31..97609ec71 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -174,10 +174,3 @@ void BT::DecoratorRetryNode::Exec() } } -int BT::DecoratorRetryNode::DrawType() -{ - // Lock acquistion - - return BT::DECORATOR; -} - diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index cf3fcc0fa..22b003590 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -15,7 +15,6 @@ BT::FallbackNode::FallbackNode(std::string name) : ControlNode::ControlNode(name) {} -BT::FallbackNode::~FallbackNode() {} BT::ReturnStatus BT::FallbackNode::Tick() { @@ -32,10 +31,10 @@ BT::ReturnStatus BT::FallbackNode::Tick() Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (children_nodes_[i]->get_type() == BT::ACTION_NODE) + if (children_nodes_[i]->Type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. - child_i_status_ = children_nodes_[i]->get_status(); + child_i_status_ = children_nodes_[i]->Status(); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { @@ -46,7 +45,7 @@ BT::ReturnStatus BT::FallbackNode::Tick() // waits for the tick to arrive to the child do { - child_i_status_ = children_nodes_[i]->get_status(); + child_i_status_ = children_nodes_[i]->Status(); std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS @@ -58,7 +57,7 @@ BT::ReturnStatus BT::FallbackNode::Tick() // 2) if it's not an action: // Send the tick and wait for the response; child_i_status_ = children_nodes_[i]->Tick(); - children_nodes_[i]->set_status(child_i_status_); + children_nodes_[i]->SetStatus(child_i_status_); } // Ponderate on which status to send to the parent @@ -66,23 +65,23 @@ BT::ReturnStatus BT::FallbackNode::Tick() { if (child_i_status_ == BT::SUCCESS) { - children_nodes_[i]->set_status(BT::IDLE); // the child goes in idle if it has returned success. + children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. } // If the child status is not failure, halt the next children and return the status to your parent. DEBUG_STDOUT(get_name() << " is HALTING children from " << (i+1)); HaltChildren(i+1); - set_status(child_i_status_); + SetStatus(child_i_status_); return child_i_status_; } else { // the child returned failure. - children_nodes_[i]->set_status(BT::IDLE); + children_nodes_[i]->SetStatus(BT::IDLE); if (i == N_of_children_ - 1) { // If the child status is failure, and it is the last child to be ticked, // then the sequence has failed. - set_status(BT::FAILURE); + SetStatus(BT::FAILURE); return BT::FAILURE; } } @@ -91,9 +90,3 @@ BT::ReturnStatus BT::FallbackNode::Tick() return BT::EXIT; } -int BT::FallbackNode::DrawType() -{ - // Lock acquistion - - return BT::SELECTOR; -} diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index c3abe8b68..a3bf3d56b 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -27,9 +27,6 @@ BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, int reset_p } -BT::FallbackNodeWithMemory::~FallbackNodeWithMemory() {} - - BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() { DEBUG_STDOUT(get_name() << " ticked, memory counter: "<< current_child_idx_); @@ -46,12 +43,12 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (children_nodes_[current_child_idx_]->get_type() == BT::ACTION_NODE) + if (children_nodes_[current_child_idx_]->Type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. - child_i_status_ = children_nodes_[current_child_idx_]->get_status(); + child_i_status_ = children_nodes_[current_child_idx_]->Status(); DEBUG_STDOUT(get_name() << " It is an action " << children_nodes_[current_child_idx_]->get_name() << " with status: " << child_i_status_); @@ -64,7 +61,7 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() // waits for the tick to arrive to the child do { - child_i_status_ = children_nodes_[current_child_idx_]->get_status(); + child_i_status_ = children_nodes_[current_child_idx_]->Status(); std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS @@ -76,7 +73,7 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() // 2) if it's not an action: // Send the tick and wait for the response; child_i_status_ = children_nodes_[current_child_idx_]->Tick(); - children_nodes_[current_child_idx_]->set_status(child_i_status_); + children_nodes_[current_child_idx_]->SetStatus(child_i_status_); } @@ -84,7 +81,7 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() if (child_i_status_ == BT::SUCCESS ||child_i_status_ == BT::FAILURE ) { // the child goes in idle if it has returned success or failure. - children_nodes_[current_child_idx_]->set_status(BT::IDLE); + children_nodes_[current_child_idx_]->SetStatus(BT::IDLE); } if (child_i_status_ != BT::FAILURE) @@ -96,7 +93,7 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() { current_child_idx_ = 0; } - set_status(child_i_status_); + SetStatus(child_i_status_); return child_i_status_; } else if (current_child_idx_ != N_of_children_ - 1) @@ -113,7 +110,7 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() // if it the last child and it has returned failure, reset the memory current_child_idx_ = 0; } - set_status(child_i_status_); + SetStatus(child_i_status_); return child_i_status_; } } @@ -121,11 +118,6 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() } -int BT::FallbackNodeWithMemory::DrawType() -{ - return BT::SELECTORSTAR; -} - void BT::FallbackNodeWithMemory::Halt() { current_child_idx_ = 0; diff --git a/src/leaf_node.cpp b/src/leaf_node.cpp index 87b4c0a6f..853af3cc4 100644 --- a/src/leaf_node.cpp +++ b/src/leaf_node.cpp @@ -16,15 +16,3 @@ BT::LeafNode::LeafNode(std::string name) : TreeNode(name) {} -BT::LeafNode::~LeafNode() {} - - -void BT::LeafNode::ResetColorState() -{ - color_status_ = BT::IDLE; -} - -int BT::LeafNode::Depth() -{ - return 0; -} diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 9eaee92bd..0330be8a6 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -20,8 +20,6 @@ BT::ParallelNode::ParallelNode(std::string name, int threshold_M) : ControlNode: threshold_M_ = threshold_M; } -BT::ParallelNode::~ParallelNode() {} - BT::ReturnStatus BT::ParallelNode::Tick() { success_childred_num_ = 0; @@ -34,11 +32,11 @@ BT::ReturnStatus BT::ParallelNode::Tick() { DEBUG_STDOUT(get_name() << "TICKING " << children_nodes_[i]->get_name()); - if (children_nodes_[i]->get_type() == BT::ACTION_NODE) + if (children_nodes_[i]->Type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. // Action nodes runs in another parallel, hence you cannot retrieve the status just by executing it. - child_i_status_ = children_nodes_[i]->get_status(); + child_i_status_ = children_nodes_[i]->Status(); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { @@ -49,7 +47,7 @@ BT::ReturnStatus BT::ParallelNode::Tick() // waits for the tick to arrive to the child do { - child_i_status_ = children_nodes_[i]->get_status(); + child_i_status_ = children_nodes_[i]->Status(); std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS @@ -63,18 +61,18 @@ BT::ReturnStatus BT::ParallelNode::Tick() switch (child_i_status_) { case BT::SUCCESS: - children_nodes_[i]->set_status(BT::IDLE); // the child goes in idle if it has returned success. + children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. if (++success_childred_num_ == threshold_M_) { success_childred_num_ = 0; failure_childred_num_ = 0; HaltChildren(0); // halts all running children. The execution is done. - set_status(child_i_status_); + SetStatus(child_i_status_); return child_i_status_; } break; case BT::FAILURE: - children_nodes_[i]->set_status(BT::IDLE); // the child goes in idle if it has returned failure. + children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. if (++failure_childred_num_ > N_of_children_- threshold_M_) { DEBUG_STDOUT("*******PARALLEL" << get_name() @@ -83,12 +81,12 @@ BT::ReturnStatus BT::ParallelNode::Tick() success_childred_num_ = 0; failure_childred_num_ = 0; HaltChildren(0); // halts all running children. The execution is hopeless. - set_status(child_i_status_); + SetStatus(child_i_status_); return child_i_status_; } break; case BT::RUNNING: - set_status(child_i_status_); + SetStatus(child_i_status_); break; default: break; @@ -104,11 +102,6 @@ void BT::ParallelNode::Halt() BT::ControlNode::Halt(); } -int BT::ParallelNode::DrawType() -{ - return BT::PARALLEL; -} - unsigned int BT::ParallelNode::get_threshold_M() { diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index dd91059a6..59ac5d968 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -18,7 +18,6 @@ BT::SequenceNode::SequenceNode(std::string name) : ControlNode::ControlNode(name) {} -BT::SequenceNode::~SequenceNode() {} BT::ReturnStatus BT::SequenceNode::Tick() { @@ -34,10 +33,10 @@ BT::ReturnStatus BT::SequenceNode::Tick() Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (children_nodes_[i]->get_type() == BT::ACTION_NODE) + if (children_nodes_[i]->Type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. - child_i_status_ = children_nodes_[i]->get_status(); + child_i_status_ = children_nodes_[i]->Status(); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { @@ -48,7 +47,7 @@ BT::ReturnStatus BT::SequenceNode::Tick() // waits for the tick to arrive to the child do { - child_i_status_ = children_nodes_[i]->get_status(); + child_i_status_ = children_nodes_[i]->Status(); std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS @@ -60,7 +59,7 @@ BT::ReturnStatus BT::SequenceNode::Tick() // 2) if it's not an action: // Send the tick and wait for the response; child_i_status_ = children_nodes_[i]->Tick(); - children_nodes_[i]->set_status(child_i_status_); + children_nodes_[i]->SetStatus(child_i_status_); } // Ponderate on which status to send to the parent if (child_i_status_ != BT::SUCCESS) @@ -68,32 +67,27 @@ BT::ReturnStatus BT::SequenceNode::Tick() // If the child status is not success, halt the next children and return the status to your parent. if (child_i_status_ == BT::FAILURE) { - children_nodes_[i]->set_status(BT::IDLE); // the child goes in idle if it has returned failure. + children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. } DEBUG_STDOUT(get_name() << " is HALTING children from " << (i+1)); HaltChildren(i+1); - set_status(child_i_status_); + SetStatus(child_i_status_); return child_i_status_; } else { // the child returned success. - children_nodes_[i]->set_status(BT::IDLE); + children_nodes_[i]->SetStatus(BT::IDLE); if (i == N_of_children_ - 1) { // If the child status is success, and it is the last child to be ticked, // then the sequence has succeeded. - set_status(BT::SUCCESS); + SetStatus(BT::SUCCESS); return BT::SUCCESS; } } } return BT::EXIT; } - -int BT::SequenceNode::DrawType() -{ - return BT::SEQUENCE; -} diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 9609ede3b..481bb7171 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -30,9 +30,6 @@ BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, int reset_p } -BT::SequenceNodeWithMemory::~SequenceNodeWithMemory() {} - - BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() { DEBUG_STDOUT(get_name() << " ticked, memory counter: "<< current_child_idx_); @@ -49,12 +46,12 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (children_nodes_[current_child_idx_]->get_type() == BT::ACTION_NODE) + if (children_nodes_[current_child_idx_]->Type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. - child_i_status_ = children_nodes_[current_child_idx_]->get_status(); + child_i_status_ = children_nodes_[current_child_idx_]->Status(); DEBUG_STDOUT(get_name() << " It is an action " << children_nodes_[current_child_idx_]->get_name() << " with status: " << child_i_status_); @@ -67,7 +64,7 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() // waits for the tick to arrive to the child do { - child_i_status_ = children_nodes_[current_child_idx_]->get_status(); + child_i_status_ = children_nodes_[current_child_idx_]->Status(); std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS @@ -79,14 +76,14 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() // 2) if it's not an action: // Send the tick and wait for the response; child_i_status_ = children_nodes_[current_child_idx_]->Tick(); - children_nodes_[current_child_idx_]->set_status(child_i_status_); + children_nodes_[current_child_idx_]->SetStatus(child_i_status_); } if (child_i_status_ == BT::SUCCESS ||child_i_status_ == BT::FAILURE ) { // the child goes in idle if it has returned success or failure. - children_nodes_[current_child_idx_]->set_status(BT::IDLE); + children_nodes_[current_child_idx_]->SetStatus(BT::IDLE); } if (child_i_status_ != BT::SUCCESS) @@ -98,7 +95,7 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() { current_child_idx_ = 0; } - set_status(child_i_status_); + SetStatus(child_i_status_); return child_i_status_; } else if (current_child_idx_ != N_of_children_ - 1) @@ -115,7 +112,7 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() // if it the last child and it has returned SUCCESS, reset the memory current_child_idx_ = 0; } - set_status(child_i_status_); + SetStatus(child_i_status_); return child_i_status_; } } @@ -123,12 +120,6 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() } -int BT::SequenceNodeWithMemory::DrawType() -{ - return BT::SEQUENCESTAR; -} - - void BT::SequenceNodeWithMemory::Halt() { current_child_idx_ = 0; diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 4afa724eb..96c110a4b 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -19,18 +19,13 @@ BT::TreeNode::TreeNode(std::string name) : tick_engine(0) // Initialization name_ = name; is_state_updated_ = false; - set_status(BT::IDLE); + SetStatus(BT::IDLE); } BT::TreeNode::~TreeNode() {} -void BT::TreeNode::set_status(ReturnStatus new_status) +void BT::TreeNode::SetStatus(ReturnStatus new_status) { - if (new_status != BT::IDLE) - { - set_color_status(new_status); - } - // Lock acquistion std::unique_lock UniqueLock(state_mutex_); @@ -38,69 +33,28 @@ void BT::TreeNode::set_status(ReturnStatus new_status) status_ = new_status; } -BT::ReturnStatus BT::TreeNode::get_status() +BT::ReturnStatus BT::TreeNode::Status() const { // Lock acquistion - DEBUG_STDOUT(get_name() << " is setting its status to " << status_); + DEBUG_STDOUT(Name() << " is setting its status to " << status_); std::lock_guard LockGuard(state_mutex_); - return status_; } -BT::ReturnStatus BT::TreeNode::get_color_status() -{ - // Lock acquistion - std::lock_guard LockGuard(color_state_mutex_); - - return color_status_; -} - -void BT::TreeNode::set_color_status(ReturnStatus new_color_status) -{ - // Lock acquistion - std::lock_guard LockGuard(color_state_mutex_); - // state_ update - color_status_ = new_color_status; -} - -float BT::TreeNode::get_x_pose() -{ - return x_pose_; -} - -void BT::TreeNode::set_x_pose(float x_pose) -{ - x_pose_ = x_pose; -} -float BT::TreeNode::get_x_shift() -{ - return x_shift_; -} - -void BT::TreeNode::set_x_shift(float x_shift) -{ - x_shift_ = x_shift; -} - -void BT::TreeNode::set_name(std::string new_name) +void BT::TreeNode::SetName(const std::string &new_name) { name_ = new_name; } -std::string BT::TreeNode::get_name() +const std::string& BT::TreeNode::Name() const { return name_; } -BT::NodeType BT::TreeNode::get_type() -{ - return type_; -} - -bool BT::TreeNode::is_halted() +bool BT::TreeNode::IsHalted() const { - return get_status() == BT::HALTED; + return Status() == BT::HALTED; } From 86a775d54d012528b59c599fa863802ef0de893e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Apr 2018 22:38:25 +0200 Subject: [PATCH 003/125] minor changes --- include/behavior_tree/control_node.h | 7 +++++-- include/behavior_tree/decorator_negation_node.h | 2 ++ include/behavior_tree/decorator_retry_node.h | 3 +++ src/control_node.cpp | 4 ++-- 4 files changed, 12 insertions(+), 4 deletions(-) diff --git a/include/behavior_tree/control_node.h b/include/behavior_tree/control_node.h index 1edfe6582..2b2ea67ef 100644 --- a/include/behavior_tree/control_node.h +++ b/include/behavior_tree/control_node.h @@ -30,10 +30,13 @@ namespace BT void AddChild(TreeNode* child); // The method used to know the number of children - unsigned int GetChildrenNumber(); - std::vector GetChildren(); + unsigned int ChildrenCount() const; + + const std::vector& Children() const; + // The method used to interrupt the execution of the node virtual void Halt() override; + void HaltChildren(int i); // Methods used to access the node state without the diff --git a/include/behavior_tree/decorator_negation_node.h b/include/behavior_tree/decorator_negation_node.h index 24e3d5dfe..ddb71a641 100644 --- a/include/behavior_tree/decorator_negation_node.h +++ b/include/behavior_tree/decorator_negation_node.h @@ -15,6 +15,8 @@ namespace BT // The method that is going to be executed by the thread void Exec(); void AddChild(TreeNode* child); + + virtual NodeType Type() const override { return DECORATOR_NODE; } }; } diff --git a/include/behavior_tree/decorator_retry_node.h b/include/behavior_tree/decorator_retry_node.h index 733285f82..661729be7 100644 --- a/include/behavior_tree/decorator_retry_node.h +++ b/include/behavior_tree/decorator_retry_node.h @@ -14,6 +14,9 @@ namespace BT // The method that is going to be executed by the thread void Exec(); + + virtual NodeType Type() const override { return DECORATOR_NODE; } + private: unsigned int NTries_; unsigned int TryIndx_; diff --git a/src/control_node.cpp b/src/control_node.cpp index dac295ca1..410ab399d 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -37,7 +37,7 @@ void BT::ControlNode::AddChild(TreeNode* child) children_states_.push_back(BT::IDLE); } -unsigned int BT::ControlNode::GetChildrenNumber() +unsigned int BT::ControlNode::ChildrenCount() const { return children_nodes_.size(); } @@ -49,7 +49,7 @@ void BT::ControlNode::Halt() SetStatus(BT::HALTED); } -std::vector BT::ControlNode::GetChildren() +const std::vector &BT::ControlNode::Children() const { return children_nodes_; } From b1f88e3b89dd93673fbfb26f3478e8c2d2398e55 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Apr 2018 22:40:15 +0200 Subject: [PATCH 004/125] API updated --- gtest/gtest_tree.cpp | 163 +++++++++++++++++++++---------------------- 1 file changed, 81 insertions(+), 82 deletions(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index c210a7fc5..75c91471a 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -365,7 +365,7 @@ TEST_F(SimpleSequenceTest, ConditionTrue) // Ticking the root node BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::RUNNING, action->get_status()); + ASSERT_EQ(BT::RUNNING, action->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); } @@ -378,7 +378,7 @@ TEST_F(SimpleSequenceTest, ConditionTurnToFalse) state = root->Tick(); ASSERT_EQ(BT::FAILURE, state); - ASSERT_EQ(BT::HALTED, action->get_status()); + ASSERT_EQ(BT::HALTED, action->Status()); root->Halt(); } @@ -387,7 +387,7 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) { BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); } @@ -403,12 +403,11 @@ TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) state = root->Tick(); state = root->Tick(); - ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::RUNNING, seq_1->get_status()); - ASSERT_EQ(BT::HALTED, seq_2->get_status()); - ASSERT_EQ(BT::HALTED, action_2->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::RUNNING, seq_1->Status()); + ASSERT_EQ(BT::HALTED, seq_2->Status()); + ASSERT_EQ(BT::HALTED, action_2->Status()); root->Halt(); } @@ -422,7 +421,7 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse) state = root->Tick(); ASSERT_EQ(BT::FAILURE, state); - ASSERT_EQ(BT::HALTED, action_1->get_status()); + ASSERT_EQ(BT::HALTED, action_1->Status()); root->Halt(); } @@ -435,7 +434,7 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditions2ToFalse) state = root->Tick(); ASSERT_EQ(BT::FAILURE, state); - ASSERT_EQ(BT::HALTED, action_1->get_status()); + ASSERT_EQ(BT::HALTED, action_1->Status()); root->Halt(); } @@ -448,7 +447,7 @@ TEST_F(SimpleFallbackTest, ConditionTrue) condition->set_boolean_value(true); BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::IDLE, action->get_status()); + ASSERT_EQ(BT::IDLE, action->Status()); ASSERT_EQ(BT::SUCCESS, state); root->Halt(); } @@ -465,7 +464,7 @@ TEST_F(SimpleFallbackTest, ConditionToFalse) state = root->Tick(); ASSERT_EQ(BT::SUCCESS, state); - ASSERT_EQ(BT::HALTED, action->get_status()); + ASSERT_EQ(BT::HALTED, action->Status()); root->Halt(); } @@ -483,7 +482,7 @@ TEST_F(ComplexFallbackTest, Condition1ToTrue) ASSERT_EQ(BT::SUCCESS, state); - ASSERT_EQ(BT::HALTED, action_1->get_status()); + ASSERT_EQ(BT::HALTED, action_1->Status()); root->Halt(); } @@ -499,7 +498,7 @@ TEST_F(ComplexFallbackTest, Condition2ToTrue) state = root->Tick(); ASSERT_EQ(BT::SUCCESS, state); - ASSERT_EQ(BT::HALTED, action_1->get_status()); + ASSERT_EQ(BT::HALTED, action_1->Status()); root->Halt(); } @@ -513,7 +512,7 @@ TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) BT::ReturnStatus state = root->Tick(); ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); root->Halt(); } @@ -526,7 +525,7 @@ TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) BT::ReturnStatus state = root->Tick(); ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); root->Halt(); } @@ -539,7 +538,7 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) BT::ReturnStatus state = root->Tick(); std::this_thread::sleep_for(std::chrono::seconds(1)); - ASSERT_EQ(BT::RUNNING, action->get_status()); + ASSERT_EQ(BT::RUNNING, action->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); } @@ -554,7 +553,7 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) state = root->Tick(); ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action->get_status()); + ASSERT_EQ(BT::RUNNING, action->Status()); root->Halt(); } @@ -564,8 +563,8 @@ TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) { BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::IDLE, action_2->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::IDLE, action_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -580,8 +579,8 @@ TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) state = root->Tick(); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::IDLE, action_2->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::IDLE, action_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); } @@ -594,8 +593,8 @@ TEST_F(ComplexSequenceWithMemoryTest, Conditions2ToFalse) state = root->Tick(); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::IDLE, action_2->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::IDLE, action_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -611,7 +610,7 @@ TEST_F(ComplexSequenceWithMemoryTest, Action1Done) std::this_thread::sleep_for(std::chrono::seconds(10)); root->Tick(); - ASSERT_EQ(BT::RUNNING, action_2->get_status()); + ASSERT_EQ(BT::RUNNING, action_2->Status()); root->Halt(); } @@ -624,7 +623,7 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) BT::ReturnStatus state = root->Tick(); std::this_thread::sleep_for(std::chrono::seconds(1)); - ASSERT_EQ(BT::RUNNING, action->get_status()); + ASSERT_EQ(BT::RUNNING, action->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -641,7 +640,7 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) state = root->Tick(); ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action->get_status()); + ASSERT_EQ(BT::RUNNING, action->Status()); root->Halt(); } @@ -652,8 +651,8 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) { BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::IDLE, action_1->get_status()); - ASSERT_EQ(BT::IDLE, action_2->get_status()); + ASSERT_EQ(BT::IDLE, action_1->Status()); + ASSERT_EQ(BT::IDLE, action_2->Status()); ASSERT_EQ(BT::SUCCESS, state); root->Halt(); @@ -664,8 +663,8 @@ TEST_F(ComplexFallbackWithMemoryTest, Condition1False) condition_1->set_boolean_value(false); BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::IDLE, action_1->get_status()); - ASSERT_EQ(BT::IDLE, action_2->get_status()); + ASSERT_EQ(BT::IDLE, action_1->Status()); + ASSERT_EQ(BT::IDLE, action_2->Status()); ASSERT_EQ(BT::SUCCESS, state); root->Halt(); @@ -678,8 +677,8 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) condition_2->set_boolean_value(false); BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::IDLE, action_2->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::IDLE, action_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -697,8 +696,8 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) state = root->Tick(); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::IDLE, action_2->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::IDLE, action_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -716,8 +715,8 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) state = root->Tick(); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::IDLE, action_2->get_status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::IDLE, action_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -735,8 +734,8 @@ TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) std::this_thread::sleep_for(std::chrono::seconds(5)); state = root->Tick(); - ASSERT_EQ(BT::IDLE, action_1->get_status()); - ASSERT_EQ(BT::RUNNING, action_2->get_status()); + ASSERT_EQ(BT::IDLE, action_1->Status()); + ASSERT_EQ(BT::RUNNING, action_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -747,10 +746,10 @@ TEST_F(SimpleParallelTest, ConditionsTrue) { BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::IDLE, condition_1->get_status()); - ASSERT_EQ(BT::IDLE, condition_2->get_status()); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::RUNNING, action_2->get_status()); + ASSERT_EQ(BT::IDLE, condition_1->Status()); + ASSERT_EQ(BT::IDLE, condition_2->Status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::RUNNING, action_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -765,10 +764,10 @@ TEST_F(SimpleParallelTest, Threshold_3) std::this_thread::sleep_for(std::chrono::seconds(5)); BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::IDLE, condition_1->get_status()); - ASSERT_EQ(BT::IDLE, condition_2->get_status()); - ASSERT_EQ(BT::IDLE, action_1->get_status()); - ASSERT_EQ(BT::HALTED, action_2->get_status()); + ASSERT_EQ(BT::IDLE, condition_1->Status()); + ASSERT_EQ(BT::IDLE, condition_2->Status()); + ASSERT_EQ(BT::IDLE, action_1->Status()); + ASSERT_EQ(BT::HALTED, action_2->Status()); ASSERT_EQ(BT::SUCCESS, state); root->Halt(); @@ -780,10 +779,10 @@ TEST_F(SimpleParallelTest, Threshold_1) root->set_threshold_M(1); BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::IDLE, condition_1->get_status()); - ASSERT_EQ(BT::IDLE, condition_2->get_status()); - ASSERT_EQ(BT::IDLE, action_1->get_status()); - ASSERT_EQ(BT::IDLE, action_2->get_status()); + ASSERT_EQ(BT::IDLE, condition_1->Status()); + ASSERT_EQ(BT::IDLE, condition_2->Status()); + ASSERT_EQ(BT::IDLE, action_1->Status()); + ASSERT_EQ(BT::IDLE, action_2->Status()); ASSERT_EQ(BT::SUCCESS, state); root->Halt(); @@ -792,14 +791,14 @@ TEST_F(ComplexParallelTest, ConditionsTrue) { BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::IDLE, condition_1->get_status()); - ASSERT_EQ(BT::IDLE, condition_2->get_status()); - ASSERT_EQ(BT::IDLE, condition_3->get_status()); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::RUNNING, action_2->get_status()); - ASSERT_EQ(BT::IDLE, action_3->get_status()); - ASSERT_EQ(BT::RUNNING, parallel_1->get_status()); - ASSERT_EQ(BT::IDLE, parallel_2->get_status()); + ASSERT_EQ(BT::IDLE, condition_1->Status()); + ASSERT_EQ(BT::IDLE, condition_2->Status()); + ASSERT_EQ(BT::IDLE, condition_3->Status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::RUNNING, action_2->Status()); + ASSERT_EQ(BT::IDLE, action_3->Status()); + ASSERT_EQ(BT::RUNNING, parallel_1->Status()); + ASSERT_EQ(BT::IDLE, parallel_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -812,14 +811,14 @@ TEST_F(ComplexParallelTest, Condition3False) condition_3->set_boolean_value(false); BT::ReturnStatus state = root->Tick(); - ASSERT_EQ(BT::IDLE, condition_1->get_status()); - ASSERT_EQ(BT::IDLE, condition_2->get_status()); - ASSERT_EQ(BT::IDLE, condition_3->get_status()); - ASSERT_EQ(BT::RUNNING, action_1->get_status()); - ASSERT_EQ(BT::RUNNING, action_2->get_status()); - ASSERT_EQ(BT::RUNNING, action_3->get_status()); - ASSERT_EQ(BT::RUNNING, parallel_1->get_status()); - ASSERT_EQ(BT::RUNNING, parallel_2->get_status()); + ASSERT_EQ(BT::IDLE, condition_1->Status()); + ASSERT_EQ(BT::IDLE, condition_2->Status()); + ASSERT_EQ(BT::IDLE, condition_3->Status()); + ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::RUNNING, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_3->Status()); + ASSERT_EQ(BT::RUNNING, parallel_1->Status()); + ASSERT_EQ(BT::RUNNING, parallel_2->Status()); ASSERT_EQ(BT::RUNNING, state); root->Halt(); @@ -836,19 +835,19 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) std::this_thread::sleep_for(std::chrono::seconds(5)); - ASSERT_EQ(BT::IDLE, condition_1->get_status()); - ASSERT_EQ(BT::IDLE, condition_2->get_status()); - ASSERT_EQ(BT::IDLE, condition_3->get_status()); - ASSERT_EQ(BT::SUCCESS, action_1->get_status()); // success not read yet by the node parallel_1 - ASSERT_EQ(BT::RUNNING, parallel_1->get_status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded + ASSERT_EQ(BT::IDLE, condition_1->Status()); + ASSERT_EQ(BT::IDLE, condition_2->Status()); + ASSERT_EQ(BT::IDLE, condition_3->Status()); + ASSERT_EQ(BT::SUCCESS, action_1->Status()); // success not read yet by the node parallel_1 + ASSERT_EQ(BT::RUNNING, parallel_1->Status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded state = root->Tick(); - ASSERT_EQ(BT::IDLE, action_1->get_status()); - ASSERT_EQ(BT::IDLE, parallel_1->get_status()); - ASSERT_EQ(BT::HALTED, action_2->get_status()); - ASSERT_EQ(BT::RUNNING, action_3->get_status()); - ASSERT_EQ(BT::RUNNING, parallel_2->get_status()); + ASSERT_EQ(BT::IDLE, action_1->Status()); + ASSERT_EQ(BT::IDLE, parallel_1->Status()); + ASSERT_EQ(BT::HALTED, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_3->Status()); + ASSERT_EQ(BT::RUNNING, parallel_2->Status()); ASSERT_EQ(BT::RUNNING, state); @@ -856,11 +855,11 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) std::this_thread::sleep_for(std::chrono::seconds(15)); state = root->Tick(); - ASSERT_EQ(BT::IDLE, parallel_2->get_status()); - ASSERT_EQ(BT::IDLE, action_1->get_status()); - ASSERT_EQ(BT::IDLE, parallel_1->get_status()); - ASSERT_EQ(BT::IDLE, action_3->get_status()); - ASSERT_EQ(BT::IDLE, parallel_2->get_status()); + ASSERT_EQ(BT::IDLE, parallel_2->Status()); + ASSERT_EQ(BT::IDLE, action_1->Status()); + ASSERT_EQ(BT::IDLE, parallel_1->Status()); + ASSERT_EQ(BT::IDLE, action_3->Status()); + ASSERT_EQ(BT::IDLE, parallel_2->Status()); ASSERT_EQ(BT::SUCCESS, state); root->Halt(); From 5b9e2145ff31823bac28f68eea7aaa560f6d9d99 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 11:47:51 +0200 Subject: [PATCH 005/125] directory renamed --- .gitignore | 1 + gtest/gtest_tree.cpp | 2 +- gtest/include/action_test_node.h | 2 +- gtest/include/condition_test_node.h | 2 +- include/behavior_tree/behavior_tree.h | 20 ------------------- .../action_node.h | 0 include/behavior_tree_core/behavior_tree.h | 20 +++++++++++++++++++ .../condition_node.h | 0 .../control_node.h | 2 +- .../decorator_negation_node.h | 2 +- .../decorator_retry_node.h | 2 +- .../exceptions.h | 0 .../fallback_node.h | 2 +- .../fallback_node_with_memory.h | 2 +- .../leaf_node.h | 2 +- .../parallel_node.h | 2 +- .../sequence_node.h | 2 +- .../sequence_node_with_memory.h | 2 +- .../tick_engine.h | 0 .../tree_node.h | 6 +++--- src/action_node.cpp | 2 +- src/condition_node.cpp | 2 +- src/control_node.cpp | 2 +- src/exceptions.cpp | 2 +- src/fallback_node.cpp | 2 +- src/fallback_node_with_memory.cpp | 2 +- src/leaf_node.cpp | 2 +- src/parallel_node.cpp | 2 +- src/sequence_node.cpp | 2 +- src/sequence_node_with_memory.cpp | 2 +- src/tick_engine.cpp | 2 +- src/tree_node.cpp | 2 +- 32 files changed, 48 insertions(+), 47 deletions(-) delete mode 100644 include/behavior_tree/behavior_tree.h rename include/{behavior_tree => behavior_tree_core}/action_node.h (100%) create mode 100644 include/behavior_tree_core/behavior_tree.h rename include/{behavior_tree => behavior_tree_core}/condition_node.h (100%) rename include/{behavior_tree => behavior_tree_core}/control_node.h (96%) rename include/{behavior_tree => behavior_tree_core}/decorator_negation_node.h (91%) rename include/{behavior_tree => behavior_tree_core}/decorator_retry_node.h (92%) rename include/{behavior_tree => behavior_tree_core}/exceptions.h (100%) rename include/{behavior_tree => behavior_tree_core}/fallback_node.h (88%) rename include/{behavior_tree => behavior_tree_core}/fallback_node_with_memory.h (92%) rename include/{behavior_tree => behavior_tree_core}/leaf_node.h (84%) rename include/{behavior_tree => behavior_tree_core}/parallel_node.h (93%) rename include/{behavior_tree => behavior_tree_core}/sequence_node.h (87%) rename include/{behavior_tree => behavior_tree_core}/sequence_node_with_memory.h (92%) rename include/{behavior_tree => behavior_tree_core}/tick_engine.h (100%) rename include/{behavior_tree => behavior_tree_core}/tree_node.h (96%) diff --git a/.gitignore b/.gitignore index b25c15b81..dab621299 100644 --- a/.gitignore +++ b/.gitignore @@ -1 +1,2 @@ *~ +/CMakeLists.txt.user diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 75c91471a..037494360 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -14,7 +14,7 @@ #include #include "action_test_node.h" #include "condition_test_node.h" -#include "behavior_tree/behavior_tree.h" +#include "behavior_tree_core/behavior_tree.h" diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index cd5156653..1cfce769e 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -1,7 +1,7 @@ #ifndef ACTIONTEST_H #define ACTIONTEST_H -#include "behavior_tree/action_node.h" +#include "behavior_tree_core/action_node.h" namespace BT { diff --git a/gtest/include/condition_test_node.h b/gtest/include/condition_test_node.h index 91472f081..a5157bd84 100644 --- a/gtest/include/condition_test_node.h +++ b/gtest/include/condition_test_node.h @@ -1,7 +1,7 @@ #ifndef CONDITIONTEST_H #define CONDITIONTEST_H -#include "behavior_tree/condition_node.h" +#include "behavior_tree_core/condition_node.h" namespace BT { diff --git a/include/behavior_tree/behavior_tree.h b/include/behavior_tree/behavior_tree.h deleted file mode 100644 index f73f1fd08..000000000 --- a/include/behavior_tree/behavior_tree.h +++ /dev/null @@ -1,20 +0,0 @@ -#ifndef BEHAVIOR_TREE_H -#define BEHAVIOR_TREE_H - -#include "behavior_tree/parallel_node.h" -#include "behavior_tree/fallback_node.h" -#include "behavior_tree/sequence_node.h" - -#include "behavior_tree/sequence_node_with_memory.h" -#include "behavior_tree/fallback_node_with_memory.h" - -#include "behavior_tree/action_node.h" -#include "behavior_tree/condition_node.h" - -#include "behavior_tree/decorator_negation_node.h" -#include "behavior_tree/decorator_retry_node.h" - -#include "behavior_tree/exceptions.h" - - -#endif // BEHAVIOR_TREE_H diff --git a/include/behavior_tree/action_node.h b/include/behavior_tree_core/action_node.h similarity index 100% rename from include/behavior_tree/action_node.h rename to include/behavior_tree_core/action_node.h diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h new file mode 100644 index 000000000..4b2de72b2 --- /dev/null +++ b/include/behavior_tree_core/behavior_tree.h @@ -0,0 +1,20 @@ +#ifndef BEHAVIOR_TREE_H +#define BEHAVIOR_TREE_H + +#include "behavior_tree_core/parallel_node.h" +#include "behavior_tree_core/fallback_node.h" +#include "behavior_tree_core/sequence_node.h" + +#include "behavior_tree_core/sequence_node_with_memory.h" +#include "behavior_tree_core/fallback_node_with_memory.h" + +#include "behavior_tree_core/action_node.h" +#include "behavior_tree_core/condition_node.h" + +#include "behavior_tree_core/decorator_negation_node.h" +#include "behavior_tree_core/decorator_retry_node.h" + +#include "behavior_tree_core/exceptions.h" + + +#endif // BEHAVIOR_TREE_H diff --git a/include/behavior_tree/condition_node.h b/include/behavior_tree_core/condition_node.h similarity index 100% rename from include/behavior_tree/condition_node.h rename to include/behavior_tree_core/condition_node.h diff --git a/include/behavior_tree/control_node.h b/include/behavior_tree_core/control_node.h similarity index 96% rename from include/behavior_tree/control_node.h rename to include/behavior_tree_core/control_node.h index 2b2ea67ef..ed9c92d4f 100644 --- a/include/behavior_tree/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -3,7 +3,7 @@ #include -#include "behavior_tree/tree_node.h" +#include "behavior_tree_core/tree_node.h" namespace BT { diff --git a/include/behavior_tree/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h similarity index 91% rename from include/behavior_tree/decorator_negation_node.h rename to include/behavior_tree_core/decorator_negation_node.h index ddb71a641..6f0babd99 100644 --- a/include/behavior_tree/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -1,7 +1,7 @@ #ifndef DECORATORNEGATIONNODE_H #define DECORATORNEGATIONNODE_H -#include "behavior_tree/control_node.h" +#include "behavior_tree_core/control_node.h" namespace BT { diff --git a/include/behavior_tree/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h similarity index 92% rename from include/behavior_tree/decorator_retry_node.h rename to include/behavior_tree_core/decorator_retry_node.h index 661729be7..e60653004 100644 --- a/include/behavior_tree/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -1,7 +1,7 @@ #ifndef DECORATORRETRYNODE_H #define DECORATORRETRYNODE_H -#include "behavior_tree/control_node.h" +#include "behavior_tree_core/control_node.h" namespace BT { diff --git a/include/behavior_tree/exceptions.h b/include/behavior_tree_core/exceptions.h similarity index 100% rename from include/behavior_tree/exceptions.h rename to include/behavior_tree_core/exceptions.h diff --git a/include/behavior_tree/fallback_node.h b/include/behavior_tree_core/fallback_node.h similarity index 88% rename from include/behavior_tree/fallback_node.h rename to include/behavior_tree_core/fallback_node.h index 61a297ede..b3cb76604 100644 --- a/include/behavior_tree/fallback_node.h +++ b/include/behavior_tree_core/fallback_node.h @@ -1,7 +1,7 @@ #ifndef FALLBACKNODE_H #define FALLBACKNODE_H -#include "behavior_tree/control_node.h" +#include "behavior_tree_core/control_node.h" namespace BT { diff --git a/include/behavior_tree/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h similarity index 92% rename from include/behavior_tree/fallback_node_with_memory.h rename to include/behavior_tree_core/fallback_node_with_memory.h index f3ab1b7b9..dc3b742ee 100644 --- a/include/behavior_tree/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -1,6 +1,6 @@ #ifndef FALLBACK_NODE_WITH_MEMORY_H #define FALLBACK_NODE_WITH_MEMORY_H -#include "behavior_tree/control_node.h" +#include "behavior_tree_core/control_node.h" namespace BT diff --git a/include/behavior_tree/leaf_node.h b/include/behavior_tree_core/leaf_node.h similarity index 84% rename from include/behavior_tree/leaf_node.h rename to include/behavior_tree_core/leaf_node.h index 52a3a9722..b7cedbc96 100644 --- a/include/behavior_tree/leaf_node.h +++ b/include/behavior_tree_core/leaf_node.h @@ -3,7 +3,7 @@ #include -#include "behavior_tree/tree_node.h" +#include "behavior_tree_core/tree_node.h" namespace BT { diff --git a/include/behavior_tree/parallel_node.h b/include/behavior_tree_core/parallel_node.h similarity index 93% rename from include/behavior_tree/parallel_node.h rename to include/behavior_tree_core/parallel_node.h index 9bad36cc9..24395f72e 100644 --- a/include/behavior_tree/parallel_node.h +++ b/include/behavior_tree_core/parallel_node.h @@ -1,7 +1,7 @@ #ifndef PARALLEL_NODE_H #define PARALLEL_NODE_H -#include "behavior_tree/control_node.h" +#include "behavior_tree_core/control_node.h" namespace BT { diff --git a/include/behavior_tree/sequence_node.h b/include/behavior_tree_core/sequence_node.h similarity index 87% rename from include/behavior_tree/sequence_node.h rename to include/behavior_tree_core/sequence_node.h index f4b4ecbfd..3431c7525 100644 --- a/include/behavior_tree/sequence_node.h +++ b/include/behavior_tree_core/sequence_node.h @@ -1,7 +1,7 @@ #ifndef SEQUENCENODE_H #define SEQUENCENODE_H -#include "behavior_tree/control_node.h" +#include "behavior_tree_core/control_node.h" namespace BT { diff --git a/include/behavior_tree/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h similarity index 92% rename from include/behavior_tree/sequence_node_with_memory.h rename to include/behavior_tree_core/sequence_node_with_memory.h index f3dc68f42..82600d22f 100644 --- a/include/behavior_tree/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -2,7 +2,7 @@ #define SEQUENCE_NODE_WITH_MEMORY_H -#include "behavior_tree/control_node.h" +#include "behavior_tree_core/control_node.h" diff --git a/include/behavior_tree/tick_engine.h b/include/behavior_tree_core/tick_engine.h similarity index 100% rename from include/behavior_tree/tick_engine.h rename to include/behavior_tree_core/tick_engine.h diff --git a/include/behavior_tree/tree_node.h b/include/behavior_tree_core/tree_node.h similarity index 96% rename from include/behavior_tree/tree_node.h rename to include/behavior_tree_core/tree_node.h index 04f1f7497..5d5653bed 100644 --- a/include/behavior_tree/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -20,8 +20,8 @@ #include #include -#include "behavior_tree/tick_engine.h" -#include "behavior_tree/exceptions.h" +#include "behavior_tree_core/tick_engine.h" +#include "behavior_tree_core/exceptions.h" namespace BT { @@ -81,7 +81,7 @@ namespace BT // The constructor and the distructor TreeNode(std::string name); - ~TreeNode(); + virtual ~TreeNode(); // The method that is going to be executed when the node receive a tick virtual BT::ReturnStatus Tick() = 0; diff --git a/src/action_node.cpp b/src/action_node.cpp index b48de6cfd..d49535ec5 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree/action_node.h" +#include "behavior_tree_core/action_node.h" #include diff --git a/src/condition_node.cpp b/src/condition_node.cpp index 96460bafa..25fbff7b0 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree/condition_node.h" +#include "behavior_tree_core/condition_node.h" #include BT::ConditionNode::ConditionNode(std::string name) : diff --git a/src/control_node.cpp b/src/control_node.cpp index 410ab399d..9b5406fd1 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -11,7 +11,7 @@ */ -#include "behavior_tree/control_node.h" +#include "behavior_tree_core/control_node.h" #include #include diff --git a/src/exceptions.cpp b/src/exceptions.cpp index 3a5deb05a..ff7008327 100644 --- a/src/exceptions.cpp +++ b/src/exceptions.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree/exceptions.h" +#include "behavior_tree_core/exceptions.h" #include BT::BehaviorTreeException::BehaviorTreeException(const std::string Message) diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 22b003590..5b1d6baa4 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree/fallback_node.h" +#include "behavior_tree_core/fallback_node.h" #include BT::FallbackNode::FallbackNode(std::string name) : ControlNode::ControlNode(name) {} diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index a3bf3d56b..cd173b6a5 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree/fallback_node_with_memory.h" +#include "behavior_tree_core/fallback_node_with_memory.h" #include BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name) : ControlNode::ControlNode(name) diff --git a/src/leaf_node.cpp b/src/leaf_node.cpp index 853af3cc4..a0855670f 100644 --- a/src/leaf_node.cpp +++ b/src/leaf_node.cpp @@ -11,7 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree/leaf_node.h" +#include "behavior_tree_core/leaf_node.h" #include BT::LeafNode::LeafNode(std::string name) : TreeNode(name) {} diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 0330be8a6..30ae16288 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -12,7 +12,7 @@ */ -#include "behavior_tree/parallel_node.h" +#include "behavior_tree_core/parallel_node.h" #include BT::ParallelNode::ParallelNode(std::string name, int threshold_M) : ControlNode::ControlNode(name) diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 59ac5d968..04e14f31f 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -12,7 +12,7 @@ */ -#include "behavior_tree/sequence_node.h" +#include "behavior_tree_core/sequence_node.h" #include diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 481bb7171..8add7c812 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -12,7 +12,7 @@ */ -#include "behavior_tree/sequence_node_with_memory.h" +#include "behavior_tree_core/sequence_node_with_memory.h" #include diff --git a/src/tick_engine.cpp b/src/tick_engine.cpp index ce68f9d17..3cd8c40d3 100644 --- a/src/tick_engine.cpp +++ b/src/tick_engine.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree/tick_engine.h" +#include "behavior_tree_core/tick_engine.h" TickEngine::TickEngine(int initial_value) { diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 96c110a4b..8a2bb8ff8 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -10,7 +10,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree/tree_node.h" +#include "behavior_tree_core/tree_node.h" #include From ee91c1130eb197b59f956baf4cc8cda8d05ecf51 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 11:49:15 +0200 Subject: [PATCH 006/125] fix in CMakeLists.txt --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2c9c51529..43705ea9a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -81,7 +81,7 @@ elseif(GTEST_FOUND) include_directories(gtest/include) add_executable(behavior_tree_core_test ${BT_Tests} ) - target_link_libraries(btpp_test + target_link_libraries(behavior_tree_core_test behavior_tree_core ${GTEST_LIBRARIES} ${GTEST_MAIN_LIBRARIES} ) From fd21426225575f519e40e33e69adaf63f965399c Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 12:25:41 +0200 Subject: [PATCH 007/125] fixing compilation of tests --- .gitignore | 1 + .travis.yml | 9 +++++++++ CMakeLists.txt | 2 +- 3 files changed, 11 insertions(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index dab621299..fda8c879c 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,3 @@ *~ /CMakeLists.txt.user +build* diff --git a/.travis.yml b/.travis.yml index eadd19180..8c1609638 100644 --- a/.travis.yml +++ b/.travis.yml @@ -23,6 +23,15 @@ matrix: before_install: - sudo apt-get update && sudo apt-get --reinstall install -qq build-essential +# see motivation here https://www.eriksmistad.no/getting-started-with-google-test-on-ubuntu/ + - sudo apt-get --reinstall install -qq libgtest-dev cmake + - cd /usr/src/gtest + - sudo cmake CMakeLists.txt + - sudo make + - sudo cp *.a /usr/lib + +# copy or symlink libgtest.a and libgtest_main.a to your /usr/lib folder +sudo cp *.a /usr/lib install: - if [ "$ROS_DISTRO" != "none" ]; then git clone https://github.com/ros-industrial/industrial_ci.git .ci_config; fi diff --git a/CMakeLists.txt b/CMakeLists.txt index 43705ea9a..feffc2dfa 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_tree_core) set(CMAKE_BUILD_TYPE Release) -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11 -Werror=return-type") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11 -pthread -Werror=return-type") ############################################################# # http://answers.ros.org/question/230877/optionally-build-a-package-with-catkin/ From 8405a2421c7ffe02ee85ec19bbd559cf44148b12 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 12:47:08 +0200 Subject: [PATCH 008/125] Adding clang format --- .clang-format | 67 +++++++++++++++++++++++++++++++++++++++++++++ run_clang_format.sh | 3 ++ 2 files changed, 70 insertions(+) create mode 100644 .clang-format create mode 100755 run_clang_format.sh diff --git a/.clang-format b/.clang-format new file mode 100644 index 000000000..34524d527 --- /dev/null +++ b/.clang-format @@ -0,0 +1,67 @@ +--- +BasedOnStyle: Google +AccessModifierOffset: -2 +ConstructorInitializerIndentWidth: 2 +AlignEscapedNewlinesLeft: false +AlignTrailingComments: true +AllowAllParametersOfDeclarationOnNextLine: false +AllowShortIfStatementsOnASingleLine: false +AllowShortLoopsOnASingleLine: false +AllowShortFunctionsOnASingleLine: None +AllowShortLoopsOnASingleLine: false +AlwaysBreakTemplateDeclarations: true +AlwaysBreakBeforeMultilineStrings: false +BreakBeforeBinaryOperators: false +BreakBeforeTernaryOperators: false +BreakConstructorInitializersBeforeComma: true +BinPackParameters: true +ColumnLimit: 120 +ConstructorInitializerAllOnOneLineOrOnePerLine: true +DerivePointerBinding: false +PointerBindsToType: true +ExperimentalAutoDetectBinPacking: false +IndentCaseLabels: true +MaxEmptyLinesToKeep: 1 +NamespaceIndentation: None +ObjCSpaceBeforeProtocolList: true +PenaltyBreakBeforeFirstCallParameter: 19 +PenaltyBreakComment: 60 +PenaltyBreakString: 1 +PenaltyBreakFirstLessLess: 1000 +PenaltyExcessCharacter: 1000 +PenaltyReturnTypeOnItsOwnLine: 90 +SpacesBeforeTrailingComments: 2 +Cpp11BracedListStyle: true +Standard: Auto +IndentWidth: 4 +TabWidth: 4 +UseTab: Never +IndentFunctionDeclarationAfterType: false +SpacesInParentheses: false +SpacesInAngles: false +SpaceInEmptyParentheses: false +SpacesInCStyleCastParentheses: false +SpaceAfterControlStatementKeyword: true +SpaceBeforeAssignmentOperators: true +ContinuationIndentWidth: 4 +SortIncludes: false +SpaceAfterCStyleCast: false + +# Configure each individual brace in BraceWrapping +BreakBeforeBraces: Custom + +# Control of individual brace wrapping cases +BraceWrapping: { + AfterClass: 'true' + AfterControlStatement: 'true' + AfterEnum : 'true' + AfterFunction : 'true' + AfterNamespace : 'true' + AfterStruct : 'true' + AfterUnion : 'true' + BeforeCatch : 'true' + BeforeElse : 'true' + IndentBraces : 'false' +} +... + diff --git a/run_clang_format.sh b/run_clang_format.sh new file mode 100755 index 000000000..cf3d51a14 --- /dev/null +++ b/run_clang_format.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +find . -name '*.h' -or -name '*.hpp' -or -name '*.cpp' | xargs clang-format-3.8 -i -style=file $1 From 54d87b0b734c306bd587ec26e08b20000e8886f9 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 12:55:49 +0200 Subject: [PATCH 009/125] Update .travis.yml --- .travis.yml | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/.travis.yml b/.travis.yml index 8c1609638..b79ce97f9 100644 --- a/.travis.yml +++ b/.travis.yml @@ -23,15 +23,13 @@ matrix: before_install: - sudo apt-get update && sudo apt-get --reinstall install -qq build-essential -# see motivation here https://www.eriksmistad.no/getting-started-with-google-test-on-ubuntu/ + # GTest: see motivation here https://www.eriksmistad.no/getting-started-with-google-test-on-ubuntu/ - sudo apt-get --reinstall install -qq libgtest-dev cmake - cd /usr/src/gtest - sudo cmake CMakeLists.txt - sudo make - sudo cp *.a /usr/lib - -# copy or symlink libgtest.a and libgtest_main.a to your /usr/lib folder -sudo cp *.a /usr/lib + install: - if [ "$ROS_DISTRO" != "none" ]; then git clone https://github.com/ros-industrial/industrial_ci.git .ci_config; fi From 28cd4e23dd4e1585f9888ecb50c26283efe518e4 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 13:00:59 +0200 Subject: [PATCH 010/125] Update .travis.yml --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index b79ce97f9..9767812b5 100644 --- a/.travis.yml +++ b/.travis.yml @@ -29,7 +29,7 @@ before_install: - sudo cmake CMakeLists.txt - sudo make - sudo cp *.a /usr/lib - + - cd $TRAVIS_BUILD_DIR install: - if [ "$ROS_DISTRO" != "none" ]; then git clone https://github.com/ros-industrial/industrial_ci.git .ci_config; fi From 094cb8023be0f6050972fef37632a311b6ea7507 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 15:22:01 +0200 Subject: [PATCH 011/125] fixed compilation with DEBUG_STDOUT is active --- gtest/src/action_test_node.cpp | 6 +++--- src/action_node.cpp | 4 ++-- src/control_node.cpp | 8 ++++---- src/fallback_node.cpp | 4 ++-- src/fallback_node_with_memory.cpp | 8 ++++---- src/parallel_node.cpp | 6 +++--- src/sequence_node.cpp | 4 ++-- src/sequence_node_with_memory.cpp | 8 ++++---- templates/action_node_template.cpp | 4 ++-- 9 files changed, 26 insertions(+), 26 deletions(-) diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 7ab5718e4..8d90d0f77 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -28,19 +28,19 @@ BT::ReturnStatus BT::ActionTestNode::Tick() int i = 0; while (Status() != BT::HALTED && i++ < time_) { - DEBUG_STDOUT(" Action " << get_name() << "running! Thread id:" << std::this_thread::get_id()); + DEBUG_STDOUT(" Action " << Name() << "running! Thread id:" << std::this_thread::get_id()); std::this_thread::sleep_for(std::chrono::seconds(1)); } if (Status() != BT::HALTED) { if (boolean_value_) { - DEBUG_STDOUT(" Action " << get_name() << " Done!"); + DEBUG_STDOUT(" Action " << Name() << " Done!"); return BT::SUCCESS; } else { - DEBUG_STDOUT(" Action " << get_name() << " FAILED!"); + DEBUG_STDOUT(" Action " << Name() << " FAILED!"); return BT::FAILURE; } } diff --git a/src/action_node.cpp b/src/action_node.cpp index d49535ec5..92de80c25 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -26,10 +26,10 @@ void BT::ActionNode::WaitForTick() while (true) { // Waiting for the tick to come - DEBUG_STDOUT(get_name() << " WAIT FOR TICK"); + DEBUG_STDOUT(Name() << " WAIT FOR TICK"); tick_engine.Wait(); - DEBUG_STDOUT(get_name() << " TICK RECEIVED"); + DEBUG_STDOUT(Name() << " TICK RECEIVED"); // Running state SetStatus(BT::RUNNING); diff --git a/src/control_node.cpp b/src/control_node.cpp index 9b5406fd1..6686aa6fe 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -29,7 +29,7 @@ void BT::ControlNode::AddChild(TreeNode* child) // { // if (children_nodes_[i] == child) // { -// throw BehaviorTreeException("'" + child->get_name() + "' is already a '" + get_name() + "' child."); +// throw BehaviorTreeException("'" + child->Name() + "' is already a '" + get_name() + "' child."); // } // } @@ -44,7 +44,7 @@ unsigned int BT::ControlNode::ChildrenCount() const void BT::ControlNode::Halt() { - DEBUG_STDOUT("HALTING: "<< get_name()); + DEBUG_STDOUT("HALTING: "<< Name()); HaltChildren(0); SetStatus(BT::HALTED); } @@ -60,11 +60,11 @@ void BT::ControlNode::HaltChildren(int i) { if (children_nodes_[j]->Status() == BT::RUNNING) { - DEBUG_STDOUT("SENDING HALT TO CHILD " << children_nodes_[j]-> get_name()); + DEBUG_STDOUT("SENDING HALT TO CHILD " << children_nodes_[j]->Name()); children_nodes_[j]->Halt(); } else{ - DEBUG_STDOUT("NO NEED TO HALT " << children_nodes_[j]-> get_name() + DEBUG_STDOUT("NO NEED TO HALT " << children_nodes_[j]->Name() << "STATUS" << children_nodes_[j]->Status()); } } diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 5b1d6baa4..12b7b48e4 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -39,7 +39,7 @@ BT::ReturnStatus BT::FallbackNode::Tick() if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(get_name() << "NEEDS TO TICK " << children_nodes_[i]->get_name()); + DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[i]->Name()); children_nodes_[i]->tick_engine.Tick(); // waits for the tick to arrive to the child @@ -68,7 +68,7 @@ BT::ReturnStatus BT::FallbackNode::Tick() children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. } // If the child status is not failure, halt the next children and return the status to your parent. - DEBUG_STDOUT(get_name() << " is HALTING children from " << (i+1)); + DEBUG_STDOUT(Name() << " is HALTING children from " << (i+1)); HaltChildren(i+1); SetStatus(child_i_status_); return child_i_status_; diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index cd173b6a5..cfb7993e2 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -29,7 +29,7 @@ BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, int reset_p BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() { - DEBUG_STDOUT(get_name() << " ticked, memory counter: "<< current_child_idx_); + DEBUG_STDOUT(Name() << " ticked, memory counter: "<< current_child_idx_); // Vector size initialization. N_of_children_ could change at runtime if you edit the tree N_of_children_ = children_nodes_.size(); @@ -49,13 +49,13 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. child_i_status_ = children_nodes_[current_child_idx_]->Status(); - DEBUG_STDOUT(get_name() << " It is an action " << children_nodes_[current_child_idx_]->get_name() + DEBUG_STDOUT(Name() << " It is an action " << children_nodes_[current_child_idx_]->Name() << " with status: " << child_i_status_); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(get_name() << "NEEDS TO TICK " << children_nodes_[current_child_idx_]->get_name()); + DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[current_child_idx_]->Name()); children_nodes_[current_child_idx_]->tick_engine.Tick(); // waits for the tick to arrive to the child @@ -87,7 +87,7 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() if (child_i_status_ != BT::FAILURE) { // If the child status is not success, return the status - DEBUG_STDOUT("the status of: " << get_name() << " becomes " << child_i_status_); + DEBUG_STDOUT("the status of: " << Name() << " becomes " << child_i_status_); if (child_i_status_ == BT::SUCCESS && (reset_policy_ == BT::ON_SUCCESS || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) { diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 30ae16288..ab9fe2914 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -30,7 +30,7 @@ BT::ReturnStatus BT::ParallelNode::Tick() // Routing the tree according to the sequence node's logic: for (unsigned int i = 0; i < N_of_children_; i++) { - DEBUG_STDOUT(get_name() << "TICKING " << children_nodes_[i]->get_name()); + DEBUG_STDOUT(Name() << "TICKING " << children_nodes_[i]->Name()); if (children_nodes_[i]->Type() == BT::ACTION_NODE) { @@ -41,7 +41,7 @@ BT::ReturnStatus BT::ParallelNode::Tick() if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1 If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(get_name() << "NEEDS TO TICK " << children_nodes_[i]->get_name()); + DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[i]->Name()); children_nodes_[i]->tick_engine.Tick(); // waits for the tick to arrive to the child @@ -75,7 +75,7 @@ BT::ReturnStatus BT::ParallelNode::Tick() children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. if (++failure_childred_num_ > N_of_children_- threshold_M_) { - DEBUG_STDOUT("*******PARALLEL" << get_name() + DEBUG_STDOUT("*******PARALLEL" << Name() << " FAILED****** failure_childred_num_:" << failure_childred_num_); success_childred_num_ = 0; diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 04e14f31f..9d9cfd934 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -41,7 +41,7 @@ BT::ReturnStatus BT::SequenceNode::Tick() if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(get_name() << "NEEDS TO TICK " << children_nodes_[i]->get_name()); + DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[i]->Name()); children_nodes_[i]->tick_engine.Tick(); // waits for the tick to arrive to the child @@ -70,7 +70,7 @@ BT::ReturnStatus BT::SequenceNode::Tick() children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. } - DEBUG_STDOUT(get_name() << " is HALTING children from " << (i+1)); + DEBUG_STDOUT(Name() << " is HALTING children from " << (i+1)); HaltChildren(i+1); SetStatus(child_i_status_); return child_i_status_; diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 8add7c812..dd7a60fa6 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -32,7 +32,7 @@ BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, int reset_p BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() { - DEBUG_STDOUT(get_name() << " ticked, memory counter: "<< current_child_idx_); + DEBUG_STDOUT(Name() << " ticked, memory counter: "<< current_child_idx_); // Vector size initialization. N_of_children_ could change at runtime if you edit the tree N_of_children_ = children_nodes_.size(); @@ -52,13 +52,13 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. child_i_status_ = children_nodes_[current_child_idx_]->Status(); - DEBUG_STDOUT(get_name() << " It is an action " << children_nodes_[current_child_idx_]->get_name() + DEBUG_STDOUT(Name() << " It is an action " << children_nodes_[current_child_idx_]->Name() << " with status: " << child_i_status_); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(get_name() << "NEEDS TO TICK " << children_nodes_[current_child_idx_]->get_name()); + DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[current_child_idx_]->Name()); children_nodes_[current_child_idx_]->tick_engine.Tick(); // waits for the tick to arrive to the child @@ -89,7 +89,7 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() if (child_i_status_ != BT::SUCCESS) { // If the child status is not success, return the status - DEBUG_STDOUT("the status of: " << get_name() << " becomes " << child_i_status_); + DEBUG_STDOUT("the status of: " << Name() << " becomes " << child_i_status_); if (child_i_status_ == BT::FAILURE && (reset_policy_ == BT::ON_FAILURE || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) { diff --git a/templates/action_node_template.cpp b/templates/action_node_template.cpp index d8e82aa1d..668287a89 100644 --- a/templates/action_node_template.cpp +++ b/templates/action_node_template.cpp @@ -14,10 +14,10 @@ void BT::CLASSNAME::WaitForTick() { // Waiting for the first tick to come - DEBUG_STDOUT(get_name() << " WAIT FOR TICK"); + DEBUG_STDOUT(Name() << " WAIT FOR TICK"); tick_engine.Wait(); - DEBUG_STDOUT(get_name() << " TICK RECEIVED"); + DEBUG_STDOUT(Name() << " TICK RECEIVED"); // Running state set_status(BT::RUNNING); From 482d0c52edb9a877d1fa9e60588a0ccbcad0cbd3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 15:28:25 +0200 Subject: [PATCH 012/125] Copyright updated --- README.md | 1 + gtest/src/action_test_node.cpp | 3 ++- include/behavior_tree_core/action_node.h | 14 ++++++++++++++ include/behavior_tree_core/behavior_tree.h | 14 ++++++++++++++ include/behavior_tree_core/condition_node.h | 13 +++++++++++++ include/behavior_tree_core/control_node.h | 13 +++++++++++++ .../decorator_negation_node.h | 13 +++++++++++++ .../behavior_tree_core/decorator_retry_node.h | 13 +++++++++++++ include/behavior_tree_core/exceptions.h | 13 +++++++++++++ include/behavior_tree_core/fallback_node.h | 13 +++++++++++++ .../fallback_node_with_memory.h | 13 +++++++++++++ include/behavior_tree_core/leaf_node.h | 13 +++++++++++++ include/behavior_tree_core/parallel_node.h | 13 +++++++++++++ include/behavior_tree_core/sequence_node.h | 13 +++++++++++++ .../sequence_node_with_memory.h | 17 +++++++++++++---- include/behavior_tree_core/tick_engine.h | 15 +++++++++++++-- include/behavior_tree_core/tree_node.h | 13 +++++++++++++ src/action_node.cpp | 4 +++- src/condition_node.cpp | 4 +++- src/control_node.cpp | 3 ++- src/exceptions.cpp | 4 +++- src/fallback_node.cpp | 4 +++- src/fallback_node_with_memory.cpp | 4 +++- src/leaf_node.cpp | 5 +++-- src/parallel_node.cpp | 4 ++-- src/sequence_node.cpp | 4 ++-- src/sequence_node_with_memory.cpp | 5 +++-- src/tick_engine.cpp | 4 +++- src/tree_node.cpp | 4 +++- 29 files changed, 233 insertions(+), 23 deletions(-) diff --git a/README.md b/README.md index 22d23cd5e..d84d6bd6c 100644 --- a/README.md +++ b/README.md @@ -127,6 +127,7 @@ LICENSE The MIT License (MIT) Copyright (c) 2014-2018 Michele Colledanchise +Copyright (c) 2018 Davide Faconti Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 8d90d0f77..acc15e840 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -1,4 +1,5 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 71ae7d014..3b6bc9ef8 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -1,3 +1,17 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + + #ifndef BEHAVIORTREECORE_ACTIONNODE_H #define BEHAVIORTREECORE_ACTIONNODE_H diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index 4b2de72b2..87c86dece 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -1,3 +1,17 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + + #ifndef BEHAVIOR_TREE_H #define BEHAVIOR_TREE_H diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index cf30f6899..d0ea09ca4 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef CONDITIONNODE_H #define CONDITIONNODE_H diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index ed9c92d4f..73388e6f7 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef CONTROLNODE_H #define CONTROLNODE_H diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h index 6f0babd99..3caa70343 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef DECORATORNEGATIONNODE_H #define DECORATORNEGATIONNODE_H diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h index e60653004..bcddef44b 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef DECORATORRETRYNODE_H #define DECORATORRETRYNODE_H diff --git a/include/behavior_tree_core/exceptions.h b/include/behavior_tree_core/exceptions.h index 1d7369a68..dcca1c8cb 100644 --- a/include/behavior_tree_core/exceptions.h +++ b/include/behavior_tree_core/exceptions.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef EXCEPTIONS_H #define EXCEPTIONS_H diff --git a/include/behavior_tree_core/fallback_node.h b/include/behavior_tree_core/fallback_node.h index b3cb76604..0e071ba70 100644 --- a/include/behavior_tree_core/fallback_node.h +++ b/include/behavior_tree_core/fallback_node.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef FALLBACKNODE_H #define FALLBACKNODE_H diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index dc3b742ee..c90ec9007 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef FALLBACK_NODE_WITH_MEMORY_H #define FALLBACK_NODE_WITH_MEMORY_H #include "behavior_tree_core/control_node.h" diff --git a/include/behavior_tree_core/leaf_node.h b/include/behavior_tree_core/leaf_node.h index b7cedbc96..2bdcad1ab 100644 --- a/include/behavior_tree_core/leaf_node.h +++ b/include/behavior_tree_core/leaf_node.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef LEAFNODE_H #define LEAFNODE_H diff --git a/include/behavior_tree_core/parallel_node.h b/include/behavior_tree_core/parallel_node.h index 24395f72e..1d4c04d7a 100644 --- a/include/behavior_tree_core/parallel_node.h +++ b/include/behavior_tree_core/parallel_node.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef PARALLEL_NODE_H #define PARALLEL_NODE_H diff --git a/include/behavior_tree_core/sequence_node.h b/include/behavior_tree_core/sequence_node.h index 3431c7525..e97c23e29 100644 --- a/include/behavior_tree_core/sequence_node.h +++ b/include/behavior_tree_core/sequence_node.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef SEQUENCENODE_H #define SEQUENCENODE_H diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index 82600d22f..e34281e6d 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -1,12 +1,21 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef SEQUENCE_NODE_WITH_MEMORY_H #define SEQUENCE_NODE_WITH_MEMORY_H - #include "behavior_tree_core/control_node.h" - - - namespace BT { class SequenceNodeWithMemory : public ControlNode diff --git a/include/behavior_tree_core/tick_engine.h b/include/behavior_tree_core/tick_engine.h index b201437e4..b04e29f6f 100644 --- a/include/behavior_tree_core/tick_engine.h +++ b/include/behavior_tree_core/tick_engine.h @@ -1,8 +1,19 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef TICK_ENGINE_H #define TICK_ENGINE_H - - #include #include #include diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 5d5653bed..e290064cc 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -1,3 +1,16 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #ifndef BEHAVIORTREECORE_TREENODE_H #define BEHAVIORTREECORE_TREENODE_H diff --git a/src/action_node.cpp b/src/action_node.cpp index 92de80c25..b9aeaa86f 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -1,4 +1,5 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, @@ -10,6 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ + #include "behavior_tree_core/action_node.h" #include diff --git a/src/condition_node.cpp b/src/condition_node.cpp index 25fbff7b0..4c507cb0b 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -1,4 +1,5 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, @@ -10,6 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ + #include "behavior_tree_core/condition_node.h" #include diff --git a/src/control_node.cpp b/src/control_node.cpp index 6686aa6fe..4fba88d38 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -1,4 +1,5 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, diff --git a/src/exceptions.cpp b/src/exceptions.cpp index ff7008327..c8ec0ec9d 100644 --- a/src/exceptions.cpp +++ b/src/exceptions.cpp @@ -1,4 +1,5 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, @@ -10,6 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ + #include "behavior_tree_core/exceptions.h" #include diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 12b7b48e4..b0e65e85c 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -1,4 +1,5 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, @@ -10,6 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ + #include "behavior_tree_core/fallback_node.h" #include diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index cfb7993e2..eb9359480 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -1,4 +1,5 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, @@ -10,6 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ + #include "behavior_tree_core/fallback_node_with_memory.h" #include diff --git a/src/leaf_node.cpp b/src/leaf_node.cpp index a0855670f..15c2e144f 100644 --- a/src/leaf_node.cpp +++ b/src/leaf_node.cpp @@ -1,5 +1,5 @@ - -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, @@ -11,6 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ + #include "behavior_tree_core/leaf_node.h" #include diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index ab9fe2914..1d7038322 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -1,5 +1,5 @@ - -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 9d9cfd934..50d903422 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -1,5 +1,5 @@ - -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index dd7a60fa6..2e8265948 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -1,5 +1,5 @@ - -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, @@ -12,6 +12,7 @@ */ + #include "behavior_tree_core/sequence_node_with_memory.h" #include diff --git a/src/tick_engine.cpp b/src/tick_engine.cpp index 3cd8c40d3..c07a934c1 100644 --- a/src/tick_engine.cpp +++ b/src/tick_engine.cpp @@ -1,4 +1,5 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, @@ -10,6 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ + #include "behavior_tree_core/tick_engine.h" TickEngine::TickEngine(int initial_value) diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 8a2bb8ff8..ada1ffa9f 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -1,4 +1,5 @@ -/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, @@ -10,6 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ + #include "behavior_tree_core/tree_node.h" #include From 33eec5f1d1537073ab489e9321fef97c6ba3cf8d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 15:16:00 +0200 Subject: [PATCH 013/125] added decorator node --- CMakeLists.txt | 1 + include/behavior_tree_core/action_node.h | 2 +- include/behavior_tree_core/condition_node.h | 2 +- include/behavior_tree_core/control_node.h | 2 +- .../decorator_negation_node.h | 5 +- include/behavior_tree_core/decorator_node.h | 40 ++++++++++++ .../behavior_tree_core/decorator_retry_node.h | 6 +- src/control_node.cpp | 16 ++--- src/decorator_node.cpp | 64 +++++++++++++++++++ templates/action_node_template.cpp | 6 +- templates/condition_node_template.cpp | 4 +- 11 files changed, 125 insertions(+), 23 deletions(-) create mode 100644 include/behavior_tree_core/decorator_node.h create mode 100644 src/decorator_node.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index feffc2dfa..b9262adb3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -39,6 +39,7 @@ endif(catkin_FOUND) set(BT_Source src/action_node.cpp + src/decorator_node.cpp src/condition_node.cpp src/control_node.cpp src/exceptions.cpp diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 3b6bc9ef8..ccc9fece7 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -34,7 +34,7 @@ class ActionNode : public LeafNode // conditional waiting (only mutual access) bool WriteState(ReturnStatus new_state); - virtual NodeType Type() const override { return ACTION_NODE; } + virtual NodeType Type() const override final { return ACTION_NODE; } protected: // The thread that will execute the node diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index d0ea09ca4..423f75b36 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -32,7 +32,7 @@ namespace BT // conditional waiting (only mutual access) bool WriteState(ReturnStatus new_state); - virtual NodeType Type() const override { return CONDITION_NODE; } + virtual NodeType Type() const override final { return CONDITION_NODE; } }; } diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index 73388e6f7..dbc9e5b31 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -56,7 +56,7 @@ namespace BT // conditional waiting (only mutual access) bool WriteState(ReturnStatus new_state); - virtual NodeType Type() const override { return CONTROL_NODE; } + virtual NodeType Type() const override final { return CONTROL_NODE; } }; } diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h index 3caa70343..c3cd8ce75 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -14,11 +14,11 @@ #ifndef DECORATORNEGATIONNODE_H #define DECORATORNEGATIONNODE_H -#include "behavior_tree_core/control_node.h" +#include "behavior_tree_core/decorator_node.h" namespace BT { - class DecoratorNegationNode : public ControlNode + class DecoratorNegationNode : public DecoratorNode { public: // Constructor @@ -29,7 +29,6 @@ namespace BT void Exec(); void AddChild(TreeNode* child); - virtual NodeType Type() const override { return DECORATOR_NODE; } }; } diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h new file mode 100644 index 000000000..38cc124bc --- /dev/null +++ b/include/behavior_tree_core/decorator_node.h @@ -0,0 +1,40 @@ +#ifndef DECORATORNODE_H +#define DECORATORNODE_H + +#include + +#include "behavior_tree_core/tree_node.h" + +namespace BT +{ + class DecoratorNode : public TreeNode + { + protected: + + TreeNode* child_node_; + ReturnStatus child_state_; + + public: + // Constructor + DecoratorNode(std::string name); + ~DecoratorNode() = default; + + // The method used to fill the child vector + void AddChild(TreeNode* child); + + const TreeNode* Child() const; + + // The method used to interrupt the execution of the node + virtual void Halt() override; + + void HaltChild(); + + // Methods used to access the node state without the + // conditional waiting (only mutual access) + bool WriteState(ReturnStatus new_state); + + virtual NodeType Type() const override final { return DECORATOR_NODE; } + }; +} + +#endif diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h index bcddef44b..29ce8e420 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -14,11 +14,11 @@ #ifndef DECORATORRETRYNODE_H #define DECORATORRETRYNODE_H -#include "behavior_tree_core/control_node.h" +#include "behavior_tree_core/decorator_node.h" namespace BT { - class DecoratorRetryNode : public ControlNode + class DecoratorRetryNode : public DecoratorNode { public: // Constructor @@ -28,8 +28,6 @@ namespace BT // The method that is going to be executed by the thread void Exec(); - virtual NodeType Type() const override { return DECORATOR_NODE; } - private: unsigned int NTries_; unsigned int TryIndx_; diff --git a/src/control_node.cpp b/src/control_node.cpp index 4fba88d38..b9ae5d807 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -25,14 +25,14 @@ BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) void BT::ControlNode::AddChild(TreeNode* child) { -// // Checking if the child is not already present -// for (unsigned int i=0; iName() + "' is already a '" + get_name() + "' child."); -// } -// } + // Checking if the child is not already present + for (auto node: children_nodes_) + { + if (node == child) + { + throw BehaviorTreeException("'" + child->Name() + "' is already a '" + Name() + "' child."); + } + } children_nodes_.push_back(child); children_states_.push_back(BT::IDLE); diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp new file mode 100644 index 000000000..872cedf92 --- /dev/null +++ b/src/decorator_node.cpp @@ -0,0 +1,64 @@ +/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + + +#include "behavior_tree_core/decorator_node.h" +#include +#include + +BT::DecoratorNode::DecoratorNode(std::string name) : + TreeNode::TreeNode(name), + child_node_(nullptr), + child_state_(BT::IDLE) +{ + // TODO(...) In case it is desired to set to idle remove the ReturnStatus + // type in order to set the member variable + // ReturnStatus child_i_status_ = BT::IDLE; // commented out as unused +} + +void BT::DecoratorNode::AddChild(TreeNode* child) +{ + if (child_node_ ) + { + throw BehaviorTreeException("Decorator '" + Name() + "' has already a child assigned"); + } + + child_node_ = child; + child_state_ = BT::IDLE; +} + + +void BT::DecoratorNode::Halt() +{ + DEBUG_STDOUT("HALTING: "<< Name()); + HaltChild(); + SetStatus(BT::HALTED); +} + +const BT::TreeNode* BT::DecoratorNode::Child() const +{ + return child_node_; +} + +void BT::DecoratorNode::HaltChild() +{ + if (child_node_->Status() == BT::RUNNING) + { + DEBUG_STDOUT("SENDING HALT TO CHILD " << child_node_->Name()); + child_node_->Halt(); + } + else{ + DEBUG_STDOUT("NO NEED TO HALT " << child_node_->Name() + << "STATUS" << child_node_->Status()); + } +} + diff --git a/templates/action_node_template.cpp b/templates/action_node_template.cpp index 668287a89..4ad0320d9 100644 --- a/templates/action_node_template.cpp +++ b/templates/action_node_template.cpp @@ -20,10 +20,10 @@ void BT::CLASSNAME::WaitForTick() DEBUG_STDOUT(Name() << " TICK RECEIVED"); // Running state - set_status(BT::RUNNING); + SetStatus(BT::RUNNING); // Perform action... - while(get_status() != BT::HALTED) + while(Status() != BT::HALTED) { /*HERE THE CODE TO EXECUTE FOR THE ACTION. wHEN THE ACTION HAS FINISHED CORRECLTY, CALL set_status(BT::SUCCESS) @@ -36,7 +36,7 @@ void BT::CLASSNAME::WaitForTick() void BT::CLASSNAME::Halt() { /*HERE THE CODE TO PERFORM WHEN THE ACTION IS HALTED*/ - set_status(BT::HALTED); + SetStatus(BT::HALTED); DEBUG_STDOUT("HALTED state set!"); } diff --git a/templates/condition_node_template.cpp b/templates/condition_node_template.cpp index 09b818ce6..1f1bac46f 100644 --- a/templates/condition_node_template.cpp +++ b/templates/condition_node_template.cpp @@ -14,12 +14,12 @@ BT::ReturnStatus BT::CLASSNAME::Tick() if (/*CONDITION TO CHECK*/) { - set_status(BT::SUCCESS); + SetStatus(BT::SUCCESS); return BT::SUCCESS; } else { - set_status(BT::FAILURE); + SetStatus(BT::FAILURE); return BT::FAILURE; } } From d577d04b3f62526b4b768047e59e230c2310cafd Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 16:59:08 +0200 Subject: [PATCH 014/125] added first sample of the factory class --- CMakeLists.txt | 1 + include/behavior_tree_core/bt_factory.h | 114 ++++++++++++++++++++++++ src/bt_factory.cpp | 43 +++++++++ 3 files changed, 158 insertions(+) create mode 100644 include/behavior_tree_core/bt_factory.h create mode 100644 src/bt_factory.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index b9262adb3..145ca53a6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -51,6 +51,7 @@ set(BT_Source src/fallback_node_with_memory.cpp src/sequence_node_with_memory.cpp src/tree_node.cpp + src/bt_factory.cpp ) include_directories(include) diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h new file mode 100644 index 000000000..2a0105b68 --- /dev/null +++ b/include/behavior_tree_core/bt_factory.h @@ -0,0 +1,114 @@ +/* Copyright (C) 2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef BT_FACTORY_H +#define BT_FACTORY_H + +#include +#include +#include +#include +#include + +#include "behavior_tree_core/action_node.h" +#include "behavior_tree_core/control_node.h" +#include "behavior_tree_core/condition_node.h" +#include "behavior_tree_core/decorator_node.h" + +namespace BT +{ + +typedef std::set RequiredParameters; + +// We call Parameters the set of Key/Values that canbe read from file and are +// used to parametrize an object. it is up to the user's code to parse the string. +typedef std::map NodeParameters; + +// The term "Builder" refers to the Builder Ppattern (https://en.wikipedia.org/wiki/Builder_pattern) +typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; + +class BehaviorTreeFactory +{ + public: + + BehaviorTreeFactory(); + + bool unregisterBuilder(const std::string& ID); + + template + void registerBuilder(const std::string& ID); + + void registerSimpleAction(const std::string& ID, std::function tick_functor); + + void registerSimpleDecorator(const std::string& ID, std::function tick_functor); + + std::unique_ptr instantiateTreeNode(const std::string& ID, const NodeParameters& params); + + const std::map & builders() const + { + return builders_; + } + +private: + + std::map builders_; +}; + + +//----------------------------------------------- + +template inline +void BehaviorTreeFactory::registerBuilder(const std::string &ID) +{ + static_assert(std::is_base_of::value || + std::is_base_of::value || + std::is_base_of::value || + std::is_base_of::value, + "[registerBuilder]: accepts only classed derived from either ActionNode, DecoratorNode, ControlNode or ConditionNode"); + + constexpr bool default_constructable = std::is_constructible::value; + constexpr bool param_constructable = std::is_constructible::value; + + static_assert( param_constructable || param_constructable , + "[registerBuilder]: the registered class must have a Constructor with signature:\n\n" + " (const std::string&, const NodeParameters&)\n" + " or\n" + " (const std::string&)" ); + + auto it = builders_.find(ID); + if( it != builders_.end()) + { + throw BehaviorTreeException("ID '" + ID + "' already registered"); + } + + NodeBuilder builder = [default_constructable, ID](const std::string& name, const NodeParameters& params) + { + if( default_constructable && params.empty() ) + { + return std::unique_ptr(new T(name) ); + } + if( !param_constructable && !params.empty() ) + { + throw BehaviorTreeException("Trying to instantiate a TreeNode that can NOT accept NodeParameters in the Constructor: [" + + ID + " / " + name +"]"); + } + return std::unique_ptr(new T(name, params) ); + + }; + + builders_.insert( std::make_pair(ID,builder) ); +} + + +} // end namespace +#endif // BT_FACTORY_H diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp new file mode 100644 index 000000000..0a7844976 --- /dev/null +++ b/src/bt_factory.cpp @@ -0,0 +1,43 @@ +#include "behavior_tree_core/bt_factory.h" + +namespace BT +{ +BehaviorTreeFactory::BehaviorTreeFactory() +{ +} + +bool BehaviorTreeFactory::unregisterBuilder(const std::string &ID) +{ + auto it = builders_.find(ID); + if( it == builders_.end()) + { + return false; + } + builders_.erase(ID); + return true; +} + +void BehaviorTreeFactory::registerSimpleAction(const std::string &ID, + std::function tick_functor) +{ + +} + +void BehaviorTreeFactory::registerSimpleDecorator(const std::string &ID, + std::function tick_functor) +{ + +} + +std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::string &ID, + const NodeParameters ¶ms) +{ + auto it = builders_.find(ID); + if( it == builders_.end()) + { + throw BehaviorTreeException("ID '" + ID + "' not registered"); + } + return it->second(ID, params); +} + +} // end namespace From 2e09aaa4c69a65bbb90871a22aea856a62fbd46b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 17:22:29 +0200 Subject: [PATCH 015/125] miscellaneous cleanups --- include/behavior_tree_core/bt_factory.h | 2 +- include/behavior_tree_core/control_node.h | 4 ---- include/behavior_tree_core/decorator_node.h | 3 --- .../fallback_node_with_memory.h | 11 ++++++----- include/behavior_tree_core/leaf_node.h | 3 --- .../sequence_node_with_memory.h | 8 ++++---- src/action_node.cpp | 3 --- src/bt_factory.cpp | 13 +++++++++++++ src/condition_node.cpp | 1 - src/control_node.cpp | 4 +--- src/decorator_node.cpp | 7 ++----- src/exceptions.cpp | 1 - src/fallback_node.cpp | 7 +++++-- src/fallback_node_with_memory.cpp | 17 +++++++---------- src/leaf_node.cpp | 1 - src/parallel_node.cpp | 8 +++++--- src/sequence_node.cpp | 4 ++-- src/sequence_node_with_memory.cpp | 18 ++++++------------ src/tree_node.cpp | 19 +++++-------------- 19 files changed, 57 insertions(+), 77 deletions(-) diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 2a0105b68..4d4205e7b 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -14,7 +14,7 @@ #ifndef BT_FACTORY_H #define BT_FACTORY_H -#include + #include #include #include diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index dbc9e5b31..e76e10bd0 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -15,7 +15,6 @@ #define CONTROLNODE_H #include - #include "behavior_tree_core/tree_node.h" namespace BT @@ -26,9 +25,6 @@ namespace BT // Children vector std::vector children_nodes_; - // Children states - std::vector children_states_; - // Vector size unsigned int N_of_children_; //child i status. Used to rout the ticks diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index 38cc124bc..5f25039da 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -1,8 +1,6 @@ #ifndef DECORATORNODE_H #define DECORATORNODE_H -#include - #include "behavior_tree_core/tree_node.h" namespace BT @@ -12,7 +10,6 @@ namespace BT protected: TreeNode* child_node_; - ReturnStatus child_state_; public: // Constructor diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index c90ec9007..826a680d5 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -13,25 +13,26 @@ #ifndef FALLBACK_NODE_WITH_MEMORY_H #define FALLBACK_NODE_WITH_MEMORY_H -#include "behavior_tree_core/control_node.h" +#include "behavior_tree_core/control_node.h" namespace BT { class FallbackNodeWithMemory : public ControlNode { public: - // Constructor - FallbackNodeWithMemory(std::string name); - FallbackNodeWithMemory(std::string name, int reset_policy); + + FallbackNodeWithMemory(std::string name, ResetPolity reset_policy = BT::ON_SUCCESS_OR_FAILURE); + ~FallbackNodeWithMemory() = default; // The method that is going to be executed by the thread virtual BT::ReturnStatus Tick() override; + virtual void Halt() override; private: unsigned int current_child_idx_; - unsigned int reset_policy_; + ResetPolity reset_policy_; }; } diff --git a/include/behavior_tree_core/leaf_node.h b/include/behavior_tree_core/leaf_node.h index 2bdcad1ab..9a490cf94 100644 --- a/include/behavior_tree_core/leaf_node.h +++ b/include/behavior_tree_core/leaf_node.h @@ -14,8 +14,6 @@ #ifndef LEAFNODE_H #define LEAFNODE_H -#include - #include "behavior_tree_core/tree_node.h" namespace BT @@ -26,7 +24,6 @@ namespace BT public: LeafNode(std::string name); ~LeafNode() = default; - }; } diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index e34281e6d..5e2eb426e 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -21,9 +21,9 @@ namespace BT class SequenceNodeWithMemory : public ControlNode { public: - // Constructor - SequenceNodeWithMemory(std::string name); - SequenceNodeWithMemory(std::string name, int reset_policy); + + SequenceNodeWithMemory(std::string name, ResetPolity reset_policy = BT::ON_SUCCESS_OR_FAILURE); + ~SequenceNodeWithMemory() = default; // The method that is going to be executed by the thread @@ -31,7 +31,7 @@ class SequenceNodeWithMemory : public ControlNode virtual void Halt() override; private: unsigned int current_child_idx_; - unsigned int reset_policy_; + ResetPolity reset_policy_; }; } diff --git a/src/action_node.cpp b/src/action_node.cpp index b9aeaa86f..b202a3dea 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -13,8 +13,6 @@ #include "behavior_tree_core/action_node.h" -#include - BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name) { @@ -24,7 +22,6 @@ BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name) void BT::ActionNode::WaitForTick() { - while (true) { // Waiting for the tick to come diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 0a7844976..04a01e5ec 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -1,3 +1,16 @@ +/* Copyright (C) 2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + #include "behavior_tree_core/bt_factory.h" namespace BT diff --git a/src/condition_node.cpp b/src/condition_node.cpp index 4c507cb0b..87361c4a1 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -13,7 +13,6 @@ #include "behavior_tree_core/condition_node.h" -#include BT::ConditionNode::ConditionNode(std::string name) : LeafNode::LeafNode(name) diff --git a/src/control_node.cpp b/src/control_node.cpp index b9ae5d807..ab9f7cda9 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -13,8 +13,7 @@ #include "behavior_tree_core/control_node.h" -#include -#include + BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) { @@ -35,7 +34,6 @@ void BT::ControlNode::AddChild(TreeNode* child) } children_nodes_.push_back(child); - children_states_.push_back(BT::IDLE); } unsigned int BT::ControlNode::ChildrenCount() const diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 872cedf92..bcfc88f18 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -12,13 +12,11 @@ #include "behavior_tree_core/decorator_node.h" -#include -#include + BT::DecoratorNode::DecoratorNode(std::string name) : TreeNode::TreeNode(name), - child_node_(nullptr), - child_state_(BT::IDLE) + child_node_(nullptr) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable @@ -33,7 +31,6 @@ void BT::DecoratorNode::AddChild(TreeNode* child) } child_node_ = child; - child_state_ = BT::IDLE; } diff --git a/src/exceptions.cpp b/src/exceptions.cpp index c8ec0ec9d..7b251f041 100644 --- a/src/exceptions.cpp +++ b/src/exceptions.cpp @@ -13,7 +13,6 @@ #include "behavior_tree_core/exceptions.h" -#include BT::BehaviorTreeException::BehaviorTreeException(const std::string Message) { diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index b0e65e85c..108986fa1 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -13,9 +13,10 @@ #include "behavior_tree_core/fallback_node.h" -#include -BT::FallbackNode::FallbackNode(std::string name) : ControlNode::ControlNode(name) {} +BT::FallbackNode::FallbackNode(std::string name) : + ControlNode::ControlNode(name) +{} BT::ReturnStatus BT::FallbackNode::Tick() @@ -48,6 +49,8 @@ BT::ReturnStatus BT::FallbackNode::Tick() do { child_i_status_ = children_nodes_[i]->Status(); + + // TODO / FIXME. Use a condition_variable instead std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index eb9359480..07421972e 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -13,19 +13,14 @@ #include "behavior_tree_core/fallback_node_with_memory.h" -#include - -BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name) : ControlNode::ControlNode(name) -{ - reset_policy_ = BT::ON_SUCCESS_OR_FAILURE; - current_child_idx_ = 0; // initialize the current running child -} -BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, int reset_policy) : ControlNode::ControlNode(name) +BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, ResetPolity reset_policy) : + ControlNode::ControlNode(name), + current_child_idx_(0), + reset_policy_( reset_policy ) { - reset_policy_ = reset_policy; - current_child_idx_ = 0; // initialize the current running child + } @@ -64,6 +59,8 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() do { child_i_status_ = children_nodes_[current_child_idx_]->Status(); + + // TODO / FIXME. Use a condition_variable instead std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS diff --git a/src/leaf_node.cpp b/src/leaf_node.cpp index 15c2e144f..bee007d3c 100644 --- a/src/leaf_node.cpp +++ b/src/leaf_node.cpp @@ -13,7 +13,6 @@ #include "behavior_tree_core/leaf_node.h" -#include BT::LeafNode::LeafNode(std::string name) : TreeNode(name) {} diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 1d7038322..38d67c2b9 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -13,11 +13,11 @@ #include "behavior_tree_core/parallel_node.h" -#include -BT::ParallelNode::ParallelNode(std::string name, int threshold_M) : ControlNode::ControlNode(name) +BT::ParallelNode::ParallelNode(std::string name, int threshold_M) : + ControlNode::ControlNode(name), + threshold_M_( threshold_M ) { - threshold_M_ = threshold_M; } BT::ReturnStatus BT::ParallelNode::Tick() @@ -48,6 +48,8 @@ BT::ReturnStatus BT::ParallelNode::Tick() do { child_i_status_ = children_nodes_[i]->Status(); + + // TODO / FIXME. Use a condition_variable instead std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 50d903422..5d27a0489 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -13,8 +13,6 @@ #include "behavior_tree_core/sequence_node.h" -#include - BT::SequenceNode::SequenceNode(std::string name) : ControlNode::ControlNode(name) {} @@ -48,6 +46,8 @@ BT::ReturnStatus BT::SequenceNode::Tick() do { child_i_status_ = children_nodes_[i]->Status(); + + // TODO / FIXME. Use a condition_variable instead std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 2e8265948..e9f209a22 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -14,20 +14,12 @@ #include "behavior_tree_core/sequence_node_with_memory.h" -#include - -BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name) : ControlNode::ControlNode(name) -{ - reset_policy_ = BT::ON_SUCCESS_OR_FAILURE; - current_child_idx_ = 0; // initialize the current running child -} - - -BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, int reset_policy) : ControlNode::ControlNode(name) +BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolity reset_policy) : + ControlNode::ControlNode(name), + current_child_idx_(0), + reset_policy_(reset_policy) { - reset_policy_ = reset_policy; - current_child_idx_ = 0; // initialize the current running child } @@ -66,6 +58,8 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() do { child_i_status_ = children_nodes_[current_child_idx_]->Status(); + + // TODO / FIXME. Use a condition_variable instead std::this_thread::sleep_for(std::chrono::milliseconds(10)); } while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS diff --git a/src/tree_node.cpp b/src/tree_node.cpp index ada1ffa9f..a26e31a41 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -11,41 +11,32 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/tree_node.h" -#include - -BT::TreeNode::TreeNode(std::string name) : tick_engine(0) +BT::TreeNode::TreeNode(std::string name) : + name_(name), + is_state_updated_(false), + status_(BT::IDLE), + tick_engine(0) { - // Initialization - name_ = name; - is_state_updated_ = false; - SetStatus(BT::IDLE); } BT::TreeNode::~TreeNode() {} void BT::TreeNode::SetStatus(ReturnStatus new_status) { - // Lock acquistion std::unique_lock UniqueLock(state_mutex_); - - // state_ update status_ = new_status; } BT::ReturnStatus BT::TreeNode::Status() const { - // Lock acquistion DEBUG_STDOUT(Name() << " is setting its status to " << status_); std::lock_guard LockGuard(state_mutex_); return status_; } - - void BT::TreeNode::SetName(const std::string &new_name) { name_ = new_name; From 69942201b11d018d31418a847d01f9dfc7afa000 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 17:43:31 +0200 Subject: [PATCH 016/125] using condition variable instead of sleeps --- include/behavior_tree_core/tree_node.h | 5 ++++- src/fallback_node.cpp | 11 +---------- src/fallback_node_with_memory.cpp | 11 +---------- src/parallel_node.cpp | 11 +---------- src/sequence_node.cpp | 11 +---------- src/sequence_node_with_memory.cpp | 11 +---------- src/tree_node.cpp | 22 ++++++++++++++++++---- 7 files changed, 27 insertions(+), 55 deletions(-) diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index e290064cc..5708133a2 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -77,11 +77,11 @@ namespace BT private: // Node name std::string name_; + ReturnStatus status_; protected: // The node state that must be treated in a thread-safe way bool is_state_updated_; - ReturnStatus status_; mutable std::mutex state_mutex_; std::condition_variable state_condition_variable_; @@ -110,6 +110,9 @@ namespace BT const std::string& Name() const; void SetName(const std::string& new_name); + + BT::ReturnStatus waitValidStatus(); + virtual NodeType Type() const = 0; }; diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 108986fa1..30d434adc 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -45,16 +45,7 @@ BT::ReturnStatus BT::FallbackNode::Tick() DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[i]->Name()); children_nodes_[i]->tick_engine.Tick(); - // waits for the tick to arrive to the child - do - { - child_i_status_ = children_nodes_[i]->Status(); - - // TODO / FIXME. Use a condition_variable instead - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } - while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS - && child_i_status_ != BT::FAILURE); + child_i_status_ = children_nodes_[i]->waitValidStatus(); } } else diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 07421972e..7d3b968bd 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -55,16 +55,7 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[current_child_idx_]->Name()); children_nodes_[current_child_idx_]->tick_engine.Tick(); - // waits for the tick to arrive to the child - do - { - child_i_status_ = children_nodes_[current_child_idx_]->Status(); - - // TODO / FIXME. Use a condition_variable instead - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } - while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS - && child_i_status_ != BT::FAILURE); + child_i_status_ = children_nodes_[current_child_idx_]->waitValidStatus(); } } else diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 38d67c2b9..33d61210b 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -44,16 +44,7 @@ BT::ReturnStatus BT::ParallelNode::Tick() DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[i]->Name()); children_nodes_[i]->tick_engine.Tick(); - // waits for the tick to arrive to the child - do - { - child_i_status_ = children_nodes_[i]->Status(); - - // TODO / FIXME. Use a condition_variable instead - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } - while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS - && child_i_status_ != BT::FAILURE); + child_i_status_ = children_nodes_[i]->waitValidStatus(); } } else diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 5d27a0489..22dd6515c 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -42,16 +42,7 @@ BT::ReturnStatus BT::SequenceNode::Tick() DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[i]->Name()); children_nodes_[i]->tick_engine.Tick(); - // waits for the tick to arrive to the child - do - { - child_i_status_ = children_nodes_[i]->Status(); - - // TODO / FIXME. Use a condition_variable instead - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } - while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS - && child_i_status_ != BT::FAILURE); + child_i_status_ = children_nodes_[i]->waitValidStatus(); } } else diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index e9f209a22..5221c6dfb 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -54,16 +54,7 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[current_child_idx_]->Name()); children_nodes_[current_child_idx_]->tick_engine.Tick(); - // waits for the tick to arrive to the child - do - { - child_i_status_ = children_nodes_[current_child_idx_]->Status(); - - // TODO / FIXME. Use a condition_variable instead - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } - while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS - && child_i_status_ != BT::FAILURE); + child_i_status_ = children_nodes_[current_child_idx_]->waitValidStatus(); } } else diff --git a/src/tree_node.cpp b/src/tree_node.cpp index a26e31a41..794e2993e 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -25,14 +25,16 @@ BT::TreeNode::~TreeNode() {} void BT::TreeNode::SetStatus(ReturnStatus new_status) { - std::unique_lock UniqueLock(state_mutex_); - status_ = new_status; + { + std::unique_lock UniqueLock(state_mutex_); + is_state_updated_ = (status_!= new_status); + status_ = new_status; + } + state_condition_variable_.notify_all(); } BT::ReturnStatus BT::TreeNode::Status() const { - DEBUG_STDOUT(Name() << " is setting its status to " << status_); - std::lock_guard LockGuard(state_mutex_); return status_; } @@ -42,6 +44,18 @@ void BT::TreeNode::SetName(const std::string &new_name) name_ = new_name; } +BT::ReturnStatus BT::TreeNode::waitValidStatus() +{ + std::unique_lock lk( state_mutex_ ); + + state_condition_variable_.wait(lk, [&](){ + return (status_ == BT::RUNNING || + status_ == BT::SUCCESS || + status_ != BT::FAILURE); + }); + return status_; +} + const std::string& BT::TreeNode::Name() const { return name_; From a52c1eaf7a3f1dcb4b06cc8f1c21362a7a33a1c0 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 17:54:11 +0200 Subject: [PATCH 017/125] cleanup: minimize the scope of N_of_children --- include/behavior_tree_core/control_node.h | 2 -- src/fallback_node.cpp | 26 +++++++++++---------- src/fallback_node_with_memory.cpp | 28 +++++++++++------------ src/parallel_node.cpp | 6 ++--- src/sequence_node.cpp | 25 ++++++++++---------- src/sequence_node_with_memory.cpp | 23 ++++++++++--------- 6 files changed, 56 insertions(+), 54 deletions(-) diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index e76e10bd0..81d76982f 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -25,8 +25,6 @@ namespace BT // Children vector std::vector children_nodes_; - // Vector size - unsigned int N_of_children_; //child i status. Used to rout the ticks ReturnStatus child_i_status_; diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 30d434adc..a16f26a18 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -23,37 +23,39 @@ BT::ReturnStatus BT::FallbackNode::Tick() { { // gets the number of children. The number could change if, at runtime, one edits the tree. - N_of_children_ = children_nodes_.size(); + const int N_of_children = children_nodes_.size(); // Routing the ticks according to the fallback node's logic: - for (unsigned int i = 0; i < N_of_children_; i++) + for ( int i=0; i < N_of_children; i++) { + auto& child_node = children_nodes_[i]; + /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. We want this thread detached so we can cancel its execution (when the action no longer receive ticks). Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (children_nodes_[i]->Type() == BT::ACTION_NODE) + if (child_node->Type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. - child_i_status_ = children_nodes_[i]->Status(); + child_i_status_ = child_node->Status(); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[i]->Name()); - children_nodes_[i]->tick_engine.Tick(); + DEBUG_STDOUT(Name() << "NEEDS TO TICK " << child_node->Name()); + child_node->tick_engine.Tick(); - child_i_status_ = children_nodes_[i]->waitValidStatus(); + child_i_status_ = child_node->waitValidStatus(); } } else { // 2) if it's not an action: // Send the tick and wait for the response; - child_i_status_ = children_nodes_[i]->Tick(); - children_nodes_[i]->SetStatus(child_i_status_); + child_i_status_ = child_node->Tick(); + child_node->SetStatus(child_i_status_); } // Ponderate on which status to send to the parent @@ -61,7 +63,7 @@ BT::ReturnStatus BT::FallbackNode::Tick() { if (child_i_status_ == BT::SUCCESS) { - children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. + child_node->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. } // If the child status is not failure, halt the next children and return the status to your parent. DEBUG_STDOUT(Name() << " is HALTING children from " << (i+1)); @@ -72,8 +74,8 @@ BT::ReturnStatus BT::FallbackNode::Tick() else { // the child returned failure. - children_nodes_[i]->SetStatus(BT::IDLE); - if (i == N_of_children_ - 1) + child_node->SetStatus(BT::IDLE); + if (i == N_of_children - 1) { // If the child status is failure, and it is the last child to be ticked, // then the sequence has failed. diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 7d3b968bd..7b81429c6 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -29,49 +29,49 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() DEBUG_STDOUT(Name() << " ticked, memory counter: "<< current_child_idx_); // Vector size initialization. N_of_children_ could change at runtime if you edit the tree - N_of_children_ = children_nodes_.size(); + const unsigned N_of_children = children_nodes_.size(); // Routing the ticks according to the fallback node's (with memory) logic: - while (current_child_idx_ < N_of_children_) + while (current_child_idx_ < N_of_children) { + auto& current_child_node = children_nodes_[current_child_idx_]; + /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. We want this thread detached so we can cancel its execution (when the action no longer receive ticks). Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (children_nodes_[current_child_idx_]->Type() == BT::ACTION_NODE) + if (current_child_node->Type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. - child_i_status_ = children_nodes_[current_child_idx_]->Status(); - DEBUG_STDOUT(Name() << " It is an action " << children_nodes_[current_child_idx_]->Name() + child_i_status_ = current_child_node->Status(); + DEBUG_STDOUT(Name() << " It is an action " << current_child_node->Name() << " with status: " << child_i_status_); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[current_child_idx_]->Name()); - children_nodes_[current_child_idx_]->tick_engine.Tick(); + DEBUG_STDOUT(Name() << "NEEDS TO TICK " << current_child_node->Name()); + current_child_node->tick_engine.Tick(); - child_i_status_ = children_nodes_[current_child_idx_]->waitValidStatus(); + child_i_status_ = current_child_node->waitValidStatus(); } } else { // 2) if it's not an action: // Send the tick and wait for the response; - child_i_status_ = children_nodes_[current_child_idx_]->Tick(); - children_nodes_[current_child_idx_]->SetStatus(child_i_status_); - + child_i_status_ = current_child_node->Tick(); + current_child_node->SetStatus(child_i_status_); } - if (child_i_status_ == BT::SUCCESS ||child_i_status_ == BT::FAILURE ) { // the child goes in idle if it has returned success or failure. - children_nodes_[current_child_idx_]->SetStatus(BT::IDLE); + current_child_node->SetStatus(BT::IDLE); } if (child_i_status_ != BT::FAILURE) @@ -86,7 +86,7 @@ BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() SetStatus(child_i_status_); return child_i_status_; } - else if (current_child_idx_ != N_of_children_ - 1) + else if (current_child_idx_ != N_of_children - 1) { // If the child status is failure, continue to the next child // (if any, hence if(current_child_ != N_of_children_ - 1) ) in the for loop (if any). diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 33d61210b..2cf9b0009 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -25,10 +25,10 @@ BT::ReturnStatus BT::ParallelNode::Tick() success_childred_num_ = 0; failure_childred_num_ = 0; // Vector size initialization. N_of_children_ could change at runtime if you edit the tree - N_of_children_ = children_nodes_.size(); + const unsigned N_of_children = children_nodes_.size(); // Routing the tree according to the sequence node's logic: - for (unsigned int i = 0; i < N_of_children_; i++) + for (unsigned int i = 0; i < N_of_children; i++) { DEBUG_STDOUT(Name() << "TICKING " << children_nodes_[i]->Name()); @@ -66,7 +66,7 @@ BT::ReturnStatus BT::ParallelNode::Tick() break; case BT::FAILURE: children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. - if (++failure_childred_num_ > N_of_children_- threshold_M_) + if (++failure_childred_num_ > N_of_children - threshold_M_) { DEBUG_STDOUT("*******PARALLEL" << Name() << " FAILED****** failure_childred_num_:" << failure_childred_num_); diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 22dd6515c..585158110 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -20,37 +20,38 @@ BT::SequenceNode::SequenceNode(std::string name) : ControlNode::ControlNode(name BT::ReturnStatus BT::SequenceNode::Tick() { // gets the number of children. The number could change if, at runtime, one edits the tree. - N_of_children_ = children_nodes_.size(); + const int N_of_children = children_nodes_.size(); // Routing the ticks according to the sequence node's logic: - for (unsigned int i = 0; i < N_of_children_; i++) + for (unsigned int i = 0; i < N_of_children; i++) { + auto& child_node = children_nodes_[i]; /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. We want this thread detached so we can cancel its execution (when the action no longer receive ticks). Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (children_nodes_[i]->Type() == BT::ACTION_NODE) + if (child_node->Type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. - child_i_status_ = children_nodes_[i]->Status(); + child_i_status_ = child_node->Status(); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[i]->Name()); - children_nodes_[i]->tick_engine.Tick(); + DEBUG_STDOUT(Name() << "NEEDS TO TICK " << child_node->Name()); + child_node->tick_engine.Tick(); - child_i_status_ = children_nodes_[i]->waitValidStatus(); + child_i_status_ = child_node->waitValidStatus(); } } else { // 2) if it's not an action: // Send the tick and wait for the response; - child_i_status_ = children_nodes_[i]->Tick(); - children_nodes_[i]->SetStatus(child_i_status_); + child_i_status_ = child_node->Tick(); + child_node->SetStatus(child_i_status_); } // Ponderate on which status to send to the parent if (child_i_status_ != BT::SUCCESS) @@ -58,7 +59,7 @@ BT::ReturnStatus BT::SequenceNode::Tick() // If the child status is not success, halt the next children and return the status to your parent. if (child_i_status_ == BT::FAILURE) { - children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. + child_node->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. } DEBUG_STDOUT(Name() << " is HALTING children from " << (i+1)); @@ -69,9 +70,9 @@ BT::ReturnStatus BT::SequenceNode::Tick() else { // the child returned success. - children_nodes_[i]->SetStatus(BT::IDLE); + child_node->SetStatus(BT::IDLE); - if (i == N_of_children_ - 1) + if (i == N_of_children - 1) { // If the child status is success, and it is the last child to be ticked, // then the sequence has succeeded. diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 5221c6dfb..d4dd223d6 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -28,7 +28,7 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() DEBUG_STDOUT(Name() << " ticked, memory counter: "<< current_child_idx_); // Vector size initialization. N_of_children_ could change at runtime if you edit the tree - N_of_children_ = children_nodes_.size(); + const unsigned N_of_children_ = children_nodes_.size(); // Routing the ticks according to the sequence node's (with memory) logic: while (current_child_idx_ < N_of_children_) @@ -38,38 +38,39 @@ BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ + const auto& current_child_node = children_nodes_[current_child_idx_]; - if (children_nodes_[current_child_idx_]->Type() == BT::ACTION_NODE) + if (current_child_node->Type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. - child_i_status_ = children_nodes_[current_child_idx_]->Status(); - DEBUG_STDOUT(Name() << " It is an action " << children_nodes_[current_child_idx_]->Name() + child_i_status_ = current_child_node->Status(); + DEBUG_STDOUT(Name() << " It is an action " << child_node->Name() << " with status: " << child_i_status_); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[current_child_idx_]->Name()); - children_nodes_[current_child_idx_]->tick_engine.Tick(); + DEBUG_STDOUT(Name() << "NEEDS TO TICK " << child_node->Name()); + current_child_node->tick_engine.Tick(); - child_i_status_ = children_nodes_[current_child_idx_]->waitValidStatus(); + child_i_status_ = current_child_node->waitValidStatus(); } } else { // 2) if it's not an action: // Send the tick and wait for the response; - child_i_status_ = children_nodes_[current_child_idx_]->Tick(); - children_nodes_[current_child_idx_]->SetStatus(child_i_status_); + child_i_status_ = current_child_node->Tick(); + current_child_node->SetStatus(child_i_status_); } - if (child_i_status_ == BT::SUCCESS ||child_i_status_ == BT::FAILURE ) + if (child_i_status_ == BT::SUCCESS || child_i_status_ == BT::FAILURE ) { // the child goes in idle if it has returned success or failure. - children_nodes_[current_child_idx_]->SetStatus(BT::IDLE); + current_child_node->SetStatus(BT::IDLE); } if (child_i_status_ != BT::SUCCESS) From d3b10935f4e0f44725c3287e5b69c6fd5a363392 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Apr 2018 18:04:12 +0200 Subject: [PATCH 018/125] ReturnStatus NodeStatus --- gtest/gtest_tree.cpp | 62 +++++++++---------- gtest/include/action_test_node.h | 2 +- gtest/include/condition_test_node.h | 2 +- gtest/src/action_test_node.cpp | 2 +- gtest/src/condition_test_node.cpp | 2 +- include/behavior_tree_core/action_node.h | 2 +- include/behavior_tree_core/bt_factory.h | 4 +- include/behavior_tree_core/condition_node.h | 2 +- include/behavior_tree_core/control_node.h | 4 +- include/behavior_tree_core/decorator_node.h | 2 +- include/behavior_tree_core/fallback_node.h | 2 +- .../fallback_node_with_memory.h | 2 +- include/behavior_tree_core/parallel_node.h | 2 +- include/behavior_tree_core/sequence_node.h | 2 +- .../sequence_node_with_memory.h | 2 +- include/behavior_tree_core/tree_node.h | 12 ++-- src/action_node.cpp | 2 +- src/bt_factory.cpp | 4 +- src/fallback_node.cpp | 4 +- src/fallback_node_with_memory.cpp | 2 +- src/parallel_node.cpp | 2 +- src/sequence_node.cpp | 4 +- src/sequence_node_with_memory.cpp | 2 +- src/tree_node.cpp | 8 +-- 24 files changed, 67 insertions(+), 67 deletions(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 037494360..4ed874c08 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -363,7 +363,7 @@ TEST_F(SimpleSequenceTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::RUNNING, action->Status()); ASSERT_EQ(BT::RUNNING, state); @@ -373,7 +373,7 @@ TEST_F(SimpleSequenceTest, ConditionTrue) TEST_F(SimpleSequenceTest, ConditionTurnToFalse) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition->set_boolean_value(false); state = root->Tick(); @@ -385,7 +385,7 @@ TEST_F(SimpleSequenceTest, ConditionTurnToFalse) TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::RUNNING, action_1->Status()); ASSERT_EQ(BT::RUNNING, state); @@ -395,7 +395,7 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); state = root->Tick(); @@ -414,7 +414,7 @@ TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition_1->set_boolean_value(false); @@ -427,7 +427,7 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse) TEST_F(ComplexSequenceTest, ComplexSequenceConditions2ToFalse) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition_2->set_boolean_value(false); @@ -445,7 +445,7 @@ TEST_F(SimpleFallbackTest, ConditionTrue) std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node condition->set_boolean_value(true); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::IDLE, action->Status()); ASSERT_EQ(BT::SUCCESS, state); @@ -457,7 +457,7 @@ TEST_F(SimpleFallbackTest, ConditionToFalse) { condition->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition->set_boolean_value(true); @@ -474,7 +474,7 @@ TEST_F(ComplexFallbackTest, Condition1ToTrue) condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition_1->set_boolean_value(true); @@ -491,7 +491,7 @@ TEST_F(ComplexFallbackTest, Condition2ToTrue) condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition_2->set_boolean_value(true); @@ -509,7 +509,7 @@ TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) condition_1->set_boolean_value(false); condition_2->set_boolean_value(true); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::RUNNING, state); ASSERT_EQ(BT::RUNNING, action_1->Status()); @@ -522,7 +522,7 @@ TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) condition_2->set_boolean_value(false); condition_1->set_boolean_value(true); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::RUNNING, state); ASSERT_EQ(BT::RUNNING, action_1->Status()); @@ -535,7 +535,7 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); std::this_thread::sleep_for(std::chrono::seconds(1)); ASSERT_EQ(BT::RUNNING, action->Status()); @@ -546,7 +546,7 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition->set_boolean_value(false); @@ -561,7 +561,7 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::RUNNING, action_1->Status()); ASSERT_EQ(BT::IDLE, action_2->Status()); @@ -573,7 +573,7 @@ TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition_1->set_boolean_value(false); @@ -587,7 +587,7 @@ TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) TEST_F(ComplexSequenceWithMemoryTest, Conditions2ToFalse) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition_2->set_boolean_value(false); @@ -620,7 +620,7 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node condition->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); std::this_thread::sleep_for(std::chrono::seconds(1)); ASSERT_EQ(BT::RUNNING, action->Status()); @@ -634,7 +634,7 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) { condition->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition->set_boolean_value(true); state = root->Tick(); @@ -649,7 +649,7 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::IDLE, action_1->Status()); ASSERT_EQ(BT::IDLE, action_2->Status()); @@ -661,7 +661,7 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) TEST_F(ComplexFallbackWithMemoryTest, Condition1False) { condition_1->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::IDLE, action_1->Status()); ASSERT_EQ(BT::IDLE, action_2->Status()); @@ -675,7 +675,7 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) { condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::RUNNING, action_1->Status()); ASSERT_EQ(BT::IDLE, action_2->Status()); @@ -691,7 +691,7 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) { condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition_1->set_boolean_value(true); state = root->Tick(); @@ -709,7 +709,7 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) condition_2->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); condition_2->set_boolean_value(true); @@ -728,7 +728,7 @@ TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); state = root->Tick(); std::this_thread::sleep_for(std::chrono::seconds(5)); @@ -744,7 +744,7 @@ TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) TEST_F(SimpleParallelTest, ConditionsTrue) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::IDLE, condition_1->Status()); ASSERT_EQ(BT::IDLE, condition_2->Status()); @@ -762,7 +762,7 @@ TEST_F(SimpleParallelTest, Threshold_3) action_2->set_time(200); root->Tick(); std::this_thread::sleep_for(std::chrono::seconds(5)); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::IDLE, condition_1->Status()); ASSERT_EQ(BT::IDLE, condition_2->Status()); @@ -777,7 +777,7 @@ TEST_F(SimpleParallelTest, Threshold_3) TEST_F(SimpleParallelTest, Threshold_1) { root->set_threshold_M(1); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::IDLE, condition_1->Status()); ASSERT_EQ(BT::IDLE, condition_2->Status()); @@ -789,7 +789,7 @@ TEST_F(SimpleParallelTest, Threshold_1) } TEST_F(ComplexParallelTest, ConditionsTrue) { - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::IDLE, condition_1->Status()); ASSERT_EQ(BT::IDLE, condition_2->Status()); @@ -809,7 +809,7 @@ TEST_F(ComplexParallelTest, ConditionsTrue) TEST_F(ComplexParallelTest, Condition3False) { condition_3->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::IDLE, condition_1->Status()); ASSERT_EQ(BT::IDLE, condition_2->Status()); @@ -831,7 +831,7 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) action_3->set_time(10); condition_3->set_boolean_value(false); - BT::ReturnStatus state = root->Tick(); + BT::NodeStatus state = root->Tick(); std::this_thread::sleep_for(std::chrono::seconds(5)); diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index 1cfce769e..50bff5fdd 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -14,7 +14,7 @@ namespace BT virtual ~ActionTestNode() = default; // The method that is going to be executed by the thread - virtual BT::ReturnStatus Tick() override; + virtual BT::NodeStatus Tick() override; void set_time(int time); // The method used to interrupt the execution of the node diff --git a/gtest/include/condition_test_node.h b/gtest/include/condition_test_node.h index a5157bd84..6f7afd2d7 100644 --- a/gtest/include/condition_test_node.h +++ b/gtest/include/condition_test_node.h @@ -14,7 +14,7 @@ namespace BT void set_boolean_value(bool boolean_value); // The method that is going to be executed by the thread - virtual BT::ReturnStatus Tick() override; + virtual BT::NodeStatus Tick() override; private: bool boolean_value_; }; diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index acc15e840..f2aceb2b8 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -23,7 +23,7 @@ BT::ActionTestNode::ActionTestNode(std::string name) : ActionNode::ActionNode(na } -BT::ReturnStatus BT::ActionTestNode::Tick() +BT::NodeStatus BT::ActionTestNode::Tick() { int i = 0; diff --git a/gtest/src/condition_test_node.cpp b/gtest/src/condition_test_node.cpp index 92fe18a18..f89a92ef2 100644 --- a/gtest/src/condition_test_node.cpp +++ b/gtest/src/condition_test_node.cpp @@ -21,7 +21,7 @@ BT::ConditionTestNode::ConditionTestNode(std::string name) : ConditionNode::Cond BT::ConditionTestNode::~ConditionTestNode() {} -BT::ReturnStatus BT::ConditionTestNode::Tick() +BT::NodeStatus BT::ConditionTestNode::Tick() { // Condition checking and state update diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index ccc9fece7..295d3e510 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -32,7 +32,7 @@ class ActionNode : public LeafNode // Methods used to access the node state without the // conditional waiting (only mutual access) - bool WriteState(ReturnStatus new_state); + bool WriteState(NodeStatus new_state); virtual NodeType Type() const override final { return ACTION_NODE; } diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 4d4205e7b..3bb7b30de 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -48,9 +48,9 @@ class BehaviorTreeFactory template void registerBuilder(const std::string& ID); - void registerSimpleAction(const std::string& ID, std::function tick_functor); + void registerSimpleAction(const std::string& ID, std::function tick_functor); - void registerSimpleDecorator(const std::string& ID, std::function tick_functor); + void registerSimpleDecorator(const std::string& ID, std::function tick_functor); std::unique_ptr instantiateTreeNode(const std::string& ID, const NodeParameters& params); diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index 423f75b36..8e02d7326 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -30,7 +30,7 @@ namespace BT // Methods used to access the node state without the // conditional waiting (only mutual access) - bool WriteState(ReturnStatus new_state); + bool WriteState(NodeStatus new_state); virtual NodeType Type() const override final { return CONDITION_NODE; } diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index 81d76982f..9f5261aa0 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -26,7 +26,7 @@ namespace BT std::vector children_nodes_; //child i status. Used to rout the ticks - ReturnStatus child_i_status_; + NodeStatus child_i_status_; public: // Constructor @@ -48,7 +48,7 @@ namespace BT // Methods used to access the node state without the // conditional waiting (only mutual access) - bool WriteState(ReturnStatus new_state); + bool WriteState(NodeStatus new_state); virtual NodeType Type() const override final { return CONTROL_NODE; } }; diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index 5f25039da..a87efe7de 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -28,7 +28,7 @@ namespace BT // Methods used to access the node state without the // conditional waiting (only mutual access) - bool WriteState(ReturnStatus new_state); + bool WriteState(NodeStatus new_state); virtual NodeType Type() const override final { return DECORATOR_NODE; } }; diff --git a/include/behavior_tree_core/fallback_node.h b/include/behavior_tree_core/fallback_node.h index 0e071ba70..0e2ea6983 100644 --- a/include/behavior_tree_core/fallback_node.h +++ b/include/behavior_tree_core/fallback_node.h @@ -26,7 +26,7 @@ namespace BT ~FallbackNode() = default; // The method that is going to be executed by the thread - virtual BT::ReturnStatus Tick() override; + virtual BT::NodeStatus Tick() override; }; } diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index 826a680d5..74004274d 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -27,7 +27,7 @@ class FallbackNodeWithMemory : public ControlNode ~FallbackNodeWithMemory() = default; // The method that is going to be executed by the thread - virtual BT::ReturnStatus Tick() override; + virtual BT::NodeStatus Tick() override; virtual void Halt() override; private: diff --git a/include/behavior_tree_core/parallel_node.h b/include/behavior_tree_core/parallel_node.h index 1d4c04d7a..a5d6d1709 100644 --- a/include/behavior_tree_core/parallel_node.h +++ b/include/behavior_tree_core/parallel_node.h @@ -26,7 +26,7 @@ class ParallelNode : public ControlNode ~ParallelNode() = default; // The method that is going to be executed by the thread - virtual BT::ReturnStatus Tick() override; + virtual BT::NodeStatus Tick() override; virtual void Halt() override; unsigned int get_threshold_M(); diff --git a/include/behavior_tree_core/sequence_node.h b/include/behavior_tree_core/sequence_node.h index e97c23e29..9f1f0ba33 100644 --- a/include/behavior_tree_core/sequence_node.h +++ b/include/behavior_tree_core/sequence_node.h @@ -26,7 +26,7 @@ class SequenceNode : public ControlNode ~SequenceNode() = default; // The method that is going to be executed by the thread - virtual BT::ReturnStatus Tick() override; + virtual BT::NodeStatus Tick() override; }; } diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index 5e2eb426e..273ba8d17 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -27,7 +27,7 @@ class SequenceNodeWithMemory : public ControlNode ~SequenceNodeWithMemory() = default; // The method that is going to be executed by the thread - virtual BT::ReturnStatus Tick() override; + virtual BT::NodeStatus Tick() override; virtual void Halt() override; private: unsigned int current_child_idx_; diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 5708133a2..59e3c6b99 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -51,7 +51,7 @@ namespace BT // time step, but the task is not yet complete; // - "Idle" indicates that the node hasn't run yet. // - "Halted" indicates that the node has been halted by its father. - enum ReturnStatus {RUNNING, SUCCESS, FAILURE, IDLE, HALTED, EXIT}; + enum NodeStatus {RUNNING, SUCCESS, FAILURE, IDLE, HALTED, EXIT}; // Enumerates the options for when a parallel node is considered to have failed: // - "FAIL_ON_ONE" indicates that the node will return failure as soon as one of @@ -77,7 +77,7 @@ namespace BT private: // Node name std::string name_; - ReturnStatus status_; + NodeStatus status_; protected: // The node state that must be treated in a thread-safe way @@ -97,21 +97,21 @@ namespace BT virtual ~TreeNode(); // The method that is going to be executed when the node receive a tick - virtual BT::ReturnStatus Tick() = 0; + virtual BT::NodeStatus Tick() = 0; // The method used to interrupt the execution of the node virtual void Halt() = 0; bool IsHalted() const; - ReturnStatus Status() const; - void SetStatus(ReturnStatus new_status); + NodeStatus Status() const; + void SetStatus(NodeStatus new_status); const std::string& Name() const; void SetName(const std::string& new_name); - BT::ReturnStatus waitValidStatus(); + BT::NodeStatus waitValidStatus(); virtual NodeType Type() const = 0; diff --git a/src/action_node.cpp b/src/action_node.cpp index b202a3dea..d5bab1ce2 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -32,7 +32,7 @@ void BT::ActionNode::WaitForTick() // Running state SetStatus(BT::RUNNING); - BT::ReturnStatus status = Tick(); + BT::NodeStatus status = Tick(); SetStatus(status); } } diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 04a01e5ec..af153e55d 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -31,13 +31,13 @@ bool BehaviorTreeFactory::unregisterBuilder(const std::string &ID) } void BehaviorTreeFactory::registerSimpleAction(const std::string &ID, - std::function tick_functor) + std::function tick_functor) { } void BehaviorTreeFactory::registerSimpleDecorator(const std::string &ID, - std::function tick_functor) + std::function tick_functor) { } diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index a16f26a18..8208f14ab 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -19,11 +19,11 @@ BT::FallbackNode::FallbackNode(std::string name) : {} -BT::ReturnStatus BT::FallbackNode::Tick() +BT::NodeStatus BT::FallbackNode::Tick() { { // gets the number of children. The number could change if, at runtime, one edits the tree. - const int N_of_children = children_nodes_.size(); + const unsigned N_of_children = children_nodes_.size(); // Routing the ticks according to the fallback node's logic: diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 7b81429c6..b732bd0af 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -24,7 +24,7 @@ BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, ResetPolity } -BT::ReturnStatus BT::FallbackNodeWithMemory::Tick() +BT::NodeStatus BT::FallbackNodeWithMemory::Tick() { DEBUG_STDOUT(Name() << " ticked, memory counter: "<< current_child_idx_); diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 2cf9b0009..ae9124a78 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -20,7 +20,7 @@ BT::ParallelNode::ParallelNode(std::string name, int threshold_M) : { } -BT::ReturnStatus BT::ParallelNode::Tick() +BT::NodeStatus BT::ParallelNode::Tick() { success_childred_num_ = 0; failure_childred_num_ = 0; diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 585158110..f512c04e0 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -17,10 +17,10 @@ BT::SequenceNode::SequenceNode(std::string name) : ControlNode::ControlNode(name) {} -BT::ReturnStatus BT::SequenceNode::Tick() +BT::NodeStatus BT::SequenceNode::Tick() { // gets the number of children. The number could change if, at runtime, one edits the tree. - const int N_of_children = children_nodes_.size(); + const unsigned N_of_children = children_nodes_.size(); // Routing the ticks according to the sequence node's logic: diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index d4dd223d6..646b9e366 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -23,7 +23,7 @@ BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolity } -BT::ReturnStatus BT::SequenceNodeWithMemory::Tick() +BT::NodeStatus BT::SequenceNodeWithMemory::Tick() { DEBUG_STDOUT(Name() << " ticked, memory counter: "<< current_child_idx_); diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 794e2993e..2e95ef940 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -15,15 +15,15 @@ BT::TreeNode::TreeNode(std::string name) : name_(name), - is_state_updated_(false), status_(BT::IDLE), + is_state_updated_(false), tick_engine(0) { } BT::TreeNode::~TreeNode() {} -void BT::TreeNode::SetStatus(ReturnStatus new_status) +void BT::TreeNode::SetStatus(NodeStatus new_status) { { std::unique_lock UniqueLock(state_mutex_); @@ -33,7 +33,7 @@ void BT::TreeNode::SetStatus(ReturnStatus new_status) state_condition_variable_.notify_all(); } -BT::ReturnStatus BT::TreeNode::Status() const +BT::NodeStatus BT::TreeNode::Status() const { std::lock_guard LockGuard(state_mutex_); return status_; @@ -44,7 +44,7 @@ void BT::TreeNode::SetName(const std::string &new_name) name_ = new_name; } -BT::ReturnStatus BT::TreeNode::waitValidStatus() +BT::NodeStatus BT::TreeNode::waitValidStatus() { std::unique_lock lk( state_mutex_ ); From fc6e850e109fe5febaff221dff13ad3663059736 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 20 Apr 2018 10:03:54 +0200 Subject: [PATCH 019/125] clang format applied --- .clang-format | 3 +- gtest/gtest_tree.cpp | 97 ++------ gtest/include/action_test_node.h | 35 ++- gtest/include/condition_test_node.h | 25 +- gtest/src/action_test_node.cpp | 9 - gtest/src/condition_test_node.cpp | 33 ++- include/behavior_tree_core/action_node.h | 12 +- include/behavior_tree_core/behavior_tree.h | 4 +- include/behavior_tree_core/bt_factory.h | 57 ++--- include/behavior_tree_core/condition_node.h | 30 +-- include/behavior_tree_core/control_node.h | 51 +++-- .../decorator_negation_node.h | 21 +- include/behavior_tree_core/decorator_node.h | 42 ++-- .../behavior_tree_core/decorator_retry_node.h | 24 +- include/behavior_tree_core/exceptions.h | 17 +- include/behavior_tree_core/fallback_node.h | 18 +- .../fallback_node_with_memory.h | 10 +- include/behavior_tree_core/leaf_node.h | 14 +- include/behavior_tree_core/parallel_node.h | 7 +- include/behavior_tree_core/sequence_node.h | 2 +- .../sequence_node_with_memory.h | 9 +- include/behavior_tree_core/tick_engine.h | 5 +- include/behavior_tree_core/tree_node.h | 162 +++++++------ src/action_node.cpp | 2 - src/bt_factory.cpp | 18 +- src/condition_node.cpp | 10 +- src/control_node.cpp | 17 +- src/decorator_negation_node.cpp | 214 +++++++++--------- src/decorator_node.cpp | 20 +- src/decorator_retry_node.cpp | 85 +++---- src/example.cpp | 15 +- src/exceptions.cpp | 1 - src/fallback_node.cpp | 18 +- src/fallback_node_with_memory.cpp | 25 +- src/leaf_node.cpp | 6 +- src/parallel_node.cpp | 68 +++--- src/sequence_node.cpp | 12 +- src/sequence_node_with_memory.cpp | 24 +- src/tick_engine.cpp | 5 +- src/tree.cpp | 17 +- src/tree_node.cpp | 23 +- templates/action_node_template.cpp | 16 +- templates/condition_node_template.cpp | 29 ++- 43 files changed, 599 insertions(+), 713 deletions(-) diff --git a/.clang-format b/.clang-format index 34524d527..7d2721dbe 100644 --- a/.clang-format +++ b/.clang-format @@ -30,7 +30,7 @@ PenaltyBreakString: 1 PenaltyBreakFirstLessLess: 1000 PenaltyExcessCharacter: 1000 PenaltyReturnTypeOnItsOwnLine: 90 -SpacesBeforeTrailingComments: 2 +SpacesBeforeTrailingComments: 3 Cpp11BracedListStyle: true Standard: Auto IndentWidth: 4 @@ -46,6 +46,7 @@ SpaceBeforeAssignmentOperators: true ContinuationIndentWidth: 4 SortIncludes: false SpaceAfterCStyleCast: false +ReflowComments: false # Configure each individual brace in BraceWrapping BreakBeforeBraces: Custom diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 4ed874c08..9841c77e3 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -10,17 +10,14 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include #include "action_test_node.h" #include "condition_test_node.h" #include "behavior_tree_core/behavior_tree.h" - - struct SimpleSequenceTest : testing::Test { - BT:: SequenceNode* root; + BT::SequenceNode* root; BT::ActionTestNode* action; BT::ConditionTestNode* condition; SimpleSequenceTest() @@ -35,15 +32,14 @@ struct SimpleSequenceTest : testing::Test } }; - struct ComplexSequenceTest : testing::Test { - BT:: SequenceNode* root; + BT::SequenceNode* root; BT::ActionTestNode* action_1; BT::ConditionTestNode* condition_1; BT::ConditionTestNode* condition_2; - BT:: SequenceNode* seq_conditions; + BT::SequenceNode* seq_conditions; ComplexSequenceTest() { @@ -62,18 +58,17 @@ struct ComplexSequenceTest : testing::Test } }; - struct ComplexSequence2ActionsTest : testing::Test { - BT:: SequenceNode* root; + BT::SequenceNode* root; BT::ActionTestNode* action_1; BT::ActionTestNode* action_2; BT::ConditionTestNode* condition_1; BT::ConditionTestNode* condition_2; - BT:: SequenceNode* seq_1; - BT:: SequenceNode* seq_2; + BT::SequenceNode* seq_1; + BT::SequenceNode* seq_2; ComplexSequence2ActionsTest() { @@ -91,17 +86,15 @@ struct ComplexSequence2ActionsTest : testing::Test seq_2->AddChild(condition_2); seq_2->AddChild(action_2); - root = new BT::SequenceNode("root"); root->AddChild(seq_1); root->AddChild(seq_2); } }; - struct SimpleFallbackTest : testing::Test { - BT:: FallbackNode* root; + BT::FallbackNode* root; BT::ActionTestNode* action; BT::ConditionTestNode* condition; SimpleFallbackTest() @@ -116,15 +109,14 @@ struct SimpleFallbackTest : testing::Test } }; - struct ComplexFallbackTest : testing::Test { - BT:: FallbackNode* root; + BT::FallbackNode* root; BT::ActionTestNode* action_1; BT::ConditionTestNode* condition_1; BT::ConditionTestNode* condition_2; - BT:: FallbackNode* sel_conditions; + BT::FallbackNode* sel_conditions; ComplexFallbackTest() { @@ -142,17 +134,14 @@ struct ComplexFallbackTest : testing::Test } }; - - - struct BehaviorTreeTest : testing::Test { - BT:: SequenceNode* root; + BT::SequenceNode* root; BT::ActionTestNode* action_1; BT::ConditionTestNode* condition_1; BT::ConditionTestNode* condition_2; - BT:: FallbackNode* sel_conditions; + BT::FallbackNode* sel_conditions; BehaviorTreeTest() { @@ -170,12 +159,9 @@ struct BehaviorTreeTest : testing::Test } }; - - - struct SimpleSequenceWithMemoryTest : testing::Test { - BT:: SequenceNodeWithMemory* root; + BT::SequenceNodeWithMemory* root; BT::ActionTestNode* action; BT::ConditionTestNode* condition; SimpleSequenceWithMemoryTest() @@ -192,7 +178,7 @@ struct SimpleSequenceWithMemoryTest : testing::Test struct ComplexSequenceWithMemoryTest : testing::Test { - BT:: SequenceNodeWithMemory* root; + BT::SequenceNodeWithMemory* root; BT::ActionTestNode* action_1; BT::ActionTestNode* action_2; @@ -200,15 +186,14 @@ struct ComplexSequenceWithMemoryTest : testing::Test BT::ConditionTestNode* condition_1; BT::ConditionTestNode* condition_2; - BT:: SequenceNodeWithMemory* seq_conditions; - BT:: SequenceNodeWithMemory* seq_actions; + BT::SequenceNodeWithMemory* seq_conditions; + BT::SequenceNodeWithMemory* seq_actions; ComplexSequenceWithMemoryTest() { action_1 = new BT::ActionTestNode("action 1"); action_2 = new BT::ActionTestNode("action 2"); - condition_1 = new BT::ConditionTestNode("condition 1"); condition_2 = new BT::ConditionTestNode("condition 2"); @@ -246,7 +231,7 @@ struct SimpleFallbackWithMemoryTest : testing::Test struct ComplexFallbackWithMemoryTest : testing::Test { - BT:: FallbackNodeWithMemory* root; + BT::FallbackNodeWithMemory* root; BT::ActionTestNode* action_1; BT::ActionTestNode* action_2; @@ -254,8 +239,8 @@ struct ComplexFallbackWithMemoryTest : testing::Test BT::ConditionTestNode* condition_1; BT::ConditionTestNode* condition_2; - BT:: FallbackNodeWithMemory* fal_conditions; - BT:: FallbackNodeWithMemory* fal_actions; + BT::FallbackNodeWithMemory* fal_conditions; + BT::FallbackNodeWithMemory* fal_actions; ComplexFallbackWithMemoryTest() { @@ -279,7 +264,6 @@ struct ComplexFallbackWithMemoryTest : testing::Test } }; - struct SimpleParallelTest : testing::Test { BT::ParallelNode* root; @@ -294,7 +278,6 @@ struct SimpleParallelTest : testing::Test action_1 = new BT::ActionTestNode("action 1"); condition_1 = new BT::ConditionTestNode("condition 1"); - action_2 = new BT::ActionTestNode("action 2"); condition_2 = new BT::ConditionTestNode("condition 2"); @@ -307,7 +290,6 @@ struct SimpleParallelTest : testing::Test } }; - struct ComplexParallelTest : testing::Test { BT::ParallelNode* root; @@ -328,11 +310,9 @@ struct ComplexParallelTest : testing::Test action_1 = new BT::ActionTestNode("action 1"); condition_1 = new BT::ConditionTestNode("condition 1"); - action_2 = new BT::ActionTestNode("action 2"); condition_2 = new BT::ConditionTestNode("condition 2"); - action_3 = new BT::ActionTestNode("action 3"); condition_3 = new BT::ConditionTestNode("condition 3"); @@ -353,12 +333,8 @@ struct ComplexParallelTest : testing::Test } }; - - /****************TESTS START HERE***************************/ - - TEST_F(SimpleSequenceTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; @@ -370,7 +346,6 @@ TEST_F(SimpleSequenceTest, ConditionTrue) root->Halt(); } - TEST_F(SimpleSequenceTest, ConditionTurnToFalse) { BT::NodeStatus state = root->Tick(); @@ -382,7 +357,6 @@ TEST_F(SimpleSequenceTest, ConditionTurnToFalse) root->Halt(); } - TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) { BT::NodeStatus state = root->Tick(); @@ -392,7 +366,6 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) root->Halt(); } - TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) { BT::NodeStatus state = root->Tick(); @@ -438,8 +411,6 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditions2ToFalse) root->Halt(); } - - TEST_F(SimpleFallbackTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; @@ -452,7 +423,6 @@ TEST_F(SimpleFallbackTest, ConditionTrue) root->Halt(); } - TEST_F(SimpleFallbackTest, ConditionToFalse) { condition->set_boolean_value(false); @@ -460,7 +430,6 @@ TEST_F(SimpleFallbackTest, ConditionToFalse) BT::NodeStatus state = root->Tick(); condition->set_boolean_value(true); - state = root->Tick(); ASSERT_EQ(BT::SUCCESS, state); @@ -468,7 +437,6 @@ TEST_F(SimpleFallbackTest, ConditionToFalse) root->Halt(); } - TEST_F(ComplexFallbackTest, Condition1ToTrue) { condition_1->set_boolean_value(false); @@ -502,8 +470,6 @@ TEST_F(ComplexFallbackTest, Condition2ToTrue) root->Halt(); } - - TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) { condition_1->set_boolean_value(false); @@ -530,7 +496,6 @@ TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) root->Halt(); } - TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; @@ -543,7 +508,6 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) root->Halt(); } - TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) { BT::NodeStatus state = root->Tick(); @@ -558,7 +522,6 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) root->Halt(); } - TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) { BT::NodeStatus state = root->Tick(); @@ -570,7 +533,6 @@ TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) root->Halt(); } - TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) { BT::NodeStatus state = root->Tick(); @@ -629,7 +591,6 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) root->Halt(); } - TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) { condition->set_boolean_value(false); @@ -645,8 +606,6 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) root->Halt(); } - - TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) { BT::NodeStatus state = root->Tick(); @@ -670,7 +629,6 @@ TEST_F(ComplexFallbackWithMemoryTest, Condition1False) root->Halt(); } - TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) { condition_1->set_boolean_value(false); @@ -684,9 +642,6 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) root->Halt(); } - - - TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) { condition_1->set_boolean_value(false); @@ -741,7 +696,6 @@ TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) root->Halt(); } - TEST_F(SimpleParallelTest, ConditionsTrue) { BT::NodeStatus state = root->Tick(); @@ -755,7 +709,6 @@ TEST_F(SimpleParallelTest, ConditionsTrue) root->Halt(); } - TEST_F(SimpleParallelTest, Threshold_3) { root->set_threshold_M(3); @@ -773,7 +726,6 @@ TEST_F(SimpleParallelTest, Threshold_3) root->Halt(); } - TEST_F(SimpleParallelTest, Threshold_1) { root->set_threshold_M(1); @@ -804,8 +756,6 @@ TEST_F(ComplexParallelTest, ConditionsTrue) root->Halt(); } - - TEST_F(ComplexParallelTest, Condition3False) { condition_3->set_boolean_value(false); @@ -824,7 +774,6 @@ TEST_F(ComplexParallelTest, Condition3False) root->Halt(); } - TEST_F(ComplexParallelTest, Condition3FalseAction1Done) { action_2->set_time(10); @@ -834,12 +783,11 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) BT::NodeStatus state = root->Tick(); std::this_thread::sleep_for(std::chrono::seconds(5)); - ASSERT_EQ(BT::IDLE, condition_1->Status()); ASSERT_EQ(BT::IDLE, condition_2->Status()); ASSERT_EQ(BT::IDLE, condition_3->Status()); - ASSERT_EQ(BT::SUCCESS, action_1->Status()); // success not read yet by the node parallel_1 - ASSERT_EQ(BT::RUNNING, parallel_1->Status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded + ASSERT_EQ(BT::SUCCESS, action_1->Status()); // success not read yet by the node parallel_1 + ASSERT_EQ(BT::RUNNING, parallel_1->Status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded state = root->Tick(); @@ -850,7 +798,6 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) ASSERT_EQ(BT::RUNNING, parallel_2->Status()); ASSERT_EQ(BT::RUNNING, state); - state = root->Tick(); std::this_thread::sleep_for(std::chrono::seconds(15)); state = root->Tick(); @@ -865,10 +812,8 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) root->Halt(); } -int main(int argc, char **argv) +int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } - - diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index 50bff5fdd..d525d80a3 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -5,28 +5,27 @@ namespace BT { - class ActionTestNode : public ActionNode - { +class ActionTestNode : public ActionNode +{ + public: + // Constructor + ActionTestNode(std::string Name); + virtual ~ActionTestNode() = default; - public: - // Constructor - ActionTestNode(std::string Name); - virtual ~ActionTestNode() = default; + // The method that is going to be executed by the thread + virtual BT::NodeStatus Tick() override; + void set_time(int time); - // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; - void set_time(int time); - - // The method used to interrupt the execution of the node - virtual void Halt() override; - void set_boolean_value(bool boolean_value); - private: - int time_; - bool boolean_value_; + // The method used to interrupt the execution of the node + virtual void Halt() override; + void set_boolean_value(bool boolean_value); - ///ReturnStatus status_; + private: + int time_; + bool boolean_value_; - }; + ///ReturnStatus status_; +}; } #endif diff --git a/gtest/include/condition_test_node.h b/gtest/include/condition_test_node.h index 6f7afd2d7..70febb2b7 100644 --- a/gtest/include/condition_test_node.h +++ b/gtest/include/condition_test_node.h @@ -5,19 +5,20 @@ namespace BT { - class ConditionTestNode : public ConditionNode - { - public: - // Constructor - ConditionTestNode(std::string Name); - ~ConditionTestNode(); - void set_boolean_value(bool boolean_value); +class ConditionTestNode : public ConditionNode +{ + public: + // Constructor + ConditionTestNode(std::string Name); + ~ConditionTestNode(); + void set_boolean_value(bool boolean_value); + + // The method that is going to be executed by the thread + virtual BT::NodeStatus Tick() override; - // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; - private: - bool boolean_value_; - }; + private: + bool boolean_value_; +}; } #endif diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index f2aceb2b8..2085085b1 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -11,21 +11,17 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "action_test_node.h" #include - BT::ActionTestNode::ActionTestNode(std::string name) : ActionNode::ActionNode(name) { boolean_value_ = true; time_ = 3; } - BT::NodeStatus BT::ActionTestNode::Tick() { - int i = 0; while (Status() != BT::HALTED && i++ < time_) { @@ -57,17 +53,12 @@ void BT::ActionTestNode::Halt() DEBUG_STDOUT("HALTED state set!"); } - void BT::ActionTestNode::set_time(int time) { time_ = time; } - - void BT::ActionTestNode::set_boolean_value(bool boolean_value) { boolean_value_ = boolean_value; } - - diff --git a/gtest/src/condition_test_node.cpp b/gtest/src/condition_test_node.cpp index f89a92ef2..59d4281ba 100644 --- a/gtest/src/condition_test_node.cpp +++ b/gtest/src/condition_test_node.cpp @@ -10,7 +10,6 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "condition_test_node.h" #include @@ -19,29 +18,27 @@ BT::ConditionTestNode::ConditionTestNode(std::string name) : ConditionNode::Cond boolean_value_ = true; } -BT::ConditionTestNode::~ConditionTestNode() {} +BT::ConditionTestNode::~ConditionTestNode() +{ +} BT::NodeStatus BT::ConditionTestNode::Tick() { - // Condition checking and state update - - if (boolean_value_) - { - SetStatus(BT::SUCCESS); - return BT::SUCCESS; - } - else - { - SetStatus(BT::FAILURE); - return BT::FAILURE; - } + // Condition checking and state update + + if (boolean_value_) + { + SetStatus(BT::SUCCESS); + return BT::SUCCESS; + } + else + { + SetStatus(BT::FAILURE); + return BT::FAILURE; + } } - - - void BT::ConditionTestNode::set_boolean_value(bool boolean_value) { boolean_value_ = boolean_value; } - diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 295d3e510..fc2dd17bf 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -11,7 +11,6 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #ifndef BEHAVIORTREECORE_ACTIONNODE_H #define BEHAVIORTREECORE_ACTIONNODE_H @@ -19,10 +18,9 @@ namespace BT { - class ActionNode : public LeafNode { -public: + public: // Constructor ActionNode(std::string name); ~ActionNode() = default; @@ -34,12 +32,14 @@ class ActionNode : public LeafNode // conditional waiting (only mutual access) bool WriteState(NodeStatus new_state); - virtual NodeType Type() const override final { return ACTION_NODE; } + virtual NodeType Type() const override final + { + return ACTION_NODE; + } -protected: + protected: // The thread that will execute the node std::thread thread_; - }; } diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index 87c86dece..17afb3973 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -11,7 +11,6 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #ifndef BEHAVIOR_TREE_H #define BEHAVIOR_TREE_H @@ -30,5 +29,4 @@ #include "behavior_tree_core/exceptions.h" - -#endif // BEHAVIOR_TREE_H +#endif // BEHAVIOR_TREE_H diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 3bb7b30de..abcbbeec1 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -14,7 +14,6 @@ #ifndef BT_FACTORY_H #define BT_FACTORY_H - #include #include #include @@ -27,7 +26,6 @@ namespace BT { - typedef std::set RequiredParameters; // We call Parameters the set of Key/Values that canbe read from file and are @@ -35,12 +33,11 @@ typedef std::set RequiredParameters; typedef std::map NodeParameters; // The term "Builder" refers to the Builder Ppattern (https://en.wikipedia.org/wiki/Builder_pattern) -typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; +typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; class BehaviorTreeFactory { public: - BehaviorTreeFactory(); bool unregisterBuilder(const std::string& ID); @@ -54,61 +51,57 @@ class BehaviorTreeFactory std::unique_ptr instantiateTreeNode(const std::string& ID, const NodeParameters& params); - const std::map & builders() const + const std::map& builders() const { return builders_; } -private: - + private: std::map builders_; }; - //----------------------------------------------- -template inline -void BehaviorTreeFactory::registerBuilder(const std::string &ID) +template +inline void BehaviorTreeFactory::registerBuilder(const std::string& ID) { - static_assert(std::is_base_of::value || - std::is_base_of::value || - std::is_base_of::value || - std::is_base_of::value, - "[registerBuilder]: accepts only classed derived from either ActionNode, DecoratorNode, ControlNode or ConditionNode"); + static_assert(std::is_base_of::value || std::is_base_of::value || + std::is_base_of::value || std::is_base_of::value, + "[registerBuilder]: accepts only classed derived from either ActionNode, DecoratorNode, ControlNode " + "or ConditionNode"); - constexpr bool default_constructable = std::is_constructible::value; - constexpr bool param_constructable = std::is_constructible::value; + constexpr bool default_constructable = std::is_constructible::value; + constexpr bool param_constructable = std::is_constructible::value; - static_assert( param_constructable || param_constructable , + static_assert(param_constructable || param_constructable, "[registerBuilder]: the registered class must have a Constructor with signature:\n\n" " (const std::string&, const NodeParameters&)\n" " or\n" - " (const std::string&)" ); + " (const std::string&)"); auto it = builders_.find(ID); - if( it != builders_.end()) + if (it != builders_.end()) { throw BehaviorTreeException("ID '" + ID + "' already registered"); } - NodeBuilder builder = [default_constructable, ID](const std::string& name, const NodeParameters& params) - { - if( default_constructable && params.empty() ) + NodeBuilder builder = [default_constructable, ID](const std::string& name, const NodeParameters& params) { + if (default_constructable && params.empty()) { - return std::unique_ptr(new T(name) ); + return std::unique_ptr(new T(name)); } - if( !param_constructable && !params.empty() ) + if (!param_constructable && !params.empty()) { - throw BehaviorTreeException("Trying to instantiate a TreeNode that can NOT accept NodeParameters in the Constructor: [" - + ID + " / " + name +"]"); + throw BehaviorTreeException("Trying to instantiate a TreeNode that can NOT accept NodeParameters in the " + "Constructor: [" + + ID + " / " + name + "]"); } - return std::unique_ptr(new T(name, params) ); + return std::unique_ptr(new T(name, params)); }; - builders_.insert( std::make_pair(ID,builder) ); + builders_.insert(std::make_pair(ID, builder)); } - -} // end namespace -#endif // BT_FACTORY_H +} // end namespace +#endif // BT_FACTORY_H diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index 8e02d7326..2d4a3fd38 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -18,23 +18,25 @@ namespace BT { - class ConditionNode : public LeafNode - { - public: - // Constructor - ConditionNode(std::string name); - ~ConditionNode() = default; - - // The method used to interrupt the execution of the node - virtual void Halt() override; +class ConditionNode : public LeafNode +{ + public: + // Constructor + ConditionNode(std::string name); + ~ConditionNode() = default; - // Methods used to access the node state without the - // conditional waiting (only mutual access) - bool WriteState(NodeStatus new_state); + // The method used to interrupt the execution of the node + virtual void Halt() override; - virtual NodeType Type() const override final { return CONDITION_NODE; } + // Methods used to access the node state without the + // conditional waiting (only mutual access) + bool WriteState(NodeStatus new_state); - }; + virtual NodeType Type() const override final + { + return CONDITION_NODE; + } +}; } #endif diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index 9f5261aa0..df6e57f72 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -19,39 +19,42 @@ namespace BT { - class ControlNode : public TreeNode - { - protected: - // Children vector - std::vector children_nodes_; +class ControlNode : public TreeNode +{ + protected: + // Children vector + std::vector children_nodes_; - //child i status. Used to rout the ticks - NodeStatus child_i_status_; + //child i status. Used to rout the ticks + NodeStatus child_i_status_; - public: - // Constructor - ControlNode(std::string name); - ~ControlNode() = default; + public: + // Constructor + ControlNode(std::string name); + ~ControlNode() = default; - // The method used to fill the child vector - void AddChild(TreeNode* child); + // The method used to fill the child vector + void AddChild(TreeNode* child); - // The method used to know the number of children - unsigned int ChildrenCount() const; + // The method used to know the number of children + unsigned int ChildrenCount() const; - const std::vector& Children() const; + const std::vector& Children() const; - // The method used to interrupt the execution of the node - virtual void Halt() override; + // The method used to interrupt the execution of the node + virtual void Halt() override; - void HaltChildren(int i); + void HaltChildren(int i); - // Methods used to access the node state without the - // conditional waiting (only mutual access) - bool WriteState(NodeStatus new_state); + // Methods used to access the node state without the + // conditional waiting (only mutual access) + bool WriteState(NodeStatus new_state); - virtual NodeType Type() const override final { return CONTROL_NODE; } - }; + virtual NodeType Type() const override final + { + return CONTROL_NODE; + } +}; } #endif diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h index c3cd8ce75..38b682351 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -18,18 +18,17 @@ namespace BT { - class DecoratorNegationNode : public DecoratorNode - { - public: - // Constructor - DecoratorNegationNode(std::string name); - ~DecoratorNegationNode() = default; - - // The method that is going to be executed by the thread - void Exec(); - void AddChild(TreeNode* child); +class DecoratorNegationNode : public DecoratorNode +{ + public: + // Constructor + DecoratorNegationNode(std::string name); + ~DecoratorNegationNode() = default; - }; + // The method that is going to be executed by the thread + void Exec(); + void AddChild(TreeNode* child); +}; } #endif diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index a87efe7de..716d66a12 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -5,33 +5,35 @@ namespace BT { - class DecoratorNode : public TreeNode - { - protected: - - TreeNode* child_node_; +class DecoratorNode : public TreeNode +{ + protected: + TreeNode* child_node_; - public: - // Constructor - DecoratorNode(std::string name); - ~DecoratorNode() = default; + public: + // Constructor + DecoratorNode(std::string name); + ~DecoratorNode() = default; - // The method used to fill the child vector - void AddChild(TreeNode* child); + // The method used to fill the child vector + void AddChild(TreeNode* child); - const TreeNode* Child() const; + const TreeNode* Child() const; - // The method used to interrupt the execution of the node - virtual void Halt() override; + // The method used to interrupt the execution of the node + virtual void Halt() override; - void HaltChild(); + void HaltChild(); - // Methods used to access the node state without the - // conditional waiting (only mutual access) - bool WriteState(NodeStatus new_state); + // Methods used to access the node state without the + // conditional waiting (only mutual access) + bool WriteState(NodeStatus new_state); - virtual NodeType Type() const override final { return DECORATOR_NODE; } - }; + virtual NodeType Type() const override final + { + return DECORATOR_NODE; + } +}; } #endif diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h index 29ce8e420..2e62e7bf1 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -18,20 +18,20 @@ namespace BT { - class DecoratorRetryNode : public DecoratorNode - { - public: - // Constructor - DecoratorRetryNode(std::string name, unsigned int NTries); - ~DecoratorRetryNode() = default; +class DecoratorRetryNode : public DecoratorNode +{ + public: + // Constructor + DecoratorRetryNode(std::string name, unsigned int NTries); + ~DecoratorRetryNode() = default; - // The method that is going to be executed by the thread - void Exec(); + // The method that is going to be executed by the thread + void Exec(); - private: - unsigned int NTries_; - unsigned int TryIndx_; - }; + private: + unsigned int NTries_; + unsigned int TryIndx_; +}; } #endif diff --git a/include/behavior_tree_core/exceptions.h b/include/behavior_tree_core/exceptions.h index dcca1c8cb..509b77ff2 100644 --- a/include/behavior_tree_core/exceptions.h +++ b/include/behavior_tree_core/exceptions.h @@ -19,14 +19,15 @@ namespace BT { - /// Exception class - class BehaviorTreeException : public std::exception - { - private: - const char* Message; - public: - BehaviorTreeException(const std::string Message); - }; +/// Exception class +class BehaviorTreeException : public std::exception +{ + private: + const char* Message; + + public: + BehaviorTreeException(const std::string Message); +}; } #endif diff --git a/include/behavior_tree_core/fallback_node.h b/include/behavior_tree_core/fallback_node.h index 0e2ea6983..dbdd6978f 100644 --- a/include/behavior_tree_core/fallback_node.h +++ b/include/behavior_tree_core/fallback_node.h @@ -18,16 +18,16 @@ namespace BT { - class FallbackNode : public ControlNode - { - public: - // Constructor - FallbackNode(std::string name); - ~FallbackNode() = default; +class FallbackNode : public ControlNode +{ + public: + // Constructor + FallbackNode(std::string name); + ~FallbackNode() = default; - // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; - }; + // The method that is going to be executed by the thread + virtual BT::NodeStatus Tick() override; +}; } #endif diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index 74004274d..c13e55a1d 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -20,8 +20,7 @@ namespace BT { class FallbackNodeWithMemory : public ControlNode { -public: - + public: FallbackNodeWithMemory(std::string name, ResetPolity reset_policy = BT::ON_SUCCESS_OR_FAILURE); ~FallbackNodeWithMemory() = default; @@ -30,12 +29,11 @@ class FallbackNodeWithMemory : public ControlNode virtual BT::NodeStatus Tick() override; virtual void Halt() override; -private: + + private: unsigned int current_child_idx_; ResetPolity reset_policy_; - }; } - -#endif // FALLBACK_NODE_WITH_MEMORY_H +#endif // FALLBACK_NODE_WITH_MEMORY_H diff --git a/include/behavior_tree_core/leaf_node.h b/include/behavior_tree_core/leaf_node.h index 9a490cf94..259155f23 100644 --- a/include/behavior_tree_core/leaf_node.h +++ b/include/behavior_tree_core/leaf_node.h @@ -18,13 +18,13 @@ namespace BT { - class LeafNode : public TreeNode - { - protected: - public: - LeafNode(std::string name); - ~LeafNode() = default; - }; +class LeafNode : public TreeNode +{ + protected: + public: + LeafNode(std::string name); + ~LeafNode() = default; +}; } #endif diff --git a/include/behavior_tree_core/parallel_node.h b/include/behavior_tree_core/parallel_node.h index a5d6d1709..dc4828d45 100644 --- a/include/behavior_tree_core/parallel_node.h +++ b/include/behavior_tree_core/parallel_node.h @@ -20,7 +20,7 @@ namespace BT { class ParallelNode : public ControlNode { -public: + public: // Constructor ParallelNode(std::string name, int threshold_M); ~ParallelNode() = default; @@ -32,11 +32,10 @@ class ParallelNode : public ControlNode unsigned int get_threshold_M(); void set_threshold_M(unsigned int threshold_M); -private: + private: unsigned int threshold_M_; unsigned int success_childred_num_; unsigned int failure_childred_num_; - }; } -#endif // PARALLEL_NODE_H +#endif // PARALLEL_NODE_H diff --git a/include/behavior_tree_core/sequence_node.h b/include/behavior_tree_core/sequence_node.h index 9f1f0ba33..219348079 100644 --- a/include/behavior_tree_core/sequence_node.h +++ b/include/behavior_tree_core/sequence_node.h @@ -20,7 +20,7 @@ namespace BT { class SequenceNode : public ControlNode { -public: + public: // Constructor SequenceNode(std::string name); ~SequenceNode() = default; diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index 273ba8d17..7ceb80705 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -20,8 +20,7 @@ namespace BT { class SequenceNodeWithMemory : public ControlNode { -public: - + public: SequenceNodeWithMemory(std::string name, ResetPolity reset_policy = BT::ON_SUCCESS_OR_FAILURE); ~SequenceNodeWithMemory() = default; @@ -29,11 +28,11 @@ class SequenceNodeWithMemory : public ControlNode // The method that is going to be executed by the thread virtual BT::NodeStatus Tick() override; virtual void Halt() override; -private: + + private: unsigned int current_child_idx_; ResetPolity reset_policy_; - }; } -#endif // SEQUENCE_NODE_WITH_MEMORY_H +#endif // SEQUENCE_NODE_WITH_MEMORY_H diff --git a/include/behavior_tree_core/tick_engine.h b/include/behavior_tree_core/tick_engine.h index b04e29f6f..917dea1d7 100644 --- a/include/behavior_tree_core/tick_engine.h +++ b/include/behavior_tree_core/tick_engine.h @@ -21,11 +21,12 @@ class TickEngine { -private: + private: int value_; std::mutex mutex_; std::condition_variable condition_variable_; -public: + + public: TickEngine(int initial_value); ~TickEngine(); void Wait(); diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 59e3c6b99..84e2835fd 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -14,16 +14,18 @@ #ifndef BEHAVIORTREECORE_TREENODE_H #define BEHAVIORTREECORE_TREENODE_H - #ifdef DEBUG - // #define DEBUG_STDERR(x) (std::cerr << (x)) -#define DEBUG_STDOUT(str) do { std::cout << str << std::endl; } while( false ) +// #define DEBUG_STDERR(x) (std::cerr << (x)) +#define DEBUG_STDOUT(str) \ + do \ + { \ + std::cout << str << std::endl; \ + } while (false) #else #define DEBUG_STDOUT(str) #endif - #include //#include @@ -38,84 +40,108 @@ namespace BT { - // Enumerates the possible types of a node, for drawinf we have do discriminate whoich control node it is: - - enum NodeType {ACTION_NODE, CONDITION_NODE, CONTROL_NODE, DECORATOR_NODE}; - - // Enumerates the states every node can be in after execution during a particular - // time step: - // - "Success" indicates that the node has completed running during this time step; - // - "Failure" indicates that the node has determined it will not be able to complete - // its task; - // - "Running" indicates that the node has successfully moved forward during this - // time step, but the task is not yet complete; - // - "Idle" indicates that the node hasn't run yet. - // - "Halted" indicates that the node has been halted by its father. - enum NodeStatus {RUNNING, SUCCESS, FAILURE, IDLE, HALTED, EXIT}; - - // Enumerates the options for when a parallel node is considered to have failed: - // - "FAIL_ON_ONE" indicates that the node will return failure as soon as one of - // its children fails; - // - "FAIL_ON_ALL" indicates that all of the node's children must fail before it - // returns failure. - enum FailurePolicy {FAIL_ON_ONE, FAIL_ON_ALL}; - enum ResetPolity {ON_SUCCESS_OR_FAILURE,ON_SUCCESS, ON_FAILURE}; - - // Enumerates the options for when a parallel node is considered to have succeeded: - // - "SUCCEED_ON_ONE" indicates that the node will return success as soon as one - // of its children succeeds; - // - "BT::SUCCEED_ON_ALL" indicates that all of the node's children must succeed before - // it returns success. - enum SuccessPolicy {SUCCEED_ON_ONE, SUCCEED_ON_ALL}; - - // If "BT::FAIL_ON_ONE" and "BT::SUCCEED_ON_ONE" are both active and are both trigerred in the - // same time step, failure will take precedence. +// Enumerates the possible types of a node, for drawinf we have do discriminate whoich control node it is: - // Abstract base class for Behavior Tree Nodes - class TreeNode - { - private: - // Node name - std::string name_; - NodeStatus status_; - - protected: - // The node state that must be treated in a thread-safe way - bool is_state_updated_; +enum NodeType +{ + ACTION_NODE, + CONDITION_NODE, + CONTROL_NODE, + DECORATOR_NODE +}; + +// Enumerates the states every node can be in after execution during a particular +// time step: +// - "Success" indicates that the node has completed running during this time step; +// - "Failure" indicates that the node has determined it will not be able to complete +// its task; +// - "Running" indicates that the node has successfully moved forward during this +// time step, but the task is not yet complete; +// - "Idle" indicates that the node hasn't run yet. +// - "Halted" indicates that the node has been halted by its father. +enum NodeStatus +{ + RUNNING, + SUCCESS, + FAILURE, + IDLE, + HALTED, + EXIT +}; + +// Enumerates the options for when a parallel node is considered to have failed: +// - "FAIL_ON_ONE" indicates that the node will return failure as soon as one of +// its children fails; +// - "FAIL_ON_ALL" indicates that all of the node's children must fail before it +// returns failure. +enum FailurePolicy +{ + FAIL_ON_ONE, + FAIL_ON_ALL +}; +enum ResetPolity +{ + ON_SUCCESS_OR_FAILURE, + ON_SUCCESS, + ON_FAILURE +}; + +// Enumerates the options for when a parallel node is considered to have succeeded: +// - "SUCCEED_ON_ONE" indicates that the node will return success as soon as one +// of its children succeeds; +// - "BT::SUCCEED_ON_ALL" indicates that all of the node's children must succeed before +// it returns success. +enum SuccessPolicy +{ + SUCCEED_ON_ONE, + SUCCEED_ON_ALL +}; - mutable std::mutex state_mutex_; - std::condition_variable state_condition_variable_; +// If "BT::FAIL_ON_ONE" and "BT::SUCCEED_ON_ONE" are both active and are both trigerred in the +// same time step, failure will take precedence. - public: +// Abstract base class for Behavior Tree Nodes +class TreeNode +{ + private: + // Node name + std::string name_; + NodeStatus status_; - // Node semaphore to simulate the tick - // (and to synchronize fathers and children) - TickEngine tick_engine; + protected: + // The node state that must be treated in a thread-safe way + bool is_state_updated_; - // The constructor and the distructor - TreeNode(std::string name); - virtual ~TreeNode(); + mutable std::mutex state_mutex_; + std::condition_variable state_condition_variable_; - // The method that is going to be executed when the node receive a tick - virtual BT::NodeStatus Tick() = 0; + public: + // Node semaphore to simulate the tick + // (and to synchronize fathers and children) + TickEngine tick_engine; - // The method used to interrupt the execution of the node - virtual void Halt() = 0; + // The constructor and the distructor + TreeNode(std::string name); + virtual ~TreeNode(); - bool IsHalted() const; + // The method that is going to be executed when the node receive a tick + virtual BT::NodeStatus Tick() = 0; - NodeStatus Status() const; - void SetStatus(NodeStatus new_status); + // The method used to interrupt the execution of the node + virtual void Halt() = 0; - const std::string& Name() const; - void SetName(const std::string& new_name); + bool IsHalted() const; + NodeStatus Status() const; + void SetStatus(NodeStatus new_status); - BT::NodeStatus waitValidStatus(); + const std::string& Name() const; + void SetName(const std::string& new_name); - virtual NodeType Type() const = 0; + BT::NodeStatus waitValidStatus(); - }; + virtual NodeType Type() const = 0; +}; } #endif diff --git a/src/action_node.cpp b/src/action_node.cpp index d5bab1ce2..85dfbce63 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -11,7 +11,6 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/action_node.h" BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name) @@ -19,7 +18,6 @@ BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name) thread_ = std::thread(&ActionNode::WaitForTick, this); } - void BT::ActionNode::WaitForTick() { while (true) diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index af153e55d..63806433b 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -19,10 +19,10 @@ BehaviorTreeFactory::BehaviorTreeFactory() { } -bool BehaviorTreeFactory::unregisterBuilder(const std::string &ID) +bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID) { auto it = builders_.find(ID); - if( it == builders_.end()) + if (it == builders_.end()) { return false; } @@ -30,27 +30,23 @@ bool BehaviorTreeFactory::unregisterBuilder(const std::string &ID) return true; } -void BehaviorTreeFactory::registerSimpleAction(const std::string &ID, - std::function tick_functor) +void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, std::function tick_functor) { - } -void BehaviorTreeFactory::registerSimpleDecorator(const std::string &ID, +void BehaviorTreeFactory::registerSimpleDecorator(const std::string& ID, std::function tick_functor) { - } -std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::string &ID, - const NodeParameters ¶ms) +std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::string& ID, const NodeParameters& params) { auto it = builders_.find(ID); - if( it == builders_.end()) + if (it == builders_.end()) { throw BehaviorTreeException("ID '" + ID + "' not registered"); } return it->second(ID, params); } -} // end namespace +} // end namespace diff --git a/src/condition_node.cpp b/src/condition_node.cpp index 87361c4a1..5e008b8ab 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -11,14 +11,12 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/condition_node.h" -BT::ConditionNode::ConditionNode(std::string name) : - LeafNode::LeafNode(name) +BT::ConditionNode::ConditionNode(std::string name) : LeafNode::LeafNode(name) { - } -void BT::ConditionNode::Halt() {} - +void BT::ConditionNode::Halt() +{ +} diff --git a/src/control_node.cpp b/src/control_node.cpp index ab9f7cda9..d35cb15c9 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -11,10 +11,8 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/control_node.h" - BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus @@ -25,7 +23,7 @@ BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) void BT::ControlNode::AddChild(TreeNode* child) { // Checking if the child is not already present - for (auto node: children_nodes_) + for (auto node : children_nodes_) { if (node == child) { @@ -43,29 +41,28 @@ unsigned int BT::ControlNode::ChildrenCount() const void BT::ControlNode::Halt() { - DEBUG_STDOUT("HALTING: "<< Name()); + DEBUG_STDOUT("HALTING: " << Name()); HaltChildren(0); SetStatus(BT::HALTED); } -const std::vector &BT::ControlNode::Children() const +const std::vector& BT::ControlNode::Children() const { return children_nodes_; } void BT::ControlNode::HaltChildren(int i) { - for (unsigned int j=i; j < children_nodes_.size(); j++) + for (unsigned int j = i; j < children_nodes_.size(); j++) { if (children_nodes_[j]->Status() == BT::RUNNING) { DEBUG_STDOUT("SENDING HALT TO CHILD " << children_nodes_[j]->Name()); children_nodes_[j]->Halt(); } - else{ - DEBUG_STDOUT("NO NEED TO HALT " << children_nodes_[j]->Name() - << "STATUS" << children_nodes_[j]->Status()); + else + { + DEBUG_STDOUT("NO NEED TO HALT " << children_nodes_[j]->Name() << "STATUS" << children_nodes_[j]->Status()); } } } - diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index 22c7c80f9..cff7ee697 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -1,18 +1,17 @@ #include - BT::DecoratorNegationNode::DecoratorNegationNode(std::string name) : ControlNode::ControlNode(name) { // thread_ start thread_ = boost::thread(&DecoratorNegationNode::Exec, this); } -BT::DecoratorNegationNode::~DecoratorNegationNode() {} +BT::DecoratorNegationNode::~DecoratorNegationNode() +{ +} void BT::DecoratorNegationNode::Exec() { - - // Waiting for the first tick to come tick_engine.wait(); @@ -22,12 +21,12 @@ void BT::DecoratorNegationNode::Exec() // Simulating a tick for myself tick_engine.tick(); - while(true) + while (true) { // Waiting for a tick to come tick_engine.wait(); - if(ReadState() == BT::EXIT) + if (ReadState() == BT::EXIT) { // The behavior tree is going to be destroied return; @@ -39,126 +38,126 @@ void BT::DecoratorNegationNode::Exec() // If not, the children can be ticked std::cout << get_name() << " ticked, ticking children..." << std::endl; + if (children_nodes_[0]->get_type() == BT::ACTION_NODE) + { + // 1) if it's an action: + // 1.1) read its state; + ReturnStatus ActionState = children_nodes_[0]->ReadState(); - - - if (children_nodes_[0]->get_type() == BT::ACTION_NODE) + if (ActionState == BT::IDLE) { - // 1) if it's an action: - // 1.1) read its state; - ReturnStatus ActionState = children_nodes_[0]->ReadState(); - - if (ActionState == BT::IDLE) - { - // 1.2) if it's "Idle": - // 1.2.1) ticking it; - children_nodes_[0]->tick_engine.tick(); - - // 1.2.2) retrive its state as soon as it is available; - children_states_[0] = children_nodes_[0]->GetNodeState(); - } - else if (ActionState == BT::RUNNING) - { - // 1.3) if it's "Running": - // 1.3.1) saving "Running" - children_states_[0] = BT::RUNNING; - } - else - { - // 1.4) if it's "Success" of "Failure" (it can't be "Halted"!): - // 1.2.1) ticking it; - children_nodes_[0]->tick_engine.tick(); - - // 1.2.2) saving the read state; - children_states_[0] = ActionState; - } - } - else - { - // 2) if it's not an action: - // 2.1) ticking it; + // 1.2) if it's "Idle": + // 1.2.1) ticking it; children_nodes_[0]->tick_engine.tick(); - // 2.2) retrive its state as soon as it is available; + // 1.2.2) retrive its state as soon as it is available; children_states_[0] = children_nodes_[0]->GetNodeState(); } - - // 3) if the child state is a success: - if(children_states_[0] == BT::SUCCESS) + else if (ActionState == BT::RUNNING) { - // 3.1) the node state is equal to failure since I am negating the status - SetNodeState(BT::FAILURE); - - // 3.2) resetting the state; - WriteState(BT::IDLE); - - std::cout << get_name() << " returning " << BT::FAILURE << "!" << std::endl; + // 1.3) if it's "Running": + // 1.3.1) saving "Running" + children_states_[0] = BT::RUNNING; } - else if(children_states_[0] == BT::FAILURE) - { - // 4.1) the node state is equal to success since I am negating the status - SetNodeState(BT::SUCCESS); - - // 4.2) state reset; - WriteState(BT::IDLE); - - std::cout << get_name() << " returning " << BT::SUCCESS << "!" << std::endl; - - } else - // 5) if the child state is running + else { - // 5.1) the node state is equal to running - SetNodeState(BT::RUNNING); + // 1.4) if it's "Success" of "Failure" (it can't be "Halted"!): + // 1.2.1) ticking it; + children_nodes_[0]->tick_engine.tick(); - // 5.2) state reset; - WriteState(BT::IDLE); + // 1.2.2) saving the read state; + children_states_[0] = ActionState; } - + } + else + { + // 2) if it's not an action: + // 2.1) ticking it; + children_nodes_[0]->tick_engine.tick(); + + // 2.2) retrive its state as soon as it is available; + children_states_[0] = children_nodes_[0]->GetNodeState(); + } + + // 3) if the child state is a success: + if (children_states_[0] == BT::SUCCESS) + { + // 3.1) the node state is equal to failure since I am negating the status + SetNodeState(BT::FAILURE); + + // 3.2) resetting the state; + WriteState(BT::IDLE); + + std::cout << get_name() << " returning " << BT::FAILURE << "!" << std::endl; + } + else if (children_states_[0] == BT::FAILURE) + { + // 4.1) the node state is equal to success since I am negating the status + SetNodeState(BT::SUCCESS); + + // 4.2) state reset; + WriteState(BT::IDLE); + + std::cout << get_name() << " returning " << BT::SUCCESS << "!" << std::endl; + } + else + // 5) if the child state is running + { + // 5.1) the node state is equal to running + SetNodeState(BT::RUNNING); + + // 5.2) state reset; + WriteState(BT::IDLE); + } } else { // If it was halted, all the "busy" children must be halted too std::cout << get_name() << " halted! Halting all the children..." << std::endl; - if (children_nodes_[0]->get_type() != BT::ACTION_NODE && children_states_[0] == BT::RUNNING) + if (children_nodes_[0]->get_type() != BT::ACTION_NODE && children_states_[0] == BT::RUNNING) + { + // if the control node was running: + // halting it; + children_nodes_[0]->Halt(); + + // sync with it (it's waiting on the semaphore); + children_nodes_[0]->tick_engine.tick(); + + std::cout << get_name() << " halting child " + << "!" << std::endl; + } + else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && + children_nodes_[0]->ReadState() == BT::RUNNING) + { + std::cout << get_name() << " trying halting child " + << "..." << std::endl; + + // if it's a action node that hasn't finished its job: + // trying to halt it: + if (children_nodes_[0]->Halt() == false) { - // if the control node was running: - // halting it; - children_nodes_[0]->Halt(); - - // sync with it (it's waiting on the semaphore); + // this means that, before this node could set its child state + // to "Halted", the child had already written the action outcome; + // sync with him ignoring its state; children_nodes_[0]->tick_engine.tick(); - std::cout << get_name() << " halting child " << "!" << std::endl; + std::cout << get_name() << " halting of child " + << " failed!" << std::endl; } - else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && children_nodes_[0]->ReadState() == BT::RUNNING) - { - std::cout << get_name() << " trying halting child " << "..." << std::endl; - // if it's a action node that hasn't finished its job: - // trying to halt it: - if (children_nodes_[0]->Halt() == false) - { - // this means that, before this node could set its child state - // to "Halted", the child had already written the action outcome; - // sync with him ignoring its state; - children_nodes_[0]->tick_engine.tick(); - - std::cout << get_name() << " halting of child " << " failed!" << std::endl; - } - - std::cout << get_name() << " halting of child " << " succedeed!" << std::endl; - } - else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && children_nodes_[0]->ReadState() != BT::IDLE) - { - // if it's a action node that has finished its job: - // ticking it without saving its returning state; - children_nodes_[0]->tick_engine.tick(); - } - - // updating its vector cell - children_states_[0] = BT::IDLE; + std::cout << get_name() << " halting of child " + << " succedeed!" << std::endl; + } + else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && children_nodes_[0]->ReadState() != BT::IDLE) + { + // if it's a action node that has finished its job: + // ticking it without saving its returning state; + children_nodes_[0]->tick_engine.tick(); + } + // updating its vector cell + children_states_[0] = BT::IDLE; // Resetting the node state WriteState(BT::IDLE); @@ -170,11 +169,10 @@ void BT::DecoratorNegationNode::AddChild(BT::TreeNode* child) { // Checking if the child is not already present - if (children_nodes_.size() > 0) - { - throw BehaviorTreeException("Decorators can have only one child"); - } - + if (children_nodes_.size() > 0) + { + throw BehaviorTreeException("Decorators can have only one child"); + } children_nodes_.push_back(child); children_states_.push_back(BT::IDLE); diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index bcfc88f18..8c0a87cbe 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -10,13 +10,9 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/decorator_node.h" - -BT::DecoratorNode::DecoratorNode(std::string name) : - TreeNode::TreeNode(name), - child_node_(nullptr) +BT::DecoratorNode::DecoratorNode(std::string name) : TreeNode::TreeNode(name), child_node_(nullptr) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable @@ -25,18 +21,17 @@ BT::DecoratorNode::DecoratorNode(std::string name) : void BT::DecoratorNode::AddChild(TreeNode* child) { - if (child_node_ ) + if (child_node_) { throw BehaviorTreeException("Decorator '" + Name() + "' has already a child assigned"); } - child_node_ = child; + child_node_ = child; } - void BT::DecoratorNode::Halt() { - DEBUG_STDOUT("HALTING: "<< Name()); + DEBUG_STDOUT("HALTING: " << Name()); HaltChild(); SetStatus(BT::HALTED); } @@ -53,9 +48,8 @@ void BT::DecoratorNode::HaltChild() DEBUG_STDOUT("SENDING HALT TO CHILD " << child_node_->Name()); child_node_->Halt(); } - else{ - DEBUG_STDOUT("NO NEED TO HALT " << child_node_->Name() - << "STATUS" << child_node_->Status()); + else + { + DEBUG_STDOUT("NO NEED TO HALT " << child_node_->Name() << "STATUS" << child_node_->Status()); } } - diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index 97609ec71..6d139ba84 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -1,6 +1,5 @@ #include - BT::DecoratorRetryNode::DecoratorRetryNode(std::string name, unsigned int NTries) : ControlNode::ControlNode(name) { // thread_ start @@ -8,7 +7,9 @@ BT::DecoratorRetryNode::DecoratorRetryNode(std::string name, unsigned int NTries thread_ = boost::thread(&DecoratorRetryNode::Exec, this); } -BT::DecoratorRetryNode::~DecoratorRetryNode() {} +BT::DecoratorRetryNode::~DecoratorRetryNode() +{ +} void BT::DecoratorRetryNode::Exec() { @@ -23,12 +24,12 @@ void BT::DecoratorRetryNode::Exec() // Simulating a tick for myself tick_engine.tick(); - while(true) + while (true) { // Waiting for a tick to come tick_engine.wait(); - if(ReadState() == BT::EXIT) + if (ReadState() == BT::EXIT) { // The behavior tree is going to be destroied return; @@ -86,7 +87,7 @@ void BT::DecoratorRetryNode::Exec() } // 3) if the child state is not a success: - if(children_states_[0] == BT::SUCCESS) + if (children_states_[0] == BT::SUCCESS) { SetNodeState(BT::SUCCESS); @@ -97,14 +98,13 @@ void BT::DecoratorRetryNode::Exec() } else { - if(children_states_[0] == BT::FAILURE) + if (children_states_[0] == BT::FAILURE) { children_nodes_[0]->ResetColorState(); TryIndx_++; - } - if(children_states_[0] == BT::FAILURE && TryIndx_ < NTries_) + if (children_states_[0] == BT::FAILURE && TryIndx_ < NTries_) { // 3.1) the node state is equal to running since I am rerunning the child SetNodeState(BT::RUNNING); @@ -117,60 +117,61 @@ void BT::DecoratorRetryNode::Exec() // 3.2) state reset; WriteState(BT::IDLE); std::cout << get_name() << " returning " << children_states_[0] << "!" << std::endl; - } } } - } else { // If it was halted, all the "busy" children must be halted too std::cout << get_name() << " halted! Halting all the children..." << std::endl; - if (children_nodes_[0]->get_type() != BT::ACTION_NODE && children_states_[0] == BT::RUNNING) - { - // if the control node was running: - // halting it; - children_nodes_[0]->Halt(); - - // sync with it (it's waiting on the semaphore); - children_nodes_[0]->tick_engine.tick(); - - std::cout << get_name() << " halting child " << "!" << std::endl; - } - else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && children_nodes_[0]->ReadState() == BT::RUNNING) - { - std::cout << get_name() << " trying halting child " << "..." << std::endl; + if (children_nodes_[0]->get_type() != BT::ACTION_NODE && children_states_[0] == BT::RUNNING) + { + // if the control node was running: + // halting it; + children_nodes_[0]->Halt(); - // if it's a action node that hasn't finished its job: - // trying to halt it: - if (children_nodes_[0]->Halt() == false) - { - // this means that, before this node could set its child state - // to "Halted", the child had already written the action outcome; - // sync with him ignoring its state; - children_nodes_[0]->tick_engine.tick(); + // sync with it (it's waiting on the semaphore); + children_nodes_[0]->tick_engine.tick(); - std::cout << get_name() << " halting of child " << " failed!" << std::endl; - } + std::cout << get_name() << " halting child " + << "!" << std::endl; + } + else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && + children_nodes_[0]->ReadState() == BT::RUNNING) + { + std::cout << get_name() << " trying halting child " + << "..." << std::endl; - std::cout << get_name() << " halting of child " << " succedeed!" << std::endl; - } - else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && children_nodes_[0]->ReadState() != BT::IDLE) + // if it's a action node that hasn't finished its job: + // trying to halt it: + if (children_nodes_[0]->Halt() == false) { - // if it's a action node that has finished its job: - // ticking it without saving its returning state; + // this means that, before this node could set its child state + // to "Halted", the child had already written the action outcome; + // sync with him ignoring its state; children_nodes_[0]->tick_engine.tick(); + + std::cout << get_name() << " halting of child " + << " failed!" << std::endl; } - // updating its vector cell - children_states_[0] = BT::IDLE; + std::cout << get_name() << " halting of child " + << " succedeed!" << std::endl; + } + else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && children_nodes_[0]->ReadState() != BT::IDLE) + { + // if it's a action node that has finished its job: + // ticking it without saving its returning state; + children_nodes_[0]->tick_engine.tick(); + } + // updating its vector cell + children_states_[0] = BT::IDLE; // Resetting the node state WriteState(BT::IDLE); } } } - diff --git a/src/example.cpp b/src/example.cpp index 0dee0e7ad..e2e47695d 100644 --- a/src/example.cpp +++ b/src/example.cpp @@ -1,11 +1,9 @@ #include #include - - class MyCondition : public BT::ConditionNode { -public: + public: MyCondition(std::string name); ~MyCondition(); BT::ReturnStatus Tick(); @@ -13,7 +11,6 @@ class MyCondition : public BT::ConditionNode MyCondition::MyCondition(std::string name) : BT::ConditionNode::ConditionNode(name) { - } BT::ReturnStatus MyCondition::Tick() @@ -23,10 +20,9 @@ BT::ReturnStatus MyCondition::Tick() return BT::SUCCESS; } - class MyAction : public BT::ActionNode { -public: + public: MyAction(std::string name); ~MyAction(); BT::ReturnStatus Tick(); @@ -35,10 +31,8 @@ class MyAction : public BT::ActionNode MyAction::MyAction(std::string name) : ActionNode::ActionNode(name) { - } - BT::ReturnStatus MyAction::Tick() { std::cout << "The Action is doing some operations" << std::endl; @@ -68,13 +62,10 @@ BT::ReturnStatus MyAction::Tick() void MyAction::Halt() { - } - -int main(int argc, char *argv[]) +int main(int argc, char* argv[]) { - BT::SequenceNode* seq = new BT::SequenceNode("Sequence"); MyCondition* my_con_1 = new MyCondition("Condition"); MyAction* my_act_1 = new MyAction("Action"); diff --git a/src/exceptions.cpp b/src/exceptions.cpp index 7b251f041..917e902f8 100644 --- a/src/exceptions.cpp +++ b/src/exceptions.cpp @@ -11,7 +11,6 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/exceptions.h" BT::BehaviorTreeException::BehaviorTreeException(const std::string Message) diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 8208f14ab..6ac75948f 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -11,13 +11,11 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/fallback_node.h" -BT::FallbackNode::FallbackNode(std::string name) : - ControlNode::ControlNode(name) -{} - +BT::FallbackNode::FallbackNode(std::string name) : ControlNode::ControlNode(name) +{ +} BT::NodeStatus BT::FallbackNode::Tick() { @@ -27,7 +25,7 @@ BT::NodeStatus BT::FallbackNode::Tick() // Routing the ticks according to the fallback node's logic: - for ( int i=0; i < N_of_children; i++) + for (int i = 0; i < N_of_children; i++) { auto& child_node = children_nodes_[i]; @@ -56,18 +54,17 @@ BT::NodeStatus BT::FallbackNode::Tick() // Send the tick and wait for the response; child_i_status_ = child_node->Tick(); child_node->SetStatus(child_i_status_); - } // Ponderate on which status to send to the parent if (child_i_status_ != BT::FAILURE) { if (child_i_status_ == BT::SUCCESS) { - child_node->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. + child_node->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. } // If the child status is not failure, halt the next children and return the status to your parent. - DEBUG_STDOUT(Name() << " is HALTING children from " << (i+1)); - HaltChildren(i+1); + DEBUG_STDOUT(Name() << " is HALTING children from " << (i + 1)); + HaltChildren(i + 1); SetStatus(child_i_status_); return child_i_status_; } @@ -87,4 +84,3 @@ BT::NodeStatus BT::FallbackNode::Tick() } return BT::EXIT; } - diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index b732bd0af..44f8099e1 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -11,22 +11,16 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/fallback_node_with_memory.h" - -BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, ResetPolity reset_policy) : - ControlNode::ControlNode(name), - current_child_idx_(0), - reset_policy_( reset_policy ) +BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, ResetPolity reset_policy) + : ControlNode::ControlNode(name), current_child_idx_(0), reset_policy_(reset_policy) { - } - BT::NodeStatus BT::FallbackNodeWithMemory::Tick() { - DEBUG_STDOUT(Name() << " ticked, memory counter: "<< current_child_idx_); + DEBUG_STDOUT(Name() << " ticked, memory counter: " << current_child_idx_); // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children = children_nodes_.size(); @@ -49,7 +43,7 @@ BT::NodeStatus BT::FallbackNodeWithMemory::Tick() child_i_status_ = current_child_node->Status(); DEBUG_STDOUT(Name() << " It is an action " << current_child_node->Name() - << " with status: " << child_i_status_); + << " with status: " << child_i_status_); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { @@ -68,9 +62,9 @@ BT::NodeStatus BT::FallbackNodeWithMemory::Tick() current_child_node->SetStatus(child_i_status_); } - if (child_i_status_ == BT::SUCCESS ||child_i_status_ == BT::FAILURE ) + if (child_i_status_ == BT::SUCCESS || child_i_status_ == BT::FAILURE) { - // the child goes in idle if it has returned success or failure. + // the child goes in idle if it has returned success or failure. current_child_node->SetStatus(BT::IDLE); } @@ -78,8 +72,8 @@ BT::NodeStatus BT::FallbackNodeWithMemory::Tick() { // If the child status is not success, return the status DEBUG_STDOUT("the status of: " << Name() << " becomes " << child_i_status_); - if (child_i_status_ == BT::SUCCESS && (reset_policy_ == BT::ON_SUCCESS - || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) + if (child_i_status_ == BT::SUCCESS && + (reset_policy_ == BT::ON_SUCCESS || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) { current_child_idx_ = 0; } @@ -107,11 +101,8 @@ BT::NodeStatus BT::FallbackNodeWithMemory::Tick() return BT::EXIT; } - void BT::FallbackNodeWithMemory::Halt() { current_child_idx_ = 0; BT::ControlNode::Halt(); } - - diff --git a/src/leaf_node.cpp b/src/leaf_node.cpp index bee007d3c..478026f5e 100644 --- a/src/leaf_node.cpp +++ b/src/leaf_node.cpp @@ -11,8 +11,8 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/leaf_node.h" -BT::LeafNode::LeafNode(std::string name) : TreeNode(name) {} - +BT::LeafNode::LeafNode(std::string name) : TreeNode(name) +{ +} diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index ae9124a78..e8942d2e7 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -11,12 +11,10 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/parallel_node.h" -BT::ParallelNode::ParallelNode(std::string name, int threshold_M) : - ControlNode::ControlNode(name), - threshold_M_( threshold_M ) +BT::ParallelNode::ParallelNode(std::string name, int threshold_M) + : ControlNode::ControlNode(name), threshold_M_(threshold_M) { } @@ -53,36 +51,36 @@ BT::NodeStatus BT::ParallelNode::Tick() } switch (child_i_status_) { - case BT::SUCCESS: - children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. - if (++success_childred_num_ == threshold_M_) - { - success_childred_num_ = 0; - failure_childred_num_ = 0; - HaltChildren(0); // halts all running children. The execution is done. - SetStatus(child_i_status_); - return child_i_status_; - } - break; - case BT::FAILURE: - children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. - if (++failure_childred_num_ > N_of_children - threshold_M_) - { - DEBUG_STDOUT("*******PARALLEL" << Name() - << " FAILED****** failure_childred_num_:" << failure_childred_num_); - - success_childred_num_ = 0; - failure_childred_num_ = 0; - HaltChildren(0); // halts all running children. The execution is hopeless. + case BT::SUCCESS: + children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. + if (++success_childred_num_ == threshold_M_) + { + success_childred_num_ = 0; + failure_childred_num_ = 0; + HaltChildren(0); // halts all running children. The execution is done. + SetStatus(child_i_status_); + return child_i_status_; + } + break; + case BT::FAILURE: + children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. + if (++failure_childred_num_ > N_of_children - threshold_M_) + { + DEBUG_STDOUT("*******PARALLEL" << Name() + << " FAILED****** failure_childred_num_:" << failure_childred_num_); + + success_childred_num_ = 0; + failure_childred_num_ = 0; + HaltChildren(0); // halts all running children. The execution is hopeless. + SetStatus(child_i_status_); + return child_i_status_; + } + break; + case BT::RUNNING: SetStatus(child_i_status_); - return child_i_status_; - } - break; - case BT::RUNNING: - SetStatus(child_i_status_); - break; - default: - break; + break; + default: + break; } } return BT::RUNNING; @@ -95,7 +93,6 @@ void BT::ParallelNode::Halt() BT::ControlNode::Halt(); } - unsigned int BT::ParallelNode::get_threshold_M() { return threshold_M_; @@ -105,6 +102,3 @@ void BT::ParallelNode::set_threshold_M(unsigned int threshold_M) { threshold_M_ = threshold_M; } - - - diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index f512c04e0..9f3647cad 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -11,11 +11,11 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/sequence_node.h" -BT::SequenceNode::SequenceNode(std::string name) : ControlNode::ControlNode(name) {} - +BT::SequenceNode::SequenceNode(std::string name) : ControlNode::ControlNode(name) +{ +} BT::NodeStatus BT::SequenceNode::Tick() { @@ -59,11 +59,11 @@ BT::NodeStatus BT::SequenceNode::Tick() // If the child status is not success, halt the next children and return the status to your parent. if (child_i_status_ == BT::FAILURE) { - child_node->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. + child_node->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. } - DEBUG_STDOUT(Name() << " is HALTING children from " << (i+1)); - HaltChildren(i+1); + DEBUG_STDOUT(Name() << " is HALTING children from " << (i + 1)); + HaltChildren(i + 1); SetStatus(child_i_status_); return child_i_status_; } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 646b9e366..486dcba83 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -11,21 +11,16 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - - #include "behavior_tree_core/sequence_node_with_memory.h" -BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolity reset_policy) : - ControlNode::ControlNode(name), - current_child_idx_(0), - reset_policy_(reset_policy) +BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolity reset_policy) + : ControlNode::ControlNode(name), current_child_idx_(0), reset_policy_(reset_policy) { } - BT::NodeStatus BT::SequenceNodeWithMemory::Tick() { - DEBUG_STDOUT(Name() << " ticked, memory counter: "<< current_child_idx_); + DEBUG_STDOUT(Name() << " ticked, memory counter: " << current_child_idx_); // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children_ = children_nodes_.size(); @@ -46,8 +41,7 @@ BT::NodeStatus BT::SequenceNodeWithMemory::Tick() // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. child_i_status_ = current_child_node->Status(); - DEBUG_STDOUT(Name() << " It is an action " << child_node->Name() - << " with status: " << child_i_status_); + DEBUG_STDOUT(Name() << " It is an action " << child_node->Name() << " with status: " << child_i_status_); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { @@ -64,12 +58,11 @@ BT::NodeStatus BT::SequenceNodeWithMemory::Tick() // Send the tick and wait for the response; child_i_status_ = current_child_node->Tick(); current_child_node->SetStatus(child_i_status_); - } - if (child_i_status_ == BT::SUCCESS || child_i_status_ == BT::FAILURE ) + if (child_i_status_ == BT::SUCCESS || child_i_status_ == BT::FAILURE) { - // the child goes in idle if it has returned success or failure. + // the child goes in idle if it has returned success or failure. current_child_node->SetStatus(BT::IDLE); } @@ -77,8 +70,8 @@ BT::NodeStatus BT::SequenceNodeWithMemory::Tick() { // If the child status is not success, return the status DEBUG_STDOUT("the status of: " << Name() << " becomes " << child_i_status_); - if (child_i_status_ == BT::FAILURE && (reset_policy_ == BT::ON_FAILURE - || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) + if (child_i_status_ == BT::FAILURE && + (reset_policy_ == BT::ON_FAILURE || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) { current_child_idx_ = 0; } @@ -106,7 +99,6 @@ BT::NodeStatus BT::SequenceNodeWithMemory::Tick() return BT::EXIT; } - void BT::SequenceNodeWithMemory::Halt() { current_child_idx_ = 0; diff --git a/src/tick_engine.cpp b/src/tick_engine.cpp index c07a934c1..6df4cbd11 100644 --- a/src/tick_engine.cpp +++ b/src/tick_engine.cpp @@ -11,7 +11,6 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include "behavior_tree_core/tick_engine.h" TickEngine::TickEngine(int initial_value) @@ -19,7 +18,9 @@ TickEngine::TickEngine(int initial_value) value_ = initial_value; } -TickEngine::~TickEngine() {} +TickEngine::~TickEngine() +{ +} void TickEngine::Wait() { diff --git a/src/tree.cpp b/src/tree.cpp index dd7ac1d40..7f134ff31 100644 --- a/src/tree.cpp +++ b/src/tree.cpp @@ -10,11 +10,9 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ - #include - -int main(int argc, char **argv) +int main(int argc, char** argv) { ros::init(argc, argv, "BehaviorTree"); try @@ -23,24 +21,21 @@ int main(int argc, char **argv) BT::ActionTestNode* action1 = new BT::ActionTestNode("Action 1"); // BT::ConditionTestNode* condition1 = new BT::ConditionTestNode("Condition 1"); // commented-out as unused - BT:: SequenceNode* sequence1 = new BT::SequenceNode("seq1"); - + BT::SequenceNode* sequence1 = new BT::SequenceNode("seq1"); BT::ActionTestNode* action2 = new BT::ActionTestNode("Action 2"); BT::ConditionTestNode* condition2 = new BT::ConditionTestNode("Condition 2"); - BT:: SequenceNode* sequence2 = new BT::SequenceNode("seq1"); + BT::SequenceNode* sequence2 = new BT::SequenceNode("seq1"); BT::ActionTestNode* action3 = new BT::ActionTestNode("Action 3"); BT::ConditionTestNode* condition3 = new BT::ConditionTestNode("Condition 3"); - BT:: SequenceNode* sequence3 = new BT::SequenceNode("seq1"); - + BT::SequenceNode* sequence3 = new BT::SequenceNode("seq1"); // Commented-out as unused variables // BT::ActionTestNode* action4 = new BT::ActionTestNode("Action 4"); // BT::ConditionTestNode* condition4 = new BT::ConditionTestNode("Condition 4"); // BT:: SequenceNode* sequence4 = new BT::SequenceNode("seq1"); - sequence1->AddChild(condition2); sequence1->AddChild(action1); sequence1->AddChild(sequence2); @@ -53,7 +48,7 @@ int main(int argc, char **argv) sequence3->AddChild(condition3); sequence3->AddChild(action3); - Execute(sequence1, TickPeriod_milliseconds); // from BehaviorTree.cpp + Execute(sequence1, TickPeriod_milliseconds); // from BehaviorTree.cpp } catch (BT::BehaviorTreeException& Exception) { @@ -62,5 +57,3 @@ int main(int argc, char **argv) return 0; } - - diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 2e95ef940..25a1947dd 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -13,21 +13,19 @@ #include "behavior_tree_core/tree_node.h" -BT::TreeNode::TreeNode(std::string name) : - name_(name), - status_(BT::IDLE), - is_state_updated_(false), - tick_engine(0) +BT::TreeNode::TreeNode(std::string name) : name_(name), status_(BT::IDLE), is_state_updated_(false), tick_engine(0) { } -BT::TreeNode::~TreeNode() {} +BT::TreeNode::~TreeNode() +{ +} void BT::TreeNode::SetStatus(NodeStatus new_status) { { std::unique_lock UniqueLock(state_mutex_); - is_state_updated_ = (status_!= new_status); + is_state_updated_ = (status_ != new_status); status_ = new_status; } state_condition_variable_.notify_all(); @@ -39,20 +37,17 @@ BT::NodeStatus BT::TreeNode::Status() const return status_; } -void BT::TreeNode::SetName(const std::string &new_name) +void BT::TreeNode::SetName(const std::string& new_name) { name_ = new_name; } BT::NodeStatus BT::TreeNode::waitValidStatus() { - std::unique_lock lk( state_mutex_ ); + std::unique_lock lk(state_mutex_); - state_condition_variable_.wait(lk, [&](){ - return (status_ == BT::RUNNING || - status_ == BT::SUCCESS || - status_ != BT::FAILURE); - }); + state_condition_variable_.wait( + lk, [&]() { return (status_ == BT::RUNNING || status_ == BT::SUCCESS || status_ != BT::FAILURE); }); return status_; } diff --git a/templates/action_node_template.cpp b/templates/action_node_template.cpp index 4ad0320d9..a6e7b0433 100644 --- a/templates/action_node_template.cpp +++ b/templates/action_node_template.cpp @@ -6,13 +6,14 @@ BT::CLASSNAME::CONSTRUCTOR(std::string name) : ActionNode::ActionNode(name) thread_ = std::thread(&ActionTestNode::WaitForTick, this); } -BT::CLASSNAME::~CONSTRUCTOR() {} +BT::CLASSNAME::~CONSTRUCTOR() +{ +} void BT::CLASSNAME::WaitForTick() { - while(true) + while (true) { - // Waiting for the first tick to come DEBUG_STDOUT(Name() << " WAIT FOR TICK"); @@ -23,12 +24,11 @@ void BT::CLASSNAME::WaitForTick() SetStatus(BT::RUNNING); // Perform action... - while(Status() != BT::HALTED) + while (Status() != BT::HALTED) { - /*HERE THE CODE TO EXECUTE FOR THE ACTION. + /*HERE THE CODE TO EXECUTE FOR THE ACTION. wHEN THE ACTION HAS FINISHED CORRECLTY, CALL set_status(BT::SUCCESS) - IF THE ACTION FAILS, CALL set_status(BT::FAILURE)*/ - + IF THE ACTION FAILS, CALL set_status(BT::FAILURE)*/ } } } @@ -39,5 +39,3 @@ void BT::CLASSNAME::Halt() SetStatus(BT::HALTED); DEBUG_STDOUT("HALTED state set!"); } - - diff --git a/templates/condition_node_template.cpp b/templates/condition_node_template.cpp index 1f1bac46f..7c8b4eaa8 100644 --- a/templates/condition_node_template.cpp +++ b/templates/condition_node_template.cpp @@ -1,26 +1,25 @@ #include - BT::CLASSNAME::CONSTRUCTOR(std::string name) : ConditionNode::ConditionNode(name) { - } -BT::CLASSNAME::~CONSTRUCTOR() {} +BT::CLASSNAME::~CONSTRUCTOR() +{ +} BT::ReturnStatus BT::CLASSNAME::Tick() { - // Condition checking and state update + // Condition checking and state update - if (/*CONDITION TO CHECK*/) - { - SetStatus(BT::SUCCESS); - return BT::SUCCESS; - } - else - { - SetStatus(BT::FAILURE); - return BT::FAILURE; - } + if (/*CONDITION TO CHECK*/) + { + SetStatus(BT::SUCCESS); + return BT::SUCCESS; + } + else + { + SetStatus(BT::FAILURE); + return BT::FAILURE; + } } - From bae1a64a21b98b303ff0ba6478cb13c0baf0dd12 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 20 Apr 2018 10:59:27 +0200 Subject: [PATCH 020/125] typo fixed --- include/behavior_tree_core/fallback_node_with_memory.h | 4 ++-- include/behavior_tree_core/sequence_node_with_memory.h | 4 ++-- include/behavior_tree_core/tree_node.h | 2 +- src/fallback_node_with_memory.cpp | 2 +- src/sequence_node_with_memory.cpp | 2 +- 5 files changed, 7 insertions(+), 7 deletions(-) diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index c13e55a1d..39f1dd82a 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -21,7 +21,7 @@ namespace BT class FallbackNodeWithMemory : public ControlNode { public: - FallbackNodeWithMemory(std::string name, ResetPolity reset_policy = BT::ON_SUCCESS_OR_FAILURE); + FallbackNodeWithMemory(std::string name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); ~FallbackNodeWithMemory() = default; @@ -32,7 +32,7 @@ class FallbackNodeWithMemory : public ControlNode private: unsigned int current_child_idx_; - ResetPolity reset_policy_; + ResetPolicy reset_policy_; }; } diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index 7ceb80705..4ab256cfb 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -21,7 +21,7 @@ namespace BT class SequenceNodeWithMemory : public ControlNode { public: - SequenceNodeWithMemory(std::string name, ResetPolity reset_policy = BT::ON_SUCCESS_OR_FAILURE); + SequenceNodeWithMemory(std::string name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); ~SequenceNodeWithMemory() = default; @@ -31,7 +31,7 @@ class SequenceNodeWithMemory : public ControlNode private: unsigned int current_child_idx_; - ResetPolity reset_policy_; + ResetPolicy reset_policy_; }; } diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 84e2835fd..8f2f94ea0 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -79,7 +79,7 @@ enum FailurePolicy FAIL_ON_ONE, FAIL_ON_ALL }; -enum ResetPolity +enum ResetPolicy { ON_SUCCESS_OR_FAILURE, ON_SUCCESS, diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 44f8099e1..172a64bd6 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -13,7 +13,7 @@ #include "behavior_tree_core/fallback_node_with_memory.h" -BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, ResetPolity reset_policy) +BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, ResetPolicy reset_policy) : ControlNode::ControlNode(name), current_child_idx_(0), reset_policy_(reset_policy) { } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 486dcba83..d57c7a439 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -13,7 +13,7 @@ #include "behavior_tree_core/sequence_node_with_memory.h" -BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolity reset_policy) +BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolicy reset_policy) : ControlNode::ControlNode(name), current_child_idx_(0), reset_policy_(reset_policy) { } From cc9a76bd9b74a5be6a47f39644cc0a3de5624ce3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 20 Apr 2018 11:20:50 +0200 Subject: [PATCH 021/125] bug fix --- src/tree_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 25a1947dd..e1f8e6b67 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -47,7 +47,7 @@ BT::NodeStatus BT::TreeNode::waitValidStatus() std::unique_lock lk(state_mutex_); state_condition_variable_.wait( - lk, [&]() { return (status_ == BT::RUNNING || status_ == BT::SUCCESS || status_ != BT::FAILURE); }); + lk, [&]() { return (status_ == BT::RUNNING || status_ == BT::SUCCESS || status_ == BT::FAILURE); }); return status_; } From 955baf6bbeb7719152c74e39a0386db19e732988 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 20 Apr 2018 11:21:10 +0200 Subject: [PATCH 022/125] don't force release, makes difficult to compile in debug mode --- CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 145ca53a6..50bfd1df8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,8 +1,6 @@ cmake_minimum_required(VERSION 2.8) project(behavior_tree_core) -set(CMAKE_BUILD_TYPE Release) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11 -pthread -Werror=return-type") ############################################################# From 602d14d85db4a60281e4d93a978019ec0eb2e294 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 20 Apr 2018 11:21:29 +0200 Subject: [PATCH 023/125] remove warning --- src/fallback_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 6ac75948f..df166b6a5 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -25,7 +25,7 @@ BT::NodeStatus BT::FallbackNode::Tick() // Routing the ticks according to the fallback node's logic: - for (int i = 0; i < N_of_children; i++) + for (unsigned i = 0; i < N_of_children; i++) { auto& child_node = children_nodes_[i]; From 8db859e9bd6805cef004d4c5eaec3950e2e48ca1 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 20 Apr 2018 11:21:56 +0200 Subject: [PATCH 024/125] 100 ms is a sufficient large amount of time to test asynch actions... --- gtest/gtest_tree.cpp | 16 ++++++++-------- gtest/src/action_test_node.cpp | 2 +- src/example.cpp | 6 +++--- 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 9841c77e3..119144987 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -372,7 +372,7 @@ TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) state = root->Tick(); - std::this_thread::sleep_for(std::chrono::seconds(5)); + std::this_thread::sleep_for(std::chrono::milliseconds(500)); state = root->Tick(); state = root->Tick(); @@ -501,7 +501,7 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node BT::NodeStatus state = root->Tick(); - std::this_thread::sleep_for(std::chrono::seconds(1)); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); ASSERT_EQ(BT::RUNNING, action->Status()); ASSERT_EQ(BT::RUNNING, state); @@ -569,7 +569,7 @@ TEST_F(ComplexSequenceWithMemoryTest, Action1Done) condition_2->set_boolean_value(false); root->Tick(); - std::this_thread::sleep_for(std::chrono::seconds(10)); + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); root->Tick(); ASSERT_EQ(BT::RUNNING, action_2->Status()); @@ -583,7 +583,7 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) // Ticking the root node condition->set_boolean_value(false); BT::NodeStatus state = root->Tick(); - std::this_thread::sleep_for(std::chrono::seconds(1)); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); ASSERT_EQ(BT::RUNNING, action->Status()); ASSERT_EQ(BT::RUNNING, state); @@ -686,7 +686,7 @@ TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) BT::NodeStatus state = root->Tick(); state = root->Tick(); - std::this_thread::sleep_for(std::chrono::seconds(5)); + std::this_thread::sleep_for(std::chrono::milliseconds(500)); state = root->Tick(); ASSERT_EQ(BT::IDLE, action_1->Status()); @@ -714,7 +714,7 @@ TEST_F(SimpleParallelTest, Threshold_3) root->set_threshold_M(3); action_2->set_time(200); root->Tick(); - std::this_thread::sleep_for(std::chrono::seconds(5)); + std::this_thread::sleep_for(std::chrono::milliseconds(500)); BT::NodeStatus state = root->Tick(); ASSERT_EQ(BT::IDLE, condition_1->Status()); @@ -781,7 +781,7 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) condition_3->set_boolean_value(false); BT::NodeStatus state = root->Tick(); - std::this_thread::sleep_for(std::chrono::seconds(5)); + std::this_thread::sleep_for(std::chrono::milliseconds(500)); ASSERT_EQ(BT::IDLE, condition_1->Status()); ASSERT_EQ(BT::IDLE, condition_2->Status()); @@ -799,7 +799,7 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) ASSERT_EQ(BT::RUNNING, state); state = root->Tick(); - std::this_thread::sleep_for(std::chrono::seconds(15)); + std::this_thread::sleep_for(std::chrono::milliseconds(1500)); state = root->Tick(); ASSERT_EQ(BT::IDLE, parallel_2->Status()); diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 2085085b1..7361f6b3c 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -26,7 +26,7 @@ BT::NodeStatus BT::ActionTestNode::Tick() while (Status() != BT::HALTED && i++ < time_) { DEBUG_STDOUT(" Action " << Name() << "running! Thread id:" << std::this_thread::get_id()); - std::this_thread::sleep_for(std::chrono::seconds(1)); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } if (Status() != BT::HALTED) { diff --git a/src/example.cpp b/src/example.cpp index e2e47695d..e0c6c89d6 100644 --- a/src/example.cpp +++ b/src/example.cpp @@ -36,21 +36,21 @@ MyAction::MyAction(std::string name) : ActionNode::ActionNode(name) BT::ReturnStatus MyAction::Tick() { std::cout << "The Action is doing some operations" << std::endl; - std::this_thread::sleep_for(std::chrono::seconds(5)); + std::this_thread::sleep_for(std::chrono::milliseconds(500)); if (is_halted()) { return BT::HALTED; } std::cout << "The Action is doing some others operations" << std::endl; - std::this_thread::sleep_for(std::chrono::seconds(5)); + std::this_thread::sleep_for(std::chrono::milliseconds(500)); if (is_halted()) { return BT::HALTED; } std::cout << "The Action is doing more operations" << std::endl; - std::this_thread::sleep_for(std::chrono::seconds(5)); + std::this_thread::sleep_for(std::chrono::milliseconds(500)); if (is_halted()) { return BT::HALTED; From feb440a9965bc3be8d1a5b1b240704a7f938c7ec Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 20 Apr 2018 11:54:25 +0200 Subject: [PATCH 025/125] camelCase! --- gtest/gtest_tree.cpp | 442 +++++++++--------- gtest/include/action_test_node.h | 6 +- gtest/include/condition_test_node.h | 4 +- gtest/src/action_test_node.cpp | 16 +- gtest/src/condition_test_node.cpp | 6 +- include/behavior_tree_core/action_node.h | 6 +- include/behavior_tree_core/condition_node.h | 4 +- include/behavior_tree_core/control_node.h | 14 +- .../decorator_negation_node.h | 5 +- include/behavior_tree_core/decorator_node.h | 12 +- .../behavior_tree_core/decorator_retry_node.h | 2 +- include/behavior_tree_core/fallback_node.h | 2 +- .../fallback_node_with_memory.h | 4 +- include/behavior_tree_core/parallel_node.h | 8 +- include/behavior_tree_core/sequence_node.h | 2 +- .../sequence_node_with_memory.h | 4 +- include/behavior_tree_core/tree_node.h | 20 +- src/action_node.cpp | 16 +- src/condition_node.cpp | 2 +- src/control_node.cpp | 26 +- src/decorator_node.cpp | 24 +- src/fallback_node.cpp | 26 +- src/fallback_node_with_memory.cpp | 30 +- src/parallel_node.cpp | 38 +- src/sequence_node.cpp | 26 +- src/sequence_node_with_memory.cpp | 31 +- src/tree_node.cpp | 21 +- templates/action_node_template.cpp | 4 +- 28 files changed, 402 insertions(+), 399 deletions(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 119144987..de8ba6064 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -27,8 +27,8 @@ struct SimpleSequenceTest : testing::Test root = new BT::SequenceNode("seq1"); - root->AddChild(condition); - root->AddChild(action); + root->addChild(condition); + root->addChild(action); } }; @@ -49,12 +49,12 @@ struct ComplexSequenceTest : testing::Test condition_2 = new BT::ConditionTestNode("condition 2"); seq_conditions = new BT::SequenceNode("sequence_conditions"); - seq_conditions->AddChild(condition_1); - seq_conditions->AddChild(condition_2); + seq_conditions->addChild(condition_1); + seq_conditions->addChild(condition_2); root = new BT::SequenceNode("root"); - root->AddChild(seq_conditions); - root->AddChild(action_1); + root->addChild(seq_conditions); + root->addChild(action_1); } }; @@ -80,15 +80,15 @@ struct ComplexSequence2ActionsTest : testing::Test condition_1 = new BT::ConditionTestNode("condition 1"); condition_2 = new BT::ConditionTestNode("condition 2"); - seq_1->AddChild(condition_1); - seq_1->AddChild(action_1); + seq_1->addChild(condition_1); + seq_1->addChild(action_1); - seq_2->AddChild(condition_2); - seq_2->AddChild(action_2); + seq_2->addChild(condition_2); + seq_2->addChild(action_2); root = new BT::SequenceNode("root"); - root->AddChild(seq_1); - root->AddChild(seq_2); + root->addChild(seq_1); + root->addChild(seq_2); } }; @@ -104,8 +104,8 @@ struct SimpleFallbackTest : testing::Test root = new BT::FallbackNode("seq1"); - root->AddChild(condition); - root->AddChild(action); + root->addChild(condition); + root->addChild(action); } }; @@ -125,12 +125,12 @@ struct ComplexFallbackTest : testing::Test condition_2 = new BT::ConditionTestNode("condition 2"); sel_conditions = new BT::FallbackNode("fallback_conditions"); - sel_conditions->AddChild(condition_1); - sel_conditions->AddChild(condition_2); + sel_conditions->addChild(condition_1); + sel_conditions->addChild(condition_2); root = new BT::FallbackNode("root"); - root->AddChild(sel_conditions); - root->AddChild(action_1); + root->addChild(sel_conditions); + root->addChild(action_1); } }; @@ -150,12 +150,12 @@ struct BehaviorTreeTest : testing::Test condition_2 = new BT::ConditionTestNode("condition 2"); sel_conditions = new BT::FallbackNode("fallback_conditions"); - sel_conditions->AddChild(condition_1); - sel_conditions->AddChild(condition_2); + sel_conditions->addChild(condition_1); + sel_conditions->addChild(condition_2); root = new BT::SequenceNode("root"); - root->AddChild(sel_conditions); - root->AddChild(action_1); + root->addChild(sel_conditions); + root->addChild(action_1); } }; @@ -171,8 +171,8 @@ struct SimpleSequenceWithMemoryTest : testing::Test root = new BT::SequenceNodeWithMemory("seq1"); - root->AddChild(condition); - root->AddChild(action); + root->addChild(condition); + root->addChild(action); } }; @@ -200,15 +200,15 @@ struct ComplexSequenceWithMemoryTest : testing::Test seq_conditions = new BT::SequenceNodeWithMemory("sequence_conditions"); seq_actions = new BT::SequenceNodeWithMemory("sequence_actions"); - seq_actions->AddChild(action_1); - seq_actions->AddChild(action_2); + seq_actions->addChild(action_1); + seq_actions->addChild(action_2); - seq_conditions->AddChild(condition_1); - seq_conditions->AddChild(condition_2); + seq_conditions->addChild(condition_1); + seq_conditions->addChild(condition_2); root = new BT::SequenceNodeWithMemory("root"); - root->AddChild(seq_conditions); - root->AddChild(seq_actions); + root->addChild(seq_conditions); + root->addChild(seq_actions); } }; @@ -224,8 +224,8 @@ struct SimpleFallbackWithMemoryTest : testing::Test root = new BT::FallbackNodeWithMemory("seq1"); - root->AddChild(condition); - root->AddChild(action); + root->addChild(condition); + root->addChild(action); } }; @@ -252,15 +252,15 @@ struct ComplexFallbackWithMemoryTest : testing::Test fal_conditions = new BT::FallbackNodeWithMemory("fallback_conditions"); fal_actions = new BT::FallbackNodeWithMemory("fallback_actions"); - fal_actions->AddChild(action_1); - fal_actions->AddChild(action_2); + fal_actions->addChild(action_1); + fal_actions->addChild(action_2); - fal_conditions->AddChild(condition_1); - fal_conditions->AddChild(condition_2); + fal_conditions->addChild(condition_1); + fal_conditions->addChild(condition_2); root = new BT::FallbackNodeWithMemory("root"); - root->AddChild(fal_conditions); - root->AddChild(fal_actions); + root->addChild(fal_conditions); + root->addChild(fal_actions); } }; @@ -283,10 +283,10 @@ struct SimpleParallelTest : testing::Test root = new BT::ParallelNode("par", 4); - root->AddChild(condition_1); - root->AddChild(action_1); - root->AddChild(condition_2); - root->AddChild(action_2); + root->addChild(condition_1); + root->addChild(action_1); + root->addChild(condition_2); + root->addChild(action_2); } }; @@ -320,16 +320,16 @@ struct ComplexParallelTest : testing::Test parallel_1 = new BT::ParallelNode("par1", 3); parallel_2 = new BT::ParallelNode("par2", 1); - parallel_1->AddChild(condition_1); - parallel_1->AddChild(action_1); - parallel_1->AddChild(condition_2); - parallel_1->AddChild(action_2); + parallel_1->addChild(condition_1); + parallel_1->addChild(action_1); + parallel_1->addChild(condition_2); + parallel_1->addChild(action_2); - parallel_2->AddChild(condition_3); - parallel_2->AddChild(action_3); + parallel_2->addChild(condition_3); + parallel_2->addChild(action_3); - root->AddChild(parallel_1); - root->AddChild(parallel_2); + root->addChild(parallel_1); + root->addChild(parallel_2); } }; @@ -339,76 +339,76 @@ TEST_F(SimpleSequenceTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::RUNNING, action->Status()); + ASSERT_EQ(BT::RUNNING, action->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(SimpleSequenceTest, ConditionTurnToFalse) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition->set_boolean_value(false); - state = root->Tick(); + state = root->tick(); ASSERT_EQ(BT::FAILURE, state); - ASSERT_EQ(BT::HALTED, action->Status()); - root->Halt(); + ASSERT_EQ(BT::HALTED, action->status()); + root->halt(); } TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - state = root->Tick(); + state = root->tick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - state = root->Tick(); - state = root->Tick(); + state = root->tick(); + state = root->tick(); ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::RUNNING, seq_1->Status()); - ASSERT_EQ(BT::HALTED, seq_2->Status()); - ASSERT_EQ(BT::HALTED, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::RUNNING, seq_1->status()); + ASSERT_EQ(BT::HALTED, seq_2->status()); + ASSERT_EQ(BT::HALTED, action_2->status()); - root->Halt(); + root->halt(); } TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition_1->set_boolean_value(false); - state = root->Tick(); + state = root->tick(); ASSERT_EQ(BT::FAILURE, state); - ASSERT_EQ(BT::HALTED, action_1->Status()); - root->Halt(); + ASSERT_EQ(BT::HALTED, action_1->status()); + root->halt(); } TEST_F(ComplexSequenceTest, ComplexSequenceConditions2ToFalse) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition_2->set_boolean_value(false); - state = root->Tick(); + state = root->tick(); ASSERT_EQ(BT::FAILURE, state); - ASSERT_EQ(BT::HALTED, action_1->Status()); - root->Halt(); + ASSERT_EQ(BT::HALTED, action_1->status()); + root->halt(); } TEST_F(SimpleFallbackTest, ConditionTrue) @@ -416,25 +416,25 @@ TEST_F(SimpleFallbackTest, ConditionTrue) std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node condition->set_boolean_value(true); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::IDLE, action->Status()); + ASSERT_EQ(BT::IDLE, action->status()); ASSERT_EQ(BT::SUCCESS, state); - root->Halt(); + root->halt(); } TEST_F(SimpleFallbackTest, ConditionToFalse) { condition->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition->set_boolean_value(true); - state = root->Tick(); + state = root->tick(); ASSERT_EQ(BT::SUCCESS, state); - ASSERT_EQ(BT::HALTED, action->Status()); - root->Halt(); + ASSERT_EQ(BT::HALTED, action->status()); + root->halt(); } TEST_F(ComplexFallbackTest, Condition1ToTrue) @@ -442,16 +442,16 @@ TEST_F(ComplexFallbackTest, Condition1ToTrue) condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition_1->set_boolean_value(true); - state = root->Tick(); + state = root->tick(); ASSERT_EQ(BT::SUCCESS, state); - ASSERT_EQ(BT::HALTED, action_1->Status()); - root->Halt(); + ASSERT_EQ(BT::HALTED, action_1->status()); + root->halt(); } TEST_F(ComplexFallbackTest, Condition2ToTrue) @@ -459,15 +459,15 @@ TEST_F(ComplexFallbackTest, Condition2ToTrue) condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition_2->set_boolean_value(true); - state = root->Tick(); + state = root->tick(); ASSERT_EQ(BT::SUCCESS, state); - ASSERT_EQ(BT::HALTED, action_1->Status()); - root->Halt(); + ASSERT_EQ(BT::HALTED, action_1->status()); + root->halt(); } TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) @@ -475,12 +475,12 @@ TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) condition_1->set_boolean_value(false); condition_2->set_boolean_value(true); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); - root->Halt(); + root->halt(); } TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) @@ -488,93 +488,93 @@ TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) condition_2->set_boolean_value(false); condition_1->set_boolean_value(true); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action_1->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); - root->Halt(); + root->halt(); } TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - ASSERT_EQ(BT::RUNNING, action->Status()); + ASSERT_EQ(BT::RUNNING, action->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition->set_boolean_value(false); - state = root->Tick(); + state = root->tick(); ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action->Status()); + ASSERT_EQ(BT::RUNNING, action->status()); - root->Halt(); + root->halt(); } TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::IDLE, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::IDLE, action_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition_1->set_boolean_value(false); - state = root->Tick(); + state = root->tick(); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::IDLE, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::IDLE, action_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(ComplexSequenceWithMemoryTest, Conditions2ToFalse) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition_2->set_boolean_value(false); - state = root->Tick(); + state = root->tick(); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::IDLE, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::IDLE, action_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(ComplexSequenceWithMemoryTest, Action1Done) { - root->Tick(); + root->tick(); condition_2->set_boolean_value(false); - root->Tick(); + root->tick(); std::this_thread::sleep_for(std::chrono::milliseconds(1000)); - root->Tick(); + root->tick(); - ASSERT_EQ(BT::RUNNING, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_2->status()); - root->Halt(); + root->halt(); } TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) @@ -582,80 +582,80 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node condition->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - ASSERT_EQ(BT::RUNNING, action->Status()); + ASSERT_EQ(BT::RUNNING, action->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) { condition->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition->set_boolean_value(true); - state = root->Tick(); + state = root->tick(); ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action->Status()); + ASSERT_EQ(BT::RUNNING, action->status()); - root->Halt(); + root->halt(); } TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::IDLE, action_1->Status()); - ASSERT_EQ(BT::IDLE, action_2->Status()); + ASSERT_EQ(BT::IDLE, action_1->status()); + ASSERT_EQ(BT::IDLE, action_2->status()); ASSERT_EQ(BT::SUCCESS, state); - root->Halt(); + root->halt(); } TEST_F(ComplexFallbackWithMemoryTest, Condition1False) { condition_1->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::IDLE, action_1->Status()); - ASSERT_EQ(BT::IDLE, action_2->Status()); + ASSERT_EQ(BT::IDLE, action_1->status()); + ASSERT_EQ(BT::IDLE, action_2->status()); ASSERT_EQ(BT::SUCCESS, state); - root->Halt(); + root->halt(); } TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) { condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::IDLE, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::IDLE, action_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) { condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition_1->set_boolean_value(true); - state = root->Tick(); + state = root->tick(); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::IDLE, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::IDLE, action_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) @@ -664,17 +664,17 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) condition_2->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); condition_2->set_boolean_value(true); - state = root->Tick(); + state = root->tick(); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::IDLE, action_2->Status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::IDLE, action_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) @@ -683,95 +683,95 @@ TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - state = root->Tick(); + state = root->tick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - state = root->Tick(); + state = root->tick(); - ASSERT_EQ(BT::IDLE, action_1->Status()); - ASSERT_EQ(BT::RUNNING, action_2->Status()); + ASSERT_EQ(BT::IDLE, action_1->status()); + ASSERT_EQ(BT::RUNNING, action_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(SimpleParallelTest, ConditionsTrue) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::IDLE, condition_1->Status()); - ASSERT_EQ(BT::IDLE, condition_2->Status()); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::RUNNING, action_2->Status()); + ASSERT_EQ(BT::IDLE, condition_1->status()); + ASSERT_EQ(BT::IDLE, condition_2->status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::RUNNING, action_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(SimpleParallelTest, Threshold_3) { - root->set_threshold_M(3); + root->setThresholdM(3); action_2->set_time(200); - root->Tick(); + root->tick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::IDLE, condition_1->Status()); - ASSERT_EQ(BT::IDLE, condition_2->Status()); - ASSERT_EQ(BT::IDLE, action_1->Status()); - ASSERT_EQ(BT::HALTED, action_2->Status()); + ASSERT_EQ(BT::IDLE, condition_1->status()); + ASSERT_EQ(BT::IDLE, condition_2->status()); + ASSERT_EQ(BT::IDLE, action_1->status()); + ASSERT_EQ(BT::HALTED, action_2->status()); ASSERT_EQ(BT::SUCCESS, state); - root->Halt(); + root->halt(); } TEST_F(SimpleParallelTest, Threshold_1) { - root->set_threshold_M(1); - BT::NodeStatus state = root->Tick(); + root->setThresholdM(1); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::IDLE, condition_1->Status()); - ASSERT_EQ(BT::IDLE, condition_2->Status()); - ASSERT_EQ(BT::IDLE, action_1->Status()); - ASSERT_EQ(BT::IDLE, action_2->Status()); + ASSERT_EQ(BT::IDLE, condition_1->status()); + ASSERT_EQ(BT::IDLE, condition_2->status()); + ASSERT_EQ(BT::IDLE, action_1->status()); + ASSERT_EQ(BT::IDLE, action_2->status()); ASSERT_EQ(BT::SUCCESS, state); - root->Halt(); + root->halt(); } TEST_F(ComplexParallelTest, ConditionsTrue) { - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); - ASSERT_EQ(BT::IDLE, condition_1->Status()); - ASSERT_EQ(BT::IDLE, condition_2->Status()); - ASSERT_EQ(BT::IDLE, condition_3->Status()); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::RUNNING, action_2->Status()); - ASSERT_EQ(BT::IDLE, action_3->Status()); - ASSERT_EQ(BT::RUNNING, parallel_1->Status()); - ASSERT_EQ(BT::IDLE, parallel_2->Status()); + ASSERT_EQ(BT::IDLE, condition_1->status()); + ASSERT_EQ(BT::IDLE, condition_2->status()); + ASSERT_EQ(BT::IDLE, condition_3->status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::RUNNING, action_2->status()); + ASSERT_EQ(BT::IDLE, action_3->status()); + ASSERT_EQ(BT::RUNNING, parallel_1->status()); + ASSERT_EQ(BT::IDLE, parallel_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(ComplexParallelTest, Condition3False) { condition_3->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); - - ASSERT_EQ(BT::IDLE, condition_1->Status()); - ASSERT_EQ(BT::IDLE, condition_2->Status()); - ASSERT_EQ(BT::IDLE, condition_3->Status()); - ASSERT_EQ(BT::RUNNING, action_1->Status()); - ASSERT_EQ(BT::RUNNING, action_2->Status()); - ASSERT_EQ(BT::RUNNING, action_3->Status()); - ASSERT_EQ(BT::RUNNING, parallel_1->Status()); - ASSERT_EQ(BT::RUNNING, parallel_2->Status()); + BT::NodeStatus state = root->tick(); + + ASSERT_EQ(BT::IDLE, condition_1->status()); + ASSERT_EQ(BT::IDLE, condition_2->status()); + ASSERT_EQ(BT::IDLE, condition_3->status()); + ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(BT::RUNNING, action_2->status()); + ASSERT_EQ(BT::RUNNING, action_3->status()); + ASSERT_EQ(BT::RUNNING, parallel_1->status()); + ASSERT_EQ(BT::RUNNING, parallel_2->status()); ASSERT_EQ(BT::RUNNING, state); - root->Halt(); + root->halt(); } TEST_F(ComplexParallelTest, Condition3FalseAction1Done) @@ -780,36 +780,36 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) action_3->set_time(10); condition_3->set_boolean_value(false); - BT::NodeStatus state = root->Tick(); + BT::NodeStatus state = root->tick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - ASSERT_EQ(BT::IDLE, condition_1->Status()); - ASSERT_EQ(BT::IDLE, condition_2->Status()); - ASSERT_EQ(BT::IDLE, condition_3->Status()); - ASSERT_EQ(BT::SUCCESS, action_1->Status()); // success not read yet by the node parallel_1 - ASSERT_EQ(BT::RUNNING, parallel_1->Status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded + ASSERT_EQ(BT::IDLE, condition_1->status()); + ASSERT_EQ(BT::IDLE, condition_2->status()); + ASSERT_EQ(BT::IDLE, condition_3->status()); + ASSERT_EQ(BT::SUCCESS, action_1->status()); // success not read yet by the node parallel_1 + ASSERT_EQ(BT::RUNNING, parallel_1->status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded - state = root->Tick(); + state = root->tick(); - ASSERT_EQ(BT::IDLE, action_1->Status()); - ASSERT_EQ(BT::IDLE, parallel_1->Status()); - ASSERT_EQ(BT::HALTED, action_2->Status()); - ASSERT_EQ(BT::RUNNING, action_3->Status()); - ASSERT_EQ(BT::RUNNING, parallel_2->Status()); + ASSERT_EQ(BT::IDLE, action_1->status()); + ASSERT_EQ(BT::IDLE, parallel_1->status()); + ASSERT_EQ(BT::HALTED, action_2->status()); + ASSERT_EQ(BT::RUNNING, action_3->status()); + ASSERT_EQ(BT::RUNNING, parallel_2->status()); ASSERT_EQ(BT::RUNNING, state); - state = root->Tick(); + state = root->tick(); std::this_thread::sleep_for(std::chrono::milliseconds(1500)); - state = root->Tick(); + state = root->tick(); - ASSERT_EQ(BT::IDLE, parallel_2->Status()); - ASSERT_EQ(BT::IDLE, action_1->Status()); - ASSERT_EQ(BT::IDLE, parallel_1->Status()); - ASSERT_EQ(BT::IDLE, action_3->Status()); - ASSERT_EQ(BT::IDLE, parallel_2->Status()); + ASSERT_EQ(BT::IDLE, parallel_2->status()); + ASSERT_EQ(BT::IDLE, action_1->status()); + ASSERT_EQ(BT::IDLE, parallel_1->status()); + ASSERT_EQ(BT::IDLE, action_3->status()); + ASSERT_EQ(BT::IDLE, parallel_2->status()); ASSERT_EQ(BT::SUCCESS, state); - root->Halt(); + root->halt(); } int main(int argc, char** argv) diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index d525d80a3..77f41d739 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -9,15 +9,15 @@ class ActionTestNode : public ActionNode { public: // Constructor - ActionTestNode(std::string Name); + ActionTestNode(std::string name); virtual ~ActionTestNode() = default; // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; + virtual BT::NodeStatus tick() override; void set_time(int time); // The method used to interrupt the execution of the node - virtual void Halt() override; + virtual void halt() override; void set_boolean_value(bool boolean_value); private: diff --git a/gtest/include/condition_test_node.h b/gtest/include/condition_test_node.h index 70febb2b7..07161e991 100644 --- a/gtest/include/condition_test_node.h +++ b/gtest/include/condition_test_node.h @@ -9,12 +9,12 @@ class ConditionTestNode : public ConditionNode { public: // Constructor - ConditionTestNode(std::string Name); + ConditionTestNode(std::string name); ~ConditionTestNode(); void set_boolean_value(bool boolean_value); // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; + virtual BT::NodeStatus tick() override; private: bool boolean_value_; diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 7361f6b3c..25bc2f3b4 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -20,24 +20,24 @@ BT::ActionTestNode::ActionTestNode(std::string name) : ActionNode::ActionNode(na time_ = 3; } -BT::NodeStatus BT::ActionTestNode::Tick() +BT::NodeStatus BT::ActionTestNode::tick() { int i = 0; - while (Status() != BT::HALTED && i++ < time_) + while (status() != BT::HALTED && i++ < time_) { - DEBUG_STDOUT(" Action " << Name() << "running! Thread id:" << std::this_thread::get_id()); + DEBUG_STDOUT(" Action " << name() << "running! Thread id:" << std::this_thread::get_id()); std::this_thread::sleep_for(std::chrono::milliseconds(100)); } - if (Status() != BT::HALTED) + if (status() != BT::HALTED) { if (boolean_value_) { - DEBUG_STDOUT(" Action " << Name() << " Done!"); + DEBUG_STDOUT(" Action " << name() << " Done!"); return BT::SUCCESS; } else { - DEBUG_STDOUT(" Action " << Name() << " FAILED!"); + DEBUG_STDOUT(" Action " << name() << " FAILED!"); return BT::FAILURE; } } @@ -47,9 +47,9 @@ BT::NodeStatus BT::ActionTestNode::Tick() } } -void BT::ActionTestNode::Halt() +void BT::ActionTestNode::halt() { - SetStatus(BT::HALTED); + setStatus(BT::HALTED); DEBUG_STDOUT("HALTED state set!"); } diff --git a/gtest/src/condition_test_node.cpp b/gtest/src/condition_test_node.cpp index 59d4281ba..2c295c6e3 100644 --- a/gtest/src/condition_test_node.cpp +++ b/gtest/src/condition_test_node.cpp @@ -22,18 +22,18 @@ BT::ConditionTestNode::~ConditionTestNode() { } -BT::NodeStatus BT::ConditionTestNode::Tick() +BT::NodeStatus BT::ConditionTestNode::tick() { // Condition checking and state update if (boolean_value_) { - SetStatus(BT::SUCCESS); + setStatus(BT::SUCCESS); return BT::SUCCESS; } else { - SetStatus(BT::FAILURE); + setStatus(BT::FAILURE); return BT::FAILURE; } } diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index fc2dd17bf..14bdbc313 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -26,13 +26,13 @@ class ActionNode : public LeafNode ~ActionNode() = default; // The method that is going to be executed by the thread - void WaitForTick(); + void waitForTick(); // Methods used to access the node state without the // conditional waiting (only mutual access) - bool WriteState(NodeStatus new_state); + bool writeState(NodeStatus new_state); - virtual NodeType Type() const override final + virtual NodeType type() const override final { return ACTION_NODE; } diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index 2d4a3fd38..0058085a1 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -26,13 +26,13 @@ class ConditionNode : public LeafNode ~ConditionNode() = default; // The method used to interrupt the execution of the node - virtual void Halt() override; + virtual void halt() override; // Methods used to access the node state without the // conditional waiting (only mutual access) bool WriteState(NodeStatus new_state); - virtual NodeType Type() const override final + virtual NodeType type() const override final { return CONDITION_NODE; } diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index df6e57f72..4a5bf7c98 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -34,23 +34,23 @@ class ControlNode : public TreeNode ~ControlNode() = default; // The method used to fill the child vector - void AddChild(TreeNode* child); + void addChild(TreeNode* child); // The method used to know the number of children - unsigned int ChildrenCount() const; + unsigned int childrenCount() const; - const std::vector& Children() const; + const std::vector& children() const; // The method used to interrupt the execution of the node - virtual void Halt() override; + virtual void halt() override; - void HaltChildren(int i); + void haltChildren(int i); // Methods used to access the node state without the // conditional waiting (only mutual access) - bool WriteState(NodeStatus new_state); + bool writeState(NodeStatus new_state); - virtual NodeType Type() const override final + virtual NodeType type() const override final { return CONTROL_NODE; } diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h index 38b682351..9da53cb3a 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -26,8 +26,9 @@ class DecoratorNegationNode : public DecoratorNode ~DecoratorNegationNode() = default; // The method that is going to be executed by the thread - void Exec(); - void AddChild(TreeNode* child); + void exec(); + + void setChild(TreeNode* child); }; } diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index 716d66a12..be651f791 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -16,20 +16,20 @@ class DecoratorNode : public TreeNode ~DecoratorNode() = default; // The method used to fill the child vector - void AddChild(TreeNode* child); + void setChild(TreeNode* child); - const TreeNode* Child() const; + const TreeNode* child() const; // The method used to interrupt the execution of the node - virtual void Halt() override; + virtual void halt() override; - void HaltChild(); + void haltChild(); // Methods used to access the node state without the // conditional waiting (only mutual access) - bool WriteState(NodeStatus new_state); + bool writeState(NodeStatus new_state); - virtual NodeType Type() const override final + virtual NodeType type() const override final { return DECORATOR_NODE; } diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h index 2e62e7bf1..a2b074afe 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -26,7 +26,7 @@ class DecoratorRetryNode : public DecoratorNode ~DecoratorRetryNode() = default; // The method that is going to be executed by the thread - void Exec(); + void exec(); private: unsigned int NTries_; diff --git a/include/behavior_tree_core/fallback_node.h b/include/behavior_tree_core/fallback_node.h index dbdd6978f..b12c27dc6 100644 --- a/include/behavior_tree_core/fallback_node.h +++ b/include/behavior_tree_core/fallback_node.h @@ -26,7 +26,7 @@ class FallbackNode : public ControlNode ~FallbackNode() = default; // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; + virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index 39f1dd82a..f8809d612 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -26,9 +26,9 @@ class FallbackNodeWithMemory : public ControlNode ~FallbackNodeWithMemory() = default; // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; + virtual BT::NodeStatus tick() override; - virtual void Halt() override; + virtual void halt() override; private: unsigned int current_child_idx_; diff --git a/include/behavior_tree_core/parallel_node.h b/include/behavior_tree_core/parallel_node.h index dc4828d45..9ae4c4517 100644 --- a/include/behavior_tree_core/parallel_node.h +++ b/include/behavior_tree_core/parallel_node.h @@ -26,11 +26,11 @@ class ParallelNode : public ControlNode ~ParallelNode() = default; // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; - virtual void Halt() override; + virtual BT::NodeStatus tick() override; + virtual void halt() override; - unsigned int get_threshold_M(); - void set_threshold_M(unsigned int threshold_M); + unsigned int thresholdM(); + void setThresholdM(unsigned int threshold_M); private: unsigned int threshold_M_; diff --git a/include/behavior_tree_core/sequence_node.h b/include/behavior_tree_core/sequence_node.h index 219348079..066686220 100644 --- a/include/behavior_tree_core/sequence_node.h +++ b/include/behavior_tree_core/sequence_node.h @@ -26,7 +26,7 @@ class SequenceNode : public ControlNode ~SequenceNode() = default; // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; + virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index 4ab256cfb..6c1bc25b4 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -26,8 +26,8 @@ class SequenceNodeWithMemory : public ControlNode ~SequenceNodeWithMemory() = default; // The method that is going to be executed by the thread - virtual BT::NodeStatus Tick() override; - virtual void Halt() override; + virtual BT::NodeStatus tick() override; + virtual void halt() override; private: unsigned int current_child_idx_; diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 8f2f94ea0..05250cc54 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -14,6 +14,8 @@ #ifndef BEHAVIORTREECORE_TREENODE_H #define BEHAVIORTREECORE_TREENODE_H +#define DEBUG + #ifdef DEBUG // #define DEBUG_STDERR(x) (std::cerr << (x)) #define DEBUG_STDOUT(str) \ @@ -122,25 +124,25 @@ class TreeNode // The constructor and the distructor TreeNode(std::string name); - virtual ~TreeNode(); + virtual ~TreeNode() = default; // The method that is going to be executed when the node receive a tick - virtual BT::NodeStatus Tick() = 0; + virtual BT::NodeStatus tick() = 0; // The method used to interrupt the execution of the node - virtual void Halt() = 0; + virtual void halt() = 0; - bool IsHalted() const; + bool isHalted() const; - NodeStatus Status() const; - void SetStatus(NodeStatus new_status); + NodeStatus status() const; + void setStatus(NodeStatus new_status); - const std::string& Name() const; - void SetName(const std::string& new_name); + const std::string& name() const; + void setName(const std::string& new_name); BT::NodeStatus waitValidStatus(); - virtual NodeType Type() const = 0; + virtual NodeType type() const = 0; }; } diff --git a/src/action_node.cpp b/src/action_node.cpp index 85dfbce63..6665fb05c 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -15,22 +15,22 @@ BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name) { - thread_ = std::thread(&ActionNode::WaitForTick, this); + thread_ = std::thread(&ActionNode::waitForTick, this); } -void BT::ActionNode::WaitForTick() +void BT::ActionNode::waitForTick() { while (true) { // Waiting for the tick to come - DEBUG_STDOUT(Name() << " WAIT FOR TICK"); + DEBUG_STDOUT(name() << " WAIT FOR TICK"); - tick_engine.Wait(); - DEBUG_STDOUT(Name() << " TICK RECEIVED"); + tick_engine.wait(); + DEBUG_STDOUT(name() << " TICK RECEIVED"); // Running state - SetStatus(BT::RUNNING); - BT::NodeStatus status = Tick(); - SetStatus(status); + setStatus(BT::RUNNING); + BT::NodeStatus status = tick(); + setStatus(status); } } diff --git a/src/condition_node.cpp b/src/condition_node.cpp index 5e008b8ab..d141b8f95 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -17,6 +17,6 @@ BT::ConditionNode::ConditionNode(std::string name) : LeafNode::LeafNode(name) { } -void BT::ConditionNode::Halt() +void BT::ConditionNode::halt() { } diff --git a/src/control_node.cpp b/src/control_node.cpp index d35cb15c9..5534054a4 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -20,49 +20,49 @@ BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) // ReturnStatus child_i_status_ = BT::IDLE; // commented out as unused } -void BT::ControlNode::AddChild(TreeNode* child) +void BT::ControlNode::addChild(TreeNode* child) { // Checking if the child is not already present for (auto node : children_nodes_) { if (node == child) { - throw BehaviorTreeException("'" + child->Name() + "' is already a '" + Name() + "' child."); + throw BehaviorTreeException("'" + child->name() + "' is already a '" + name() + "' child."); } } children_nodes_.push_back(child); } -unsigned int BT::ControlNode::ChildrenCount() const +unsigned int BT::ControlNode::childrenCount() const { return children_nodes_.size(); } -void BT::ControlNode::Halt() +void BT::ControlNode::halt() { - DEBUG_STDOUT("HALTING: " << Name()); - HaltChildren(0); - SetStatus(BT::HALTED); + DEBUG_STDOUT("HALTING: " << name()); + haltChildren(0); + setStatus(BT::HALTED); } -const std::vector& BT::ControlNode::Children() const +const std::vector& BT::ControlNode::children() const { return children_nodes_; } -void BT::ControlNode::HaltChildren(int i) +void BT::ControlNode::haltChildren(int i) { for (unsigned int j = i; j < children_nodes_.size(); j++) { - if (children_nodes_[j]->Status() == BT::RUNNING) + if (children_nodes_[j]->status() == BT::RUNNING) { - DEBUG_STDOUT("SENDING HALT TO CHILD " << children_nodes_[j]->Name()); - children_nodes_[j]->Halt(); + DEBUG_STDOUT("SENDING HALT TO CHILD " << children_nodes_[j]->name()); + children_nodes_[j]->halt(); } else { - DEBUG_STDOUT("NO NEED TO HALT " << children_nodes_[j]->Name() << "STATUS" << children_nodes_[j]->Status()); + DEBUG_STDOUT("NO NEED TO HALT " << children_nodes_[j]->name() << "STATUS" << children_nodes_[j]->status()); } } } diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 8c0a87cbe..650b67dff 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -19,37 +19,37 @@ BT::DecoratorNode::DecoratorNode(std::string name) : TreeNode::TreeNode(name), c // ReturnStatus child_i_status_ = BT::IDLE; // commented out as unused } -void BT::DecoratorNode::AddChild(TreeNode* child) +void BT::DecoratorNode::setChild(TreeNode* child) { if (child_node_) { - throw BehaviorTreeException("Decorator '" + Name() + "' has already a child assigned"); + throw BehaviorTreeException("Decorator '" + name() + "' has already a child assigned"); } child_node_ = child; } -void BT::DecoratorNode::Halt() +void BT::DecoratorNode::halt() { - DEBUG_STDOUT("HALTING: " << Name()); - HaltChild(); - SetStatus(BT::HALTED); + DEBUG_STDOUT("HALTING: " << name()); + haltChild(); + setStatus(BT::HALTED); } -const BT::TreeNode* BT::DecoratorNode::Child() const +const BT::TreeNode* BT::DecoratorNode::child() const { return child_node_; } -void BT::DecoratorNode::HaltChild() +void BT::DecoratorNode::haltChild() { - if (child_node_->Status() == BT::RUNNING) + if (child_node_->status() == BT::RUNNING) { - DEBUG_STDOUT("SENDING HALT TO CHILD " << child_node_->Name()); - child_node_->Halt(); + DEBUG_STDOUT("SENDING HALT TO CHILD " << child_node_->name()); + child_node_->halt(); } else { - DEBUG_STDOUT("NO NEED TO HALT " << child_node_->Name() << "STATUS" << child_node_->Status()); + DEBUG_STDOUT("NO NEED TO HALT " << child_node_->name() << "STATUS" << child_node_->status()); } } diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index df166b6a5..8fd571e4e 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -17,7 +17,7 @@ BT::FallbackNode::FallbackNode(std::string name) : ControlNode::ControlNode(name { } -BT::NodeStatus BT::FallbackNode::Tick() +BT::NodeStatus BT::FallbackNode::tick() { { // gets the number of children. The number could change if, at runtime, one edits the tree. @@ -34,16 +34,16 @@ BT::NodeStatus BT::FallbackNode::Tick() Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (child_node->Type() == BT::ACTION_NODE) + if (child_node->type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. - child_i_status_ = child_node->Status(); + child_i_status_ = child_node->status(); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(Name() << "NEEDS TO TICK " << child_node->Name()); - child_node->tick_engine.Tick(); + DEBUG_STDOUT(name() << "NEEDS TO TICK " << child_node->name()); + child_node->tick_engine.notify(); child_i_status_ = child_node->waitValidStatus(); } @@ -52,31 +52,31 @@ BT::NodeStatus BT::FallbackNode::Tick() { // 2) if it's not an action: // Send the tick and wait for the response; - child_i_status_ = child_node->Tick(); - child_node->SetStatus(child_i_status_); + child_i_status_ = child_node->tick(); + child_node->setStatus(child_i_status_); } // Ponderate on which status to send to the parent if (child_i_status_ != BT::FAILURE) { if (child_i_status_ == BT::SUCCESS) { - child_node->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. + child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned success. } // If the child status is not failure, halt the next children and return the status to your parent. - DEBUG_STDOUT(Name() << " is HALTING children from " << (i + 1)); - HaltChildren(i + 1); - SetStatus(child_i_status_); + DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); + haltChildren(i + 1); + setStatus(child_i_status_); return child_i_status_; } else { // the child returned failure. - child_node->SetStatus(BT::IDLE); + child_node->setStatus(BT::IDLE); if (i == N_of_children - 1) { // If the child status is failure, and it is the last child to be ticked, // then the sequence has failed. - SetStatus(BT::FAILURE); + setStatus(BT::FAILURE); return BT::FAILURE; } } diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 172a64bd6..233598b0e 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -18,9 +18,9 @@ BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, ResetPolicy { } -BT::NodeStatus BT::FallbackNodeWithMemory::Tick() +BT::NodeStatus BT::FallbackNodeWithMemory::tick() { - DEBUG_STDOUT(Name() << " ticked, memory counter: " << current_child_idx_); + DEBUG_STDOUT(name() << " ticked, memory counter: " << current_child_idx_); // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children = children_nodes_.size(); @@ -36,20 +36,20 @@ BT::NodeStatus BT::FallbackNodeWithMemory::Tick() For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (current_child_node->Type() == BT::ACTION_NODE) + if (current_child_node->type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. - child_i_status_ = current_child_node->Status(); - DEBUG_STDOUT(Name() << " It is an action " << current_child_node->Name() + child_i_status_ = current_child_node->status(); + DEBUG_STDOUT(name() << " It is an action " << current_child_node->name() << " with status: " << child_i_status_); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(Name() << "NEEDS TO TICK " << current_child_node->Name()); - current_child_node->tick_engine.Tick(); + DEBUG_STDOUT(name() << "NEEDS TO TICK " << current_child_node->name()); + current_child_node->tick_engine.notify(); child_i_status_ = current_child_node->waitValidStatus(); } @@ -58,26 +58,26 @@ BT::NodeStatus BT::FallbackNodeWithMemory::Tick() { // 2) if it's not an action: // Send the tick and wait for the response; - child_i_status_ = current_child_node->Tick(); - current_child_node->SetStatus(child_i_status_); + child_i_status_ = current_child_node->tick(); + current_child_node->setStatus(child_i_status_); } if (child_i_status_ == BT::SUCCESS || child_i_status_ == BT::FAILURE) { // the child goes in idle if it has returned success or failure. - current_child_node->SetStatus(BT::IDLE); + current_child_node->setStatus(BT::IDLE); } if (child_i_status_ != BT::FAILURE) { // If the child status is not success, return the status - DEBUG_STDOUT("the status of: " << Name() << " becomes " << child_i_status_); + DEBUG_STDOUT("the status of: " << name() << " becomes " << child_i_status_); if (child_i_status_ == BT::SUCCESS && (reset_policy_ == BT::ON_SUCCESS || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) { current_child_idx_ = 0; } - SetStatus(child_i_status_); + setStatus(child_i_status_); return child_i_status_; } else if (current_child_idx_ != N_of_children - 1) @@ -94,15 +94,15 @@ BT::NodeStatus BT::FallbackNodeWithMemory::Tick() // if it the last child and it has returned failure, reset the memory current_child_idx_ = 0; } - SetStatus(child_i_status_); + setStatus(child_i_status_); return child_i_status_; } } return BT::EXIT; } -void BT::FallbackNodeWithMemory::Halt() +void BT::FallbackNodeWithMemory::halt() { current_child_idx_ = 0; - BT::ControlNode::Halt(); + BT::ControlNode::halt(); } diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index e8942d2e7..8e48866c4 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -18,7 +18,7 @@ BT::ParallelNode::ParallelNode(std::string name, int threshold_M) { } -BT::NodeStatus BT::ParallelNode::Tick() +BT::NodeStatus BT::ParallelNode::tick() { success_childred_num_ = 0; failure_childred_num_ = 0; @@ -28,56 +28,56 @@ BT::NodeStatus BT::ParallelNode::Tick() // Routing the tree according to the sequence node's logic: for (unsigned int i = 0; i < N_of_children; i++) { - DEBUG_STDOUT(Name() << "TICKING " << children_nodes_[i]->Name()); + DEBUG_STDOUT(name() << "TICKING " << children_nodes_[i]->name()); - if (children_nodes_[i]->Type() == BT::ACTION_NODE) + if (children_nodes_[i]->type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. // Action nodes runs in another parallel, hence you cannot retrieve the status just by executing it. - child_i_status_ = children_nodes_[i]->Status(); + child_i_status_ = children_nodes_[i]->status(); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1 If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(Name() << "NEEDS TO TICK " << children_nodes_[i]->Name()); - children_nodes_[i]->tick_engine.Tick(); + DEBUG_STDOUT(name() << "NEEDS TO TICK " << children_nodes_[i]->name()); + children_nodes_[i]->tick_engine.notify(); child_i_status_ = children_nodes_[i]->waitValidStatus(); } } else { - child_i_status_ = children_nodes_[i]->Tick(); + child_i_status_ = children_nodes_[i]->tick(); } switch (child_i_status_) { case BT::SUCCESS: - children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned success. + children_nodes_[i]->setStatus(BT::IDLE); // the child goes in idle if it has returned success. if (++success_childred_num_ == threshold_M_) { success_childred_num_ = 0; failure_childred_num_ = 0; - HaltChildren(0); // halts all running children. The execution is done. - SetStatus(child_i_status_); + haltChildren(0); // halts all running children. The execution is done. + setStatus(child_i_status_); return child_i_status_; } break; case BT::FAILURE: - children_nodes_[i]->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. + children_nodes_[i]->setStatus(BT::IDLE); // the child goes in idle if it has returned failure. if (++failure_childred_num_ > N_of_children - threshold_M_) { - DEBUG_STDOUT("*******PARALLEL" << Name() + DEBUG_STDOUT("*******PARALLEL" << name() << " FAILED****** failure_childred_num_:" << failure_childred_num_); success_childred_num_ = 0; failure_childred_num_ = 0; - HaltChildren(0); // halts all running children. The execution is hopeless. - SetStatus(child_i_status_); + haltChildren(0); // halts all running children. The execution is hopeless. + setStatus(child_i_status_); return child_i_status_; } break; case BT::RUNNING: - SetStatus(child_i_status_); + setStatus(child_i_status_); break; default: break; @@ -86,19 +86,19 @@ BT::NodeStatus BT::ParallelNode::Tick() return BT::RUNNING; } -void BT::ParallelNode::Halt() +void BT::ParallelNode::halt() { success_childred_num_ = 0; failure_childred_num_ = 0; - BT::ControlNode::Halt(); + BT::ControlNode::halt(); } -unsigned int BT::ParallelNode::get_threshold_M() +unsigned int BT::ParallelNode::thresholdM() { return threshold_M_; } -void BT::ParallelNode::set_threshold_M(unsigned int threshold_M) +void BT::ParallelNode::setThresholdM(unsigned int threshold_M) { threshold_M_ = threshold_M; } diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 9f3647cad..8dfe017c3 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -17,7 +17,7 @@ BT::SequenceNode::SequenceNode(std::string name) : ControlNode::ControlNode(name { } -BT::NodeStatus BT::SequenceNode::Tick() +BT::NodeStatus BT::SequenceNode::tick() { // gets the number of children. The number could change if, at runtime, one edits the tree. const unsigned N_of_children = children_nodes_.size(); @@ -32,16 +32,16 @@ BT::NodeStatus BT::SequenceNode::Tick() Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - if (child_node->Type() == BT::ACTION_NODE) + if (child_node->type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. - child_i_status_ = child_node->Status(); + child_i_status_ = child_node->status(); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(Name() << "NEEDS TO TICK " << child_node->Name()); - child_node->tick_engine.Tick(); + DEBUG_STDOUT(name() << "NEEDS TO TICK " << child_node->name()); + child_node->tick_engine.notify(); child_i_status_ = child_node->waitValidStatus(); } @@ -50,8 +50,8 @@ BT::NodeStatus BT::SequenceNode::Tick() { // 2) if it's not an action: // Send the tick and wait for the response; - child_i_status_ = child_node->Tick(); - child_node->SetStatus(child_i_status_); + child_i_status_ = child_node->tick(); + child_node->setStatus(child_i_status_); } // Ponderate on which status to send to the parent if (child_i_status_ != BT::SUCCESS) @@ -59,24 +59,24 @@ BT::NodeStatus BT::SequenceNode::Tick() // If the child status is not success, halt the next children and return the status to your parent. if (child_i_status_ == BT::FAILURE) { - child_node->SetStatus(BT::IDLE); // the child goes in idle if it has returned failure. + child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned failure. } - DEBUG_STDOUT(Name() << " is HALTING children from " << (i + 1)); - HaltChildren(i + 1); - SetStatus(child_i_status_); + DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); + haltChildren(i + 1); + setStatus(child_i_status_); return child_i_status_; } else { // the child returned success. - child_node->SetStatus(BT::IDLE); + child_node->setStatus(BT::IDLE); if (i == N_of_children - 1) { // If the child status is success, and it is the last child to be ticked, // then the sequence has succeeded. - SetStatus(BT::SUCCESS); + setStatus(BT::SUCCESS); return BT::SUCCESS; } } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index d57c7a439..1970b062a 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -18,9 +18,9 @@ BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolicy { } -BT::NodeStatus BT::SequenceNodeWithMemory::Tick() +BT::NodeStatus BT::SequenceNodeWithMemory::tick() { - DEBUG_STDOUT(Name() << " ticked, memory counter: " << current_child_idx_); + DEBUG_STDOUT(name() << " ticked, memory counter: " << current_child_idx_); // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children_ = children_nodes_.size(); @@ -35,19 +35,20 @@ BT::NodeStatus BT::SequenceNodeWithMemory::Tick() */ const auto& current_child_node = children_nodes_[current_child_idx_]; - if (current_child_node->Type() == BT::ACTION_NODE) + if (current_child_node->type() == BT::ACTION_NODE) { // 1) If the child i is an action, read its state. // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. - child_i_status_ = current_child_node->Status(); - DEBUG_STDOUT(Name() << " It is an action " << child_node->Name() << " with status: " << child_i_status_); + child_i_status_ = current_child_node->status(); + DEBUG_STDOUT(name() << " It is an action " << current_child_node->name() + << " with status: " << child_i_status_); if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) { // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(Name() << "NEEDS TO TICK " << child_node->Name()); - current_child_node->tick_engine.Tick(); + DEBUG_STDOUT(name() << "NEEDS TO TICK " << current_child_node->name()); + current_child_node->tick_engine.notify(); child_i_status_ = current_child_node->waitValidStatus(); } @@ -56,26 +57,26 @@ BT::NodeStatus BT::SequenceNodeWithMemory::Tick() { // 2) if it's not an action: // Send the tick and wait for the response; - child_i_status_ = current_child_node->Tick(); - current_child_node->SetStatus(child_i_status_); + child_i_status_ = current_child_node->tick(); + current_child_node->setStatus(child_i_status_); } if (child_i_status_ == BT::SUCCESS || child_i_status_ == BT::FAILURE) { // the child goes in idle if it has returned success or failure. - current_child_node->SetStatus(BT::IDLE); + current_child_node->setStatus(BT::IDLE); } if (child_i_status_ != BT::SUCCESS) { // If the child status is not success, return the status - DEBUG_STDOUT("the status of: " << Name() << " becomes " << child_i_status_); + DEBUG_STDOUT("the status of: " << name() << " becomes " << child_i_status_); if (child_i_status_ == BT::FAILURE && (reset_policy_ == BT::ON_FAILURE || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) { current_child_idx_ = 0; } - SetStatus(child_i_status_); + setStatus(child_i_status_); return child_i_status_; } else if (current_child_idx_ != N_of_children_ - 1) @@ -92,15 +93,15 @@ BT::NodeStatus BT::SequenceNodeWithMemory::Tick() // if it the last child and it has returned SUCCESS, reset the memory current_child_idx_ = 0; } - SetStatus(child_i_status_); + setStatus(child_i_status_); return child_i_status_; } } return BT::EXIT; } -void BT::SequenceNodeWithMemory::Halt() +void BT::SequenceNodeWithMemory::halt() { current_child_idx_ = 0; - BT::ControlNode::Halt(); + BT::ControlNode::halt(); } diff --git a/src/tree_node.cpp b/src/tree_node.cpp index e1f8e6b67..e0de27803 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -13,15 +13,14 @@ #include "behavior_tree_core/tree_node.h" -BT::TreeNode::TreeNode(std::string name) : name_(name), status_(BT::IDLE), is_state_updated_(false), tick_engine(0) +BT::TreeNode::TreeNode(std::string name) : + name_(name), + status_(BT::IDLE), + is_state_updated_(false) { } -BT::TreeNode::~TreeNode() -{ -} - -void BT::TreeNode::SetStatus(NodeStatus new_status) +void BT::TreeNode::setStatus(NodeStatus new_status) { { std::unique_lock UniqueLock(state_mutex_); @@ -31,13 +30,13 @@ void BT::TreeNode::SetStatus(NodeStatus new_status) state_condition_variable_.notify_all(); } -BT::NodeStatus BT::TreeNode::Status() const +BT::NodeStatus BT::TreeNode::status() const { std::lock_guard LockGuard(state_mutex_); return status_; } -void BT::TreeNode::SetName(const std::string& new_name) +void BT::TreeNode::setName(const std::string& new_name) { name_ = new_name; } @@ -51,12 +50,12 @@ BT::NodeStatus BT::TreeNode::waitValidStatus() return status_; } -const std::string& BT::TreeNode::Name() const +const std::string& BT::TreeNode::name() const { return name_; } -bool BT::TreeNode::IsHalted() const +bool BT::TreeNode::isHalted() const { - return Status() == BT::HALTED; + return status() == BT::HALTED; } diff --git a/templates/action_node_template.cpp b/templates/action_node_template.cpp index a6e7b0433..8ceeadc7a 100644 --- a/templates/action_node_template.cpp +++ b/templates/action_node_template.cpp @@ -15,10 +15,10 @@ void BT::CLASSNAME::WaitForTick() while (true) { // Waiting for the first tick to come - DEBUG_STDOUT(Name() << " WAIT FOR TICK"); + DEBUG_STDOUT(name() << " WAIT FOR TICK"); tick_engine.Wait(); - DEBUG_STDOUT(Name() << " TICK RECEIVED"); + DEBUG_STDOUT(name() << " TICK RECEIVED"); // Running state SetStatus(BT::RUNNING); From 492a98fead33e9a3c9a0e117e5d08ce37d11021e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 20 Apr 2018 11:54:55 +0200 Subject: [PATCH 026/125] bool reade_ for TickEngine --- include/behavior_tree_core/tick_engine.h | 16 +++++++++---- src/tick_engine.cpp | 30 +++++++----------------- 2 files changed, 20 insertions(+), 26 deletions(-) diff --git a/include/behavior_tree_core/tick_engine.h b/include/behavior_tree_core/tick_engine.h index 917dea1d7..4bd15d252 100644 --- a/include/behavior_tree_core/tick_engine.h +++ b/include/behavior_tree_core/tick_engine.h @@ -19,18 +19,24 @@ #include #include + class TickEngine { private: - int value_; + bool ready_; std::mutex mutex_; std::condition_variable condition_variable_; public: - TickEngine(int initial_value); - ~TickEngine(); - void Wait(); - void Tick(); + TickEngine(bool start_as_ready = false); + + ~TickEngine() = default; + + void wait(); + + void notify(); }; + + #endif diff --git a/src/tick_engine.cpp b/src/tick_engine.cpp index 6df4cbd11..3219322d7 100644 --- a/src/tick_engine.cpp +++ b/src/tick_engine.cpp @@ -13,37 +13,25 @@ #include "behavior_tree_core/tick_engine.h" -TickEngine::TickEngine(int initial_value) -{ - value_ = initial_value; -} +// find how condition_variables work here http://es.cppreference.com/w/cpp/thread/condition_variable/wait -TickEngine::~TickEngine() +TickEngine::TickEngine(bool start_ready) : ready_(start_ready) { } -void TickEngine::Wait() +void TickEngine::wait() { - // Lock acquire (need a unique lock for the condition variable usage) std::unique_lock UniqueLock(mutex_); - - // If the state is 0 then we have to wait for a signal - if (value_ == 0) + while (!ready_) + { condition_variable_.wait(UniqueLock); - - // Once here we decrement the state - value_--; + } + ready_ = false; } -void TickEngine::Tick() +void TickEngine::notify() { - // Lock acquire - std::lock_guard LockGuard(mutex_); - - // State increment - value_++; - - // Notification + ready_ = true; condition_variable_.notify_all(); } From db401dd32d6cf0927896ff9afd2390112837b377 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 Apr 2018 10:58:32 +0200 Subject: [PATCH 027/125] comment again the "unique child" check --- include/behavior_tree_core/tick_engine.h | 3 --- src/control_node.cpp | 16 ++++++++-------- 2 files changed, 8 insertions(+), 11 deletions(-) diff --git a/include/behavior_tree_core/tick_engine.h b/include/behavior_tree_core/tick_engine.h index 4bd15d252..79a253be6 100644 --- a/include/behavior_tree_core/tick_engine.h +++ b/include/behavior_tree_core/tick_engine.h @@ -19,7 +19,6 @@ #include #include - class TickEngine { private: @@ -37,6 +36,4 @@ class TickEngine void notify(); }; - - #endif diff --git a/src/control_node.cpp b/src/control_node.cpp index 5534054a4..284fc0f21 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -22,14 +22,14 @@ BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) void BT::ControlNode::addChild(TreeNode* child) { - // Checking if the child is not already present - for (auto node : children_nodes_) - { - if (node == child) - { - throw BehaviorTreeException("'" + child->name() + "' is already a '" + name() + "' child."); - } - } + // Checking if the child is not already present + // for (auto node : children_nodes_) + // { + // if (node == child) + // { + // throw BehaviorTreeException("'" + child->name() + "' is already a '" + name() + "' child."); + // } + // } children_nodes_.push_back(child); } From 6e31f5d69a84e8c55334fc9e1bb7d2b49bac87fa Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 Apr 2018 11:01:55 +0200 Subject: [PATCH 028/125] Remove copy and paste related to Async ActionNode Remove copy and paste related to TickEngine and ActionNode Instead ofcopy and pasting in any ControlNode the same specific code to be used only in ActionNodes, put that code only once in the ActionNode itself. The only difference in the API is that the Actions implemented by the user must implement the virtual funtion asyncTick(), instead of tick(). TickEngine was moved from TreeNode to ActionNode. --- gtest/include/action_test_node.h | 5 ++- gtest/src/action_test_node.cpp | 2 +- include/behavior_tree_core/action_node.h | 17 ++++++-- include/behavior_tree_core/control_node.h | 3 -- include/behavior_tree_core/tree_node.h | 15 ------- src/action_node.cpp | 40 ++++++++++++++---- src/control_node.cpp | 2 +- src/decorator_node.cpp | 2 +- src/fallback_node.cpp | 35 +++------------- src/fallback_node_with_memory.cpp | 51 +++++------------------ src/parallel_node.cpp | 38 ++++++----------- src/sequence_node.cpp | 34 +++------------ src/sequence_node_with_memory.cpp | 45 +++++--------------- src/tree_node.cpp | 13 +++--- 14 files changed, 105 insertions(+), 197 deletions(-) diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index 77f41d739..336c03bd4 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -10,14 +10,17 @@ class ActionTestNode : public ActionNode public: // Constructor ActionTestNode(std::string name); + virtual ~ActionTestNode() = default; // The method that is going to be executed by the thread - virtual BT::NodeStatus tick() override; + virtual BT::NodeStatus asyncTick() override; + void set_time(int time); // The method used to interrupt the execution of the node virtual void halt() override; + void set_boolean_value(bool boolean_value); private: diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 25bc2f3b4..ec2a42a91 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -20,7 +20,7 @@ BT::ActionTestNode::ActionTestNode(std::string name) : ActionNode::ActionNode(na time_ = 3; } -BT::NodeStatus BT::ActionTestNode::tick() +BT::NodeStatus BT::ActionTestNode::asyncTick() { int i = 0; while (status() != BT::HALTED && i++ < time_) diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 14bdbc313..a5e138935 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -14,6 +14,7 @@ #ifndef BEHAVIORTREECORE_ACTIONNODE_H #define BEHAVIORTREECORE_ACTIONNODE_H +#include #include "leaf_node.h" namespace BT @@ -28,18 +29,28 @@ class ActionNode : public LeafNode // The method that is going to be executed by the thread void waitForTick(); - // Methods used to access the node state without the - // conditional waiting (only mutual access) - bool writeState(NodeStatus new_state); + // This method triggers the TickEngine. Do NOT remove the "final" keyword. + virtual NodeStatus tick() override final; + + // method to be implemented by the user. + virtual NodeStatus asyncTick() = 0; virtual NodeType type() const override final { return ACTION_NODE; } + void stopAndJoinThread(); + protected: // The thread that will execute the node std::thread thread_; + + // Node semaphore to simulate the tick + // (and to synchronize fathers and children) + TickEngine tick_engine_; + + std::atomic loop_; }; } diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index 4a5bf7c98..836fcce9b 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -25,9 +25,6 @@ class ControlNode : public TreeNode // Children vector std::vector children_nodes_; - //child i status. Used to rout the ticks - NodeStatus child_i_status_; - public: // Constructor ControlNode(std::string name); diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 05250cc54..1393aa37d 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -14,8 +14,6 @@ #ifndef BEHAVIORTREECORE_TREENODE_H #define BEHAVIORTREECORE_TREENODE_H -#define DEBUG - #ifdef DEBUG // #define DEBUG_STDERR(x) (std::cerr << (x)) #define DEBUG_STDOUT(str) \ @@ -29,13 +27,7 @@ #endif #include -//#include - #include -#include -#include -#include -#include #include "behavior_tree_core/tick_engine.h" #include "behavior_tree_core/exceptions.h" @@ -111,17 +103,10 @@ class TreeNode NodeStatus status_; protected: - // The node state that must be treated in a thread-safe way - bool is_state_updated_; - mutable std::mutex state_mutex_; std::condition_variable state_condition_variable_; public: - // Node semaphore to simulate the tick - // (and to synchronize fathers and children) - TickEngine tick_engine; - // The constructor and the distructor TreeNode(std::string name); virtual ~TreeNode() = default; diff --git a/src/action_node.cpp b/src/action_node.cpp index 6665fb05c..1a0378dc1 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -13,24 +13,46 @@ #include "behavior_tree_core/action_node.h" -BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name) +BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name), loop_(true) { thread_ = std::thread(&ActionNode::waitForTick, this); } void BT::ActionNode::waitForTick() { - while (true) + while (loop_.load()) { - // Waiting for the tick to come DEBUG_STDOUT(name() << " WAIT FOR TICK"); - - tick_engine.wait(); + tick_engine_.wait(); DEBUG_STDOUT(name() << " TICK RECEIVED"); - // Running state - setStatus(BT::RUNNING); - BT::NodeStatus status = tick(); - setStatus(status); + // check this again because the tick_engine_ could be + // notified from the method stopAndJoinThread + if (loop_.load()) + { + setStatus(BT::RUNNING); + BT::NodeStatus status = asyncTick(); + setStatus(status); + } + } +} + +BT::NodeStatus BT::ActionNode::tick() +{ + NodeStatus stat = status(); + + if (stat == BT::IDLE || stat == BT::HALTED) + { + DEBUG_STDOUT("NEEDS TO TICK " << name()); + tick_engine_.notify(); + stat = waitValidStatus(); } + return stat; +} + +void BT::ActionNode::stopAndJoinThread() +{ + loop_ = false; + tick_engine_.notify(); + thread_.join(); } diff --git a/src/control_node.cpp b/src/control_node.cpp index 284fc0f21..74682ee24 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -17,7 +17,7 @@ BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable - // ReturnStatus child_i_status_ = BT::IDLE; // commented out as unused + // ReturnStatus const NodeStatus child_status = BT::IDLE; // commented out as unused } void BT::ControlNode::addChild(TreeNode* child) diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 650b67dff..68f9f209e 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -16,7 +16,7 @@ BT::DecoratorNode::DecoratorNode(std::string name) : TreeNode::TreeNode(name), c { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable - // ReturnStatus child_i_status_ = BT::IDLE; // commented out as unused + // ReturnStatus const NodeStatus child_status = BT::IDLE; // commented out as unused } void BT::DecoratorNode::setChild(TreeNode* child) diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 8fd571e4e..22252e041 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -29,44 +29,21 @@ BT::NodeStatus BT::FallbackNode::tick() { auto& child_node = children_nodes_[i]; - /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. - We want this thread detached so we can cancel its execution (when the action no longer receive ticks). - Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. - For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. - */ - if (child_node->type() == BT::ACTION_NODE) - { - // 1) If the child i is an action, read its state. - child_i_status_ = child_node->status(); - - if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) - { - // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(name() << "NEEDS TO TICK " << child_node->name()); - child_node->tick_engine.notify(); + const NodeStatus child_status = child_node->tick(); + child_node->setStatus(child_status); - child_i_status_ = child_node->waitValidStatus(); - } - } - else - { - // 2) if it's not an action: - // Send the tick and wait for the response; - child_i_status_ = child_node->tick(); - child_node->setStatus(child_i_status_); - } // Ponderate on which status to send to the parent - if (child_i_status_ != BT::FAILURE) + if (child_status != BT::FAILURE) { - if (child_i_status_ == BT::SUCCESS) + if (child_status == BT::SUCCESS) { child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned success. } // If the child status is not failure, halt the next children and return the status to your parent. DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); haltChildren(i + 1); - setStatus(child_i_status_); - return child_i_status_; + setStatus(child_status); + return child_status; } else { diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 233598b0e..2705a4c01 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -30,55 +30,26 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() { auto& current_child_node = children_nodes_[current_child_idx_]; - /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. - We want this thread detached so we can cancel its execution (when the action no longer receive ticks). - Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. - For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. - */ + const NodeStatus child_status = current_child_node->tick(); + current_child_node->setStatus(child_status); - if (current_child_node->type() == BT::ACTION_NODE) - { - // 1) If the child i is an action, read its state. - // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. - - child_i_status_ = current_child_node->status(); - DEBUG_STDOUT(name() << " It is an action " << current_child_node->name() - << " with status: " << child_i_status_); - - if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) - { - // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(name() << "NEEDS TO TICK " << current_child_node->name()); - current_child_node->tick_engine.notify(); - - child_i_status_ = current_child_node->waitValidStatus(); - } - } - else - { - // 2) if it's not an action: - // Send the tick and wait for the response; - child_i_status_ = current_child_node->tick(); - current_child_node->setStatus(child_i_status_); - } - - if (child_i_status_ == BT::SUCCESS || child_i_status_ == BT::FAILURE) + if (child_status == BT::SUCCESS || child_status == BT::FAILURE) { // the child goes in idle if it has returned success or failure. current_child_node->setStatus(BT::IDLE); } - if (child_i_status_ != BT::FAILURE) + if (child_status != BT::FAILURE) { // If the child status is not success, return the status - DEBUG_STDOUT("the status of: " << name() << " becomes " << child_i_status_); - if (child_i_status_ == BT::SUCCESS && + DEBUG_STDOUT("the status of: " << name() << " becomes " << child_status); + if (child_status == BT::SUCCESS && (reset_policy_ == BT::ON_SUCCESS || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) { current_child_idx_ = 0; } - setStatus(child_i_status_); - return child_i_status_; + setStatus(child_status); + return child_status; } else if (current_child_idx_ != N_of_children - 1) { @@ -89,13 +60,13 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() else { // If it the last child. - if (child_i_status_ == BT::FAILURE) + if (child_status == BT::FAILURE) { // if it the last child and it has returned failure, reset the memory current_child_idx_ = 0; } - setStatus(child_i_status_); - return child_i_status_; + setStatus(child_status); + return child_status; } } return BT::EXIT; diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 8e48866c4..e8d7573dc 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -28,42 +28,28 @@ BT::NodeStatus BT::ParallelNode::tick() // Routing the tree according to the sequence node's logic: for (unsigned int i = 0; i < N_of_children; i++) { - DEBUG_STDOUT(name() << "TICKING " << children_nodes_[i]->name()); + TreeNode* child_node = children_nodes_[i]; - if (children_nodes_[i]->type() == BT::ACTION_NODE) - { - // 1) If the child i is an action, read its state. - // Action nodes runs in another parallel, hence you cannot retrieve the status just by executing it. - child_i_status_ = children_nodes_[i]->status(); + DEBUG_STDOUT(name() << "TICKING " << child_node); - if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) - { - // 1.1 If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(name() << "NEEDS TO TICK " << children_nodes_[i]->name()); - children_nodes_[i]->tick_engine.notify(); + NodeStatus child_status = child_node->tick(); + child_node->setStatus(child_status); - child_i_status_ = children_nodes_[i]->waitValidStatus(); - } - } - else - { - child_i_status_ = children_nodes_[i]->tick(); - } - switch (child_i_status_) + switch (child_status) { case BT::SUCCESS: - children_nodes_[i]->setStatus(BT::IDLE); // the child goes in idle if it has returned success. + child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned success. if (++success_childred_num_ == threshold_M_) { success_childred_num_ = 0; failure_childred_num_ = 0; haltChildren(0); // halts all running children. The execution is done. - setStatus(child_i_status_); - return child_i_status_; + setStatus(child_status); + return child_status; } break; case BT::FAILURE: - children_nodes_[i]->setStatus(BT::IDLE); // the child goes in idle if it has returned failure. + child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned failure. if (++failure_childred_num_ > N_of_children - threshold_M_) { DEBUG_STDOUT("*******PARALLEL" << name() @@ -72,12 +58,12 @@ BT::NodeStatus BT::ParallelNode::tick() success_childred_num_ = 0; failure_childred_num_ = 0; haltChildren(0); // halts all running children. The execution is hopeless. - setStatus(child_i_status_); - return child_i_status_; + setStatus(child_status); + return child_status; } break; case BT::RUNNING: - setStatus(child_i_status_); + setStatus(child_status); break; default: break; diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 8dfe017c3..b6783b108 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -27,45 +27,23 @@ BT::NodeStatus BT::SequenceNode::tick() for (unsigned int i = 0; i < N_of_children; i++) { auto& child_node = children_nodes_[i]; - /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. - We want this thread detached so we can cancel its execution (when the action no longer receive ticks). - Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. - For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. - */ - if (child_node->type() == BT::ACTION_NODE) - { - // 1) If the child i is an action, read its state. - child_i_status_ = child_node->status(); - if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) - { - // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(name() << "NEEDS TO TICK " << child_node->name()); - child_node->tick_engine.notify(); + const NodeStatus child_status = child_node->tick(); + child_node->setStatus(child_status); - child_i_status_ = child_node->waitValidStatus(); - } - } - else - { - // 2) if it's not an action: - // Send the tick and wait for the response; - child_i_status_ = child_node->tick(); - child_node->setStatus(child_i_status_); - } // Ponderate on which status to send to the parent - if (child_i_status_ != BT::SUCCESS) + if (child_status != BT::SUCCESS) { // If the child status is not success, halt the next children and return the status to your parent. - if (child_i_status_ == BT::FAILURE) + if (child_status == BT::FAILURE) { child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned failure. } DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); haltChildren(i + 1); - setStatus(child_i_status_); - return child_i_status_; + setStatus(child_status); + return child_status; } else { diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 1970b062a..b4afb91fc 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -35,49 +35,26 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() */ const auto& current_child_node = children_nodes_[current_child_idx_]; - if (current_child_node->type() == BT::ACTION_NODE) - { - // 1) If the child i is an action, read its state. - // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it. - - child_i_status_ = current_child_node->status(); - DEBUG_STDOUT(name() << " It is an action " << current_child_node->name() - << " with status: " << child_i_status_); - - if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED) - { - // 1.1) If the action status is not running, the sequence node sends a tick to it. - DEBUG_STDOUT(name() << "NEEDS TO TICK " << current_child_node->name()); - current_child_node->tick_engine.notify(); - - child_i_status_ = current_child_node->waitValidStatus(); - } - } - else - { - // 2) if it's not an action: - // Send the tick and wait for the response; - child_i_status_ = current_child_node->tick(); - current_child_node->setStatus(child_i_status_); - } + const NodeStatus child_status = current_child_node->tick(); + current_child_node->setStatus(child_status); - if (child_i_status_ == BT::SUCCESS || child_i_status_ == BT::FAILURE) + if (child_status == BT::SUCCESS || child_status == BT::FAILURE) { // the child goes in idle if it has returned success or failure. current_child_node->setStatus(BT::IDLE); } - if (child_i_status_ != BT::SUCCESS) + if (child_status != BT::SUCCESS) { // If the child status is not success, return the status - DEBUG_STDOUT("the status of: " << name() << " becomes " << child_i_status_); - if (child_i_status_ == BT::FAILURE && + DEBUG_STDOUT("the status of: " << name() << " becomes " << child_status); + if (child_status == BT::FAILURE && (reset_policy_ == BT::ON_FAILURE || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) { current_child_idx_ = 0; } - setStatus(child_i_status_); - return child_i_status_; + setStatus(child_status); + return child_status; } else if (current_child_idx_ != N_of_children_ - 1) { @@ -88,13 +65,13 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() else { // if it the last child. - if (child_i_status_ == BT::SUCCESS) + if (child_status == BT::SUCCESS) { // if it the last child and it has returned SUCCESS, reset the memory current_child_idx_ = 0; } - setStatus(child_i_status_); - return child_i_status_; + setStatus(child_status); + return child_status; } } return BT::EXIT; diff --git a/src/tree_node.cpp b/src/tree_node.cpp index e0de27803..33fb92ed0 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -13,21 +13,22 @@ #include "behavior_tree_core/tree_node.h" -BT::TreeNode::TreeNode(std::string name) : - name_(name), - status_(BT::IDLE), - is_state_updated_(false) +BT::TreeNode::TreeNode(std::string name) : name_(name), status_(BT::IDLE) { } void BT::TreeNode::setStatus(NodeStatus new_status) { + bool is_state_updated = false; { std::unique_lock UniqueLock(state_mutex_); - is_state_updated_ = (status_ != new_status); + is_state_updated = (status_ != new_status); status_ = new_status; } - state_condition_variable_.notify_all(); + if (is_state_updated) + { + state_condition_variable_.notify_all(); + } } BT::NodeStatus BT::TreeNode::status() const From ba982f70cf7a1ae802b674c1276b848df000c3ed Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 Apr 2018 11:21:35 +0200 Subject: [PATCH 029/125] fix memory leak in test (detected with Valgrind) --- gtest/gtest_tree.cpp | 348 +++++++++++------------ include/behavior_tree_core/action_node.h | 2 +- src/action_node.cpp | 8 + 3 files changed, 183 insertions(+), 175 deletions(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index de8ba6064..2d076f765 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -17,319 +17,319 @@ struct SimpleSequenceTest : testing::Test { - BT::SequenceNode* root; - BT::ActionTestNode* action; - BT::ConditionTestNode* condition; + std::unique_ptr root; + std::unique_ptr action; + std::unique_ptr condition; SimpleSequenceTest() { - action = new BT::ActionTestNode("action"); - condition = new BT::ConditionTestNode("condition"); + action.reset(new BT::ActionTestNode("action")); + condition.reset( new BT::ConditionTestNode("condition") ); - root = new BT::SequenceNode("seq1"); + root.reset( new BT::SequenceNode("seq1") ); - root->addChild(condition); - root->addChild(action); + root->addChild(condition.get()); + root->addChild(action.get()); } }; struct ComplexSequenceTest : testing::Test { - BT::SequenceNode* root; - BT::ActionTestNode* action_1; - BT::ConditionTestNode* condition_1; - BT::ConditionTestNode* condition_2; + std::unique_ptr root; + std::unique_ptr action_1; + std::unique_ptr condition_1; + std::unique_ptr condition_2; - BT::SequenceNode* seq_conditions; + std::unique_ptr seq_conditions; ComplexSequenceTest() { - action_1 = new BT::ActionTestNode("action 1"); + action_1.reset( new BT::ActionTestNode("action 1") ); - condition_1 = new BT::ConditionTestNode("condition 1"); - condition_2 = new BT::ConditionTestNode("condition 2"); - seq_conditions = new BT::SequenceNode("sequence_conditions"); + condition_1.reset( new BT::ConditionTestNode("condition 1" )); + condition_2.reset( new BT::ConditionTestNode("condition 2" )); + seq_conditions.reset( new BT::SequenceNode("sequence_conditions") ); - seq_conditions->addChild(condition_1); - seq_conditions->addChild(condition_2); + seq_conditions->addChild(condition_1.get()); + seq_conditions->addChild(condition_2.get()); - root = new BT::SequenceNode("root"); - root->addChild(seq_conditions); - root->addChild(action_1); + root.reset( new BT::SequenceNode("root") ); + root->addChild(seq_conditions.get()); + root->addChild(action_1.get()); } }; struct ComplexSequence2ActionsTest : testing::Test { - BT::SequenceNode* root; - BT::ActionTestNode* action_1; - BT::ActionTestNode* action_2; + std::unique_ptr root; + std::unique_ptr action_1; + std::unique_ptr action_2; - BT::ConditionTestNode* condition_1; - BT::ConditionTestNode* condition_2; + std::unique_ptr condition_1; + std::unique_ptr condition_2; - BT::SequenceNode* seq_1; - BT::SequenceNode* seq_2; + std::unique_ptr seq_1; + std::unique_ptr seq_2; ComplexSequence2ActionsTest() { - action_1 = new BT::ActionTestNode("action 1"); - action_2 = new BT::ActionTestNode("action 2"); - seq_1 = new BT::SequenceNode("sequence_1"); - seq_2 = new BT::SequenceNode("sequence_c2"); + action_1.reset( new BT::ActionTestNode("action 1") ); + action_2.reset( new BT::ActionTestNode("action 2") ); + seq_1.reset( new BT::SequenceNode("sequence_1") ); + seq_2.reset( new BT::SequenceNode("sequence_c2") ); - condition_1 = new BT::ConditionTestNode("condition 1"); - condition_2 = new BT::ConditionTestNode("condition 2"); + condition_1.reset( new BT::ConditionTestNode("condition 1") ); + condition_2.reset( new BT::ConditionTestNode("condition 2") ); - seq_1->addChild(condition_1); - seq_1->addChild(action_1); + seq_1->addChild(condition_1.get()); + seq_1->addChild(action_1.get()); - seq_2->addChild(condition_2); - seq_2->addChild(action_2); + seq_2->addChild(condition_2.get()); + seq_2->addChild(action_2.get()); - root = new BT::SequenceNode("root"); - root->addChild(seq_1); - root->addChild(seq_2); + root.reset( new BT::SequenceNode("root") ); + root->addChild(seq_1.get()); + root->addChild(seq_2.get()); } }; struct SimpleFallbackTest : testing::Test { - BT::FallbackNode* root; - BT::ActionTestNode* action; - BT::ConditionTestNode* condition; + std::unique_ptr root; + std::unique_ptr action; + std::unique_ptr condition; SimpleFallbackTest() { - action = new BT::ActionTestNode("action"); - condition = new BT::ConditionTestNode("condition"); + action.reset( new BT::ActionTestNode("action") ); + condition.reset( new BT::ConditionTestNode("condition") ); - root = new BT::FallbackNode("seq1"); + root.reset( new BT::FallbackNode("seq1") ); - root->addChild(condition); - root->addChild(action); + root->addChild(condition.get()); + root->addChild(action.get()); } }; struct ComplexFallbackTest : testing::Test { - BT::FallbackNode* root; - BT::ActionTestNode* action_1; - BT::ConditionTestNode* condition_1; - BT::ConditionTestNode* condition_2; + std::unique_ptr root; + std::unique_ptr action_1; + std::unique_ptr condition_1; + std::unique_ptr condition_2; - BT::FallbackNode* sel_conditions; + std::unique_ptr sel_conditions; ComplexFallbackTest() { - action_1 = new BT::ActionTestNode("action 1"); - condition_1 = new BT::ConditionTestNode("condition 1"); - condition_2 = new BT::ConditionTestNode("condition 2"); - sel_conditions = new BT::FallbackNode("fallback_conditions"); + action_1.reset( new BT::ActionTestNode("action 1") ); + condition_1.reset( new BT::ConditionTestNode("condition 1") ); + condition_2.reset( new BT::ConditionTestNode("condition 2") ); + sel_conditions.reset( new BT::FallbackNode("fallback_conditions") ); - sel_conditions->addChild(condition_1); - sel_conditions->addChild(condition_2); + sel_conditions->addChild(condition_1.get()); + sel_conditions->addChild(condition_2.get()); - root = new BT::FallbackNode("root"); - root->addChild(sel_conditions); - root->addChild(action_1); + root.reset( new BT::FallbackNode("root") ); + root->addChild(sel_conditions.get()); + root->addChild(action_1.get()); } }; struct BehaviorTreeTest : testing::Test { - BT::SequenceNode* root; - BT::ActionTestNode* action_1; - BT::ConditionTestNode* condition_1; - BT::ConditionTestNode* condition_2; + std::unique_ptr root; + std::unique_ptr action_1; + std::unique_ptr condition_1; + std::unique_ptr condition_2; - BT::FallbackNode* sel_conditions; + std::unique_ptr sel_conditions; BehaviorTreeTest() { - action_1 = new BT::ActionTestNode("action 1"); - condition_1 = new BT::ConditionTestNode("condition 1"); - condition_2 = new BT::ConditionTestNode("condition 2"); - sel_conditions = new BT::FallbackNode("fallback_conditions"); + action_1.reset( new BT::ActionTestNode("action 1") ); + condition_1.reset( new BT::ConditionTestNode("condition 1") ); + condition_2.reset( new BT::ConditionTestNode("condition 2") ); + sel_conditions.reset( new BT::FallbackNode("fallback_conditions") ); - sel_conditions->addChild(condition_1); - sel_conditions->addChild(condition_2); + sel_conditions->addChild(condition_1.get()); + sel_conditions->addChild(condition_2.get()); - root = new BT::SequenceNode("root"); - root->addChild(sel_conditions); - root->addChild(action_1); + root.reset( new BT::SequenceNode("root") ); + root->addChild(sel_conditions.get()); + root->addChild(action_1.get()); } }; struct SimpleSequenceWithMemoryTest : testing::Test { - BT::SequenceNodeWithMemory* root; - BT::ActionTestNode* action; - BT::ConditionTestNode* condition; + std::unique_ptr root; + std::unique_ptr action; + std::unique_ptr condition; SimpleSequenceWithMemoryTest() { - action = new BT::ActionTestNode("action"); - condition = new BT::ConditionTestNode("condition"); + action.reset( new BT::ActionTestNode("action") ); + condition.reset( new BT::ConditionTestNode("condition") ); - root = new BT::SequenceNodeWithMemory("seq1"); + root.reset( new BT::SequenceNodeWithMemory("seq1") ); - root->addChild(condition); - root->addChild(action); + root->addChild(condition.get()); + root->addChild(action.get()); } }; struct ComplexSequenceWithMemoryTest : testing::Test { - BT::SequenceNodeWithMemory* root; + std::unique_ptr root; - BT::ActionTestNode* action_1; - BT::ActionTestNode* action_2; + std::unique_ptr action_1; + std::unique_ptr action_2; - BT::ConditionTestNode* condition_1; - BT::ConditionTestNode* condition_2; + std::unique_ptr condition_1; + std::unique_ptr condition_2; - BT::SequenceNodeWithMemory* seq_conditions; - BT::SequenceNodeWithMemory* seq_actions; + std::unique_ptr seq_conditions; + std::unique_ptr seq_actions; ComplexSequenceWithMemoryTest() { - action_1 = new BT::ActionTestNode("action 1"); - action_2 = new BT::ActionTestNode("action 2"); + action_1.reset( new BT::ActionTestNode("action 1") ); + action_2.reset( new BT::ActionTestNode("action 2") ); - condition_1 = new BT::ConditionTestNode("condition 1"); - condition_2 = new BT::ConditionTestNode("condition 2"); + condition_1.reset( new BT::ConditionTestNode("condition 1") ); + condition_2.reset( new BT::ConditionTestNode("condition 2") ); - seq_conditions = new BT::SequenceNodeWithMemory("sequence_conditions"); - seq_actions = new BT::SequenceNodeWithMemory("sequence_actions"); + seq_conditions.reset( new BT::SequenceNodeWithMemory("sequence_conditions") ); + seq_actions.reset( new BT::SequenceNodeWithMemory("sequence_actions") ); - seq_actions->addChild(action_1); - seq_actions->addChild(action_2); + seq_actions->addChild(action_1.get()); + seq_actions->addChild(action_2.get()); - seq_conditions->addChild(condition_1); - seq_conditions->addChild(condition_2); + seq_conditions->addChild(condition_1.get()); + seq_conditions->addChild(condition_2.get()); - root = new BT::SequenceNodeWithMemory("root"); - root->addChild(seq_conditions); - root->addChild(seq_actions); + root.reset( new BT::SequenceNodeWithMemory("root") ); + root->addChild(seq_conditions.get()); + root->addChild(seq_actions.get()); } }; struct SimpleFallbackWithMemoryTest : testing::Test { - BT::FallbackNodeWithMemory* root; - BT::ActionTestNode* action; - BT::ConditionTestNode* condition; + std::unique_ptr root; + std::unique_ptr action; + std::unique_ptr condition; SimpleFallbackWithMemoryTest() { - action = new BT::ActionTestNode("action"); - condition = new BT::ConditionTestNode("condition"); + action.reset( new BT::ActionTestNode("action") ); + condition.reset( new BT::ConditionTestNode("condition") ); - root = new BT::FallbackNodeWithMemory("seq1"); + root.reset( new BT::FallbackNodeWithMemory("seq1") ); - root->addChild(condition); - root->addChild(action); + root->addChild(condition.get()); + root->addChild(action.get()); } }; struct ComplexFallbackWithMemoryTest : testing::Test { - BT::FallbackNodeWithMemory* root; + std::unique_ptr root; - BT::ActionTestNode* action_1; - BT::ActionTestNode* action_2; + std::unique_ptr action_1; + std::unique_ptr action_2; - BT::ConditionTestNode* condition_1; - BT::ConditionTestNode* condition_2; + std::unique_ptr condition_1; + std::unique_ptr condition_2; - BT::FallbackNodeWithMemory* fal_conditions; - BT::FallbackNodeWithMemory* fal_actions; + std::unique_ptr fal_conditions; + std::unique_ptr fal_actions; ComplexFallbackWithMemoryTest() { - action_1 = new BT::ActionTestNode("action 1"); - action_2 = new BT::ActionTestNode("action 2"); - condition_1 = new BT::ConditionTestNode("condition 1"); - condition_2 = new BT::ConditionTestNode("condition 2"); + action_1.reset( new BT::ActionTestNode("action 1") ); + action_2.reset( new BT::ActionTestNode("action 2") ); + condition_1.reset( new BT::ConditionTestNode("condition 1") ); + condition_2.reset( new BT::ConditionTestNode("condition 2") ); - fal_conditions = new BT::FallbackNodeWithMemory("fallback_conditions"); - fal_actions = new BT::FallbackNodeWithMemory("fallback_actions"); + fal_conditions.reset( new BT::FallbackNodeWithMemory("fallback_conditions") ); + fal_actions.reset( new BT::FallbackNodeWithMemory("fallback_actions") ); - fal_actions->addChild(action_1); - fal_actions->addChild(action_2); + fal_actions->addChild(action_1.get()); + fal_actions->addChild(action_2.get()); - fal_conditions->addChild(condition_1); - fal_conditions->addChild(condition_2); + fal_conditions->addChild(condition_1.get()); + fal_conditions->addChild(condition_2.get()); - root = new BT::FallbackNodeWithMemory("root"); - root->addChild(fal_conditions); - root->addChild(fal_actions); + root.reset( new BT::FallbackNodeWithMemory("root") ); + root->addChild(fal_conditions.get()); + root->addChild(fal_actions.get()); } }; struct SimpleParallelTest : testing::Test { - BT::ParallelNode* root; - BT::ActionTestNode* action_1; - BT::ConditionTestNode* condition_1; + std::unique_ptr root; + std::unique_ptr action_1; + std::unique_ptr condition_1; - BT::ActionTestNode* action_2; - BT::ConditionTestNode* condition_2; + std::unique_ptr action_2; + std::unique_ptr condition_2; SimpleParallelTest() { - action_1 = new BT::ActionTestNode("action 1"); - condition_1 = new BT::ConditionTestNode("condition 1"); + action_1.reset( new BT::ActionTestNode("action 1") ); + condition_1.reset( new BT::ConditionTestNode("condition 1") ); - action_2 = new BT::ActionTestNode("action 2"); - condition_2 = new BT::ConditionTestNode("condition 2"); + action_2.reset( new BT::ActionTestNode("action 2") ); + condition_2.reset( new BT::ConditionTestNode("condition 2") ); - root = new BT::ParallelNode("par", 4); + root.reset( new BT::ParallelNode("par", 4) ); - root->addChild(condition_1); - root->addChild(action_1); - root->addChild(condition_2); - root->addChild(action_2); + root->addChild(condition_1.get()); + root->addChild(action_1.get()); + root->addChild(condition_2.get()); + root->addChild(action_2.get()); } }; struct ComplexParallelTest : testing::Test { - BT::ParallelNode* root; - BT::ParallelNode* parallel_1; - BT::ParallelNode* parallel_2; + std::unique_ptr root; + std::unique_ptr parallel_1; + std::unique_ptr parallel_2; - BT::ActionTestNode* action_1; - BT::ConditionTestNode* condition_1; + std::unique_ptr action_1; + std::unique_ptr condition_1; - BT::ActionTestNode* action_2; - BT::ConditionTestNode* condition_2; + std::unique_ptr action_2; + std::unique_ptr condition_2; - BT::ActionTestNode* action_3; - BT::ConditionTestNode* condition_3; + std::unique_ptr action_3; + std::unique_ptr condition_3; ComplexParallelTest() { - action_1 = new BT::ActionTestNode("action 1"); - condition_1 = new BT::ConditionTestNode("condition 1"); + action_1.reset( new BT::ActionTestNode("action 1") ); + condition_1.reset( new BT::ConditionTestNode("condition 1") ); - action_2 = new BT::ActionTestNode("action 2"); - condition_2 = new BT::ConditionTestNode("condition 2"); + action_2.reset( new BT::ActionTestNode("action 2") ); + condition_2.reset( new BT::ConditionTestNode("condition 2") ); - action_3 = new BT::ActionTestNode("action 3"); - condition_3 = new BT::ConditionTestNode("condition 3"); + action_3.reset( new BT::ActionTestNode("action 3") ); + condition_3.reset( new BT::ConditionTestNode("condition 3") ); - root = new BT::ParallelNode("root", 2); - parallel_1 = new BT::ParallelNode("par1", 3); - parallel_2 = new BT::ParallelNode("par2", 1); + root.reset( new BT::ParallelNode("root", 2) ); + parallel_1.reset( new BT::ParallelNode("par1", 3) ); + parallel_2.reset( new BT::ParallelNode("par2", 1) ); - parallel_1->addChild(condition_1); - parallel_1->addChild(action_1); - parallel_1->addChild(condition_2); - parallel_1->addChild(action_2); + parallel_1->addChild(condition_1.get()); + parallel_1->addChild(action_1.get()); + parallel_1->addChild(condition_2.get()); + parallel_1->addChild(action_2.get()); - parallel_2->addChild(condition_3); - parallel_2->addChild(action_3); + parallel_2->addChild(condition_3.get()); + parallel_2->addChild(action_3.get()); - root->addChild(parallel_1); - root->addChild(parallel_2); + root->addChild(parallel_1.get()); + root->addChild(parallel_2.get()); } }; diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index a5e138935..853dbc4a8 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -24,7 +24,7 @@ class ActionNode : public LeafNode public: // Constructor ActionNode(std::string name); - ~ActionNode() = default; + virtual ~ActionNode(); // The method that is going to be executed by the thread void waitForTick(); diff --git a/src/action_node.cpp b/src/action_node.cpp index 1a0378dc1..98e5b8dfc 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -18,6 +18,14 @@ BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name), loop_(t thread_ = std::thread(&ActionNode::waitForTick, this); } +BT::ActionNode::~ActionNode() +{ + if( thread_.joinable()) + { + stopAndJoinThread(); + } +} + void BT::ActionNode::waitForTick() { while (loop_.load()) From baefffd6c6d7c22198234b5568fcf0060c2feb2f Mon Sep 17 00:00:00 2001 From: Michele Colledanchise Date: Mon, 23 Apr 2018 12:24:39 +0200 Subject: [PATCH 030/125] renaming runtime output dir to bin --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 50bfd1df8..19eb8db92 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ if(catkin_FOUND) ) else(catkin_FOUND) - set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/sample) + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) find_package(GTest) From 4f22e95d090a8e9a3c6cfd5a6c7b9ca65087b604 Mon Sep 17 00:00:00 2001 From: Michele Colledanchise Date: Mon, 23 Apr 2018 12:30:02 +0200 Subject: [PATCH 031/125] add GTests in travis --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 9767812b5..47a2fe976 100644 --- a/.travis.yml +++ b/.travis.yml @@ -39,7 +39,7 @@ before_script: - mkdir -p build script: - - if [ "$ROS_DISTRO" = "none" ]; then (cd build; cmake .. ;cmake --build . ); fi + - if [ "$ROS_DISTRO" = "none" ]; then (cd build; cmake .. ;cmake --build .; ./bin/behavior_tree_core_test); fi - if [ "$ROS_DISTRO" != "none" ]; then (.ci_config/travis.sh); fi From 59a90d811d2015b687a6dca01c3da2c319b085ac Mon Sep 17 00:00:00 2001 From: Michele Colledanchise Date: Mon, 23 Apr 2018 12:37:59 +0200 Subject: [PATCH 032/125] checking if travis can verify failed tests --- gtest/gtest_tree.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index de8ba6064..883cffe1b 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -352,7 +352,7 @@ TEST_F(SimpleSequenceTest, ConditionTurnToFalse) condition->set_boolean_value(false); state = root->tick(); - ASSERT_EQ(BT::FAILURE, state); + ASSERT_EQ(BT::SUCCESS, state); ASSERT_EQ(BT::HALTED, action->status()); root->halt(); } From 42032b42a9b272497617f299e9e2ab3a37619fd6 Mon Sep 17 00:00:00 2001 From: Michele Colledanchise Date: Mon, 23 Apr 2018 12:42:00 +0200 Subject: [PATCH 033/125] reverting to correct test. Travis works --- gtest/gtest_tree.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 883cffe1b..de8ba6064 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -352,7 +352,7 @@ TEST_F(SimpleSequenceTest, ConditionTurnToFalse) condition->set_boolean_value(false); state = root->tick(); - ASSERT_EQ(BT::SUCCESS, state); + ASSERT_EQ(BT::FAILURE, state); ASSERT_EQ(BT::HALTED, action->status()); root->halt(); } From cca04249993e054d845f50083fcbe768ab498c93 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 Apr 2018 12:44:04 +0200 Subject: [PATCH 034/125] more ActionNode implementations --- gtest/include/action_test_node.h | 2 +- gtest/src/action_test_node.cpp | 3 +- include/behavior_tree_core/action_node.h | 66 +++++++++++++++++++++--- src/action_node.cpp | 48 ++++++++++++++--- 4 files changed, 105 insertions(+), 14 deletions(-) diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index 336c03bd4..f3b0a4724 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -5,7 +5,7 @@ namespace BT { -class ActionTestNode : public ActionNode +class ActionTestNode : public AsyncActionNode { public: // Constructor diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index ec2a42a91..d79675a92 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -14,7 +14,8 @@ #include "action_test_node.h" #include -BT::ActionTestNode::ActionTestNode(std::string name) : ActionNode::ActionNode(name) +BT::ActionTestNode::ActionTestNode(std::string name): + AsyncActionNode(name) { boolean_value_ = true; time_ = 3; diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 853dbc4a8..6ad2989fb 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -17,14 +17,71 @@ #include #include "leaf_node.h" + namespace BT { + + class ActionNode : public LeafNode { public: // Constructor ActionNode(std::string name); - virtual ~ActionNode(); + ~ActionNode() = default; + + virtual NodeType type() const override final + { + return ACTION_NODE; + } +}; + + +/** + * @brief The SimpleActionNode provides a easy to use ActionNode. + * The user should simply provide a callback with this signature + * + * BT::NodeStatus funtionName(void) + * + * This avoids the hassle of inheriting from a ActionNode. + * + * Using lambdas or std::bind it is easy to pass a pointer to a method too. + * For the time being, this class of Actions can not carry use the BT::NodeParameters + * This may change in the future. + */ +class SimpleActionNode : public ActionNode +{ + public: + + typedef std::function TickFunctor; + + // Constructor: you must provide the funtion to call when tick() is invoked + SimpleActionNode(std::string name, TickFunctor tick_functor); + + ~SimpleActionNode() = default; + + virtual NodeStatus tick() override; + + protected: + TickFunctor tick_functor_; +}; + +/** + * @brief The AsyncActionNode a different thread where the action will be + * executed. + * + * The user must implement the method asyncTick() instead of tick() and + * the method halt() as usual. + * + * Remember, though, that the method asyncTick() must update the state to either + * RUNNING, SUCCESS or FAILURE, otherwise the execution of the Behavior Tree is blocked! + * + */ +class AsyncActionNode : public ActionNode +{ + public: + // Constructor + AsyncActionNode(std::string name); + virtual ~AsyncActionNode(); // The method that is going to be executed by the thread void waitForTick(); @@ -35,10 +92,6 @@ class ActionNode : public LeafNode // method to be implemented by the user. virtual NodeStatus asyncTick() = 0; - virtual NodeType type() const override final - { - return ACTION_NODE; - } void stopAndJoinThread(); @@ -52,6 +105,7 @@ class ActionNode : public LeafNode std::atomic loop_; }; -} + +}//end namespace #endif diff --git a/src/action_node.cpp b/src/action_node.cpp index 98e5b8dfc..037439be2 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -13,12 +13,48 @@ #include "behavior_tree_core/action_node.h" -BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name), loop_(true) + +BT::ActionNode::ActionNode(std::string name) : + LeafNode::LeafNode(name) +{ + +} + +//------------------------------------------------------- + +BT::SimpleActionNode::SimpleActionNode(std::string name, + BT::SimpleActionNode::TickFunctor tick_functor): + ActionNode(name), + tick_functor_(tick_functor) +{ +} + +BT::NodeStatus BT::SimpleActionNode::tick() +{ + NodeStatus prev_status = status(); + + if( prev_status == BT::IDLE || BT::HALTED) + { + setStatus(BT::RUNNING); + prev_status = BT::RUNNING; + } + + NodeStatus status = tick_functor_(); + if( status != prev_status) + { + setStatus(status); + } + return status; +} + +//------------------------------------------------------- + +BT::AsyncActionNode::AsyncActionNode(std::string name) : ActionNode(name), loop_(true) { - thread_ = std::thread(&ActionNode::waitForTick, this); + thread_ = std::thread(&AsyncActionNode::waitForTick, this); } -BT::ActionNode::~ActionNode() +BT::AsyncActionNode::~AsyncActionNode() { if( thread_.joinable()) { @@ -26,7 +62,7 @@ BT::ActionNode::~ActionNode() } } -void BT::ActionNode::waitForTick() +void BT::AsyncActionNode::waitForTick() { while (loop_.load()) { @@ -45,7 +81,7 @@ void BT::ActionNode::waitForTick() } } -BT::NodeStatus BT::ActionNode::tick() +BT::NodeStatus BT::AsyncActionNode::tick() { NodeStatus stat = status(); @@ -58,7 +94,7 @@ BT::NodeStatus BT::ActionNode::tick() return stat; } -void BT::ActionNode::stopAndJoinThread() +void BT::AsyncActionNode::stopAndJoinThread() { loop_ = false; tick_engine_.notify(); From b173dec9a288d7669d46645e494938d43eda4983 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 Apr 2018 13:11:19 +0200 Subject: [PATCH 035/125] forgotten --- include/behavior_tree_core/action_node.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 6ad2989fb..047807376 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -61,6 +61,10 @@ class SimpleActionNode : public ActionNode virtual NodeStatus tick() override; + virtual void halt() override { + // not supported + } + protected: TickFunctor tick_functor_; }; From 210ac77c863a805e672d97dbc24e1e1946c1c937 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 Apr 2018 13:58:00 +0200 Subject: [PATCH 036/125] fixing the problem with destructors --- gtest/include/action_test_node.h | 2 +- gtest/src/action_test_node.cpp | 8 ++++++-- include/behavior_tree_core/action_node.h | 25 ++++++++++++++---------- src/action_node.cpp | 19 +++++++----------- 4 files changed, 29 insertions(+), 25 deletions(-) diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index f3b0a4724..5fb513e4d 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -11,7 +11,7 @@ class ActionTestNode : public AsyncActionNode // Constructor ActionTestNode(std::string name); - virtual ~ActionTestNode() = default; + ~ActionTestNode(); // The method that is going to be executed by the thread virtual BT::NodeStatus asyncTick() override; diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index d79675a92..c52795c75 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -14,13 +14,17 @@ #include "action_test_node.h" #include -BT::ActionTestNode::ActionTestNode(std::string name): - AsyncActionNode(name) +BT::ActionTestNode::ActionTestNode(std::string name) : AsyncActionNode(name) { boolean_value_ = true; time_ = 3; } +BT::ActionTestNode::~ActionTestNode() +{ + halt(); +} + BT::NodeStatus BT::ActionTestNode::asyncTick() { int i = 0; diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 047807376..f4801a168 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -17,11 +17,8 @@ #include #include "leaf_node.h" - namespace BT { - - class ActionNode : public LeafNode { public: @@ -35,7 +32,6 @@ class ActionNode : public LeafNode } }; - /** * @brief The SimpleActionNode provides a easy to use ActionNode. * The user should simply provide a callback with this signature @@ -51,7 +47,6 @@ class ActionNode : public LeafNode class SimpleActionNode : public ActionNode { public: - typedef std::function TickFunctor; // Constructor: you must provide the funtion to call when tick() is invoked @@ -61,12 +56,13 @@ class SimpleActionNode : public ActionNode virtual NodeStatus tick() override; - virtual void halt() override { + virtual void halt() override + { // not supported } protected: - TickFunctor tick_functor_; + TickFunctor tick_functor_; }; /** @@ -80,6 +76,7 @@ class SimpleActionNode : public ActionNode * RUNNING, SUCCESS or FAILURE, otherwise the execution of the Behavior Tree is blocked! * */ + class AsyncActionNode : public ActionNode { public: @@ -93,9 +90,17 @@ class AsyncActionNode : public ActionNode // This method triggers the TickEngine. Do NOT remove the "final" keyword. virtual NodeStatus tick() override final; - // method to be implemented by the user. - virtual NodeStatus asyncTick() = 0; + // This method MUST to be overriden by the user. + virtual NodeStatus asyncTick() + { + return BT::HALTED; + } + // This method MUST to be overriden by the user. + virtual void halt() override + { + setStatus(BT::HALTED); + } void stopAndJoinThread(); @@ -110,6 +115,6 @@ class AsyncActionNode : public ActionNode std::atomic loop_; }; -}//end namespace +} //end namespace #endif diff --git a/src/action_node.cpp b/src/action_node.cpp index 037439be2..c16e93d06 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -13,19 +13,14 @@ #include "behavior_tree_core/action_node.h" - -BT::ActionNode::ActionNode(std::string name) : - LeafNode::LeafNode(name) +BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name) { - } //------------------------------------------------------- -BT::SimpleActionNode::SimpleActionNode(std::string name, - BT::SimpleActionNode::TickFunctor tick_functor): - ActionNode(name), - tick_functor_(tick_functor) +BT::SimpleActionNode::SimpleActionNode(std::string name, BT::SimpleActionNode::TickFunctor tick_functor) + : ActionNode(name), tick_functor_(tick_functor) { } @@ -33,14 +28,14 @@ BT::NodeStatus BT::SimpleActionNode::tick() { NodeStatus prev_status = status(); - if( prev_status == BT::IDLE || BT::HALTED) + if (prev_status == BT::IDLE || BT::HALTED) { setStatus(BT::RUNNING); prev_status = BT::RUNNING; } NodeStatus status = tick_functor_(); - if( status != prev_status) + if (status != prev_status) { setStatus(status); } @@ -56,7 +51,7 @@ BT::AsyncActionNode::AsyncActionNode(std::string name) : ActionNode(name), loop_ BT::AsyncActionNode::~AsyncActionNode() { - if( thread_.joinable()) + if (thread_.joinable()) { stopAndJoinThread(); } @@ -96,7 +91,7 @@ BT::NodeStatus BT::AsyncActionNode::tick() void BT::AsyncActionNode::stopAndJoinThread() { - loop_ = false; + loop_.store(false); tick_engine_.notify(); thread_.join(); } From 52fcbff84b489e7458205a03d6df72131d018b0a Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 27 Apr 2018 16:03:51 +0200 Subject: [PATCH 037/125] Action renamed --- gtest/include/action_test_node.h | 4 ++-- gtest/src/action_test_node.cpp | 2 +- include/behavior_tree_core/action_node.h | 15 ++++++++------- include/behavior_tree_core/bt_factory.h | 2 +- src/action_node.cpp | 18 +++++++++--------- 5 files changed, 21 insertions(+), 20 deletions(-) diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index 5fb513e4d..3e4eaeacd 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -5,7 +5,7 @@ namespace BT { -class ActionTestNode : public AsyncActionNode +class ActionTestNode : public ActionNode { public: // Constructor @@ -14,7 +14,7 @@ class ActionTestNode : public AsyncActionNode ~ActionTestNode(); // The method that is going to be executed by the thread - virtual BT::NodeStatus asyncTick() override; + BT::NodeStatus asyncTick() override; void set_time(int time); diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index c52795c75..ad808f957 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -14,7 +14,7 @@ #include "action_test_node.h" #include -BT::ActionTestNode::ActionTestNode(std::string name) : AsyncActionNode(name) +BT::ActionTestNode::ActionTestNode(std::string name) : ActionNode(name) { boolean_value_ = true; time_ = 3; diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index f4801a168..45771b5f0 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -19,12 +19,12 @@ namespace BT { -class ActionNode : public LeafNode +class ActionNodeBase : public LeafNode { public: // Constructor - ActionNode(std::string name); - ~ActionNode() = default; + ActionNodeBase(std::string name); + ~ActionNodeBase() = default; virtual NodeType type() const override final { @@ -44,7 +44,7 @@ class ActionNode : public LeafNode * For the time being, this class of Actions can not carry use the BT::NodeParameters * This may change in the future. */ -class SimpleActionNode : public ActionNode +class SimpleActionNode : public ActionNodeBase { public: typedef std::function TickFunctor; @@ -77,12 +77,13 @@ class SimpleActionNode : public ActionNode * */ -class AsyncActionNode : public ActionNode + +class ActionNode : public ActionNodeBase { public: // Constructor - AsyncActionNode(std::string name); - virtual ~AsyncActionNode(); + ActionNode(std::string name); + virtual ~ActionNode(); // The method that is going to be executed by the thread void waitForTick(); diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index abcbbeec1..116c5dac5 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -65,7 +65,7 @@ class BehaviorTreeFactory template inline void BehaviorTreeFactory::registerBuilder(const std::string& ID) { - static_assert(std::is_base_of::value || std::is_base_of::value || + static_assert(std::is_base_of::value || std::is_base_of::value || std::is_base_of::value || std::is_base_of::value, "[registerBuilder]: accepts only classed derived from either ActionNode, DecoratorNode, ControlNode " "or ConditionNode"); diff --git a/src/action_node.cpp b/src/action_node.cpp index c16e93d06..62ddef5a3 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -13,14 +13,14 @@ #include "behavior_tree_core/action_node.h" -BT::ActionNode::ActionNode(std::string name) : LeafNode::LeafNode(name) +BT::ActionNodeBase::ActionNodeBase(std::string name) : LeafNode::LeafNode(name) { } //------------------------------------------------------- BT::SimpleActionNode::SimpleActionNode(std::string name, BT::SimpleActionNode::TickFunctor tick_functor) - : ActionNode(name), tick_functor_(tick_functor) + : ActionNodeBase(name), tick_functor_(tick_functor) { } @@ -28,7 +28,7 @@ BT::NodeStatus BT::SimpleActionNode::tick() { NodeStatus prev_status = status(); - if (prev_status == BT::IDLE || BT::HALTED) + if (prev_status == BT::IDLE || prev_status == BT::HALTED) { setStatus(BT::RUNNING); prev_status = BT::RUNNING; @@ -44,12 +44,12 @@ BT::NodeStatus BT::SimpleActionNode::tick() //------------------------------------------------------- -BT::AsyncActionNode::AsyncActionNode(std::string name) : ActionNode(name), loop_(true) +BT::ActionNode::ActionNode(std::string name) : ActionNodeBase(name), loop_(true) { - thread_ = std::thread(&AsyncActionNode::waitForTick, this); + thread_ = std::thread(&ActionNode::waitForTick, this); } -BT::AsyncActionNode::~AsyncActionNode() +BT::ActionNode::~ActionNode() { if (thread_.joinable()) { @@ -57,7 +57,7 @@ BT::AsyncActionNode::~AsyncActionNode() } } -void BT::AsyncActionNode::waitForTick() +void BT::ActionNode::waitForTick() { while (loop_.load()) { @@ -76,7 +76,7 @@ void BT::AsyncActionNode::waitForTick() } } -BT::NodeStatus BT::AsyncActionNode::tick() +BT::NodeStatus BT::ActionNode::tick() { NodeStatus stat = status(); @@ -89,7 +89,7 @@ BT::NodeStatus BT::AsyncActionNode::tick() return stat; } -void BT::AsyncActionNode::stopAndJoinThread() +void BT::ActionNode::stopAndJoinThread() { loop_.store(false); tick_engine_.notify(); From 1596d607e624c2982ea3ebedb4f6d30552a7b9f5 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 3 May 2018 13:10:23 +0200 Subject: [PATCH 038/125] removed asyncTick in favour of executeTick() --- gtest/include/action_test_node.h | 2 +- gtest/src/action_test_node.cpp | 2 +- include/behavior_tree_core/action_node.h | 4 ++-- include/behavior_tree_core/tree_node.h | 5 ++++- src/action_node.cpp | 4 ++-- src/fallback_node.cpp | 2 +- src/fallback_node_with_memory.cpp | 2 +- src/parallel_node.cpp | 2 +- src/sequence_node.cpp | 2 +- src/sequence_node_with_memory.cpp | 2 +- src/tree_node.cpp | 5 +++++ 11 files changed, 20 insertions(+), 12 deletions(-) diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index 3e4eaeacd..93b879a4b 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -14,7 +14,7 @@ class ActionTestNode : public ActionNode ~ActionTestNode(); // The method that is going to be executed by the thread - BT::NodeStatus asyncTick() override; + BT::NodeStatus tick() override; void set_time(int time); diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index ad808f957..50ead49ce 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -25,7 +25,7 @@ BT::ActionTestNode::~ActionTestNode() halt(); } -BT::NodeStatus BT::ActionTestNode::asyncTick() +BT::NodeStatus BT::ActionTestNode::tick() { int i = 0; while (status() != BT::HALTED && i++ < time_) diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 45771b5f0..a71255729 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -89,10 +89,10 @@ class ActionNode : public ActionNodeBase void waitForTick(); // This method triggers the TickEngine. Do NOT remove the "final" keyword. - virtual NodeStatus tick() override final; + virtual NodeStatus executeTick() override final; // This method MUST to be overriden by the user. - virtual NodeStatus asyncTick() + virtual NodeStatus tick() override { return BT::HALTED; } diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 1393aa37d..fa08c5c63 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -106,13 +106,16 @@ class TreeNode mutable std::mutex state_mutex_; std::condition_variable state_condition_variable_; + // Method to be implemented by the user + virtual BT::NodeStatus tick() = 0; + public: // The constructor and the distructor TreeNode(std::string name); virtual ~TreeNode() = default; // The method that is going to be executed when the node receive a tick - virtual BT::NodeStatus tick() = 0; + virtual BT::NodeStatus executeTick(); // The method used to interrupt the execution of the node virtual void halt() = 0; diff --git a/src/action_node.cpp b/src/action_node.cpp index 62ddef5a3..889d26530 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -70,13 +70,13 @@ void BT::ActionNode::waitForTick() if (loop_.load()) { setStatus(BT::RUNNING); - BT::NodeStatus status = asyncTick(); + BT::NodeStatus status = tick(); setStatus(status); } } } -BT::NodeStatus BT::ActionNode::tick() +BT::NodeStatus BT::ActionNode::executeTick() { NodeStatus stat = status(); diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 22252e041..bfc933d5b 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -29,7 +29,7 @@ BT::NodeStatus BT::FallbackNode::tick() { auto& child_node = children_nodes_[i]; - const NodeStatus child_status = child_node->tick(); + const NodeStatus child_status = child_node->executeTick(); child_node->setStatus(child_status); // Ponderate on which status to send to the parent diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 2705a4c01..4fceda944 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -30,7 +30,7 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() { auto& current_child_node = children_nodes_[current_child_idx_]; - const NodeStatus child_status = current_child_node->tick(); + const NodeStatus child_status = current_child_node->executeTick(); current_child_node->setStatus(child_status); if (child_status == BT::SUCCESS || child_status == BT::FAILURE) diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index e8d7573dc..19dc461b1 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -32,7 +32,7 @@ BT::NodeStatus BT::ParallelNode::tick() DEBUG_STDOUT(name() << "TICKING " << child_node); - NodeStatus child_status = child_node->tick(); + NodeStatus child_status = child_node->executeTick(); child_node->setStatus(child_status); switch (child_status) diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index b6783b108..1513d934f 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -28,7 +28,7 @@ BT::NodeStatus BT::SequenceNode::tick() { auto& child_node = children_nodes_[i]; - const NodeStatus child_status = child_node->tick(); + const NodeStatus child_status = child_node->executeTick(); child_node->setStatus(child_status); // Ponderate on which status to send to the parent diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index b4afb91fc..83a9bc0de 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -35,7 +35,7 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() */ const auto& current_child_node = children_nodes_[current_child_idx_]; - const NodeStatus child_status = current_child_node->tick(); + const NodeStatus child_status = current_child_node->executeTick(); current_child_node->setStatus(child_status); if (child_status == BT::SUCCESS || child_status == BT::FAILURE) diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 33fb92ed0..0dc54734d 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -17,6 +17,11 @@ BT::TreeNode::TreeNode(std::string name) : name_(name), status_(BT::IDLE) { } +BT::NodeStatus BT::TreeNode::executeTick() +{ + return tick(); +} + void BT::TreeNode::setStatus(NodeStatus new_status) { bool is_state_updated = false; From ea50858aeb17b11848a55dd5095fe36cf021f969 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 3 May 2018 13:18:51 +0200 Subject: [PATCH 039/125] making tick() private/protected, because only executeTick() should be used --- gtest/gtest_tree.cpp | 110 +++++++++--------- include/behavior_tree_core/action_node.h | 4 +- .../decorator_negation_node.h | 4 - include/behavior_tree_core/fallback_node.h | 3 +- .../fallback_node_with_memory.h | 5 +- include/behavior_tree_core/parallel_node.h | 3 +- include/behavior_tree_core/sequence_node.h | 2 +- .../sequence_node_with_memory.h | 4 +- 8 files changed, 66 insertions(+), 69 deletions(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 2d076f765..4b962742a 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -339,7 +339,7 @@ TEST_F(SimpleSequenceTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::RUNNING, action->status()); ASSERT_EQ(BT::RUNNING, state); @@ -348,10 +348,10 @@ TEST_F(SimpleSequenceTest, ConditionTrue) TEST_F(SimpleSequenceTest, ConditionTurnToFalse) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition->set_boolean_value(false); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::FAILURE, state); ASSERT_EQ(BT::HALTED, action->status()); root->halt(); @@ -359,7 +359,7 @@ TEST_F(SimpleSequenceTest, ConditionTurnToFalse) TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::RUNNING, action_1->status()); ASSERT_EQ(BT::RUNNING, state); @@ -368,13 +368,13 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); - state = root->tick(); + state = root->executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - state = root->tick(); - state = root->tick(); + state = root->executeTick(); + state = root->executeTick(); ASSERT_EQ(BT::RUNNING, state); ASSERT_EQ(BT::RUNNING, action_1->status()); @@ -387,11 +387,11 @@ TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition_1->set_boolean_value(false); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::FAILURE, state); ASSERT_EQ(BT::HALTED, action_1->status()); @@ -400,11 +400,11 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse) TEST_F(ComplexSequenceTest, ComplexSequenceConditions2ToFalse) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition_2->set_boolean_value(false); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::FAILURE, state); ASSERT_EQ(BT::HALTED, action_1->status()); @@ -416,7 +416,7 @@ TEST_F(SimpleFallbackTest, ConditionTrue) std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node condition->set_boolean_value(true); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::IDLE, action->status()); ASSERT_EQ(BT::SUCCESS, state); @@ -427,10 +427,10 @@ TEST_F(SimpleFallbackTest, ConditionToFalse) { condition->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition->set_boolean_value(true); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::SUCCESS, state); ASSERT_EQ(BT::HALTED, action->status()); @@ -442,11 +442,11 @@ TEST_F(ComplexFallbackTest, Condition1ToTrue) condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition_1->set_boolean_value(true); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::SUCCESS, state); @@ -459,11 +459,11 @@ TEST_F(ComplexFallbackTest, Condition2ToTrue) condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition_2->set_boolean_value(true); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::SUCCESS, state); ASSERT_EQ(BT::HALTED, action_1->status()); @@ -475,7 +475,7 @@ TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) condition_1->set_boolean_value(false); condition_2->set_boolean_value(true); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::RUNNING, state); ASSERT_EQ(BT::RUNNING, action_1->status()); @@ -488,7 +488,7 @@ TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) condition_2->set_boolean_value(false); condition_1->set_boolean_value(true); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::RUNNING, state); ASSERT_EQ(BT::RUNNING, action_1->status()); @@ -500,7 +500,7 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); ASSERT_EQ(BT::RUNNING, action->status()); @@ -510,11 +510,11 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition->set_boolean_value(false); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::RUNNING, state); ASSERT_EQ(BT::RUNNING, action->status()); @@ -524,7 +524,7 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::RUNNING, action_1->status()); ASSERT_EQ(BT::IDLE, action_2->status()); @@ -535,11 +535,11 @@ TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition_1->set_boolean_value(false); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::RUNNING, action_1->status()); ASSERT_EQ(BT::IDLE, action_2->status()); @@ -549,11 +549,11 @@ TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) TEST_F(ComplexSequenceWithMemoryTest, Conditions2ToFalse) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition_2->set_boolean_value(false); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::RUNNING, action_1->status()); ASSERT_EQ(BT::IDLE, action_2->status()); @@ -564,13 +564,13 @@ TEST_F(ComplexSequenceWithMemoryTest, Conditions2ToFalse) TEST_F(ComplexSequenceWithMemoryTest, Action1Done) { - root->tick(); + root->executeTick(); condition_2->set_boolean_value(false); - root->tick(); + root->executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(1000)); - root->tick(); + root->executeTick(); ASSERT_EQ(BT::RUNNING, action_2->status()); @@ -582,7 +582,7 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node condition->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); ASSERT_EQ(BT::RUNNING, action->status()); @@ -595,10 +595,10 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) { condition->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition->set_boolean_value(true); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::RUNNING, state); ASSERT_EQ(BT::RUNNING, action->status()); @@ -608,7 +608,7 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::IDLE, action_1->status()); ASSERT_EQ(BT::IDLE, action_2->status()); @@ -620,7 +620,7 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) TEST_F(ComplexFallbackWithMemoryTest, Condition1False) { condition_1->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::IDLE, action_1->status()); ASSERT_EQ(BT::IDLE, action_2->status()); @@ -633,7 +633,7 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) { condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::RUNNING, action_1->status()); ASSERT_EQ(BT::IDLE, action_2->status()); @@ -646,10 +646,10 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) { condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition_1->set_boolean_value(true); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::RUNNING, action_1->status()); ASSERT_EQ(BT::IDLE, action_2->status()); @@ -664,11 +664,11 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) condition_2->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); condition_2->set_boolean_value(true); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::RUNNING, action_1->status()); ASSERT_EQ(BT::IDLE, action_2->status()); @@ -683,11 +683,11 @@ TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) condition_1->set_boolean_value(false); condition_2->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); - state = root->tick(); + state = root->executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::IDLE, action_1->status()); ASSERT_EQ(BT::RUNNING, action_2->status()); @@ -698,7 +698,7 @@ TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) TEST_F(SimpleParallelTest, ConditionsTrue) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::IDLE, condition_1->status()); ASSERT_EQ(BT::IDLE, condition_2->status()); @@ -713,9 +713,9 @@ TEST_F(SimpleParallelTest, Threshold_3) { root->setThresholdM(3); action_2->set_time(200); - root->tick(); + root->executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::IDLE, condition_1->status()); ASSERT_EQ(BT::IDLE, condition_2->status()); @@ -729,7 +729,7 @@ TEST_F(SimpleParallelTest, Threshold_3) TEST_F(SimpleParallelTest, Threshold_1) { root->setThresholdM(1); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::IDLE, condition_1->status()); ASSERT_EQ(BT::IDLE, condition_2->status()); @@ -741,7 +741,7 @@ TEST_F(SimpleParallelTest, Threshold_1) } TEST_F(ComplexParallelTest, ConditionsTrue) { - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::IDLE, condition_1->status()); ASSERT_EQ(BT::IDLE, condition_2->status()); @@ -759,7 +759,7 @@ TEST_F(ComplexParallelTest, ConditionsTrue) TEST_F(ComplexParallelTest, Condition3False) { condition_3->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); ASSERT_EQ(BT::IDLE, condition_1->status()); ASSERT_EQ(BT::IDLE, condition_2->status()); @@ -780,7 +780,7 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) action_3->set_time(10); condition_3->set_boolean_value(false); - BT::NodeStatus state = root->tick(); + BT::NodeStatus state = root->executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); ASSERT_EQ(BT::IDLE, condition_1->status()); @@ -789,7 +789,7 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) ASSERT_EQ(BT::SUCCESS, action_1->status()); // success not read yet by the node parallel_1 ASSERT_EQ(BT::RUNNING, parallel_1->status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::IDLE, action_1->status()); ASSERT_EQ(BT::IDLE, parallel_1->status()); @@ -798,9 +798,9 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) ASSERT_EQ(BT::RUNNING, parallel_2->status()); ASSERT_EQ(BT::RUNNING, state); - state = root->tick(); + state = root->executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(1500)); - state = root->tick(); + state = root->executeTick(); ASSERT_EQ(BT::IDLE, parallel_2->status()); ASSERT_EQ(BT::IDLE, action_1->status()); diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index a71255729..4b54cb8e1 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -54,14 +54,14 @@ class SimpleActionNode : public ActionNodeBase ~SimpleActionNode() = default; - virtual NodeStatus tick() override; - virtual void halt() override { // not supported } protected: + virtual NodeStatus tick() override; + TickFunctor tick_functor_; }; diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h index 9da53cb3a..40ed91ea1 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -25,10 +25,6 @@ class DecoratorNegationNode : public DecoratorNode DecoratorNegationNode(std::string name); ~DecoratorNegationNode() = default; - // The method that is going to be executed by the thread - void exec(); - - void setChild(TreeNode* child); }; } diff --git a/include/behavior_tree_core/fallback_node.h b/include/behavior_tree_core/fallback_node.h index b12c27dc6..aad97c505 100644 --- a/include/behavior_tree_core/fallback_node.h +++ b/include/behavior_tree_core/fallback_node.h @@ -25,9 +25,10 @@ class FallbackNode : public ControlNode FallbackNode(std::string name); ~FallbackNode() = default; - // The method that is going to be executed by the thread +private: virtual BT::NodeStatus tick() override; }; + } #endif diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index f8809d612..dcc82f30b 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -25,14 +25,13 @@ class FallbackNodeWithMemory : public ControlNode ~FallbackNodeWithMemory() = default; - // The method that is going to be executed by the thread - virtual BT::NodeStatus tick() override; - virtual void halt() override; private: unsigned int current_child_idx_; ResetPolicy reset_policy_; + + virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/parallel_node.h b/include/behavior_tree_core/parallel_node.h index 9ae4c4517..acdc3802d 100644 --- a/include/behavior_tree_core/parallel_node.h +++ b/include/behavior_tree_core/parallel_node.h @@ -26,7 +26,6 @@ class ParallelNode : public ControlNode ~ParallelNode() = default; // The method that is going to be executed by the thread - virtual BT::NodeStatus tick() override; virtual void halt() override; unsigned int thresholdM(); @@ -36,6 +35,8 @@ class ParallelNode : public ControlNode unsigned int threshold_M_; unsigned int success_childred_num_; unsigned int failure_childred_num_; + + virtual BT::NodeStatus tick() override; }; } #endif // PARALLEL_NODE_H diff --git a/include/behavior_tree_core/sequence_node.h b/include/behavior_tree_core/sequence_node.h index 066686220..d931d0baf 100644 --- a/include/behavior_tree_core/sequence_node.h +++ b/include/behavior_tree_core/sequence_node.h @@ -25,7 +25,7 @@ class SequenceNode : public ControlNode SequenceNode(std::string name); ~SequenceNode() = default; - // The method that is going to be executed by the thread +private: virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index 6c1bc25b4..6b5db0acc 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -25,13 +25,13 @@ class SequenceNodeWithMemory : public ControlNode ~SequenceNodeWithMemory() = default; - // The method that is going to be executed by the thread - virtual BT::NodeStatus tick() override; virtual void halt() override; private: unsigned int current_child_idx_; ResetPolicy reset_policy_; + + virtual BT::NodeStatus tick() override; }; } From 1cada0c951445ab5e3581e22614022d63900ca01 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 3 May 2018 14:18:27 +0200 Subject: [PATCH 040/125] various clean-ups --- include/behavior_tree_core/condition_node.h | 4 - include/behavior_tree_core/control_node.h | 9 +- .../decorator_negation_node.h | 5 +- include/behavior_tree_core/decorator_node.h | 5 +- .../behavior_tree_core/decorator_retry_node.h | 4 +- include/behavior_tree_core/parallel_node.h | 1 - src/decorator_negation_node.cpp | 198 +++-------------- src/decorator_retry_node.cpp | 199 ++++-------------- 8 files changed, 88 insertions(+), 337 deletions(-) diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index 0058085a1..79ba1e2dc 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -28,10 +28,6 @@ class ConditionNode : public LeafNode // The method used to interrupt the execution of the node virtual void halt() override; - // Methods used to access the node state without the - // conditional waiting (only mutual access) - bool WriteState(NodeStatus new_state); - virtual NodeType type() const override final { return CONDITION_NODE; diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index 836fcce9b..c43de191f 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -38,15 +38,16 @@ class ControlNode : public TreeNode const std::vector& children() const; + const TreeNode* child(unsigned index) const + { + return children().at(index); + } + // The method used to interrupt the execution of the node virtual void halt() override; void haltChildren(int i); - // Methods used to access the node state without the - // conditional waiting (only mutual access) - bool writeState(NodeStatus new_state); - virtual NodeType type() const override final { return CONTROL_NODE; diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h index 40ed91ea1..f2d6f028b 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -23,8 +23,11 @@ class DecoratorNegationNode : public DecoratorNode public: // Constructor DecoratorNegationNode(std::string name); - ~DecoratorNegationNode() = default; + + virtual ~DecoratorNegationNode() = default; + private: + virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index be651f791..8735a348d 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -25,15 +25,12 @@ class DecoratorNode : public TreeNode void haltChild(); - // Methods used to access the node state without the - // conditional waiting (only mutual access) - bool writeState(NodeStatus new_state); - virtual NodeType type() const override final { return DECORATOR_NODE; } }; + } #endif diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h index a2b074afe..7d6db98c0 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -25,12 +25,12 @@ class DecoratorRetryNode : public DecoratorNode DecoratorRetryNode(std::string name, unsigned int NTries); ~DecoratorRetryNode() = default; - // The method that is going to be executed by the thread - void exec(); private: unsigned int NTries_; unsigned int TryIndx_; + + virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/parallel_node.h b/include/behavior_tree_core/parallel_node.h index acdc3802d..8632c4ed1 100644 --- a/include/behavior_tree_core/parallel_node.h +++ b/include/behavior_tree_core/parallel_node.h @@ -25,7 +25,6 @@ class ParallelNode : public ControlNode ParallelNode(std::string name, int threshold_M); ~ParallelNode() = default; - // The method that is going to be executed by the thread virtual void halt() override; unsigned int thresholdM(); diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index cff7ee697..3c96efe69 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -1,179 +1,51 @@ -#include - -BT::DecoratorNegationNode::DecoratorNegationNode(std::string name) : ControlNode::ControlNode(name) +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#include "behavior_tree_core/decorator_negation_node.h" + +BT::DecoratorNegationNode::DecoratorNegationNode(std::string name) : DecoratorNode(name) { - // thread_ start - thread_ = boost::thread(&DecoratorNegationNode::Exec, this); } -BT::DecoratorNegationNode::~DecoratorNegationNode() +BT::NodeStatus BT::DecoratorNegationNode::tick() { -} - -void BT::DecoratorNegationNode::Exec() -{ - // Waiting for the first tick to come - tick_engine.wait(); - - // Vector size initialization - N_of_children_ = children_nodes_.size(); + setStatus(BT::RUNNING); + const NodeStatus child_state = child_node_->tick(); - // Simulating a tick for myself - tick_engine.tick(); - - while (true) + switch (child_state) { - // Waiting for a tick to come - tick_engine.wait(); - - if (ReadState() == BT::EXIT) + case BT::SUCCESS: { - // The behavior tree is going to be destroied - return; + setStatus(BT::FAILURE); } + break; - // Checking if i was halted - if (ReadState() != BT::HALTED) + case BT::FAILURE: { - // If not, the children can be ticked - std::cout << get_name() << " ticked, ticking children..." << std::endl; - - if (children_nodes_[0]->get_type() == BT::ACTION_NODE) - { - // 1) if it's an action: - // 1.1) read its state; - ReturnStatus ActionState = children_nodes_[0]->ReadState(); - - if (ActionState == BT::IDLE) - { - // 1.2) if it's "Idle": - // 1.2.1) ticking it; - children_nodes_[0]->tick_engine.tick(); - - // 1.2.2) retrive its state as soon as it is available; - children_states_[0] = children_nodes_[0]->GetNodeState(); - } - else if (ActionState == BT::RUNNING) - { - // 1.3) if it's "Running": - // 1.3.1) saving "Running" - children_states_[0] = BT::RUNNING; - } - else - { - // 1.4) if it's "Success" of "Failure" (it can't be "Halted"!): - // 1.2.1) ticking it; - children_nodes_[0]->tick_engine.tick(); - - // 1.2.2) saving the read state; - children_states_[0] = ActionState; - } - } - else - { - // 2) if it's not an action: - // 2.1) ticking it; - children_nodes_[0]->tick_engine.tick(); - - // 2.2) retrive its state as soon as it is available; - children_states_[0] = children_nodes_[0]->GetNodeState(); - } - - // 3) if the child state is a success: - if (children_states_[0] == BT::SUCCESS) - { - // 3.1) the node state is equal to failure since I am negating the status - SetNodeState(BT::FAILURE); - - // 3.2) resetting the state; - WriteState(BT::IDLE); - - std::cout << get_name() << " returning " << BT::FAILURE << "!" << std::endl; - } - else if (children_states_[0] == BT::FAILURE) - { - // 4.1) the node state is equal to success since I am negating the status - SetNodeState(BT::SUCCESS); - - // 4.2) state reset; - WriteState(BT::IDLE); - - std::cout << get_name() << " returning " << BT::SUCCESS << "!" << std::endl; - } - else - // 5) if the child state is running - { - // 5.1) the node state is equal to running - SetNodeState(BT::RUNNING); - - // 5.2) state reset; - WriteState(BT::IDLE); - } + setStatus(BT::SUCCESS); } - else - { - // If it was halted, all the "busy" children must be halted too - std::cout << get_name() << " halted! Halting all the children..." << std::endl; - - if (children_nodes_[0]->get_type() != BT::ACTION_NODE && children_states_[0] == BT::RUNNING) - { - // if the control node was running: - // halting it; - children_nodes_[0]->Halt(); - - // sync with it (it's waiting on the semaphore); - children_nodes_[0]->tick_engine.tick(); - - std::cout << get_name() << " halting child " - << "!" << std::endl; - } - else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && - children_nodes_[0]->ReadState() == BT::RUNNING) - { - std::cout << get_name() << " trying halting child " - << "..." << std::endl; - - // if it's a action node that hasn't finished its job: - // trying to halt it: - if (children_nodes_[0]->Halt() == false) - { - // this means that, before this node could set its child state - // to "Halted", the child had already written the action outcome; - // sync with him ignoring its state; - children_nodes_[0]->tick_engine.tick(); + break; - std::cout << get_name() << " halting of child " - << " failed!" << std::endl; - } - - std::cout << get_name() << " halting of child " - << " succedeed!" << std::endl; - } - else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && children_nodes_[0]->ReadState() != BT::IDLE) - { - // if it's a action node that has finished its job: - // ticking it without saving its returning state; - children_nodes_[0]->tick_engine.tick(); - } - - // updating its vector cell - children_states_[0] = BT::IDLE; - - // Resetting the node state - WriteState(BT::IDLE); + case BT::RUNNING: + { + setStatus(BT::RUNNING); } - } -} - -void BT::DecoratorNegationNode::AddChild(BT::TreeNode* child) -{ - // Checking if the child is not already present + break; - if (children_nodes_.size() > 0) - { - throw BehaviorTreeException("Decorators can have only one child"); + default: + { + // TODO throw? + } } - - children_nodes_.push_back(child); - children_states_.push_back(BT::IDLE); + return status(); } diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index 6d139ba84..523e3b0cc 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -1,177 +1,60 @@ -#include - -BT::DecoratorRetryNode::DecoratorRetryNode(std::string name, unsigned int NTries) : ControlNode::ControlNode(name) +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#include "behavior_tree_core/decorator_retry_node.h" + +BT::DecoratorRetryNode::DecoratorRetryNode(std::string name, unsigned int NTries) + : DecoratorNode(name), NTries_(NTries), TryIndx_(0) { - // thread_ start - NTries_ = NTries; - thread_ = boost::thread(&DecoratorRetryNode::Exec, this); } -BT::DecoratorRetryNode::~DecoratorRetryNode() -{ -} -void BT::DecoratorRetryNode::Exec() +BT::NodeStatus BT::DecoratorRetryNode::tick() { - int i; - - // Waiting for the first tick to come - tick_engine.wait(); - - // Vector size initialization - N_of_children_ = children_nodes_.size(); + setStatus(BT::RUNNING); + BT::NodeStatus child_state = child_node_->tick(); - // Simulating a tick for myself - tick_engine.tick(); - - while (true) + switch (child_state) { - // Waiting for a tick to come - tick_engine.wait(); - - if (ReadState() == BT::EXIT) + case BT::SUCCESS: { - // The behavior tree is going to be destroied - return; + TryIndx_ = 0; + setStatus(BT::SUCCESS); } + break; - // Checking if i was halted - if (ReadState() != BT::HALTED) + case BT::FAILURE: { - // If not, the children can be ticked - std::cout << get_name() << " ticked, ticking children..." << std::endl; - - TryIndx_ = 0; - // For each child: - //for (i = 0; i= NTries_) { - if (children_nodes_[0]->get_type() == BT::ACTION_NODE) - { - // 1) if it's an action: - // 1.1) read its state; - ReturnStatus ActionState = children_nodes_[0]->ReadState(); - - if (ActionState == BT::IDLE) - { - // 1.2) if it's "Idle": - // 1.2.1) ticking it; - children_nodes_[0]->tick_engine.tick(); - - // 1.2.2) retrive its state as soon as it is available; - children_states_[0] = children_nodes_[0]->GetNodeState(); - } - else if (ActionState == BT::RUNNING) - { - // 1.3) if it's "Running": - // 1.3.1) saving "Running" - children_states_[0] = BT::RUNNING; - } - else - { - // 1.4) if it's "Success" of "Failure" (it can't be "Halted"!): - // 1.2.1) ticking it; - children_nodes_[0]->tick_engine.tick(); - - // 1.2.2) saving the read state; - children_states_[0] = ActionState; - } - } - else - { - // 2) if it's not an action: - // 2.1) ticking it; - children_nodes_[0]->tick_engine.tick(); - - // 2.2) retrive its state as soon as it is available; - children_states_[0] = children_nodes_[0]->GetNodeState(); - } - - // 3) if the child state is not a success: - if (children_states_[0] == BT::SUCCESS) - { - SetNodeState(BT::SUCCESS); - - // 4.2) resetting the state; - WriteState(BT::IDLE); - - std::cout << get_name() << " returning " << BT::SUCCESS << "!" << std::endl; - } - else - { - if (children_states_[0] == BT::FAILURE) - { - children_nodes_[0]->ResetColorState(); - TryIndx_++; - } - - if (children_states_[0] == BT::FAILURE && TryIndx_ < NTries_) - { - // 3.1) the node state is equal to running since I am rerunning the child - SetNodeState(BT::RUNNING); - // 3.2) state reset; - WriteState(BT::IDLE); - } - else - { - SetNodeState(children_states_[0]); - // 3.2) state reset; - WriteState(BT::IDLE); - std::cout << get_name() << " returning " << children_states_[0] << "!" << std::endl; - } - } + TryIndx_ = 0; + setStatus(BT::FAILURE); } } - else - { - // If it was halted, all the "busy" children must be halted too - std::cout << get_name() << " halted! Halting all the children..." << std::endl; - - if (children_nodes_[0]->get_type() != BT::ACTION_NODE && children_states_[0] == BT::RUNNING) - { - // if the control node was running: - // halting it; - children_nodes_[0]->Halt(); - - // sync with it (it's waiting on the semaphore); - children_nodes_[0]->tick_engine.tick(); - - std::cout << get_name() << " halting child " - << "!" << std::endl; - } - else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && - children_nodes_[0]->ReadState() == BT::RUNNING) - { - std::cout << get_name() << " trying halting child " - << "..." << std::endl; - - // if it's a action node that hasn't finished its job: - // trying to halt it: - if (children_nodes_[0]->Halt() == false) - { - // this means that, before this node could set its child state - // to "Halted", the child had already written the action outcome; - // sync with him ignoring its state; - children_nodes_[0]->tick_engine.tick(); - - std::cout << get_name() << " halting of child " - << " failed!" << std::endl; - } + break; - std::cout << get_name() << " halting of child " - << " succedeed!" << std::endl; - } - else if (children_nodes_[0]->get_type() == BT::ACTION_NODE && children_nodes_[0]->ReadState() != BT::IDLE) - { - // if it's a action node that has finished its job: - // ticking it without saving its returning state; - children_nodes_[0]->tick_engine.tick(); - } - - // updating its vector cell - children_states_[0] = BT::IDLE; + case BT::RUNNING: + { + setStatus(BT::RUNNING); + } + break; - // Resetting the node state - WriteState(BT::IDLE); + default: + { + // TODO throw? } } + + return status(); } From e3ff405b3c9c5c4b56f07087eb4818c54f6b8f9b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 8 May 2018 18:25:55 +0200 Subject: [PATCH 041/125] improve readability of the test --- gtest/gtest_tree.cpp | 932 +++++++++++++++++++++---------------------- 1 file changed, 462 insertions(+), 470 deletions(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 4b962742a..efaa0e55e 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -15,321 +15,313 @@ #include "condition_test_node.h" #include "behavior_tree_core/behavior_tree.h" +using BT::NodeStatus; + struct SimpleSequenceTest : testing::Test { - std::unique_ptr root; - std::unique_ptr action; - std::unique_ptr condition; - SimpleSequenceTest() - { - action.reset(new BT::ActionTestNode("action")); - condition.reset( new BT::ConditionTestNode("condition") ); - - root.reset( new BT::SequenceNode("seq1") ); + BT::SequenceNode root; + BT::ActionTestNode action; + BT::ConditionTestNode condition; - root->addChild(condition.get()); - root->addChild(action.get()); + SimpleSequenceTest(): + root("root_sequence"), + action("action"), + condition("condition") + { + root.addChild(&condition); + root.addChild(&action); } }; struct ComplexSequenceTest : testing::Test { - std::unique_ptr root; - std::unique_ptr action_1; - std::unique_ptr condition_1; - std::unique_ptr condition_2; + BT::SequenceNode root; + BT::ActionTestNode action_1; + BT::ConditionTestNode condition_1; + BT::ConditionTestNode condition_2; - std::unique_ptr seq_conditions; + BT::SequenceNode seq_conditions; - ComplexSequenceTest() + ComplexSequenceTest(): + root("root_sequence"), + action_1("action_1"), + condition_1("condition_1"), + condition_2("condition_2"), + seq_conditions("sequence_conditions") { - action_1.reset( new BT::ActionTestNode("action 1") ); - - condition_1.reset( new BT::ConditionTestNode("condition 1" )); - condition_2.reset( new BT::ConditionTestNode("condition 2" )); - seq_conditions.reset( new BT::SequenceNode("sequence_conditions") ); - - seq_conditions->addChild(condition_1.get()); - seq_conditions->addChild(condition_2.get()); - - root.reset( new BT::SequenceNode("root") ); - root->addChild(seq_conditions.get()); - root->addChild(action_1.get()); + root.addChild(&seq_conditions); + { + seq_conditions.addChild(&condition_1); + seq_conditions.addChild(&condition_2); + } + root.addChild(&action_1); } }; struct ComplexSequence2ActionsTest : testing::Test { - std::unique_ptr root; - std::unique_ptr action_1; - std::unique_ptr action_2; - - std::unique_ptr condition_1; - std::unique_ptr condition_2; - - std::unique_ptr seq_1; - std::unique_ptr seq_2; - - ComplexSequence2ActionsTest() + BT::SequenceNode root; + BT::ActionTestNode action_1; + BT::ActionTestNode action_2; + BT::SequenceNode seq_1; + BT::SequenceNode seq_2; + + BT::ConditionTestNode condition_1; + BT::ConditionTestNode condition_2; + + ComplexSequence2ActionsTest(): + root("root_sequence"), + action_1("action_1"), + action_2("action_2"), + seq_1("sequence_1"), + seq_2("sequence_2"), + condition_1("condition_1"), + condition_2("condition_2") { - action_1.reset( new BT::ActionTestNode("action 1") ); - action_2.reset( new BT::ActionTestNode("action 2") ); - seq_1.reset( new BT::SequenceNode("sequence_1") ); - seq_2.reset( new BT::SequenceNode("sequence_c2") ); - - condition_1.reset( new BT::ConditionTestNode("condition 1") ); - condition_2.reset( new BT::ConditionTestNode("condition 2") ); - - seq_1->addChild(condition_1.get()); - seq_1->addChild(action_1.get()); - - seq_2->addChild(condition_2.get()); - seq_2->addChild(action_2.get()); - - root.reset( new BT::SequenceNode("root") ); - root->addChild(seq_1.get()); - root->addChild(seq_2.get()); + root.addChild(&seq_1); + { + seq_1.addChild(&condition_1); + seq_1.addChild(&action_1); + } + root.addChild(&seq_2); + { + seq_2.addChild(&condition_2); + seq_2.addChild(&action_2); + } } }; struct SimpleFallbackTest : testing::Test { - std::unique_ptr root; - std::unique_ptr action; - std::unique_ptr condition; - SimpleFallbackTest() - { - action.reset( new BT::ActionTestNode("action") ); - condition.reset( new BT::ConditionTestNode("condition") ); + BT::FallbackNode root; + BT::ActionTestNode action; + BT::ConditionTestNode condition; - root.reset( new BT::FallbackNode("seq1") ); - - root->addChild(condition.get()); - root->addChild(action.get()); + SimpleFallbackTest(): + root("root_fallback"), + action("action"), + condition("condition") + { + root.addChild(&condition); + root.addChild(&action); } }; struct ComplexFallbackTest : testing::Test { - std::unique_ptr root; - std::unique_ptr action_1; - std::unique_ptr condition_1; - std::unique_ptr condition_2; + BT::FallbackNode root; + BT::ActionTestNode action_1; + BT::ConditionTestNode condition_1; + BT::ConditionTestNode condition_2; - std::unique_ptr sel_conditions; + BT::FallbackNode sel_conditions; - ComplexFallbackTest() + ComplexFallbackTest(): + root("root_fallback"), + action_1("action_1"), + condition_1("condition_1"), + condition_2("condition_2"), + sel_conditions("fallback_conditions") { - action_1.reset( new BT::ActionTestNode("action 1") ); - condition_1.reset( new BT::ConditionTestNode("condition 1") ); - condition_2.reset( new BT::ConditionTestNode("condition 2") ); - sel_conditions.reset( new BT::FallbackNode("fallback_conditions") ); - - sel_conditions->addChild(condition_1.get()); - sel_conditions->addChild(condition_2.get()); - - root.reset( new BT::FallbackNode("root") ); - root->addChild(sel_conditions.get()); - root->addChild(action_1.get()); + root.addChild(&sel_conditions); + { + sel_conditions.addChild(&condition_1); + sel_conditions.addChild(&condition_2); + } + root.addChild(&action_1); } }; struct BehaviorTreeTest : testing::Test { - std::unique_ptr root; - std::unique_ptr action_1; - std::unique_ptr condition_1; - std::unique_ptr condition_2; + BT::SequenceNode root; + BT::ActionTestNode action_1; + BT::ConditionTestNode condition_1; + BT::ConditionTestNode condition_2; - std::unique_ptr sel_conditions; + BT::FallbackNode sel_conditions; - BehaviorTreeTest() + BehaviorTreeTest(): + root("root_sequence"), + action_1("action_1"), + condition_1("condition_1"), + condition_2("condition_2"), + sel_conditions("fallback_conditions") { - action_1.reset( new BT::ActionTestNode("action 1") ); - condition_1.reset( new BT::ConditionTestNode("condition 1") ); - condition_2.reset( new BT::ConditionTestNode("condition 2") ); - sel_conditions.reset( new BT::FallbackNode("fallback_conditions") ); - - sel_conditions->addChild(condition_1.get()); - sel_conditions->addChild(condition_2.get()); - root.reset( new BT::SequenceNode("root") ); - root->addChild(sel_conditions.get()); - root->addChild(action_1.get()); + root.addChild(&sel_conditions); + { + sel_conditions.addChild(&condition_1); + sel_conditions.addChild(&condition_2); + } + root.addChild(&action_1); } }; struct SimpleSequenceWithMemoryTest : testing::Test { - std::unique_ptr root; - std::unique_ptr action; - std::unique_ptr condition; - SimpleSequenceWithMemoryTest() - { - action.reset( new BT::ActionTestNode("action") ); - condition.reset( new BT::ConditionTestNode("condition") ); + BT::SequenceNodeWithMemory root; + BT::ActionTestNode action; + BT::ConditionTestNode condition; - root.reset( new BT::SequenceNodeWithMemory("seq1") ); - - root->addChild(condition.get()); - root->addChild(action.get()); + SimpleSequenceWithMemoryTest(): + root("root_sequence"), + action("action"), + condition("condition") + { + root.addChild(&condition); + root.addChild(&action); } }; struct ComplexSequenceWithMemoryTest : testing::Test { - std::unique_ptr root; + BT::SequenceNodeWithMemory root; - std::unique_ptr action_1; - std::unique_ptr action_2; + BT::ActionTestNode action_1; + BT::ActionTestNode action_2; - std::unique_ptr condition_1; - std::unique_ptr condition_2; + BT::ConditionTestNode condition_1; + BT::ConditionTestNode condition_2; - std::unique_ptr seq_conditions; - std::unique_ptr seq_actions; + BT::SequenceNodeWithMemory seq_conditions; + BT::SequenceNodeWithMemory seq_actions; - ComplexSequenceWithMemoryTest() + ComplexSequenceWithMemoryTest(): + root("root_sequence"), + action_1("action_1"), + action_2("action_2"), + condition_1("condition_1"), + condition_2("condition_2"), + seq_conditions("sequence_conditions"), + seq_actions("sequence_actions") { - action_1.reset( new BT::ActionTestNode("action 1") ); - action_2.reset( new BT::ActionTestNode("action 2") ); - - condition_1.reset( new BT::ConditionTestNode("condition 1") ); - condition_2.reset( new BT::ConditionTestNode("condition 2") ); - seq_conditions.reset( new BT::SequenceNodeWithMemory("sequence_conditions") ); - seq_actions.reset( new BT::SequenceNodeWithMemory("sequence_actions") ); - - seq_actions->addChild(action_1.get()); - seq_actions->addChild(action_2.get()); - - seq_conditions->addChild(condition_1.get()); - seq_conditions->addChild(condition_2.get()); - - root.reset( new BT::SequenceNodeWithMemory("root") ); - root->addChild(seq_conditions.get()); - root->addChild(seq_actions.get()); + root.addChild(&seq_conditions); + { + seq_conditions.addChild(&condition_1); + seq_conditions.addChild(&condition_2); + } + root.addChild(&seq_actions); + { + seq_actions.addChild(&action_1); + seq_actions.addChild(&action_2); + } } }; struct SimpleFallbackWithMemoryTest : testing::Test { - std::unique_ptr root; - std::unique_ptr action; - std::unique_ptr condition; - SimpleFallbackWithMemoryTest() - { - action.reset( new BT::ActionTestNode("action") ); - condition.reset( new BT::ConditionTestNode("condition") ); - - root.reset( new BT::FallbackNodeWithMemory("seq1") ); + BT::FallbackNodeWithMemory root; + BT::ActionTestNode action; + BT::ConditionTestNode condition; - root->addChild(condition.get()); - root->addChild(action.get()); + SimpleFallbackWithMemoryTest(): + root("root_sequence"), + action("action"), + condition("condition") + { + root.addChild(&condition); + root.addChild(&action); } }; struct ComplexFallbackWithMemoryTest : testing::Test { - std::unique_ptr root; + BT::FallbackNodeWithMemory root; - std::unique_ptr action_1; - std::unique_ptr action_2; + BT::ActionTestNode action_1; + BT::ActionTestNode action_2; - std::unique_ptr condition_1; - std::unique_ptr condition_2; + BT::ConditionTestNode condition_1; + BT::ConditionTestNode condition_2; - std::unique_ptr fal_conditions; - std::unique_ptr fal_actions; + BT::FallbackNodeWithMemory fal_conditions; + BT::FallbackNodeWithMemory fal_actions; - ComplexFallbackWithMemoryTest() + ComplexFallbackWithMemoryTest(): + root("root_fallback"), + action_1("action_1"), + action_2("action_2"), + condition_1("condition_1"), + condition_2("condition_2"), + fal_conditions("fallback_conditions"), + fal_actions("fallback_actions") { - action_1.reset( new BT::ActionTestNode("action 1") ); - action_2.reset( new BT::ActionTestNode("action 2") ); - condition_1.reset( new BT::ConditionTestNode("condition 1") ); - condition_2.reset( new BT::ConditionTestNode("condition 2") ); - - fal_conditions.reset( new BT::FallbackNodeWithMemory("fallback_conditions") ); - fal_actions.reset( new BT::FallbackNodeWithMemory("fallback_actions") ); - - fal_actions->addChild(action_1.get()); - fal_actions->addChild(action_2.get()); - - fal_conditions->addChild(condition_1.get()); - fal_conditions->addChild(condition_2.get()); - - root.reset( new BT::FallbackNodeWithMemory("root") ); - root->addChild(fal_conditions.get()); - root->addChild(fal_actions.get()); + root.addChild(&fal_conditions); + { + fal_conditions.addChild(&condition_1); + fal_conditions.addChild(&condition_2); + } + root.addChild(&fal_actions); + { + fal_actions.addChild(&action_1); + fal_actions.addChild(&action_2); + } } }; struct SimpleParallelTest : testing::Test { - std::unique_ptr root; - std::unique_ptr action_1; - std::unique_ptr condition_1; + BT::ParallelNode root; + BT::ActionTestNode action_1; + BT::ConditionTestNode condition_1; - std::unique_ptr action_2; - std::unique_ptr condition_2; + BT::ActionTestNode action_2; + BT::ConditionTestNode condition_2; - SimpleParallelTest() + SimpleParallelTest(): + root("root_parallel",4), + action_1("action_1"), + condition_1("condition_1"), + action_2("action_2"), + condition_2("condition_2") { - action_1.reset( new BT::ActionTestNode("action 1") ); - condition_1.reset( new BT::ConditionTestNode("condition 1") ); - - action_2.reset( new BT::ActionTestNode("action 2") ); - condition_2.reset( new BT::ConditionTestNode("condition 2") ); - - root.reset( new BT::ParallelNode("par", 4) ); - - root->addChild(condition_1.get()); - root->addChild(action_1.get()); - root->addChild(condition_2.get()); - root->addChild(action_2.get()); + root.addChild(&condition_1); + root.addChild(&action_1); + root.addChild(&condition_2); + root.addChild(&action_2); } }; struct ComplexParallelTest : testing::Test { - std::unique_ptr root; - std::unique_ptr parallel_1; - std::unique_ptr parallel_2; - - std::unique_ptr action_1; - std::unique_ptr condition_1; - - std::unique_ptr action_2; - std::unique_ptr condition_2; - - std::unique_ptr action_3; - std::unique_ptr condition_3; - - ComplexParallelTest() + BT::ParallelNode root; + BT::ParallelNode parallel_1; + BT::ParallelNode parallel_2; + + BT::ActionTestNode action_1; + BT::ConditionTestNode condition_1; + + BT::ActionTestNode action_2; + BT::ConditionTestNode condition_2; + + BT::ActionTestNode action_3; + BT::ConditionTestNode condition_3; + + ComplexParallelTest(): + root("root",2), + parallel_1("par1",3), + parallel_2("par2",1), + action_1("action_1"), + condition_1("condition_1"), + action_2("action_2"), + condition_2("condition_2"), + action_3("action_3"), + condition_3("condition_3") { - action_1.reset( new BT::ActionTestNode("action 1") ); - condition_1.reset( new BT::ConditionTestNode("condition 1") ); - - action_2.reset( new BT::ActionTestNode("action 2") ); - condition_2.reset( new BT::ConditionTestNode("condition 2") ); - - action_3.reset( new BT::ActionTestNode("action 3") ); - condition_3.reset( new BT::ConditionTestNode("condition 3") ); - - root.reset( new BT::ParallelNode("root", 2) ); - parallel_1.reset( new BT::ParallelNode("par1", 3) ); - parallel_2.reset( new BT::ParallelNode("par2", 1) ); - - parallel_1->addChild(condition_1.get()); - parallel_1->addChild(action_1.get()); - parallel_1->addChild(condition_2.get()); - parallel_1->addChild(action_2.get()); - - parallel_2->addChild(condition_3.get()); - parallel_2->addChild(action_3.get()); - - root->addChild(parallel_1.get()); - root->addChild(parallel_2.get()); + root.addChild(¶llel_1); + { + parallel_1.addChild(&condition_1); + parallel_1.addChild(&action_1); + parallel_1.addChild(&condition_2); + parallel_1.addChild(&action_2); + } + root.addChild(¶llel_2); + { + parallel_2.addChild(&condition_3); + parallel_2.addChild(&action_3); + } } }; @@ -339,477 +331,477 @@ TEST_F(SimpleSequenceTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, action->status()); - ASSERT_EQ(BT::RUNNING, state); - root->halt(); + ASSERT_EQ(NodeStatus::RUNNING, action.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + root.halt(); } TEST_F(SimpleSequenceTest, ConditionTurnToFalse) { - BT::NodeStatus state = root->executeTick(); - condition->set_boolean_value(false); + BT::NodeStatus state = root.executeTick(); + condition.set_boolean_value(false); - state = root->executeTick(); - ASSERT_EQ(BT::FAILURE, state); - ASSERT_EQ(BT::HALTED, action->status()); - root->halt(); + state = root.executeTick(); + ASSERT_EQ(NodeStatus::FAILURE, state); + ASSERT_EQ(NodeStatus::HALTED, action.status()); + root.halt(); } TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::RUNNING, state); - root->halt(); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + root.halt(); } TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - state = root->executeTick(); + state = root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - state = root->executeTick(); - state = root->executeTick(); + state = root.executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::RUNNING, seq_1->status()); - ASSERT_EQ(BT::HALTED, seq_2->status()); - ASSERT_EQ(BT::HALTED, action_2->status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, seq_1.status()); + ASSERT_EQ(NodeStatus::HALTED, seq_2.status()); + ASSERT_EQ(NodeStatus::HALTED, action_2.status()); - root->halt(); + root.halt(); } TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - condition_1->set_boolean_value(false); + condition_1.set_boolean_value(false); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::FAILURE, state); - ASSERT_EQ(BT::HALTED, action_1->status()); - root->halt(); + ASSERT_EQ(NodeStatus::FAILURE, state); + ASSERT_EQ(NodeStatus::HALTED, action_1.status()); + root.halt(); } TEST_F(ComplexSequenceTest, ComplexSequenceConditions2ToFalse) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - condition_2->set_boolean_value(false); + condition_2.set_boolean_value(false); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::FAILURE, state); - ASSERT_EQ(BT::HALTED, action_1->status()); - root->halt(); + ASSERT_EQ(NodeStatus::FAILURE, state); + ASSERT_EQ(NodeStatus::HALTED, action_1.status()); + root.halt(); } TEST_F(SimpleFallbackTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - condition->set_boolean_value(true); - BT::NodeStatus state = root->executeTick(); + condition.set_boolean_value(true); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::IDLE, action->status()); - ASSERT_EQ(BT::SUCCESS, state); - root->halt(); + ASSERT_EQ(NodeStatus::IDLE, action.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); + root.halt(); } TEST_F(SimpleFallbackTest, ConditionToFalse) { - condition->set_boolean_value(false); + condition.set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); - condition->set_boolean_value(true); + BT::NodeStatus state = root.executeTick(); + condition.set_boolean_value(true); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::SUCCESS, state); - ASSERT_EQ(BT::HALTED, action->status()); - root->halt(); + ASSERT_EQ(NodeStatus::SUCCESS, state); + ASSERT_EQ(NodeStatus::HALTED, action.status()); + root.halt(); } TEST_F(ComplexFallbackTest, Condition1ToTrue) { - condition_1->set_boolean_value(false); - condition_2->set_boolean_value(false); + condition_1.set_boolean_value(false); + condition_2.set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - condition_1->set_boolean_value(true); + condition_1.set_boolean_value(true); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::SUCCESS, state); + ASSERT_EQ(NodeStatus::SUCCESS, state); - ASSERT_EQ(BT::HALTED, action_1->status()); - root->halt(); + ASSERT_EQ(NodeStatus::HALTED, action_1.status()); + root.halt(); } TEST_F(ComplexFallbackTest, Condition2ToTrue) { - condition_1->set_boolean_value(false); - condition_2->set_boolean_value(false); + condition_1.set_boolean_value(false); + condition_2.set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - condition_2->set_boolean_value(true); + condition_2.set_boolean_value(true); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::SUCCESS, state); - ASSERT_EQ(BT::HALTED, action_1->status()); - root->halt(); + ASSERT_EQ(NodeStatus::SUCCESS, state); + ASSERT_EQ(NodeStatus::HALTED, action_1.status()); + root.halt(); } TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) { - condition_1->set_boolean_value(false); - condition_2->set_boolean_value(true); + condition_1.set_boolean_value(false); + condition_2.set_boolean_value(true); - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - root->halt(); + root.halt(); } TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) { - condition_2->set_boolean_value(false); - condition_1->set_boolean_value(true); + condition_2.set_boolean_value(false); + condition_1.set_boolean_value(true); - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action_1->status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - root->halt(); + root.halt(); } TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - ASSERT_EQ(BT::RUNNING, action->status()); - ASSERT_EQ(BT::RUNNING, state); - root->halt(); + ASSERT_EQ(NodeStatus::RUNNING, action.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + root.halt(); } TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - condition->set_boolean_value(false); + condition.set_boolean_value(false); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action->status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action.status()); - root->halt(); + root.halt(); } TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::IDLE, action_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - condition_1->set_boolean_value(false); + condition_1.set_boolean_value(false); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::IDLE, action_2->status()); - ASSERT_EQ(BT::RUNNING, state); - root->halt(); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + root.halt(); } TEST_F(ComplexSequenceWithMemoryTest, Conditions2ToFalse) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - condition_2->set_boolean_value(false); + condition_2.set_boolean_value(false); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::IDLE, action_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(ComplexSequenceWithMemoryTest, Action1Done) { - root->executeTick(); + root.executeTick(); - condition_2->set_boolean_value(false); + condition_2.set_boolean_value(false); - root->executeTick(); + root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(1000)); - root->executeTick(); + root.executeTick(); - ASSERT_EQ(BT::RUNNING, action_2->status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); - root->halt(); + root.halt(); } TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) { std::cout << "Ticking the root node !" << std::endl << std::endl; // Ticking the root node - condition->set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); + condition.set_boolean_value(false); + BT::NodeStatus state = root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - ASSERT_EQ(BT::RUNNING, action->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) { - condition->set_boolean_value(false); + condition.set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); - condition->set_boolean_value(true); + BT::NodeStatus state = root.executeTick(); + condition.set_boolean_value(true); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, state); - ASSERT_EQ(BT::RUNNING, action->status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action.status()); - root->halt(); + root.halt(); } TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::IDLE, action_1->status()); - ASSERT_EQ(BT::IDLE, action_2->status()); - ASSERT_EQ(BT::SUCCESS, state); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); - root->halt(); + root.halt(); } TEST_F(ComplexFallbackWithMemoryTest, Condition1False) { - condition_1->set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); + condition_1.set_boolean_value(false); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::IDLE, action_1->status()); - ASSERT_EQ(BT::IDLE, action_2->status()); - ASSERT_EQ(BT::SUCCESS, state); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); - root->halt(); + root.halt(); } TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) { - condition_1->set_boolean_value(false); - condition_2->set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); + condition_1.set_boolean_value(false); + condition_2.set_boolean_value(false); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::IDLE, action_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) { - condition_1->set_boolean_value(false); - condition_2->set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); - condition_1->set_boolean_value(true); + condition_1.set_boolean_value(false); + condition_2.set_boolean_value(false); + BT::NodeStatus state = root.executeTick(); + condition_1.set_boolean_value(true); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::IDLE, action_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) { - condition_1->set_boolean_value(false); + condition_1.set_boolean_value(false); - condition_2->set_boolean_value(false); + condition_2.set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - condition_2->set_boolean_value(true); + condition_2.set_boolean_value(true); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::IDLE, action_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) { - action_1->set_boolean_value(false); - condition_1->set_boolean_value(false); - condition_2->set_boolean_value(false); + action_1.set_boolean_value(false); + condition_1.set_boolean_value(false); + condition_2.set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - state = root->executeTick(); + state = root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::IDLE, action_1->status()); - ASSERT_EQ(BT::RUNNING, action_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(SimpleParallelTest, ConditionsTrue) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::IDLE, condition_1->status()); - ASSERT_EQ(BT::IDLE, condition_2->status()); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::RUNNING, action_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(SimpleParallelTest, Threshold_3) { - root->setThresholdM(3); - action_2->set_time(200); - root->executeTick(); + root.setThresholdM(3); + action_2.set_time(200); + root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::IDLE, condition_1->status()); - ASSERT_EQ(BT::IDLE, condition_2->status()); - ASSERT_EQ(BT::IDLE, action_1->status()); - ASSERT_EQ(BT::HALTED, action_2->status()); - ASSERT_EQ(BT::SUCCESS, state); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::HALTED, action_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); - root->halt(); + root.halt(); } TEST_F(SimpleParallelTest, Threshold_1) { - root->setThresholdM(1); - BT::NodeStatus state = root->executeTick(); + root.setThresholdM(1); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::IDLE, condition_1->status()); - ASSERT_EQ(BT::IDLE, condition_2->status()); - ASSERT_EQ(BT::IDLE, action_1->status()); - ASSERT_EQ(BT::IDLE, action_2->status()); - ASSERT_EQ(BT::SUCCESS, state); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); - root->halt(); + root.halt(); } TEST_F(ComplexParallelTest, ConditionsTrue) { - BT::NodeStatus state = root->executeTick(); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::IDLE, condition_1->status()); - ASSERT_EQ(BT::IDLE, condition_2->status()); - ASSERT_EQ(BT::IDLE, condition_3->status()); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::RUNNING, action_2->status()); - ASSERT_EQ(BT::IDLE, action_3->status()); - ASSERT_EQ(BT::RUNNING, parallel_1->status()); - ASSERT_EQ(BT::IDLE, parallel_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, parallel_1.status()); + ASSERT_EQ(NodeStatus::IDLE, parallel_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(ComplexParallelTest, Condition3False) { - condition_3->set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); + condition_3.set_boolean_value(false); + BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(BT::IDLE, condition_1->status()); - ASSERT_EQ(BT::IDLE, condition_2->status()); - ASSERT_EQ(BT::IDLE, condition_3->status()); - ASSERT_EQ(BT::RUNNING, action_1->status()); - ASSERT_EQ(BT::RUNNING, action_2->status()); - ASSERT_EQ(BT::RUNNING, action_3->status()); - ASSERT_EQ(BT::RUNNING, parallel_1->status()); - ASSERT_EQ(BT::RUNNING, parallel_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, parallel_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, parallel_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - root->halt(); + root.halt(); } TEST_F(ComplexParallelTest, Condition3FalseAction1Done) { - action_2->set_time(10); - action_3->set_time(10); + action_2.set_time(10); + action_3.set_time(10); - condition_3->set_boolean_value(false); - BT::NodeStatus state = root->executeTick(); + condition_3.set_boolean_value(false); + BT::NodeStatus state = root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(500)); - ASSERT_EQ(BT::IDLE, condition_1->status()); - ASSERT_EQ(BT::IDLE, condition_2->status()); - ASSERT_EQ(BT::IDLE, condition_3->status()); - ASSERT_EQ(BT::SUCCESS, action_1->status()); // success not read yet by the node parallel_1 - ASSERT_EQ(BT::RUNNING, parallel_1->status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_3.status()); + ASSERT_EQ(NodeStatus::SUCCESS, action_1.status()); // success not read yet by the node parallel_1 + ASSERT_EQ(NodeStatus::RUNNING, parallel_1.status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::IDLE, action_1->status()); - ASSERT_EQ(BT::IDLE, parallel_1->status()); - ASSERT_EQ(BT::HALTED, action_2->status()); - ASSERT_EQ(BT::RUNNING, action_3->status()); - ASSERT_EQ(BT::RUNNING, parallel_2->status()); - ASSERT_EQ(BT::RUNNING, state); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, parallel_1.status()); + ASSERT_EQ(NodeStatus::HALTED, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, parallel_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); - state = root->executeTick(); + state = root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(1500)); - state = root->executeTick(); + state = root.executeTick(); - ASSERT_EQ(BT::IDLE, parallel_2->status()); - ASSERT_EQ(BT::IDLE, action_1->status()); - ASSERT_EQ(BT::IDLE, parallel_1->status()); - ASSERT_EQ(BT::IDLE, action_3->status()); - ASSERT_EQ(BT::IDLE, parallel_2->status()); - ASSERT_EQ(BT::SUCCESS, state); + ASSERT_EQ(NodeStatus::IDLE, parallel_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, parallel_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, parallel_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); - root->halt(); + root.halt(); } int main(int argc, char** argv) From 8ff609c59ba16da7ac502ef33bdf9d7c7b7c29a0 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 8 May 2018 18:39:47 +0200 Subject: [PATCH 042/125] remove redundant [setStatus(status)] before [return status] --- src/fallback_node.cpp | 5 +---- src/fallback_node_with_memory.cpp | 5 +---- src/parallel_node.cpp | 3 --- src/sequence_node.cpp | 5 +---- src/sequence_node_with_memory.cpp | 11 ++++------- src/tree_node.cpp | 4 +++- 6 files changed, 10 insertions(+), 23 deletions(-) diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index bfc933d5b..e0a58ce83 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -27,10 +27,9 @@ BT::NodeStatus BT::FallbackNode::tick() for (unsigned i = 0; i < N_of_children; i++) { - auto& child_node = children_nodes_[i]; + TreeNode* child_node = children_nodes_[i]; const NodeStatus child_status = child_node->executeTick(); - child_node->setStatus(child_status); // Ponderate on which status to send to the parent if (child_status != BT::FAILURE) @@ -42,7 +41,6 @@ BT::NodeStatus BT::FallbackNode::tick() // If the child status is not failure, halt the next children and return the status to your parent. DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); haltChildren(i + 1); - setStatus(child_status); return child_status; } else @@ -53,7 +51,6 @@ BT::NodeStatus BT::FallbackNode::tick() { // If the child status is failure, and it is the last child to be ticked, // then the sequence has failed. - setStatus(BT::FAILURE); return BT::FAILURE; } } diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 4fceda944..5a48802eb 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -28,10 +28,9 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() // Routing the ticks according to the fallback node's (with memory) logic: while (current_child_idx_ < N_of_children) { - auto& current_child_node = children_nodes_[current_child_idx_]; + TreeNode* current_child_node = children_nodes_[current_child_idx_]; const NodeStatus child_status = current_child_node->executeTick(); - current_child_node->setStatus(child_status); if (child_status == BT::SUCCESS || child_status == BT::FAILURE) { @@ -48,7 +47,6 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() { current_child_idx_ = 0; } - setStatus(child_status); return child_status; } else if (current_child_idx_ != N_of_children - 1) @@ -65,7 +63,6 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() // if it the last child and it has returned failure, reset the memory current_child_idx_ = 0; } - setStatus(child_status); return child_status; } } diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 19dc461b1..15fd1a781 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -33,7 +33,6 @@ BT::NodeStatus BT::ParallelNode::tick() DEBUG_STDOUT(name() << "TICKING " << child_node); NodeStatus child_status = child_node->executeTick(); - child_node->setStatus(child_status); switch (child_status) { @@ -44,7 +43,6 @@ BT::NodeStatus BT::ParallelNode::tick() success_childred_num_ = 0; failure_childred_num_ = 0; haltChildren(0); // halts all running children. The execution is done. - setStatus(child_status); return child_status; } break; @@ -58,7 +56,6 @@ BT::NodeStatus BT::ParallelNode::tick() success_childred_num_ = 0; failure_childred_num_ = 0; haltChildren(0); // halts all running children. The execution is hopeless. - setStatus(child_status); return child_status; } break; diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 1513d934f..673c187bf 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -26,10 +26,9 @@ BT::NodeStatus BT::SequenceNode::tick() for (unsigned int i = 0; i < N_of_children; i++) { - auto& child_node = children_nodes_[i]; + TreeNode* child_node = children_nodes_[i]; const NodeStatus child_status = child_node->executeTick(); - child_node->setStatus(child_status); // Ponderate on which status to send to the parent if (child_status != BT::SUCCESS) @@ -42,7 +41,6 @@ BT::NodeStatus BT::SequenceNode::tick() DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); haltChildren(i + 1); - setStatus(child_status); return child_status; } else @@ -54,7 +52,6 @@ BT::NodeStatus BT::SequenceNode::tick() { // If the child status is success, and it is the last child to be ticked, // then the sequence has succeeded. - setStatus(BT::SUCCESS); return BT::SUCCESS; } } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 83a9bc0de..052be07f8 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -23,20 +23,19 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() DEBUG_STDOUT(name() << " ticked, memory counter: " << current_child_idx_); // Vector size initialization. N_of_children_ could change at runtime if you edit the tree - const unsigned N_of_children_ = children_nodes_.size(); + const unsigned N_of_children = children_nodes_.size(); // Routing the ticks according to the sequence node's (with memory) logic: - while (current_child_idx_ < N_of_children_) + while (current_child_idx_ < N_of_children) { /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. We want this thread detached so we can cancel its execution (when the action no longer receive ticks). Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. */ - const auto& current_child_node = children_nodes_[current_child_idx_]; + TreeNode* current_child_node = children_nodes_[current_child_idx_]; const NodeStatus child_status = current_child_node->executeTick(); - current_child_node->setStatus(child_status); if (child_status == BT::SUCCESS || child_status == BT::FAILURE) { @@ -53,10 +52,9 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() { current_child_idx_ = 0; } - setStatus(child_status); return child_status; } - else if (current_child_idx_ != N_of_children_ - 1) + else if (current_child_idx_ != N_of_children - 1) { // If the child status is success, continue to the next child // (if any, hence if(current_child_ != N_of_children_ - 1) ) in the for loop (if any). @@ -70,7 +68,6 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() // if it the last child and it has returned SUCCESS, reset the memory current_child_idx_ = 0; } - setStatus(child_status); return child_status; } } diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 0dc54734d..6be343482 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -19,7 +19,9 @@ BT::TreeNode::TreeNode(std::string name) : name_(name), status_(BT::IDLE) BT::NodeStatus BT::TreeNode::executeTick() { - return tick(); + const NodeStatus status = tick(); + setStatus(status); + return status; } void BT::TreeNode::setStatus(NodeStatus new_status) From 4a6cc7a32ae428dbc2267ff7cc80f576d55f09aa Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 9 May 2018 12:27:57 +0200 Subject: [PATCH 043/125] multiple changes, read description... 1) BT::IDLE and BT::HALTED have been merged is a single status. 2) Changed transition to IDLE in control node. Don't change a FAILURE or SUCCESS to IDLE until the Sequence of Fallback finished. 3) Unit test extended accordingly. If the ControlNode invokes setStatus(IDLE) as soon as a child node returns FAILURE or SUCCESS, it is impossible of very hard for a monitoring system to understand what happened. --- gtest/gtest_tree.cpp | 228 +++++++++++++++++------ gtest/src/action_test_node.cpp | 8 +- include/behavior_tree_core/action_node.h | 4 +- include/behavior_tree_core/tree_node.h | 1 - src/action_node.cpp | 16 +- src/control_node.cpp | 2 +- src/decorator_node.cpp | 2 +- src/example.cpp | 6 +- src/fallback_node.cpp | 50 ++--- src/fallback_node_with_memory.cpp | 19 +- src/sequence_node.cpp | 12 +- src/sequence_node_with_memory.cpp | 28 +-- src/tree_node.cpp | 2 +- 13 files changed, 249 insertions(+), 129 deletions(-) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index efaa0e55e..9b3bfd18d 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -114,19 +114,19 @@ struct ComplexFallbackTest : testing::Test BT::ConditionTestNode condition_1; BT::ConditionTestNode condition_2; - BT::FallbackNode sel_conditions; + BT::FallbackNode fal_conditions; ComplexFallbackTest(): root("root_fallback"), action_1("action_1"), condition_1("condition_1"), condition_2("condition_2"), - sel_conditions("fallback_conditions") + fal_conditions("fallback_conditions") { - root.addChild(&sel_conditions); + root.addChild(&fal_conditions); { - sel_conditions.addChild(&condition_1); - sel_conditions.addChild(&condition_2); + fal_conditions.addChild(&condition_1); + fal_conditions.addChild(&condition_2); } root.addChild(&action_1); } @@ -139,20 +139,20 @@ struct BehaviorTreeTest : testing::Test BT::ConditionTestNode condition_1; BT::ConditionTestNode condition_2; - BT::FallbackNode sel_conditions; + BT::FallbackNode fal_conditions; BehaviorTreeTest(): root("root_sequence"), action_1("action_1"), condition_1("condition_1"), condition_2("condition_2"), - sel_conditions("fallback_conditions") + fal_conditions("fallback_conditions") { - root.addChild(&sel_conditions); + root.addChild(&fal_conditions); { - sel_conditions.addChild(&condition_1); - sel_conditions.addChild(&condition_2); + fal_conditions.addChild(&condition_1); + fal_conditions.addChild(&condition_2); } root.addChild(&action_1); } @@ -196,7 +196,6 @@ struct ComplexSequenceWithMemoryTest : testing::Test seq_conditions("sequence_conditions"), seq_actions("sequence_actions") { - root.addChild(&seq_conditions); { seq_conditions.addChild(&condition_1); @@ -345,7 +344,8 @@ TEST_F(SimpleSequenceTest, ConditionTurnToFalse) state = root.executeTick(); ASSERT_EQ(NodeStatus::FAILURE, state); - ASSERT_EQ(NodeStatus::HALTED, action.status()); + ASSERT_EQ(NodeStatus::IDLE, condition.status()); + ASSERT_EQ(NodeStatus::IDLE, action.status()); root.halt(); } @@ -353,8 +353,11 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) { BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); root.halt(); } @@ -364,15 +367,28 @@ TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) state = root.executeTick(); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, seq_1.status()); + ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, seq_2.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + std::this_thread::sleep_for(std::chrono::milliseconds(500)); state = root.executeTick(); - state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); - ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - ASSERT_EQ(NodeStatus::RUNNING, seq_1.status()); - ASSERT_EQ(NodeStatus::HALTED, seq_2.status()); - ASSERT_EQ(NodeStatus::HALTED, action_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, seq_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, seq_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + + state = root.executeTick(); + + // TODO: what is a reasonable behavior in this case? root.halt(); } @@ -386,7 +402,10 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse) state = root.executeTick(); ASSERT_EQ(NodeStatus::FAILURE, state); - ASSERT_EQ(NodeStatus::HALTED, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); root.halt(); } @@ -399,7 +418,10 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditions2ToFalse) state = root.executeTick(); ASSERT_EQ(NodeStatus::FAILURE, state); - ASSERT_EQ(NodeStatus::HALTED, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); root.halt(); } @@ -410,8 +432,9 @@ TEST_F(SimpleFallbackTest, ConditionTrue) condition.set_boolean_value(true); BT::NodeStatus state = root.executeTick(); - ASSERT_EQ(NodeStatus::IDLE, action.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); + ASSERT_EQ(NodeStatus::IDLE, condition.status()); + ASSERT_EQ(NodeStatus::IDLE, action.status()); root.halt(); } @@ -425,7 +448,8 @@ TEST_F(SimpleFallbackTest, ConditionToFalse) state = root.executeTick(); ASSERT_EQ(NodeStatus::SUCCESS, state); - ASSERT_EQ(NodeStatus::HALTED, action.status()); + ASSERT_EQ(NodeStatus::IDLE, condition.status()); + ASSERT_EQ(NodeStatus::IDLE, action.status()); root.halt(); } @@ -436,13 +460,21 @@ TEST_F(ComplexFallbackTest, Condition1ToTrue) BT::NodeStatus state = root.executeTick(); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + condition_1.set_boolean_value(true); state = root.executeTick(); ASSERT_EQ(NodeStatus::SUCCESS, state); - - ASSERT_EQ(NodeStatus::HALTED, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); root.halt(); } @@ -453,12 +485,21 @@ TEST_F(ComplexFallbackTest, Condition2ToTrue) BT::NodeStatus state = root.executeTick(); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + condition_2.set_boolean_value(true); state = root.executeTick(); ASSERT_EQ(NodeStatus::SUCCESS, state); - ASSERT_EQ(NodeStatus::HALTED, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); root.halt(); } @@ -470,6 +511,9 @@ TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) BT::NodeStatus state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::SUCCESS, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); root.halt(); @@ -483,6 +527,9 @@ TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) BT::NodeStatus state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::SUCCESS, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); root.halt(); @@ -490,13 +537,12 @@ TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) TEST_F(SimpleSequenceWithMemoryTest, ConditionTrue) { - std::cout << "Ticking the root node !" << std::endl << std::endl; - // Ticking the root node BT::NodeStatus state = root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - ASSERT_EQ(NodeStatus::RUNNING, action.status()); ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::SUCCESS, condition.status()); + ASSERT_EQ(NodeStatus::RUNNING, action.status()); root.halt(); } @@ -504,11 +550,15 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) { BT::NodeStatus state = root.executeTick(); - condition.set_boolean_value(false); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::SUCCESS, condition.status()); + ASSERT_EQ(NodeStatus::RUNNING, action.status()); + condition.set_boolean_value(false); state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::SUCCESS, condition.status()); ASSERT_EQ(NodeStatus::RUNNING, action.status()); root.halt(); @@ -518,24 +568,33 @@ TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) { BT::NodeStatus state = root.executeTick(); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::RUNNING, state); root.halt(); } -TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) +TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFase) { BT::NodeStatus state = root.executeTick(); condition_1.set_boolean_value(false); - state = root.executeTick(); - + // change in condition_1 does not affect the state of the tree, + // since the seq_conditions was executed already + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::RUNNING, state); + root.halt(); } @@ -544,41 +603,69 @@ TEST_F(ComplexSequenceWithMemoryTest, Conditions2ToFalse) BT::NodeStatus state = root.executeTick(); condition_2.set_boolean_value(false); - state = root.executeTick(); - + // change in condition_2 does not affect the state of the tree, + // since the seq_conditions was executed already + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::RUNNING, state); root.halt(); } -TEST_F(ComplexSequenceWithMemoryTest, Action1Done) +TEST_F(ComplexSequenceWithMemoryTest, Action1DoneSeq) { root.executeTick(); condition_2.set_boolean_value(false); - root.executeTick(); - std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + + // change in condition_2 does not affect the state of the tree, + // since the seq_conditions was executed already + ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + + std::this_thread::sleep_for(std::chrono::milliseconds(400)); root.executeTick(); + ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status()); + ASSERT_EQ(NodeStatus::SUCCESS, action_1.status()); ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + std::this_thread::sleep_for(std::chrono::milliseconds(400)); + root.executeTick(); + + ASSERT_EQ(NodeStatus::SUCCESS, root.status()); + ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, seq_actions.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + root.halt(); } TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) { - std::cout << "Ticking the root node !" << std::endl << std::endl; - // Ticking the root node condition.set_boolean_value(false); BT::NodeStatus state = root.executeTick(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - ASSERT_EQ(NodeStatus::RUNNING, action.status()); ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::FAILURE, condition.status()); + ASSERT_EQ(NodeStatus::RUNNING, action.status()); root.halt(); } @@ -586,13 +673,17 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) { condition.set_boolean_value(false); - BT::NodeStatus state = root.executeTick(); - condition.set_boolean_value(true); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::FAILURE, condition.status()); + ASSERT_EQ(NodeStatus::RUNNING, action.status()); + + condition.set_boolean_value(true); state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::FAILURE, condition.status()); ASSERT_EQ(NodeStatus::RUNNING, action.status()); root.halt(); @@ -602,9 +693,13 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) { BT::NodeStatus state = root.executeTick(); + ASSERT_EQ(NodeStatus::SUCCESS, state); + ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, fal_actions.status()); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::SUCCESS, state); root.halt(); } @@ -614,9 +709,13 @@ TEST_F(ComplexFallbackWithMemoryTest, Condition1False) condition_1.set_boolean_value(false); BT::NodeStatus state = root.executeTick(); + ASSERT_EQ(NodeStatus::SUCCESS, state); + ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::IDLE, fal_actions.status()); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::SUCCESS, state); root.halt(); } @@ -627,9 +726,13 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) condition_2.set_boolean_value(false); BT::NodeStatus state = root.executeTick(); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::RUNNING, state); root.halt(); } @@ -639,13 +742,17 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) condition_1.set_boolean_value(false); condition_2.set_boolean_value(false); BT::NodeStatus state = root.executeTick(); - condition_1.set_boolean_value(true); + condition_1.set_boolean_value(true); state = root.executeTick(); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::RUNNING, state); root.halt(); } @@ -653,18 +760,19 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) { condition_1.set_boolean_value(false); - condition_2.set_boolean_value(false); - BT::NodeStatus state = root.executeTick(); condition_2.set_boolean_value(true); - state = root.executeTick(); + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::RUNNING, state); root.halt(); } @@ -681,9 +789,13 @@ TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) std::this_thread::sleep_for(std::chrono::milliseconds(500)); state = root.executeTick(); - ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status()); + ASSERT_EQ(NodeStatus::FAILURE, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); root.halt(); } @@ -712,7 +824,7 @@ TEST_F(SimpleParallelTest, Threshold_3) ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::HALTED, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); root.halt(); @@ -785,7 +897,7 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, parallel_1.status()); - ASSERT_EQ(NodeStatus::HALTED, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); ASSERT_EQ(NodeStatus::RUNNING, action_3.status()); ASSERT_EQ(NodeStatus::RUNNING, parallel_2.status()); ASSERT_EQ(NodeStatus::RUNNING, state); diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 50ead49ce..7d1913895 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -28,12 +28,12 @@ BT::ActionTestNode::~ActionTestNode() BT::NodeStatus BT::ActionTestNode::tick() { int i = 0; - while (status() != BT::HALTED && i++ < time_) + while (status() != BT::IDLE && i++ < time_) { DEBUG_STDOUT(" Action " << name() << "running! Thread id:" << std::this_thread::get_id()); std::this_thread::sleep_for(std::chrono::milliseconds(100)); } - if (status() != BT::HALTED) + if (status() != BT::IDLE) { if (boolean_value_) { @@ -48,13 +48,13 @@ BT::NodeStatus BT::ActionTestNode::tick() } else { - return BT::HALTED; + return BT::IDLE; } } void BT::ActionTestNode::halt() { - setStatus(BT::HALTED); + setStatus(BT::IDLE); DEBUG_STDOUT("HALTED state set!"); } diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 4b54cb8e1..98d519a9c 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -94,13 +94,13 @@ class ActionNode : public ActionNodeBase // This method MUST to be overriden by the user. virtual NodeStatus tick() override { - return BT::HALTED; + return BT::IDLE; } // This method MUST to be overriden by the user. virtual void halt() override { - setStatus(BT::HALTED); + setStatus(BT::IDLE); } void stopAndJoinThread(); diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index fa08c5c63..4be0a4ff2 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -59,7 +59,6 @@ enum NodeStatus SUCCESS, FAILURE, IDLE, - HALTED, EXIT }; diff --git a/src/action_node.cpp b/src/action_node.cpp index 889d26530..1302b334d 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -28,7 +28,7 @@ BT::NodeStatus BT::SimpleActionNode::tick() { NodeStatus prev_status = status(); - if (prev_status == BT::IDLE || prev_status == BT::HALTED) + if (prev_status == BT::IDLE || prev_status == BT::IDLE) { setStatus(BT::RUNNING); prev_status = BT::RUNNING; @@ -68,10 +68,8 @@ void BT::ActionNode::waitForTick() // check this again because the tick_engine_ could be // notified from the method stopAndJoinThread if (loop_.load()) - { - setStatus(BT::RUNNING); - BT::NodeStatus status = tick(); - setStatus(status); + { + setStatus( tick() ); } } } @@ -79,13 +77,13 @@ void BT::ActionNode::waitForTick() BT::NodeStatus BT::ActionNode::executeTick() { NodeStatus stat = status(); + tick_engine_.notify(); - if (stat == BT::IDLE || stat == BT::HALTED) + if (stat == BT::IDLE) { - DEBUG_STDOUT("NEEDS TO TICK " << name()); - tick_engine_.notify(); - stat = waitValidStatus(); + setStatus(BT::RUNNING); } + stat = waitValidStatus(); return stat; } diff --git a/src/control_node.cpp b/src/control_node.cpp index 74682ee24..307219090 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -43,7 +43,7 @@ void BT::ControlNode::halt() { DEBUG_STDOUT("HALTING: " << name()); haltChildren(0); - setStatus(BT::HALTED); + setStatus(BT::IDLE); } const std::vector& BT::ControlNode::children() const diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 68f9f209e..2aeb73696 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -33,7 +33,7 @@ void BT::DecoratorNode::halt() { DEBUG_STDOUT("HALTING: " << name()); haltChild(); - setStatus(BT::HALTED); + setStatus(BT::IDLE); } const BT::TreeNode* BT::DecoratorNode::child() const diff --git a/src/example.cpp b/src/example.cpp index e0c6c89d6..44414f12d 100644 --- a/src/example.cpp +++ b/src/example.cpp @@ -39,21 +39,21 @@ BT::ReturnStatus MyAction::Tick() std::this_thread::sleep_for(std::chrono::milliseconds(500)); if (is_halted()) { - return BT::HALTED; + return BT::IDLE; } std::cout << "The Action is doing some others operations" << std::endl; std::this_thread::sleep_for(std::chrono::milliseconds(500)); if (is_halted()) { - return BT::HALTED; + return BT::IDLE; } std::cout << "The Action is doing more operations" << std::endl; std::this_thread::sleep_for(std::chrono::milliseconds(500)); if (is_halted()) { - return BT::HALTED; + return BT::IDLE; } std::cout << "The Action has succeeded" << std::endl; diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index e0a58ce83..40786e630 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -19,40 +19,44 @@ BT::FallbackNode::FallbackNode(std::string name) : ControlNode::ControlNode(name BT::NodeStatus BT::FallbackNode::tick() { - { - // gets the number of children. The number could change if, at runtime, one edits the tree. - const unsigned N_of_children = children_nodes_.size(); + // gets the number of children. The number could change if, at runtime, one edits the tree. + const unsigned N_of_children = children_nodes_.size(); - // Routing the ticks according to the fallback node's logic: + // Routing the ticks according to the fallback node's logic: - for (unsigned i = 0; i < N_of_children; i++) - { - TreeNode* child_node = children_nodes_[i]; + for (unsigned i = 0; i < N_of_children; i++) + { + TreeNode* child_node = children_nodes_[i]; - const NodeStatus child_status = child_node->executeTick(); + const NodeStatus child_status = child_node->executeTick(); - // Ponderate on which status to send to the parent - if (child_status != BT::FAILURE) + // Ponderate on which status to send to the parent + if (child_status != BT::FAILURE) + { + if (child_status == BT::SUCCESS) { - if (child_status == BT::SUCCESS) + for (unsigned t=0; t<=i; t++) { - child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned success. + children_nodes_[t]->setStatus(BT::IDLE); } - // If the child status is not failure, halt the next children and return the status to your parent. - DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); - haltChildren(i + 1); - return child_status; } - else + // If the child status is not failure, halt the next children and return the status to your parent. + DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); + haltChildren(i + 1); + return child_status; + } + else + { + // the child returned failure. + if (i == N_of_children - 1) { - // the child returned failure. - child_node->setStatus(BT::IDLE); - if (i == N_of_children - 1) + // If the child status is failure, and it is the last child to be ticked, + // then the sequence has failed. + for (unsigned t=0; t<=i; t++) { - // If the child status is failure, and it is the last child to be ticked, - // then the sequence has failed. - return BT::FAILURE; + children_nodes_[t]->setStatus(BT::IDLE); } + return BT::FAILURE; } } } diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 5a48802eb..148f5afcf 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -32,19 +32,16 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() const NodeStatus child_status = current_child_node->executeTick(); - if (child_status == BT::SUCCESS || child_status == BT::FAILURE) - { - // the child goes in idle if it has returned success or failure. - current_child_node->setStatus(BT::IDLE); - } - if (child_status != BT::FAILURE) { // If the child status is not success, return the status DEBUG_STDOUT("the status of: " << name() << " becomes " << child_status); - if (child_status == BT::SUCCESS && - (reset_policy_ == BT::ON_SUCCESS || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) + if (child_status == BT::SUCCESS && reset_policy_ != BT::ON_FAILURE) { + for (unsigned t=0; t<=current_child_idx_; t++) + { + children_nodes_[t]->setStatus(BT::IDLE); + } current_child_idx_ = 0; } return child_status; @@ -58,8 +55,12 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() else { // If it the last child. - if (child_status == BT::FAILURE) + if (child_status == BT::FAILURE && reset_policy_ != BT::ON_SUCCESS ) { + for (unsigned t=0; t<=current_child_idx_; t++) + { + children_nodes_[t]->setStatus(BT::IDLE); + } // if it the last child and it has returned failure, reset the memory current_child_idx_ = 0; } diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 673c187bf..51e4d0f3f 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -36,7 +36,10 @@ BT::NodeStatus BT::SequenceNode::tick() // If the child status is not success, halt the next children and return the status to your parent. if (child_status == BT::FAILURE) { - child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned failure. + for(unsigned t=0; t<=i; t++) + { + children_nodes_[t]->setStatus( BT::IDLE ); + } } DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); @@ -45,13 +48,14 @@ BT::NodeStatus BT::SequenceNode::tick() } else { - // the child returned success. - child_node->setStatus(BT::IDLE); - if (i == N_of_children - 1) { // If the child status is success, and it is the last child to be ticked, // then the sequence has succeeded. + for(auto &ch: children_nodes_) + { + ch->setStatus( BT::IDLE ); + } return BT::SUCCESS; } } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 052be07f8..af5fc41c5 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -20,14 +20,14 @@ BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolicy BT::NodeStatus BT::SequenceNodeWithMemory::tick() { - DEBUG_STDOUT(name() << " ticked, memory counter: " << current_child_idx_); - // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children = children_nodes_.size(); // Routing the ticks according to the sequence node's (with memory) logic: while (current_child_idx_ < N_of_children) { + DEBUG_STDOUT(name() << " ticked, memory counter: " << current_child_idx_); + /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. We want this thread detached so we can cancel its execution (when the action no longer receive ticks). Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. @@ -37,24 +37,22 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() const NodeStatus child_status = current_child_node->executeTick(); - if (child_status == BT::SUCCESS || child_status == BT::FAILURE) - { - // the child goes in idle if it has returned success or failure. - current_child_node->setStatus(BT::IDLE); - } - if (child_status != BT::SUCCESS) { // If the child status is not success, return the status DEBUG_STDOUT("the status of: " << name() << " becomes " << child_status); - if (child_status == BT::FAILURE && - (reset_policy_ == BT::ON_FAILURE || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE)) - { + + if (child_status == BT::FAILURE && reset_policy_ != BT::ON_SUCCESS ) + { + for (unsigned t=0; t<=current_child_idx_; t++) + { + children_nodes_[t]->setStatus(BT::IDLE); + } current_child_idx_ = 0; } return child_status; } - else if (current_child_idx_ != N_of_children - 1) + else if (current_child_idx_ < N_of_children - 1) { // If the child status is success, continue to the next child // (if any, hence if(current_child_ != N_of_children_ - 1) ) in the for loop (if any). @@ -63,9 +61,13 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() else { // if it the last child. - if (child_status == BT::SUCCESS) + if (child_status == BT::SUCCESS || reset_policy_ != BT::ON_FAILURE) { // if it the last child and it has returned SUCCESS, reset the memory + for (unsigned t=0; t<=current_child_idx_; t++) + { + children_nodes_[t]->setStatus(BT::IDLE); + } current_child_idx_ = 0; } return child_status; diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 6be343482..f537f5fdd 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -65,5 +65,5 @@ const std::string& BT::TreeNode::name() const bool BT::TreeNode::isHalted() const { - return status() == BT::HALTED; + return status() == BT::IDLE; } From c5e268d9fc340f4d23df10b693135423bdb0927c Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 9 May 2018 12:28:06 +0200 Subject: [PATCH 044/125] forgotten --- templates/action_node_template.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/templates/action_node_template.cpp b/templates/action_node_template.cpp index 8ceeadc7a..ea5316ced 100644 --- a/templates/action_node_template.cpp +++ b/templates/action_node_template.cpp @@ -24,7 +24,7 @@ void BT::CLASSNAME::WaitForTick() SetStatus(BT::RUNNING); // Perform action... - while (Status() != BT::HALTED) + while (Status() != BT::IDLE) { /*HERE THE CODE TO EXECUTE FOR THE ACTION. wHEN THE ACTION HAS FINISHED CORRECLTY, CALL set_status(BT::SUCCESS) @@ -36,6 +36,6 @@ void BT::CLASSNAME::WaitForTick() void BT::CLASSNAME::Halt() { /*HERE THE CODE TO PERFORM WHEN THE ACTION IS HALTED*/ - SetStatus(BT::HALTED); + SetStatus(BT::IDLE); DEBUG_STDOUT("HALTED state set!"); } From 34febd21d1154fcf285b6ea6faa3b445fcea8398 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 11 May 2018 10:30:32 +0200 Subject: [PATCH 045/125] added subscriber to state change --- include/behavior_tree_core/signal.h | 51 ++++++++++++++++++++++++++ include/behavior_tree_core/tree_node.h | 27 ++++++++++++-- src/tree_node.cpp | 14 +++++-- 3 files changed, 85 insertions(+), 7 deletions(-) create mode 100644 include/behavior_tree_core/signal.h diff --git a/include/behavior_tree_core/signal.h b/include/behavior_tree_core/signal.h new file mode 100644 index 000000000..6006dcb08 --- /dev/null +++ b/include/behavior_tree_core/signal.h @@ -0,0 +1,51 @@ +#ifndef SIMPLE_SIGNAL_H +#define SIMPLE_SIGNAL_H + +#include +#include +#include + +namespace BT{ + +/** + * Super simple Signal/Slop implementation, AKA "Observable pattern". + * The subscriber is active until it goes out of scope or Subscriber::reset() is called. + */ +template +class Signal{ +public: + + using CallableFunction = std::function; + using Subscriber = std::shared_ptr; + + void notify(CallableArgs... args) + { + for (size_t i=0; i< subscribers_.size(); ) + { + if( auto sub = subscribers_[i].lock() ) + { + (*sub)(args...); + i++; + } + else{ + subscribers_.erase( subscribers_.begin()+i ); + } + } + } + + Subscriber subscribe(CallableFunction func) + { + Subscriber sub = std::make_shared(std::move(func)); + subscribers_.emplace_back(sub); + return sub; + } + +private: + + std::vector> subscribers_; + +}; + +} + +#endif // SIMPLE_SIGNAL_H diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 4be0a4ff2..b3f66c2a0 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -31,6 +31,7 @@ #include "behavior_tree_core/tick_engine.h" #include "behavior_tree_core/exceptions.h" +#include "behavior_tree_core/signal.h" namespace BT { @@ -55,10 +56,10 @@ enum NodeType // - "Halted" indicates that the node has been halted by its father. enum NodeStatus { + IDLE, RUNNING, SUCCESS, FAILURE, - IDLE, EXIT }; @@ -100,10 +101,10 @@ class TreeNode // Node name std::string name_; NodeStatus status_; + std::condition_variable state_condition_variable_; + mutable std::mutex state_mutex_; protected: - mutable std::mutex state_mutex_; - std::condition_variable state_condition_variable_; // Method to be implemented by the user virtual BT::NodeStatus tick() = 0; @@ -130,6 +131,26 @@ class TreeNode BT::NodeStatus waitValidStatus(); virtual NodeType type() const = 0; + + using StatusChangeSignal = Signal; + using StatusChangeSubscriber = StatusChangeSignal::Subscriber; + using StatusChangeCallback = StatusChangeSignal::CallableFunction; + + /** + * @brief subscribeToStatusChange is used to attach a callback to a status change. + * AS soon as StatusChangeSubscriber goes out of scope (it is a shared_ptr) the callback + * is unsubscribed + * + * @param callback. Must have signature void funcname(NodeStatus prev_status, NodeStatus new_status) + * + * @return the subscriber. + */ + StatusChangeSubscriber subscribeToStatusChange(StatusChangeCallback callback); + +private: + + StatusChangeSignal state_change_signal_; + }; } diff --git a/src/tree_node.cpp b/src/tree_node.cpp index f537f5fdd..9a68a46e8 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -26,16 +26,17 @@ BT::NodeStatus BT::TreeNode::executeTick() void BT::TreeNode::setStatus(NodeStatus new_status) { - bool is_state_updated = false; + NodeStatus prev_status; { std::unique_lock UniqueLock(state_mutex_); - is_state_updated = (status_ != new_status); + prev_status = status_; status_ = new_status; } - if (is_state_updated) + if (prev_status != new_status) { state_condition_variable_.notify_all(); - } + state_change_signal_.notify(*this, prev_status, new_status); +} } BT::NodeStatus BT::TreeNode::status() const @@ -67,3 +68,8 @@ bool BT::TreeNode::isHalted() const { return status() == BT::IDLE; } + +BT::TreeNode::StatusChangeSubscriber BT::TreeNode::subscribeToStatusChange(BT::TreeNode::StatusChangeCallback callback) +{ + return state_change_signal_.subscribe(callback); +} From 024d4d6681b26cddf53ec2e2e685de63e7badae8 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 11 May 2018 10:31:35 +0200 Subject: [PATCH 046/125] minor change in test --- gtest/include/action_test_node.h | 3 +-- gtest/src/action_test_node.cpp | 8 ++++++-- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index 93b879a4b..cdefa664f 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -26,8 +26,7 @@ class ActionTestNode : public ActionNode private: int time_; bool boolean_value_; - - ///ReturnStatus status_; + std::atomic_bool stop_loop_; }; } diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 7d1913895..668347217 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -18,6 +18,7 @@ BT::ActionTestNode::ActionTestNode(std::string name) : ActionNode(name) { boolean_value_ = true; time_ = 3; + stop_loop_ = false; } BT::ActionTestNode::~ActionTestNode() @@ -27,13 +28,15 @@ BT::ActionTestNode::~ActionTestNode() BT::NodeStatus BT::ActionTestNode::tick() { + stop_loop_ = false; int i = 0; - while (status() != BT::IDLE && i++ < time_) + while ( !stop_loop_ && i++ < time_) { DEBUG_STDOUT(" Action " << name() << "running! Thread id:" << std::this_thread::get_id()); std::this_thread::sleep_for(std::chrono::milliseconds(100)); } - if (status() != BT::IDLE) + + if ( !stop_loop_ ) { if (boolean_value_) { @@ -54,6 +57,7 @@ BT::NodeStatus BT::ActionTestNode::tick() void BT::ActionTestNode::halt() { + stop_loop_ = true; setStatus(BT::IDLE); DEBUG_STDOUT("HALTED state set!"); } From 21669db287eaeef3c6678e468d606d8df2b3ff30 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 11 May 2018 10:31:53 +0200 Subject: [PATCH 047/125] unit test added --- gtest/gtest_tree.cpp | 80 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 80 insertions(+) diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 9b3bfd18d..34a3867a4 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -58,6 +58,27 @@ struct ComplexSequenceTest : testing::Test } }; +struct SequenceTripleActionTest : testing::Test +{ + BT::SequenceNode root; + BT::ActionTestNode action_1; + BT::ActionTestNode action_2; + BT::ActionTestNode action_3; + + SequenceTripleActionTest(): + root("root_sequence"), + action_1("action_1"), + action_2("action_2"), + action_3("action_3") + { + root.addChild(&action_1); + root.addChild(&action_2); + root.addChild(&action_3); + + } +}; + + struct ComplexSequence2ActionsTest : testing::Test { BT::SequenceNode root; @@ -361,6 +382,65 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue) root.halt(); } +TEST_F(SequenceTripleActionTest, TripleAction) +{ + using namespace BT; + using namespace std::chrono; + const auto timeout = system_clock::now() + milliseconds(650); + + action_1.set_time(2); + action_2.set_time(2); + action_3.set_time(2); + // the sequence is supposed to finish in (200 ms * 3) = 600 ms + + bool done_1 = false, done_2 = false, done_3 = false; + + auto sub1 = action_1.subscribeToStatusChange( + [&done_1](const TreeNode& , NodeStatus,NodeStatus status) + { + if( status == NodeStatus::SUCCESS) done_1 = true; + }); + + auto sub2 = action_2.subscribeToStatusChange( + [&done_2](const TreeNode& , NodeStatus,NodeStatus status) + { + if( status == NodeStatus::SUCCESS) done_2 = true; + }); + + auto sub3 = action_3.subscribeToStatusChange( + [&done_3](const TreeNode& , NodeStatus,NodeStatus status) + { + if( status == NodeStatus::SUCCESS) done_3 = true; + }); + + // first tick + NodeStatus state = root.executeTick(); + + ASSERT_EQ(NodeStatus::RUNNING, state); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + + // continue until succesfull + while ( state != NodeStatus::SUCCESS && system_clock::now() < timeout) + { + std::this_thread::sleep_for( milliseconds( 20) ); + state = root.executeTick(); + } + + ASSERT_EQ(NodeStatus::SUCCESS, state); + ASSERT_TRUE(done_1); + ASSERT_TRUE(done_2); + ASSERT_TRUE(done_3); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_TRUE(system_clock::now() < timeout); // no timeout should occur + + root.halt(); +} + + TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) { BT::NodeStatus state = root.executeTick(); From 9d4ab81478e98e73713f104c100fa49fdad12e4e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 11 May 2018 10:33:19 +0200 Subject: [PATCH 048/125] minor change, does not seems to affect the execution of the tests --- src/action_node.cpp | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/src/action_node.cpp b/src/action_node.cpp index 1302b334d..a88732f67 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -28,7 +28,7 @@ BT::NodeStatus BT::SimpleActionNode::tick() { NodeStatus prev_status = status(); - if (prev_status == BT::IDLE || prev_status == BT::IDLE) + if (prev_status == BT::IDLE) { setStatus(BT::RUNNING); prev_status = BT::RUNNING; @@ -69,6 +69,10 @@ void BT::ActionNode::waitForTick() // notified from the method stopAndJoinThread if (loop_.load()) { + if (status() == BT::IDLE) + { + setStatus(BT::RUNNING); + } setStatus( tick() ); } } @@ -76,14 +80,15 @@ void BT::ActionNode::waitForTick() BT::NodeStatus BT::ActionNode::executeTick() { - NodeStatus stat = status(); - tick_engine_.notify(); - - if (stat == BT::IDLE) + //send signal to other thread. + // The other thread is in charge for changing the status + if (status() == BT::IDLE) { - setStatus(BT::RUNNING); + tick_engine_.notify(); } - stat = waitValidStatus(); + + // block as long as the state is BT::IDLE + const NodeStatus stat = waitValidStatus(); return stat; } From 5edcd5469e334cc4e4fccff07a9150fb06ae51ac Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 4 May 2018 16:05:47 +0200 Subject: [PATCH 049/125] adding decorators --- .../decorator_repeat_node.h | 37 ++++++++++ .../decorator_subtree_node.h | 34 +++++++++ src/decorator_repeat_node.cpp | 69 +++++++++++++++++++ 3 files changed, 140 insertions(+) create mode 100644 include/behavior_tree_core/decorator_repeat_node.h create mode 100644 include/behavior_tree_core/decorator_subtree_node.h create mode 100644 src/decorator_repeat_node.cpp diff --git a/include/behavior_tree_core/decorator_repeat_node.h b/include/behavior_tree_core/decorator_repeat_node.h new file mode 100644 index 000000000..85569c6db --- /dev/null +++ b/include/behavior_tree_core/decorator_repeat_node.h @@ -0,0 +1,37 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef DECORATOR_REPEAT_NODE_H +#define DECORATOR_REPEAT_NODE_H + +#include "behavior_tree_core/decorator_node.h" + +namespace BT +{ +class DecoratorRepeatNode : public DecoratorNode +{ + public: + // Constructor + DecoratorRepeatNode(std::string name, unsigned int NTries); + + ~DecoratorRepeatNode() = default; + + private: + unsigned NTries_; + unsigned TryIndx_; + + virtual BT::NodeStatus tick() override; +}; +} + +#endif diff --git a/include/behavior_tree_core/decorator_subtree_node.h b/include/behavior_tree_core/decorator_subtree_node.h new file mode 100644 index 000000000..b00b6461c --- /dev/null +++ b/include/behavior_tree_core/decorator_subtree_node.h @@ -0,0 +1,34 @@ +#ifndef DECORATOR_SUBTREE_NODE_H +#define DECORATOR_SUBTREE_NODE_H + +#include "behavior_tree_core/decorator_node.h" + +namespace BT +{ +class DecoratorSubtreeNode : public DecoratorNode +{ + public: + // Constructor + DecoratorSubtreeNode(std::string name) : DecoratorNode(name) + { + } + + virtual ~DecoratorSubtreeNode() = default; + + private: + virtual BT::NodeStatus tick() + { + NodeStatus prev_status = status(); + if ( prev_status== BT::IDLE || prev_status == BT::HALTED) + { + setStatus(BT::RUNNING); + } + auto status = child_node_->executeTick(); + setStatus(status); + return status; + } +}; + +} + +#endif // DECORATOR_SUBTREE_NODE_H diff --git a/src/decorator_repeat_node.cpp b/src/decorator_repeat_node.cpp new file mode 100644 index 000000000..063d92cf2 --- /dev/null +++ b/src/decorator_repeat_node.cpp @@ -0,0 +1,69 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#include "behavior_tree_core/decorator_repeat_node.h" + +BT::DecoratorRepeatNode::DecoratorRepeatNode(std::string name, unsigned int NTries) + : DecoratorNode(name), NTries_(NTries), TryIndx_(0) +{ +} + +BT::DecoratorRepeatNode::DecoratorRepeatNode(std::string name, const BT::NodeParameters& params) + : DecoratorNode(name), NTries_(1), TryIndx_(0) +{ + auto it = params.find("num_cycles"); + if (it == params.end()) + { + throw std::runtime_error("[DecoratorRepeatNode] requires a parameter callen 'num_cycles'"); + } + NTries_ = std::stoul(it->second); +} + +BT::NodeStatus BT::DecoratorRepeatNode::tick() +{ + setStatus(BT::RUNNING); + BT::NodeStatus child_state = child_node_->executeTick(); + + switch (child_state) + { + case BT::SUCCESS: + { + TryIndx_++; + if (TryIndx_ >= NTries_) + { + setStatus(BT::SUCCESS); + } + } + break; + + case BT::FAILURE: + { + TryIndx_ = 0; + setStatus(BT::FAILURE); + } + break; + + case BT::RUNNING: + { + setStatus(BT::RUNNING); + } + break; + + default: + { + // TODO throw? + } + } + + return status(); +} From 57d3cdae31f3a838dc440c82d7636950b2bca790 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 4 May 2018 16:24:21 +0200 Subject: [PATCH 050/125] Added run-time factory --- 3rdparty/tinyXML2/tinyxml2.cpp | 2826 +++++++++++++++++ 3rdparty/tinyXML2/tinyxml2.h | 2314 ++++++++++++++ CMakeLists.txt | 10 +- gtest/gtest_factory.cpp | 184 ++ gtest/include/crossdoor_dummy_nodes.h | 70 + include/behavior_tree_core/behavior_tree.h | 12 +- include/behavior_tree_core/bt_factory.h | 111 +- include/behavior_tree_core/decorator_node.h | 1 + .../decorator_repeat_node.h | 2 + .../behavior_tree_core/decorator_retry_node.h | 3 + include/behavior_tree_core/tree_node.h | 63 +- include/behavior_tree_core/xml_parsing.h | 104 + src/behavior_tree.cpp | 64 + src/bt_factory.cpp | 32 +- src/decorator_negation_node.cpp | 2 +- src/decorator_node.cpp | 1 + src/decorator_retry_node.cpp | 12 +- src/xml_parsing.cpp | 241 ++ 18 files changed, 5986 insertions(+), 66 deletions(-) create mode 100755 3rdparty/tinyXML2/tinyxml2.cpp create mode 100755 3rdparty/tinyXML2/tinyxml2.h create mode 100644 gtest/gtest_factory.cpp create mode 100644 gtest/include/crossdoor_dummy_nodes.h create mode 100644 include/behavior_tree_core/xml_parsing.h create mode 100644 src/behavior_tree.cpp create mode 100644 src/xml_parsing.cpp diff --git a/3rdparty/tinyXML2/tinyxml2.cpp b/3rdparty/tinyXML2/tinyxml2.cpp new file mode 100755 index 000000000..89b791336 --- /dev/null +++ b/3rdparty/tinyXML2/tinyxml2.cpp @@ -0,0 +1,2826 @@ +/* +Original code by Lee Thomason (www.grinninglizard.com) + +This software is provided 'as-is', without any express or implied +warranty. In no event will the authors be held liable for any +damages arising from the use of this software. + +Permission is granted to anyone to use this software for any +purpose, including commercial applications, and to alter it and +redistribute it freely, subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must +not claim that you wrote the original software. If you use this +software in a product, an acknowledgment in the product documentation +would be appreciated but is not required. + +2. Altered source versions must be plainly marked as such, and +must not be misrepresented as being the original software. + +3. This notice may not be removed or altered from any source +distribution. +*/ + +#include "tinyxml2.h" + +#include // yes, this one new style header, is in the Android SDK. +#if defined(ANDROID_NDK) || defined(__BORLANDC__) || defined(__QNXNTO__) +# include +# include +#else +# include +# include +#endif + +#if defined(_MSC_VER) && (_MSC_VER >= 1400 ) && (!defined WINCE) + // Microsoft Visual Studio, version 2005 and higher. Not WinCE. + /*int _snprintf_s( + char *buffer, + size_t sizeOfBuffer, + size_t count, + const char *format [, + argument] ... + );*/ + static inline int TIXML_SNPRINTF( char* buffer, size_t size, const char* format, ... ) + { + va_list va; + va_start( va, format ); + int result = vsnprintf_s( buffer, size, _TRUNCATE, format, va ); + va_end( va ); + return result; + } + + static inline int TIXML_VSNPRINTF( char* buffer, size_t size, const char* format, va_list va ) + { + int result = vsnprintf_s( buffer, size, _TRUNCATE, format, va ); + return result; + } + + #define TIXML_VSCPRINTF _vscprintf + #define TIXML_SSCANF sscanf_s +#elif defined _MSC_VER + // Microsoft Visual Studio 2003 and earlier or WinCE + #define TIXML_SNPRINTF _snprintf + #define TIXML_VSNPRINTF _vsnprintf + #define TIXML_SSCANF sscanf + #if (_MSC_VER < 1400 ) && (!defined WINCE) + // Microsoft Visual Studio 2003 and not WinCE. + #define TIXML_VSCPRINTF _vscprintf // VS2003's C runtime has this, but VC6 C runtime or WinCE SDK doesn't have. + #else + // Microsoft Visual Studio 2003 and earlier or WinCE. + static inline int TIXML_VSCPRINTF( const char* format, va_list va ) + { + int len = 512; + for (;;) { + len = len*2; + char* str = new char[len](); + const int required = _vsnprintf(str, len, format, va); + delete[] str; + if ( required != -1 ) { + TIXMLASSERT( required >= 0 ); + len = required; + break; + } + } + TIXMLASSERT( len >= 0 ); + return len; + } + #endif +#else + // GCC version 3 and higher + //#warning( "Using sn* functions." ) + #define TIXML_SNPRINTF snprintf + #define TIXML_VSNPRINTF vsnprintf + static inline int TIXML_VSCPRINTF( const char* format, va_list va ) + { + int len = vsnprintf( 0, 0, format, va ); + TIXMLASSERT( len >= 0 ); + return len; + } + #define TIXML_SSCANF sscanf +#endif + + +static const char LINE_FEED = (char)0x0a; // all line endings are normalized to LF +static const char LF = LINE_FEED; +static const char CARRIAGE_RETURN = (char)0x0d; // CR gets filtered out +static const char CR = CARRIAGE_RETURN; +static const char SINGLE_QUOTE = '\''; +static const char DOUBLE_QUOTE = '\"'; + +// Bunch of unicode info at: +// http://www.unicode.org/faq/utf_bom.html +// ef bb bf (Microsoft "lead bytes") - designates UTF-8 + +static const unsigned char TIXML_UTF_LEAD_0 = 0xefU; +static const unsigned char TIXML_UTF_LEAD_1 = 0xbbU; +static const unsigned char TIXML_UTF_LEAD_2 = 0xbfU; + +namespace tinyxml2 +{ + +struct Entity { + const char* pattern; + int length; + char value; +}; + +static const int NUM_ENTITIES = 5; +static const Entity entities[NUM_ENTITIES] = { + { "quot", 4, DOUBLE_QUOTE }, + { "amp", 3, '&' }, + { "apos", 4, SINGLE_QUOTE }, + { "lt", 2, '<' }, + { "gt", 2, '>' } +}; + + +StrPair::~StrPair() +{ + Reset(); +} + + +void StrPair::TransferTo( StrPair* other ) +{ + if ( this == other ) { + return; + } + // This in effect implements the assignment operator by "moving" + // ownership (as in auto_ptr). + + TIXMLASSERT( other != 0 ); + TIXMLASSERT( other->_flags == 0 ); + TIXMLASSERT( other->_start == 0 ); + TIXMLASSERT( other->_end == 0 ); + + other->Reset(); + + other->_flags = _flags; + other->_start = _start; + other->_end = _end; + + _flags = 0; + _start = 0; + _end = 0; +} + + +void StrPair::Reset() +{ + if ( _flags & NEEDS_DELETE ) { + delete [] _start; + } + _flags = 0; + _start = 0; + _end = 0; +} + + +void StrPair::SetStr( const char* str, int flags ) +{ + TIXMLASSERT( str ); + Reset(); + size_t len = strlen( str ); + TIXMLASSERT( _start == 0 ); + _start = new char[ len+1 ]; + memcpy( _start, str, len+1 ); + _end = _start + len; + _flags = flags | NEEDS_DELETE; +} + + +char* StrPair::ParseText( char* p, const char* endTag, int strFlags, int* curLineNumPtr ) +{ + TIXMLASSERT( p ); + TIXMLASSERT( endTag && *endTag ); + TIXMLASSERT(curLineNumPtr); + + char* start = p; + char endChar = *endTag; + size_t length = strlen( endTag ); + + // Inner loop of text parsing. + while ( *p ) { + if ( *p == endChar && strncmp( p, endTag, length ) == 0 ) { + Set( start, p, strFlags ); + return p + length; + } else if (*p == '\n') { + ++(*curLineNumPtr); + } + ++p; + TIXMLASSERT( p ); + } + return 0; +} + + +char* StrPair::ParseName( char* p ) +{ + if ( !p || !(*p) ) { + return 0; + } + if ( !XMLUtil::IsNameStartChar( *p ) ) { + return 0; + } + + char* const start = p; + ++p; + while ( *p && XMLUtil::IsNameChar( *p ) ) { + ++p; + } + + Set( start, p, 0 ); + return p; +} + + +void StrPair::CollapseWhitespace() +{ + // Adjusting _start would cause undefined behavior on delete[] + TIXMLASSERT( ( _flags & NEEDS_DELETE ) == 0 ); + // Trim leading space. + _start = XMLUtil::SkipWhiteSpace( _start, 0 ); + + if ( *_start ) { + const char* p = _start; // the read pointer + char* q = _start; // the write pointer + + while( *p ) { + if ( XMLUtil::IsWhiteSpace( *p )) { + p = XMLUtil::SkipWhiteSpace( p, 0 ); + if ( *p == 0 ) { + break; // don't write to q; this trims the trailing space. + } + *q = ' '; + ++q; + } + *q = *p; + ++q; + ++p; + } + *q = 0; + } +} + + +const char* StrPair::GetStr() +{ + TIXMLASSERT( _start ); + TIXMLASSERT( _end ); + if ( _flags & NEEDS_FLUSH ) { + *_end = 0; + _flags ^= NEEDS_FLUSH; + + if ( _flags ) { + const char* p = _start; // the read pointer + char* q = _start; // the write pointer + + while( p < _end ) { + if ( (_flags & NEEDS_NEWLINE_NORMALIZATION) && *p == CR ) { + // CR-LF pair becomes LF + // CR alone becomes LF + // LF-CR becomes LF + if ( *(p+1) == LF ) { + p += 2; + } + else { + ++p; + } + *q = LF; + ++q; + } + else if ( (_flags & NEEDS_NEWLINE_NORMALIZATION) && *p == LF ) { + if ( *(p+1) == CR ) { + p += 2; + } + else { + ++p; + } + *q = LF; + ++q; + } + else if ( (_flags & NEEDS_ENTITY_PROCESSING) && *p == '&' ) { + // Entities handled by tinyXML2: + // - special entities in the entity table [in/out] + // - numeric character reference [in] + // 中 or 中 + + if ( *(p+1) == '#' ) { + const int buflen = 10; + char buf[buflen] = { 0 }; + int len = 0; + char* adjusted = const_cast( XMLUtil::GetCharacterRef( p, buf, &len ) ); + if ( adjusted == 0 ) { + *q = *p; + ++p; + ++q; + } + else { + TIXMLASSERT( 0 <= len && len <= buflen ); + TIXMLASSERT( q + len <= adjusted ); + p = adjusted; + memcpy( q, buf, len ); + q += len; + } + } + else { + bool entityFound = false; + for( int i = 0; i < NUM_ENTITIES; ++i ) { + const Entity& entity = entities[i]; + if ( strncmp( p + 1, entity.pattern, entity.length ) == 0 + && *( p + entity.length + 1 ) == ';' ) { + // Found an entity - convert. + *q = entity.value; + ++q; + p += entity.length + 2; + entityFound = true; + break; + } + } + if ( !entityFound ) { + // fixme: treat as error? + ++p; + ++q; + } + } + } + else { + *q = *p; + ++p; + ++q; + } + } + *q = 0; + } + // The loop below has plenty going on, and this + // is a less useful mode. Break it out. + if ( _flags & NEEDS_WHITESPACE_COLLAPSING ) { + CollapseWhitespace(); + } + _flags = (_flags & NEEDS_DELETE); + } + TIXMLASSERT( _start ); + return _start; +} + + + + +// --------- XMLUtil ----------- // + +const char* XMLUtil::writeBoolTrue = "true"; +const char* XMLUtil::writeBoolFalse = "false"; + +void XMLUtil::SetBoolSerialization(const char* writeTrue, const char* writeFalse) +{ + static const char* defTrue = "true"; + static const char* defFalse = "false"; + + writeBoolTrue = (writeTrue) ? writeTrue : defTrue; + writeBoolFalse = (writeFalse) ? writeFalse : defFalse; +} + + +const char* XMLUtil::ReadBOM( const char* p, bool* bom ) +{ + TIXMLASSERT( p ); + TIXMLASSERT( bom ); + *bom = false; + const unsigned char* pu = reinterpret_cast(p); + // Check for BOM: + if ( *(pu+0) == TIXML_UTF_LEAD_0 + && *(pu+1) == TIXML_UTF_LEAD_1 + && *(pu+2) == TIXML_UTF_LEAD_2 ) { + *bom = true; + p += 3; + } + TIXMLASSERT( p ); + return p; +} + + +void XMLUtil::ConvertUTF32ToUTF8( unsigned long input, char* output, int* length ) +{ + const unsigned long BYTE_MASK = 0xBF; + const unsigned long BYTE_MARK = 0x80; + const unsigned long FIRST_BYTE_MARK[7] = { 0x00, 0x00, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC }; + + if (input < 0x80) { + *length = 1; + } + else if ( input < 0x800 ) { + *length = 2; + } + else if ( input < 0x10000 ) { + *length = 3; + } + else if ( input < 0x200000 ) { + *length = 4; + } + else { + *length = 0; // This code won't convert this correctly anyway. + return; + } + + output += *length; + + // Scary scary fall throughs are annotated with carefully designed comments + // to suppress compiler warnings such as -Wimplicit-fallthrough in gcc + switch (*length) { + case 4: + --output; + *output = (char)((input | BYTE_MARK) & BYTE_MASK); + input >>= 6; + //fall through + case 3: + --output; + *output = (char)((input | BYTE_MARK) & BYTE_MASK); + input >>= 6; + //fall through + case 2: + --output; + *output = (char)((input | BYTE_MARK) & BYTE_MASK); + input >>= 6; + //fall through + case 1: + --output; + *output = (char)(input | FIRST_BYTE_MARK[*length]); + break; + default: + TIXMLASSERT( false ); + } +} + + +const char* XMLUtil::GetCharacterRef( const char* p, char* value, int* length ) +{ + // Presume an entity, and pull it out. + *length = 0; + + if ( *(p+1) == '#' && *(p+2) ) { + unsigned long ucs = 0; + TIXMLASSERT( sizeof( ucs ) >= 4 ); + ptrdiff_t delta = 0; + unsigned mult = 1; + static const char SEMICOLON = ';'; + + if ( *(p+2) == 'x' ) { + // Hexadecimal. + const char* q = p+3; + if ( !(*q) ) { + return 0; + } + + q = strchr( q, SEMICOLON ); + + if ( !q ) { + return 0; + } + TIXMLASSERT( *q == SEMICOLON ); + + delta = q-p; + --q; + + while ( *q != 'x' ) { + unsigned int digit = 0; + + if ( *q >= '0' && *q <= '9' ) { + digit = *q - '0'; + } + else if ( *q >= 'a' && *q <= 'f' ) { + digit = *q - 'a' + 10; + } + else if ( *q >= 'A' && *q <= 'F' ) { + digit = *q - 'A' + 10; + } + else { + return 0; + } + TIXMLASSERT( digit < 16 ); + TIXMLASSERT( digit == 0 || mult <= UINT_MAX / digit ); + const unsigned int digitScaled = mult * digit; + TIXMLASSERT( ucs <= ULONG_MAX - digitScaled ); + ucs += digitScaled; + TIXMLASSERT( mult <= UINT_MAX / 16 ); + mult *= 16; + --q; + } + } + else { + // Decimal. + const char* q = p+2; + if ( !(*q) ) { + return 0; + } + + q = strchr( q, SEMICOLON ); + + if ( !q ) { + return 0; + } + TIXMLASSERT( *q == SEMICOLON ); + + delta = q-p; + --q; + + while ( *q != '#' ) { + if ( *q >= '0' && *q <= '9' ) { + const unsigned int digit = *q - '0'; + TIXMLASSERT( digit < 10 ); + TIXMLASSERT( digit == 0 || mult <= UINT_MAX / digit ); + const unsigned int digitScaled = mult * digit; + TIXMLASSERT( ucs <= ULONG_MAX - digitScaled ); + ucs += digitScaled; + } + else { + return 0; + } + TIXMLASSERT( mult <= UINT_MAX / 10 ); + mult *= 10; + --q; + } + } + // convert the UCS to UTF-8 + ConvertUTF32ToUTF8( ucs, value, length ); + return p + delta + 1; + } + return p+1; +} + + +void XMLUtil::ToStr( int v, char* buffer, int bufferSize ) +{ + TIXML_SNPRINTF( buffer, bufferSize, "%d", v ); +} + + +void XMLUtil::ToStr( unsigned v, char* buffer, int bufferSize ) +{ + TIXML_SNPRINTF( buffer, bufferSize, "%u", v ); +} + + +void XMLUtil::ToStr( bool v, char* buffer, int bufferSize ) +{ + TIXML_SNPRINTF( buffer, bufferSize, "%s", v ? writeBoolTrue : writeBoolFalse); +} + +/* + ToStr() of a number is a very tricky topic. + https://github.com/leethomason/tinyxml2/issues/106 +*/ +void XMLUtil::ToStr( float v, char* buffer, int bufferSize ) +{ + TIXML_SNPRINTF( buffer, bufferSize, "%.8g", v ); +} + + +void XMLUtil::ToStr( double v, char* buffer, int bufferSize ) +{ + TIXML_SNPRINTF( buffer, bufferSize, "%.17g", v ); +} + + +void XMLUtil::ToStr(int64_t v, char* buffer, int bufferSize) +{ + // horrible syntax trick to make the compiler happy about %lld + TIXML_SNPRINTF(buffer, bufferSize, "%lld", (long long)v); +} + + +bool XMLUtil::ToInt( const char* str, int* value ) +{ + if ( TIXML_SSCANF( str, "%d", value ) == 1 ) { + return true; + } + return false; +} + +bool XMLUtil::ToUnsigned( const char* str, unsigned *value ) +{ + if ( TIXML_SSCANF( str, "%u", value ) == 1 ) { + return true; + } + return false; +} + +bool XMLUtil::ToBool( const char* str, bool* value ) +{ + int ival = 0; + if ( ToInt( str, &ival )) { + *value = (ival==0) ? false : true; + return true; + } + if ( StringEqual( str, "true" ) ) { + *value = true; + return true; + } + else if ( StringEqual( str, "false" ) ) { + *value = false; + return true; + } + return false; +} + + +bool XMLUtil::ToFloat( const char* str, float* value ) +{ + if ( TIXML_SSCANF( str, "%f", value ) == 1 ) { + return true; + } + return false; +} + + +bool XMLUtil::ToDouble( const char* str, double* value ) +{ + if ( TIXML_SSCANF( str, "%lf", value ) == 1 ) { + return true; + } + return false; +} + + +bool XMLUtil::ToInt64(const char* str, int64_t* value) +{ + long long v = 0; // horrible syntax trick to make the compiler happy about %lld + if (TIXML_SSCANF(str, "%lld", &v) == 1) { + *value = (int64_t)v; + return true; + } + return false; +} + + +char* XMLDocument::Identify( char* p, XMLNode** node ) +{ + TIXMLASSERT( node ); + TIXMLASSERT( p ); + char* const start = p; + int const startLine = _parseCurLineNum; + p = XMLUtil::SkipWhiteSpace( p, &_parseCurLineNum ); + if( !*p ) { + *node = 0; + TIXMLASSERT( p ); + return p; + } + + // These strings define the matching patterns: + static const char* xmlHeader = { "( _commentPool ); + returnNode->_parseLineNum = _parseCurLineNum; + p += xmlHeaderLen; + } + else if ( XMLUtil::StringEqual( p, commentHeader, commentHeaderLen ) ) { + returnNode = CreateUnlinkedNode( _commentPool ); + returnNode->_parseLineNum = _parseCurLineNum; + p += commentHeaderLen; + } + else if ( XMLUtil::StringEqual( p, cdataHeader, cdataHeaderLen ) ) { + XMLText* text = CreateUnlinkedNode( _textPool ); + returnNode = text; + returnNode->_parseLineNum = _parseCurLineNum; + p += cdataHeaderLen; + text->SetCData( true ); + } + else if ( XMLUtil::StringEqual( p, dtdHeader, dtdHeaderLen ) ) { + returnNode = CreateUnlinkedNode( _commentPool ); + returnNode->_parseLineNum = _parseCurLineNum; + p += dtdHeaderLen; + } + else if ( XMLUtil::StringEqual( p, elementHeader, elementHeaderLen ) ) { + returnNode = CreateUnlinkedNode( _elementPool ); + returnNode->_parseLineNum = _parseCurLineNum; + p += elementHeaderLen; + } + else { + returnNode = CreateUnlinkedNode( _textPool ); + returnNode->_parseLineNum = _parseCurLineNum; // Report line of first non-whitespace character + p = start; // Back it up, all the text counts. + _parseCurLineNum = startLine; + } + + TIXMLASSERT( returnNode ); + TIXMLASSERT( p ); + *node = returnNode; + return p; +} + + +bool XMLDocument::Accept( XMLVisitor* visitor ) const +{ + TIXMLASSERT( visitor ); + if ( visitor->VisitEnter( *this ) ) { + for ( const XMLNode* node=FirstChild(); node; node=node->NextSibling() ) { + if ( !node->Accept( visitor ) ) { + break; + } + } + } + return visitor->VisitExit( *this ); +} + + +// --------- XMLNode ----------- // + +XMLNode::XMLNode( XMLDocument* doc ) : + _document( doc ), + _parent( 0 ), + _value(), + _parseLineNum( 0 ), + _firstChild( 0 ), _lastChild( 0 ), + _prev( 0 ), _next( 0 ), + _userData( 0 ), + _memPool( 0 ) +{ +} + + +XMLNode::~XMLNode() +{ + DeleteChildren(); + if ( _parent ) { + _parent->Unlink( this ); + } +} + +const char* XMLNode::Value() const +{ + // Edge case: XMLDocuments don't have a Value. Return null. + if ( this->ToDocument() ) + return 0; + return _value.GetStr(); +} + +void XMLNode::SetValue( const char* str, bool staticMem ) +{ + if ( staticMem ) { + _value.SetInternedStr( str ); + } + else { + _value.SetStr( str ); + } +} + +XMLNode* XMLNode::DeepClone(XMLDocument* target) const +{ + XMLNode* clone = this->ShallowClone(target); + if (!clone) return 0; + + for (const XMLNode* child = this->FirstChild(); child; child = child->NextSibling()) { + XMLNode* childClone = child->DeepClone(target); + TIXMLASSERT(childClone); + clone->InsertEndChild(childClone); + } + return clone; +} + +void XMLNode::DeleteChildren() +{ + while( _firstChild ) { + TIXMLASSERT( _lastChild ); + DeleteChild( _firstChild ); + } + _firstChild = _lastChild = 0; +} + + +void XMLNode::Unlink( XMLNode* child ) +{ + TIXMLASSERT( child ); + TIXMLASSERT( child->_document == _document ); + TIXMLASSERT( child->_parent == this ); + if ( child == _firstChild ) { + _firstChild = _firstChild->_next; + } + if ( child == _lastChild ) { + _lastChild = _lastChild->_prev; + } + + if ( child->_prev ) { + child->_prev->_next = child->_next; + } + if ( child->_next ) { + child->_next->_prev = child->_prev; + } + child->_next = 0; + child->_prev = 0; + child->_parent = 0; +} + + +void XMLNode::DeleteChild( XMLNode* node ) +{ + TIXMLASSERT( node ); + TIXMLASSERT( node->_document == _document ); + TIXMLASSERT( node->_parent == this ); + Unlink( node ); + TIXMLASSERT(node->_prev == 0); + TIXMLASSERT(node->_next == 0); + TIXMLASSERT(node->_parent == 0); + DeleteNode( node ); +} + + +XMLNode* XMLNode::InsertEndChild( XMLNode* addThis ) +{ + TIXMLASSERT( addThis ); + if ( addThis->_document != _document ) { + TIXMLASSERT( false ); + return 0; + } + InsertChildPreamble( addThis ); + + if ( _lastChild ) { + TIXMLASSERT( _firstChild ); + TIXMLASSERT( _lastChild->_next == 0 ); + _lastChild->_next = addThis; + addThis->_prev = _lastChild; + _lastChild = addThis; + + addThis->_next = 0; + } + else { + TIXMLASSERT( _firstChild == 0 ); + _firstChild = _lastChild = addThis; + + addThis->_prev = 0; + addThis->_next = 0; + } + addThis->_parent = this; + return addThis; +} + + +XMLNode* XMLNode::InsertFirstChild( XMLNode* addThis ) +{ + TIXMLASSERT( addThis ); + if ( addThis->_document != _document ) { + TIXMLASSERT( false ); + return 0; + } + InsertChildPreamble( addThis ); + + if ( _firstChild ) { + TIXMLASSERT( _lastChild ); + TIXMLASSERT( _firstChild->_prev == 0 ); + + _firstChild->_prev = addThis; + addThis->_next = _firstChild; + _firstChild = addThis; + + addThis->_prev = 0; + } + else { + TIXMLASSERT( _lastChild == 0 ); + _firstChild = _lastChild = addThis; + + addThis->_prev = 0; + addThis->_next = 0; + } + addThis->_parent = this; + return addThis; +} + + +XMLNode* XMLNode::InsertAfterChild( XMLNode* afterThis, XMLNode* addThis ) +{ + TIXMLASSERT( addThis ); + if ( addThis->_document != _document ) { + TIXMLASSERT( false ); + return 0; + } + + TIXMLASSERT( afterThis ); + + if ( afterThis->_parent != this ) { + TIXMLASSERT( false ); + return 0; + } + if ( afterThis == addThis ) { + // Current state: BeforeThis -> AddThis -> OneAfterAddThis + // Now AddThis must disappear from it's location and then + // reappear between BeforeThis and OneAfterAddThis. + // So just leave it where it is. + return addThis; + } + + if ( afterThis->_next == 0 ) { + // The last node or the only node. + return InsertEndChild( addThis ); + } + InsertChildPreamble( addThis ); + addThis->_prev = afterThis; + addThis->_next = afterThis->_next; + afterThis->_next->_prev = addThis; + afterThis->_next = addThis; + addThis->_parent = this; + return addThis; +} + + + + +const XMLElement* XMLNode::FirstChildElement( const char* name ) const +{ + for( const XMLNode* node = _firstChild; node; node = node->_next ) { + const XMLElement* element = node->ToElementWithName( name ); + if ( element ) { + return element; + } + } + return 0; +} + + +const XMLElement* XMLNode::LastChildElement( const char* name ) const +{ + for( const XMLNode* node = _lastChild; node; node = node->_prev ) { + const XMLElement* element = node->ToElementWithName( name ); + if ( element ) { + return element; + } + } + return 0; +} + + +const XMLElement* XMLNode::NextSiblingElement( const char* name ) const +{ + for( const XMLNode* node = _next; node; node = node->_next ) { + const XMLElement* element = node->ToElementWithName( name ); + if ( element ) { + return element; + } + } + return 0; +} + + +const XMLElement* XMLNode::PreviousSiblingElement( const char* name ) const +{ + for( const XMLNode* node = _prev; node; node = node->_prev ) { + const XMLElement* element = node->ToElementWithName( name ); + if ( element ) { + return element; + } + } + return 0; +} + + +char* XMLNode::ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr ) +{ + // This is a recursive method, but thinking about it "at the current level" + // it is a pretty simple flat list: + // + // + // + // With a special case: + // + // + // + // + // Where the closing element (/foo) *must* be the next thing after the opening + // element, and the names must match. BUT the tricky bit is that the closing + // element will be read by the child. + // + // 'endTag' is the end tag for this node, it is returned by a call to a child. + // 'parentEnd' is the end tag for the parent, which is filled in and returned. + + XMLDocument::DepthTracker tracker(_document); + if (_document->Error()) + return 0; + + while( p && *p ) { + XMLNode* node = 0; + + p = _document->Identify( p, &node ); + TIXMLASSERT( p ); + if ( node == 0 ) { + break; + } + + int initialLineNum = node->_parseLineNum; + + StrPair endTag; + p = node->ParseDeep( p, &endTag, curLineNumPtr ); + if ( !p ) { + DeleteNode( node ); + if ( !_document->Error() ) { + _document->SetError( XML_ERROR_PARSING, initialLineNum, 0); + } + break; + } + + XMLDeclaration* decl = node->ToDeclaration(); + if ( decl ) { + // Declarations are only allowed at document level + bool wellLocated = ( ToDocument() != 0 ); + if ( wellLocated ) { + // Multiple declarations are allowed but all declarations + // must occur before anything else + for ( const XMLNode* existingNode = _document->FirstChild(); existingNode; existingNode = existingNode->NextSibling() ) { + if ( !existingNode->ToDeclaration() ) { + wellLocated = false; + break; + } + } + } + if ( !wellLocated ) { + _document->SetError( XML_ERROR_PARSING_DECLARATION, initialLineNum, "XMLDeclaration value=%s", decl->Value()); + DeleteNode( node ); + break; + } + } + + XMLElement* ele = node->ToElement(); + if ( ele ) { + // We read the end tag. Return it to the parent. + if ( ele->ClosingType() == XMLElement::CLOSING ) { + if ( parentEndTag ) { + ele->_value.TransferTo( parentEndTag ); + } + node->_memPool->SetTracked(); // created and then immediately deleted. + DeleteNode( node ); + return p; + } + + // Handle an end tag returned to this level. + // And handle a bunch of annoying errors. + bool mismatch = false; + if ( endTag.Empty() ) { + if ( ele->ClosingType() == XMLElement::OPEN ) { + mismatch = true; + } + } + else { + if ( ele->ClosingType() != XMLElement::OPEN ) { + mismatch = true; + } + else if ( !XMLUtil::StringEqual( endTag.GetStr(), ele->Name() ) ) { + mismatch = true; + } + } + if ( mismatch ) { + _document->SetError( XML_ERROR_MISMATCHED_ELEMENT, initialLineNum, "XMLElement name=%s", ele->Name()); + DeleteNode( node ); + break; + } + } + InsertEndChild( node ); + } + return 0; +} + +/*static*/ void XMLNode::DeleteNode( XMLNode* node ) +{ + if ( node == 0 ) { + return; + } + TIXMLASSERT(node->_document); + if (!node->ToDocument()) { + node->_document->MarkInUse(node); + } + + MemPool* pool = node->_memPool; + node->~XMLNode(); + pool->Free( node ); +} + +void XMLNode::InsertChildPreamble( XMLNode* insertThis ) const +{ + TIXMLASSERT( insertThis ); + TIXMLASSERT( insertThis->_document == _document ); + + if (insertThis->_parent) { + insertThis->_parent->Unlink( insertThis ); + } + else { + insertThis->_document->MarkInUse(insertThis); + insertThis->_memPool->SetTracked(); + } +} + +const XMLElement* XMLNode::ToElementWithName( const char* name ) const +{ + const XMLElement* element = this->ToElement(); + if ( element == 0 ) { + return 0; + } + if ( name == 0 ) { + return element; + } + if ( XMLUtil::StringEqual( element->Name(), name ) ) { + return element; + } + return 0; +} + +// --------- XMLText ---------- // +char* XMLText::ParseDeep( char* p, StrPair*, int* curLineNumPtr ) +{ + if ( this->CData() ) { + p = _value.ParseText( p, "]]>", StrPair::NEEDS_NEWLINE_NORMALIZATION, curLineNumPtr ); + if ( !p ) { + _document->SetError( XML_ERROR_PARSING_CDATA, _parseLineNum, 0 ); + } + return p; + } + else { + int flags = _document->ProcessEntities() ? StrPair::TEXT_ELEMENT : StrPair::TEXT_ELEMENT_LEAVE_ENTITIES; + if ( _document->WhitespaceMode() == COLLAPSE_WHITESPACE ) { + flags |= StrPair::NEEDS_WHITESPACE_COLLAPSING; + } + + p = _value.ParseText( p, "<", flags, curLineNumPtr ); + if ( p && *p ) { + return p-1; + } + if ( !p ) { + _document->SetError( XML_ERROR_PARSING_TEXT, _parseLineNum, 0 ); + } + } + return 0; +} + + +XMLNode* XMLText::ShallowClone( XMLDocument* doc ) const +{ + if ( !doc ) { + doc = _document; + } + XMLText* text = doc->NewText( Value() ); // fixme: this will always allocate memory. Intern? + text->SetCData( this->CData() ); + return text; +} + + +bool XMLText::ShallowEqual( const XMLNode* compare ) const +{ + TIXMLASSERT( compare ); + const XMLText* text = compare->ToText(); + return ( text && XMLUtil::StringEqual( text->Value(), Value() ) ); +} + + +bool XMLText::Accept( XMLVisitor* visitor ) const +{ + TIXMLASSERT( visitor ); + return visitor->Visit( *this ); +} + + +// --------- XMLComment ---------- // + +XMLComment::XMLComment( XMLDocument* doc ) : XMLNode( doc ) +{ +} + + +XMLComment::~XMLComment() +{ +} + + +char* XMLComment::ParseDeep( char* p, StrPair*, int* curLineNumPtr ) +{ + // Comment parses as text. + p = _value.ParseText( p, "-->", StrPair::COMMENT, curLineNumPtr ); + if ( p == 0 ) { + _document->SetError( XML_ERROR_PARSING_COMMENT, _parseLineNum, 0 ); + } + return p; +} + + +XMLNode* XMLComment::ShallowClone( XMLDocument* doc ) const +{ + if ( !doc ) { + doc = _document; + } + XMLComment* comment = doc->NewComment( Value() ); // fixme: this will always allocate memory. Intern? + return comment; +} + + +bool XMLComment::ShallowEqual( const XMLNode* compare ) const +{ + TIXMLASSERT( compare ); + const XMLComment* comment = compare->ToComment(); + return ( comment && XMLUtil::StringEqual( comment->Value(), Value() )); +} + + +bool XMLComment::Accept( XMLVisitor* visitor ) const +{ + TIXMLASSERT( visitor ); + return visitor->Visit( *this ); +} + + +// --------- XMLDeclaration ---------- // + +XMLDeclaration::XMLDeclaration( XMLDocument* doc ) : XMLNode( doc ) +{ +} + + +XMLDeclaration::~XMLDeclaration() +{ + //printf( "~XMLDeclaration\n" ); +} + + +char* XMLDeclaration::ParseDeep( char* p, StrPair*, int* curLineNumPtr ) +{ + // Declaration parses as text. + p = _value.ParseText( p, "?>", StrPair::NEEDS_NEWLINE_NORMALIZATION, curLineNumPtr ); + if ( p == 0 ) { + _document->SetError( XML_ERROR_PARSING_DECLARATION, _parseLineNum, 0 ); + } + return p; +} + + +XMLNode* XMLDeclaration::ShallowClone( XMLDocument* doc ) const +{ + if ( !doc ) { + doc = _document; + } + XMLDeclaration* dec = doc->NewDeclaration( Value() ); // fixme: this will always allocate memory. Intern? + return dec; +} + + +bool XMLDeclaration::ShallowEqual( const XMLNode* compare ) const +{ + TIXMLASSERT( compare ); + const XMLDeclaration* declaration = compare->ToDeclaration(); + return ( declaration && XMLUtil::StringEqual( declaration->Value(), Value() )); +} + + + +bool XMLDeclaration::Accept( XMLVisitor* visitor ) const +{ + TIXMLASSERT( visitor ); + return visitor->Visit( *this ); +} + +// --------- XMLUnknown ---------- // + +XMLUnknown::XMLUnknown( XMLDocument* doc ) : XMLNode( doc ) +{ +} + + +XMLUnknown::~XMLUnknown() +{ +} + + +char* XMLUnknown::ParseDeep( char* p, StrPair*, int* curLineNumPtr ) +{ + // Unknown parses as text. + p = _value.ParseText( p, ">", StrPair::NEEDS_NEWLINE_NORMALIZATION, curLineNumPtr ); + if ( !p ) { + _document->SetError( XML_ERROR_PARSING_UNKNOWN, _parseLineNum, 0 ); + } + return p; +} + + +XMLNode* XMLUnknown::ShallowClone( XMLDocument* doc ) const +{ + if ( !doc ) { + doc = _document; + } + XMLUnknown* text = doc->NewUnknown( Value() ); // fixme: this will always allocate memory. Intern? + return text; +} + + +bool XMLUnknown::ShallowEqual( const XMLNode* compare ) const +{ + TIXMLASSERT( compare ); + const XMLUnknown* unknown = compare->ToUnknown(); + return ( unknown && XMLUtil::StringEqual( unknown->Value(), Value() )); +} + + +bool XMLUnknown::Accept( XMLVisitor* visitor ) const +{ + TIXMLASSERT( visitor ); + return visitor->Visit( *this ); +} + +// --------- XMLAttribute ---------- // + +const char* XMLAttribute::Name() const +{ + return _name.GetStr(); +} + +const char* XMLAttribute::Value() const +{ + return _value.GetStr(); +} + +char* XMLAttribute::ParseDeep( char* p, bool processEntities, int* curLineNumPtr ) +{ + // Parse using the name rules: bug fix, was using ParseText before + p = _name.ParseName( p ); + if ( !p || !*p ) { + return 0; + } + + // Skip white space before = + p = XMLUtil::SkipWhiteSpace( p, curLineNumPtr ); + if ( *p != '=' ) { + return 0; + } + + ++p; // move up to opening quote + p = XMLUtil::SkipWhiteSpace( p, curLineNumPtr ); + if ( *p != '\"' && *p != '\'' ) { + return 0; + } + + char endTag[2] = { *p, 0 }; + ++p; // move past opening quote + + p = _value.ParseText( p, endTag, processEntities ? StrPair::ATTRIBUTE_VALUE : StrPair::ATTRIBUTE_VALUE_LEAVE_ENTITIES, curLineNumPtr ); + return p; +} + + +void XMLAttribute::SetName( const char* n ) +{ + _name.SetStr( n ); +} + + +XMLError XMLAttribute::QueryIntValue( int* value ) const +{ + if ( XMLUtil::ToInt( Value(), value )) { + return XML_SUCCESS; + } + return XML_WRONG_ATTRIBUTE_TYPE; +} + + +XMLError XMLAttribute::QueryUnsignedValue( unsigned int* value ) const +{ + if ( XMLUtil::ToUnsigned( Value(), value )) { + return XML_SUCCESS; + } + return XML_WRONG_ATTRIBUTE_TYPE; +} + + +XMLError XMLAttribute::QueryInt64Value(int64_t* value) const +{ + if (XMLUtil::ToInt64(Value(), value)) { + return XML_SUCCESS; + } + return XML_WRONG_ATTRIBUTE_TYPE; +} + + +XMLError XMLAttribute::QueryBoolValue( bool* value ) const +{ + if ( XMLUtil::ToBool( Value(), value )) { + return XML_SUCCESS; + } + return XML_WRONG_ATTRIBUTE_TYPE; +} + + +XMLError XMLAttribute::QueryFloatValue( float* value ) const +{ + if ( XMLUtil::ToFloat( Value(), value )) { + return XML_SUCCESS; + } + return XML_WRONG_ATTRIBUTE_TYPE; +} + + +XMLError XMLAttribute::QueryDoubleValue( double* value ) const +{ + if ( XMLUtil::ToDouble( Value(), value )) { + return XML_SUCCESS; + } + return XML_WRONG_ATTRIBUTE_TYPE; +} + + +void XMLAttribute::SetAttribute( const char* v ) +{ + _value.SetStr( v ); +} + + +void XMLAttribute::SetAttribute( int v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + _value.SetStr( buf ); +} + + +void XMLAttribute::SetAttribute( unsigned v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + _value.SetStr( buf ); +} + + +void XMLAttribute::SetAttribute(int64_t v) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr(v, buf, BUF_SIZE); + _value.SetStr(buf); +} + + + +void XMLAttribute::SetAttribute( bool v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + _value.SetStr( buf ); +} + +void XMLAttribute::SetAttribute( double v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + _value.SetStr( buf ); +} + +void XMLAttribute::SetAttribute( float v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + _value.SetStr( buf ); +} + + +// --------- XMLElement ---------- // +XMLElement::XMLElement( XMLDocument* doc ) : XMLNode( doc ), + _closingType( OPEN ), + _rootAttribute( 0 ) +{ +} + + +XMLElement::~XMLElement() +{ + while( _rootAttribute ) { + XMLAttribute* next = _rootAttribute->_next; + DeleteAttribute( _rootAttribute ); + _rootAttribute = next; + } +} + + +const XMLAttribute* XMLElement::FindAttribute( const char* name ) const +{ + for( XMLAttribute* a = _rootAttribute; a; a = a->_next ) { + if ( XMLUtil::StringEqual( a->Name(), name ) ) { + return a; + } + } + return 0; +} + + +const char* XMLElement::Attribute( const char* name, const char* value ) const +{ + const XMLAttribute* a = FindAttribute( name ); + if ( !a ) { + return 0; + } + if ( !value || XMLUtil::StringEqual( a->Value(), value )) { + return a->Value(); + } + return 0; +} + +int XMLElement::IntAttribute(const char* name, int defaultValue) const +{ + int i = defaultValue; + QueryIntAttribute(name, &i); + return i; +} + +unsigned XMLElement::UnsignedAttribute(const char* name, unsigned defaultValue) const +{ + unsigned i = defaultValue; + QueryUnsignedAttribute(name, &i); + return i; +} + +int64_t XMLElement::Int64Attribute(const char* name, int64_t defaultValue) const +{ + int64_t i = defaultValue; + QueryInt64Attribute(name, &i); + return i; +} + +bool XMLElement::BoolAttribute(const char* name, bool defaultValue) const +{ + bool b = defaultValue; + QueryBoolAttribute(name, &b); + return b; +} + +double XMLElement::DoubleAttribute(const char* name, double defaultValue) const +{ + double d = defaultValue; + QueryDoubleAttribute(name, &d); + return d; +} + +float XMLElement::FloatAttribute(const char* name, float defaultValue) const +{ + float f = defaultValue; + QueryFloatAttribute(name, &f); + return f; +} + +const char* XMLElement::GetText() const +{ + if ( FirstChild() && FirstChild()->ToText() ) { + return FirstChild()->Value(); + } + return 0; +} + + +void XMLElement::SetText( const char* inText ) +{ + if ( FirstChild() && FirstChild()->ToText() ) + FirstChild()->SetValue( inText ); + else { + XMLText* theText = GetDocument()->NewText( inText ); + InsertFirstChild( theText ); + } +} + + +void XMLElement::SetText( int v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + SetText( buf ); +} + + +void XMLElement::SetText( unsigned v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + SetText( buf ); +} + + +void XMLElement::SetText(int64_t v) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr(v, buf, BUF_SIZE); + SetText(buf); +} + + +void XMLElement::SetText( bool v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + SetText( buf ); +} + + +void XMLElement::SetText( float v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + SetText( buf ); +} + + +void XMLElement::SetText( double v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + SetText( buf ); +} + + +XMLError XMLElement::QueryIntText( int* ival ) const +{ + if ( FirstChild() && FirstChild()->ToText() ) { + const char* t = FirstChild()->Value(); + if ( XMLUtil::ToInt( t, ival ) ) { + return XML_SUCCESS; + } + return XML_CAN_NOT_CONVERT_TEXT; + } + return XML_NO_TEXT_NODE; +} + + +XMLError XMLElement::QueryUnsignedText( unsigned* uval ) const +{ + if ( FirstChild() && FirstChild()->ToText() ) { + const char* t = FirstChild()->Value(); + if ( XMLUtil::ToUnsigned( t, uval ) ) { + return XML_SUCCESS; + } + return XML_CAN_NOT_CONVERT_TEXT; + } + return XML_NO_TEXT_NODE; +} + + +XMLError XMLElement::QueryInt64Text(int64_t* ival) const +{ + if (FirstChild() && FirstChild()->ToText()) { + const char* t = FirstChild()->Value(); + if (XMLUtil::ToInt64(t, ival)) { + return XML_SUCCESS; + } + return XML_CAN_NOT_CONVERT_TEXT; + } + return XML_NO_TEXT_NODE; +} + + +XMLError XMLElement::QueryBoolText( bool* bval ) const +{ + if ( FirstChild() && FirstChild()->ToText() ) { + const char* t = FirstChild()->Value(); + if ( XMLUtil::ToBool( t, bval ) ) { + return XML_SUCCESS; + } + return XML_CAN_NOT_CONVERT_TEXT; + } + return XML_NO_TEXT_NODE; +} + + +XMLError XMLElement::QueryDoubleText( double* dval ) const +{ + if ( FirstChild() && FirstChild()->ToText() ) { + const char* t = FirstChild()->Value(); + if ( XMLUtil::ToDouble( t, dval ) ) { + return XML_SUCCESS; + } + return XML_CAN_NOT_CONVERT_TEXT; + } + return XML_NO_TEXT_NODE; +} + + +XMLError XMLElement::QueryFloatText( float* fval ) const +{ + if ( FirstChild() && FirstChild()->ToText() ) { + const char* t = FirstChild()->Value(); + if ( XMLUtil::ToFloat( t, fval ) ) { + return XML_SUCCESS; + } + return XML_CAN_NOT_CONVERT_TEXT; + } + return XML_NO_TEXT_NODE; +} + +int XMLElement::IntText(int defaultValue) const +{ + int i = defaultValue; + QueryIntText(&i); + return i; +} + +unsigned XMLElement::UnsignedText(unsigned defaultValue) const +{ + unsigned i = defaultValue; + QueryUnsignedText(&i); + return i; +} + +int64_t XMLElement::Int64Text(int64_t defaultValue) const +{ + int64_t i = defaultValue; + QueryInt64Text(&i); + return i; +} + +bool XMLElement::BoolText(bool defaultValue) const +{ + bool b = defaultValue; + QueryBoolText(&b); + return b; +} + +double XMLElement::DoubleText(double defaultValue) const +{ + double d = defaultValue; + QueryDoubleText(&d); + return d; +} + +float XMLElement::FloatText(float defaultValue) const +{ + float f = defaultValue; + QueryFloatText(&f); + return f; +} + + +XMLAttribute* XMLElement::FindOrCreateAttribute( const char* name ) +{ + XMLAttribute* last = 0; + XMLAttribute* attrib = 0; + for( attrib = _rootAttribute; + attrib; + last = attrib, attrib = attrib->_next ) { + if ( XMLUtil::StringEqual( attrib->Name(), name ) ) { + break; + } + } + if ( !attrib ) { + attrib = CreateAttribute(); + TIXMLASSERT( attrib ); + if ( last ) { + TIXMLASSERT( last->_next == 0 ); + last->_next = attrib; + } + else { + TIXMLASSERT( _rootAttribute == 0 ); + _rootAttribute = attrib; + } + attrib->SetName( name ); + } + return attrib; +} + + +void XMLElement::DeleteAttribute( const char* name ) +{ + XMLAttribute* prev = 0; + for( XMLAttribute* a=_rootAttribute; a; a=a->_next ) { + if ( XMLUtil::StringEqual( name, a->Name() ) ) { + if ( prev ) { + prev->_next = a->_next; + } + else { + _rootAttribute = a->_next; + } + DeleteAttribute( a ); + break; + } + prev = a; + } +} + + +char* XMLElement::ParseAttributes( char* p, int* curLineNumPtr ) +{ + XMLAttribute* prevAttribute = 0; + + // Read the attributes. + while( p ) { + p = XMLUtil::SkipWhiteSpace( p, curLineNumPtr ); + if ( !(*p) ) { + _document->SetError( XML_ERROR_PARSING_ELEMENT, _parseLineNum, "XMLElement name=%s", Name() ); + return 0; + } + + // attribute. + if (XMLUtil::IsNameStartChar( *p ) ) { + XMLAttribute* attrib = CreateAttribute(); + TIXMLASSERT( attrib ); + attrib->_parseLineNum = _document->_parseCurLineNum; + + int attrLineNum = attrib->_parseLineNum; + + p = attrib->ParseDeep( p, _document->ProcessEntities(), curLineNumPtr ); + if ( !p || Attribute( attrib->Name() ) ) { + DeleteAttribute( attrib ); + _document->SetError( XML_ERROR_PARSING_ATTRIBUTE, attrLineNum, "XMLElement name=%s", Name() ); + return 0; + } + // There is a minor bug here: if the attribute in the source xml + // document is duplicated, it will not be detected and the + // attribute will be doubly added. However, tracking the 'prevAttribute' + // avoids re-scanning the attribute list. Preferring performance for + // now, may reconsider in the future. + if ( prevAttribute ) { + TIXMLASSERT( prevAttribute->_next == 0 ); + prevAttribute->_next = attrib; + } + else { + TIXMLASSERT( _rootAttribute == 0 ); + _rootAttribute = attrib; + } + prevAttribute = attrib; + } + // end of the tag + else if ( *p == '>' ) { + ++p; + break; + } + // end of the tag + else if ( *p == '/' && *(p+1) == '>' ) { + _closingType = CLOSED; + return p+2; // done; sealed element. + } + else { + _document->SetError( XML_ERROR_PARSING_ELEMENT, _parseLineNum, 0 ); + return 0; + } + } + return p; +} + +void XMLElement::DeleteAttribute( XMLAttribute* attribute ) +{ + if ( attribute == 0 ) { + return; + } + MemPool* pool = attribute->_memPool; + attribute->~XMLAttribute(); + pool->Free( attribute ); +} + +XMLAttribute* XMLElement::CreateAttribute() +{ + TIXMLASSERT( sizeof( XMLAttribute ) == _document->_attributePool.ItemSize() ); + XMLAttribute* attrib = new (_document->_attributePool.Alloc() ) XMLAttribute(); + TIXMLASSERT( attrib ); + attrib->_memPool = &_document->_attributePool; + attrib->_memPool->SetTracked(); + return attrib; +} + +// +// +// foobar +// +char* XMLElement::ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr ) +{ + // Read the element name. + p = XMLUtil::SkipWhiteSpace( p, curLineNumPtr ); + + // The closing element is the form. It is + // parsed just like a regular element then deleted from + // the DOM. + if ( *p == '/' ) { + _closingType = CLOSING; + ++p; + } + + p = _value.ParseName( p ); + if ( _value.Empty() ) { + return 0; + } + + p = ParseAttributes( p, curLineNumPtr ); + if ( !p || !*p || _closingType != OPEN ) { + return p; + } + + p = XMLNode::ParseDeep( p, parentEndTag, curLineNumPtr ); + return p; +} + + + +XMLNode* XMLElement::ShallowClone( XMLDocument* doc ) const +{ + if ( !doc ) { + doc = _document; + } + XMLElement* element = doc->NewElement( Value() ); // fixme: this will always allocate memory. Intern? + for( const XMLAttribute* a=FirstAttribute(); a; a=a->Next() ) { + element->SetAttribute( a->Name(), a->Value() ); // fixme: this will always allocate memory. Intern? + } + return element; +} + + +bool XMLElement::ShallowEqual( const XMLNode* compare ) const +{ + TIXMLASSERT( compare ); + const XMLElement* other = compare->ToElement(); + if ( other && XMLUtil::StringEqual( other->Name(), Name() )) { + + const XMLAttribute* a=FirstAttribute(); + const XMLAttribute* b=other->FirstAttribute(); + + while ( a && b ) { + if ( !XMLUtil::StringEqual( a->Value(), b->Value() ) ) { + return false; + } + a = a->Next(); + b = b->Next(); + } + if ( a || b ) { + // different count + return false; + } + return true; + } + return false; +} + + +bool XMLElement::Accept( XMLVisitor* visitor ) const +{ + TIXMLASSERT( visitor ); + if ( visitor->VisitEnter( *this, _rootAttribute ) ) { + for ( const XMLNode* node=FirstChild(); node; node=node->NextSibling() ) { + if ( !node->Accept( visitor ) ) { + break; + } + } + } + return visitor->VisitExit( *this ); +} + + +// --------- XMLDocument ----------- // + +// Warning: List must match 'enum XMLError' +const char* XMLDocument::_errorNames[XML_ERROR_COUNT] = { + "XML_SUCCESS", + "XML_NO_ATTRIBUTE", + "XML_WRONG_ATTRIBUTE_TYPE", + "XML_ERROR_FILE_NOT_FOUND", + "XML_ERROR_FILE_COULD_NOT_BE_OPENED", + "XML_ERROR_FILE_READ_ERROR", + "UNUSED_XML_ERROR_ELEMENT_MISMATCH", + "XML_ERROR_PARSING_ELEMENT", + "XML_ERROR_PARSING_ATTRIBUTE", + "UNUSED_XML_ERROR_IDENTIFYING_TAG", + "XML_ERROR_PARSING_TEXT", + "XML_ERROR_PARSING_CDATA", + "XML_ERROR_PARSING_COMMENT", + "XML_ERROR_PARSING_DECLARATION", + "XML_ERROR_PARSING_UNKNOWN", + "XML_ERROR_EMPTY_DOCUMENT", + "XML_ERROR_MISMATCHED_ELEMENT", + "XML_ERROR_PARSING", + "XML_CAN_NOT_CONVERT_TEXT", + "XML_NO_TEXT_NODE", + "XML_ELEMENT_DEPTH_EXCEEDED" +}; + + +XMLDocument::XMLDocument( bool processEntities, Whitespace whitespaceMode ) : + XMLNode( 0 ), + _writeBOM( false ), + _processEntities( processEntities ), + _errorID(XML_SUCCESS), + _whitespaceMode( whitespaceMode ), + _errorStr(), + _errorLineNum( 0 ), + _charBuffer( 0 ), + _parseCurLineNum( 0 ), + _parsingDepth(0), + _unlinked(), + _elementPool(), + _attributePool(), + _textPool(), + _commentPool() +{ + // avoid VC++ C4355 warning about 'this' in initializer list (C4355 is off by default in VS2012+) + _document = this; +} + + +XMLDocument::~XMLDocument() +{ + Clear(); +} + + +void XMLDocument::MarkInUse(XMLNode* node) +{ + TIXMLASSERT(node); + TIXMLASSERT(node->_parent == 0); + + for (int i = 0; i < _unlinked.Size(); ++i) { + if (node == _unlinked[i]) { + _unlinked.SwapRemove(i); + break; + } + } +} + +void XMLDocument::Clear() +{ + DeleteChildren(); + while( _unlinked.Size()) { + DeleteNode(_unlinked[0]); // Will remove from _unlinked as part of delete. + } + +#ifdef TINYXML2_DEBUG + const bool hadError = Error(); +#endif + ClearError(); + + delete [] _charBuffer; + _charBuffer = 0; + _parsingDepth = 0; + +#if 0 + _textPool.Trace( "text" ); + _elementPool.Trace( "element" ); + _commentPool.Trace( "comment" ); + _attributePool.Trace( "attribute" ); +#endif + +#ifdef TINYXML2_DEBUG + if ( !hadError ) { + TIXMLASSERT( _elementPool.CurrentAllocs() == _elementPool.Untracked() ); + TIXMLASSERT( _attributePool.CurrentAllocs() == _attributePool.Untracked() ); + TIXMLASSERT( _textPool.CurrentAllocs() == _textPool.Untracked() ); + TIXMLASSERT( _commentPool.CurrentAllocs() == _commentPool.Untracked() ); + } +#endif +} + + +void XMLDocument::DeepCopy(XMLDocument* target) const +{ + TIXMLASSERT(target); + if (target == this) { + return; // technically success - a no-op. + } + + target->Clear(); + for (const XMLNode* node = this->FirstChild(); node; node = node->NextSibling()) { + target->InsertEndChild(node->DeepClone(target)); + } +} + +XMLElement* XMLDocument::NewElement( const char* name ) +{ + XMLElement* ele = CreateUnlinkedNode( _elementPool ); + ele->SetName( name ); + return ele; +} + + +XMLComment* XMLDocument::NewComment( const char* str ) +{ + XMLComment* comment = CreateUnlinkedNode( _commentPool ); + comment->SetValue( str ); + return comment; +} + + +XMLText* XMLDocument::NewText( const char* str ) +{ + XMLText* text = CreateUnlinkedNode( _textPool ); + text->SetValue( str ); + return text; +} + + +XMLDeclaration* XMLDocument::NewDeclaration( const char* str ) +{ + XMLDeclaration* dec = CreateUnlinkedNode( _commentPool ); + dec->SetValue( str ? str : "xml version=\"1.0\" encoding=\"UTF-8\"" ); + return dec; +} + + +XMLUnknown* XMLDocument::NewUnknown( const char* str ) +{ + XMLUnknown* unk = CreateUnlinkedNode( _commentPool ); + unk->SetValue( str ); + return unk; +} + +static FILE* callfopen( const char* filepath, const char* mode ) +{ + TIXMLASSERT( filepath ); + TIXMLASSERT( mode ); +#if defined(_MSC_VER) && (_MSC_VER >= 1400 ) && (!defined WINCE) + FILE* fp = 0; + errno_t err = fopen_s( &fp, filepath, mode ); + if ( err ) { + return 0; + } +#else + FILE* fp = fopen( filepath, mode ); +#endif + return fp; +} + +void XMLDocument::DeleteNode( XMLNode* node ) { + TIXMLASSERT( node ); + TIXMLASSERT(node->_document == this ); + if (node->_parent) { + node->_parent->DeleteChild( node ); + } + else { + // Isn't in the tree. + // Use the parent delete. + // Also, we need to mark it tracked: we 'know' + // it was never used. + node->_memPool->SetTracked(); + // Call the static XMLNode version: + XMLNode::DeleteNode(node); + } +} + + +XMLError XMLDocument::LoadFile( const char* filename ) +{ + if ( !filename ) { + TIXMLASSERT( false ); + SetError( XML_ERROR_FILE_COULD_NOT_BE_OPENED, 0, "filename=" ); + return _errorID; + } + + Clear(); + FILE* fp = callfopen( filename, "rb" ); + if ( !fp ) { + SetError( XML_ERROR_FILE_NOT_FOUND, 0, "filename=%s", filename ); + return _errorID; + } + LoadFile( fp ); + fclose( fp ); + return _errorID; +} + +// This is likely overengineered template art to have a check that unsigned long value incremented +// by one still fits into size_t. If size_t type is larger than unsigned long type +// (x86_64-w64-mingw32 target) then the check is redundant and gcc and clang emit +// -Wtype-limits warning. This piece makes the compiler select code with a check when a check +// is useful and code with no check when a check is redundant depending on how size_t and unsigned long +// types sizes relate to each other. +template += sizeof(size_t))> +struct LongFitsIntoSizeTMinusOne { + static bool Fits( unsigned long value ) + { + return value < (size_t)-1; + } +}; + +template <> +struct LongFitsIntoSizeTMinusOne { + static bool Fits( unsigned long ) + { + return true; + } +}; + +XMLError XMLDocument::LoadFile( FILE* fp ) +{ + Clear(); + + fseek( fp, 0, SEEK_SET ); + if ( fgetc( fp ) == EOF && ferror( fp ) != 0 ) { + SetError( XML_ERROR_FILE_READ_ERROR, 0, 0 ); + return _errorID; + } + + fseek( fp, 0, SEEK_END ); + const long filelength = ftell( fp ); + fseek( fp, 0, SEEK_SET ); + if ( filelength == -1L ) { + SetError( XML_ERROR_FILE_READ_ERROR, 0, 0 ); + return _errorID; + } + TIXMLASSERT( filelength >= 0 ); + + if ( !LongFitsIntoSizeTMinusOne<>::Fits( filelength ) ) { + // Cannot handle files which won't fit in buffer together with null terminator + SetError( XML_ERROR_FILE_READ_ERROR, 0, 0 ); + return _errorID; + } + + if ( filelength == 0 ) { + SetError( XML_ERROR_EMPTY_DOCUMENT, 0, 0 ); + return _errorID; + } + + const size_t size = filelength; + TIXMLASSERT( _charBuffer == 0 ); + _charBuffer = new char[size+1]; + size_t read = fread( _charBuffer, 1, size, fp ); + if ( read != size ) { + SetError( XML_ERROR_FILE_READ_ERROR, 0, 0 ); + return _errorID; + } + + _charBuffer[size] = 0; + + Parse(); + return _errorID; +} + + +XMLError XMLDocument::SaveFile( const char* filename, bool compact ) +{ + if ( !filename ) { + TIXMLASSERT( false ); + SetError( XML_ERROR_FILE_COULD_NOT_BE_OPENED, 0, "filename=" ); + return _errorID; + } + + FILE* fp = callfopen( filename, "w" ); + if ( !fp ) { + SetError( XML_ERROR_FILE_COULD_NOT_BE_OPENED, 0, "filename=%s", filename ); + return _errorID; + } + SaveFile(fp, compact); + fclose( fp ); + return _errorID; +} + + +XMLError XMLDocument::SaveFile( FILE* fp, bool compact ) +{ + // Clear any error from the last save, otherwise it will get reported + // for *this* call. + ClearError(); + XMLPrinter stream( fp, compact ); + Print( &stream ); + return _errorID; +} + + +XMLError XMLDocument::Parse( const char* p, size_t len ) +{ + Clear(); + + if ( len == 0 || !p || !*p ) { + SetError( XML_ERROR_EMPTY_DOCUMENT, 0, 0 ); + return _errorID; + } + if ( len == (size_t)(-1) ) { + len = strlen( p ); + } + TIXMLASSERT( _charBuffer == 0 ); + _charBuffer = new char[ len+1 ]; + memcpy( _charBuffer, p, len ); + _charBuffer[len] = 0; + + Parse(); + if ( Error() ) { + // clean up now essentially dangling memory. + // and the parse fail can put objects in the + // pools that are dead and inaccessible. + DeleteChildren(); + _elementPool.Clear(); + _attributePool.Clear(); + _textPool.Clear(); + _commentPool.Clear(); + } + return _errorID; +} + + +void XMLDocument::Print( XMLPrinter* streamer ) const +{ + if ( streamer ) { + Accept( streamer ); + } + else { + XMLPrinter stdoutStreamer( stdout ); + Accept( &stdoutStreamer ); + } +} + + +void XMLDocument::SetError( XMLError error, int lineNum, const char* format, ... ) +{ + TIXMLASSERT( error >= 0 && error < XML_ERROR_COUNT ); + _errorID = error; + _errorLineNum = lineNum; + _errorStr.Reset(); + + size_t BUFFER_SIZE = 1000; + char* buffer = new char[BUFFER_SIZE]; + + TIXML_SNPRINTF(buffer, BUFFER_SIZE, "Error=%s ErrorID=%d (0x%x) Line number=%d", ErrorIDToName(error), int(error), int(error), lineNum); + + if (format) { + size_t len = strlen(buffer); + TIXML_SNPRINTF(buffer + len, BUFFER_SIZE - len, ": "); + len = strlen(buffer); + + va_list va; + va_start(va, format); + TIXML_VSNPRINTF(buffer + len, BUFFER_SIZE - len, format, va); + va_end(va); + } + _errorStr.SetStr(buffer); + delete[] buffer; +} + + +/*static*/ const char* XMLDocument::ErrorIDToName(XMLError errorID) +{ + TIXMLASSERT( errorID >= 0 && errorID < XML_ERROR_COUNT ); + const char* errorName = _errorNames[errorID]; + TIXMLASSERT( errorName && errorName[0] ); + return errorName; +} + +const char* XMLDocument::ErrorStr() const +{ + return _errorStr.Empty() ? "" : _errorStr.GetStr(); +} + + +void XMLDocument::PrintError() const +{ + printf("%s\n", ErrorStr()); +} + +const char* XMLDocument::ErrorName() const +{ + return ErrorIDToName(_errorID); +} + +void XMLDocument::Parse() +{ + TIXMLASSERT( NoChildren() ); // Clear() must have been called previously + TIXMLASSERT( _charBuffer ); + _parseCurLineNum = 1; + _parseLineNum = 1; + char* p = _charBuffer; + p = XMLUtil::SkipWhiteSpace( p, &_parseCurLineNum ); + p = const_cast( XMLUtil::ReadBOM( p, &_writeBOM ) ); + if ( !*p ) { + SetError( XML_ERROR_EMPTY_DOCUMENT, 0, 0 ); + return; + } + ParseDeep(p, 0, &_parseCurLineNum ); +} + +void XMLDocument::PushDepth() +{ + _parsingDepth++; + if (_parsingDepth == TINYXML2_MAX_ELEMENT_DEPTH) { + SetError(XML_ELEMENT_DEPTH_EXCEEDED, _parseCurLineNum, "Element nesting is too deep." ); + } +} + +void XMLDocument::PopDepth() +{ + TIXMLASSERT(_parsingDepth > 0); + --_parsingDepth; +} + +XMLPrinter::XMLPrinter( FILE* file, bool compact, int depth ) : + _elementJustOpened( false ), + _stack(), + _firstElement( true ), + _fp( file ), + _depth( depth ), + _textDepth( -1 ), + _processEntities( true ), + _compactMode( compact ), + _buffer() +{ + for( int i=0; i'] = true; // not required, but consistency is nice + _buffer.Push( 0 ); +} + + +void XMLPrinter::Print( const char* format, ... ) +{ + va_list va; + va_start( va, format ); + + if ( _fp ) { + vfprintf( _fp, format, va ); + } + else { + const int len = TIXML_VSCPRINTF( format, va ); + // Close out and re-start the va-args + va_end( va ); + TIXMLASSERT( len >= 0 ); + va_start( va, format ); + TIXMLASSERT( _buffer.Size() > 0 && _buffer[_buffer.Size() - 1] == 0 ); + char* p = _buffer.PushArr( len ) - 1; // back up over the null terminator. + TIXML_VSNPRINTF( p, len+1, format, va ); + } + va_end( va ); +} + + +void XMLPrinter::Write( const char* data, size_t size ) +{ + if ( _fp ) { + fwrite ( data , sizeof(char), size, _fp); + } + else { + char* p = _buffer.PushArr( static_cast(size) ) - 1; // back up over the null terminator. + memcpy( p, data, size ); + p[size] = 0; + } +} + + +void XMLPrinter::Putc( char ch ) +{ + if ( _fp ) { + fputc ( ch, _fp); + } + else { + char* p = _buffer.PushArr( sizeof(char) ) - 1; // back up over the null terminator. + p[0] = ch; + p[1] = 0; + } +} + + +void XMLPrinter::PrintSpace( int depth ) +{ + for( int i=0; i 0 && *q < ENTITY_RANGE ) { + // Check for entities. If one is found, flush + // the stream up until the entity, write the + // entity, and keep looking. + if ( flag[(unsigned char)(*q)] ) { + while ( p < q ) { + const size_t delta = q - p; + const int toPrint = ( INT_MAX < delta ) ? INT_MAX : (int)delta; + Write( p, toPrint ); + p += toPrint; + } + bool entityPatternPrinted = false; + for( int i=0; i( bom ) ); + } + if ( writeDec ) { + PushDeclaration( "xml version=\"1.0\"" ); + } +} + + +void XMLPrinter::OpenElement( const char* name, bool compactMode ) +{ + SealElementIfJustOpened(); + _stack.Push( name ); + + if ( _textDepth < 0 && !_firstElement && !compactMode ) { + Putc( '\n' ); + } + if ( !compactMode ) { + PrintSpace( _depth ); + } + + Write ( "<" ); + Write ( name ); + + _elementJustOpened = true; + _firstElement = false; + ++_depth; +} + + +void XMLPrinter::PushAttribute( const char* name, const char* value ) +{ + TIXMLASSERT( _elementJustOpened ); + Putc ( ' ' ); + Write( name ); + Write( "=\"" ); + PrintString( value, false ); + Putc ( '\"' ); +} + + +void XMLPrinter::PushAttribute( const char* name, int v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + PushAttribute( name, buf ); +} + + +void XMLPrinter::PushAttribute( const char* name, unsigned v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + PushAttribute( name, buf ); +} + + +void XMLPrinter::PushAttribute(const char* name, int64_t v) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr(v, buf, BUF_SIZE); + PushAttribute(name, buf); +} + + +void XMLPrinter::PushAttribute( const char* name, bool v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + PushAttribute( name, buf ); +} + + +void XMLPrinter::PushAttribute( const char* name, double v ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( v, buf, BUF_SIZE ); + PushAttribute( name, buf ); +} + + +void XMLPrinter::CloseElement( bool compactMode ) +{ + --_depth; + const char* name = _stack.Pop(); + + if ( _elementJustOpened ) { + Write( "/>" ); + } + else { + if ( _textDepth < 0 && !compactMode) { + Putc( '\n' ); + PrintSpace( _depth ); + } + Write ( "" ); + } + + if ( _textDepth == _depth ) { + _textDepth = -1; + } + if ( _depth == 0 && !compactMode) { + Putc( '\n' ); + } + _elementJustOpened = false; +} + + +void XMLPrinter::SealElementIfJustOpened() +{ + if ( !_elementJustOpened ) { + return; + } + _elementJustOpened = false; + Putc( '>' ); +} + + +void XMLPrinter::PushText( const char* text, bool cdata ) +{ + _textDepth = _depth-1; + + SealElementIfJustOpened(); + if ( cdata ) { + Write( "" ); + } + else { + PrintString( text, true ); + } +} + +void XMLPrinter::PushText( int64_t value ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( value, buf, BUF_SIZE ); + PushText( buf, false ); +} + +void XMLPrinter::PushText( int value ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( value, buf, BUF_SIZE ); + PushText( buf, false ); +} + + +void XMLPrinter::PushText( unsigned value ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( value, buf, BUF_SIZE ); + PushText( buf, false ); +} + + +void XMLPrinter::PushText( bool value ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( value, buf, BUF_SIZE ); + PushText( buf, false ); +} + + +void XMLPrinter::PushText( float value ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( value, buf, BUF_SIZE ); + PushText( buf, false ); +} + + +void XMLPrinter::PushText( double value ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr( value, buf, BUF_SIZE ); + PushText( buf, false ); +} + + +void XMLPrinter::PushComment( const char* comment ) +{ + SealElementIfJustOpened(); + if ( _textDepth < 0 && !_firstElement && !_compactMode) { + Putc( '\n' ); + PrintSpace( _depth ); + } + _firstElement = false; + + Write( "" ); +} + + +void XMLPrinter::PushDeclaration( const char* value ) +{ + SealElementIfJustOpened(); + if ( _textDepth < 0 && !_firstElement && !_compactMode) { + Putc( '\n' ); + PrintSpace( _depth ); + } + _firstElement = false; + + Write( "" ); +} + + +void XMLPrinter::PushUnknown( const char* value ) +{ + SealElementIfJustOpened(); + if ( _textDepth < 0 && !_firstElement && !_compactMode) { + Putc( '\n' ); + PrintSpace( _depth ); + } + _firstElement = false; + + Write( "' ); +} + + +bool XMLPrinter::VisitEnter( const XMLDocument& doc ) +{ + _processEntities = doc.ProcessEntities(); + if ( doc.HasBOM() ) { + PushHeader( true, false ); + } + return true; +} + + +bool XMLPrinter::VisitEnter( const XMLElement& element, const XMLAttribute* attribute ) +{ + const XMLElement* parentElem = 0; + if ( element.Parent() ) { + parentElem = element.Parent()->ToElement(); + } + const bool compactMode = parentElem ? CompactMode( *parentElem ) : _compactMode; + OpenElement( element.Name(), compactMode ); + while ( attribute ) { + PushAttribute( attribute->Name(), attribute->Value() ); + attribute = attribute->Next(); + } + return true; +} + + +bool XMLPrinter::VisitExit( const XMLElement& element ) +{ + CloseElement( CompactMode(element) ); + return true; +} + + +bool XMLPrinter::Visit( const XMLText& text ) +{ + PushText( text.Value(), text.CData() ); + return true; +} + + +bool XMLPrinter::Visit( const XMLComment& comment ) +{ + PushComment( comment.Value() ); + return true; +} + +bool XMLPrinter::Visit( const XMLDeclaration& declaration ) +{ + PushDeclaration( declaration.Value() ); + return true; +} + + +bool XMLPrinter::Visit( const XMLUnknown& unknown ) +{ + PushUnknown( unknown.Value() ); + return true; +} + +} // namespace tinyxml2 diff --git a/3rdparty/tinyXML2/tinyxml2.h b/3rdparty/tinyXML2/tinyxml2.h new file mode 100755 index 000000000..66d7b7ee9 --- /dev/null +++ b/3rdparty/tinyXML2/tinyxml2.h @@ -0,0 +1,2314 @@ +/* +Original code by Lee Thomason (www.grinninglizard.com) + +This software is provided 'as-is', without any express or implied +warranty. In no event will the authors be held liable for any +damages arising from the use of this software. + +Permission is granted to anyone to use this software for any +purpose, including commercial applications, and to alter it and +redistribute it freely, subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must +not claim that you wrote the original software. If you use this +software in a product, an acknowledgment in the product documentation +would be appreciated but is not required. + +2. Altered source versions must be plainly marked as such, and +must not be misrepresented as being the original software. + +3. This notice may not be removed or altered from any source +distribution. +*/ + +#ifndef TINYXML2_INCLUDED +#define TINYXML2_INCLUDED + +#if defined(ANDROID_NDK) || defined(__BORLANDC__) || defined(__QNXNTO__) +# include +# include +# include +# include +# include +# if defined(__PS3__) +# include +# endif +#else +# include +# include +# include +# include +# include +#endif +#include + +/* + TODO: intern strings instead of allocation. +*/ +/* + gcc: + g++ -Wall -DTINYXML2_DEBUG tinyxml2.cpp xmltest.cpp -o gccxmltest.exe + + Formatting, Artistic Style: + AStyle.exe --style=1tbs --indent-switches --break-closing-brackets --indent-preprocessor tinyxml2.cpp tinyxml2.h +*/ + +#if defined( _DEBUG ) || defined (__DEBUG__) +# ifndef TINYXML2_DEBUG +# define TINYXML2_DEBUG +# endif +#endif + +#ifdef _MSC_VER +# pragma warning(push) +# pragma warning(disable: 4251) +#endif + +#ifdef _WIN32 +# ifdef TINYXML2_EXPORT +# define TINYXML2_LIB __declspec(dllexport) +# elif defined(TINYXML2_IMPORT) +# define TINYXML2_LIB __declspec(dllimport) +# else +# define TINYXML2_LIB +# endif +#elif __GNUC__ >= 4 +# define TINYXML2_LIB __attribute__((visibility("default"))) +#else +# define TINYXML2_LIB +#endif + + +#if defined(TINYXML2_DEBUG) +# if defined(_MSC_VER) +# // "(void)0," is for suppressing C4127 warning in "assert(false)", "assert(true)" and the like +# define TIXMLASSERT( x ) if ( !((void)0,(x))) { __debugbreak(); } +# elif defined (ANDROID_NDK) +# include +# define TIXMLASSERT( x ) if ( !(x)) { __android_log_assert( "assert", "grinliz", "ASSERT in '%s' at %d.", __FILE__, __LINE__ ); } +# else +# include +# define TIXMLASSERT assert +# endif +#else +# define TIXMLASSERT( x ) {} +#endif + + +/* Versioning, past 1.0.14: + http://semver.org/ +*/ +static const int TIXML2_MAJOR_VERSION = 6; +static const int TIXML2_MINOR_VERSION = 2; +static const int TIXML2_PATCH_VERSION = 0; + +#define TINYXML2_MAJOR_VERSION 6 +#define TINYXML2_MINOR_VERSION 2 +#define TINYXML2_PATCH_VERSION 0 + +// A fixed element depth limit is problematic. There needs to be a +// limit to avoid a stack overflow. However, that limit varies per +// system, and the capacity of the stack. On the other hand, it's a trivial +// attack that can result from ill, malicious, or even correctly formed XML, +// so there needs to be a limit in place. +static const int TINYXML2_MAX_ELEMENT_DEPTH = 100; + +namespace tinyxml2 +{ +class XMLDocument; +class XMLElement; +class XMLAttribute; +class XMLComment; +class XMLText; +class XMLDeclaration; +class XMLUnknown; +class XMLPrinter; + +/* + A class that wraps strings. Normally stores the start and end + pointers into the XML file itself, and will apply normalization + and entity translation if actually read. Can also store (and memory + manage) a traditional char[] +*/ +class StrPair +{ +public: + enum { + NEEDS_ENTITY_PROCESSING = 0x01, + NEEDS_NEWLINE_NORMALIZATION = 0x02, + NEEDS_WHITESPACE_COLLAPSING = 0x04, + + TEXT_ELEMENT = NEEDS_ENTITY_PROCESSING | NEEDS_NEWLINE_NORMALIZATION, + TEXT_ELEMENT_LEAVE_ENTITIES = NEEDS_NEWLINE_NORMALIZATION, + ATTRIBUTE_NAME = 0, + ATTRIBUTE_VALUE = NEEDS_ENTITY_PROCESSING | NEEDS_NEWLINE_NORMALIZATION, + ATTRIBUTE_VALUE_LEAVE_ENTITIES = NEEDS_NEWLINE_NORMALIZATION, + COMMENT = NEEDS_NEWLINE_NORMALIZATION + }; + + StrPair() : _flags( 0 ), _start( 0 ), _end( 0 ) {} + ~StrPair(); + + void Set( char* start, char* end, int flags ) { + TIXMLASSERT( start ); + TIXMLASSERT( end ); + Reset(); + _start = start; + _end = end; + _flags = flags | NEEDS_FLUSH; + } + + const char* GetStr(); + + bool Empty() const { + return _start == _end; + } + + void SetInternedStr( const char* str ) { + Reset(); + _start = const_cast(str); + } + + void SetStr( const char* str, int flags=0 ); + + char* ParseText( char* in, const char* endTag, int strFlags, int* curLineNumPtr ); + char* ParseName( char* in ); + + void TransferTo( StrPair* other ); + void Reset(); + +private: + void CollapseWhitespace(); + + enum { + NEEDS_FLUSH = 0x100, + NEEDS_DELETE = 0x200 + }; + + int _flags; + char* _start; + char* _end; + + StrPair( const StrPair& other ); // not supported + void operator=( StrPair& other ); // not supported, use TransferTo() +}; + + +/* + A dynamic array of Plain Old Data. Doesn't support constructors, etc. + Has a small initial memory pool, so that low or no usage will not + cause a call to new/delete +*/ +template +class DynArray +{ +public: + DynArray() : + _mem( _pool ), + _allocated( INITIAL_SIZE ), + _size( 0 ) + { + } + + ~DynArray() { + if ( _mem != _pool ) { + delete [] _mem; + } + } + + void Clear() { + _size = 0; + } + + void Push( T t ) { + TIXMLASSERT( _size < INT_MAX ); + EnsureCapacity( _size+1 ); + _mem[_size] = t; + ++_size; + } + + T* PushArr( int count ) { + TIXMLASSERT( count >= 0 ); + TIXMLASSERT( _size <= INT_MAX - count ); + EnsureCapacity( _size+count ); + T* ret = &_mem[_size]; + _size += count; + return ret; + } + + T Pop() { + TIXMLASSERT( _size > 0 ); + --_size; + return _mem[_size]; + } + + void PopArr( int count ) { + TIXMLASSERT( _size >= count ); + _size -= count; + } + + bool Empty() const { + return _size == 0; + } + + T& operator[](int i) { + TIXMLASSERT( i>= 0 && i < _size ); + return _mem[i]; + } + + const T& operator[](int i) const { + TIXMLASSERT( i>= 0 && i < _size ); + return _mem[i]; + } + + const T& PeekTop() const { + TIXMLASSERT( _size > 0 ); + return _mem[ _size - 1]; + } + + int Size() const { + TIXMLASSERT( _size >= 0 ); + return _size; + } + + int Capacity() const { + TIXMLASSERT( _allocated >= INITIAL_SIZE ); + return _allocated; + } + + void SwapRemove(int i) { + TIXMLASSERT(i >= 0 && i < _size); + TIXMLASSERT(_size > 0); + _mem[i] = _mem[_size - 1]; + --_size; + } + + const T* Mem() const { + TIXMLASSERT( _mem ); + return _mem; + } + + T* Mem() { + TIXMLASSERT( _mem ); + return _mem; + } + +private: + DynArray( const DynArray& ); // not supported + void operator=( const DynArray& ); // not supported + + void EnsureCapacity( int cap ) { + TIXMLASSERT( cap > 0 ); + if ( cap > _allocated ) { + TIXMLASSERT( cap <= INT_MAX / 2 ); + int newAllocated = cap * 2; + T* newMem = new T[newAllocated]; + TIXMLASSERT( newAllocated >= _size ); + memcpy( newMem, _mem, sizeof(T)*_size ); // warning: not using constructors, only works for PODs + if ( _mem != _pool ) { + delete [] _mem; + } + _mem = newMem; + _allocated = newAllocated; + } + } + + T* _mem; + T _pool[INITIAL_SIZE]; + int _allocated; // objects allocated + int _size; // number objects in use +}; + + +/* + Parent virtual class of a pool for fast allocation + and deallocation of objects. +*/ +class MemPool +{ +public: + MemPool() {} + virtual ~MemPool() {} + + virtual int ItemSize() const = 0; + virtual void* Alloc() = 0; + virtual void Free( void* ) = 0; + virtual void SetTracked() = 0; + virtual void Clear() = 0; +}; + + +/* + Template child class to create pools of the correct type. +*/ +template< int ITEM_SIZE > +class MemPoolT : public MemPool +{ +public: + MemPoolT() : _blockPtrs(), _root(0), _currentAllocs(0), _nAllocs(0), _maxAllocs(0), _nUntracked(0) {} + ~MemPoolT() { + Clear(); + } + + void Clear() { + // Delete the blocks. + while( !_blockPtrs.Empty()) { + Block* lastBlock = _blockPtrs.Pop(); + delete lastBlock; + } + _root = 0; + _currentAllocs = 0; + _nAllocs = 0; + _maxAllocs = 0; + _nUntracked = 0; + } + + virtual int ItemSize() const { + return ITEM_SIZE; + } + int CurrentAllocs() const { + return _currentAllocs; + } + + virtual void* Alloc() { + if ( !_root ) { + // Need a new block. + Block* block = new Block(); + _blockPtrs.Push( block ); + + Item* blockItems = block->items; + for( int i = 0; i < ITEMS_PER_BLOCK - 1; ++i ) { + blockItems[i].next = &(blockItems[i + 1]); + } + blockItems[ITEMS_PER_BLOCK - 1].next = 0; + _root = blockItems; + } + Item* const result = _root; + TIXMLASSERT( result != 0 ); + _root = _root->next; + + ++_currentAllocs; + if ( _currentAllocs > _maxAllocs ) { + _maxAllocs = _currentAllocs; + } + ++_nAllocs; + ++_nUntracked; + return result; + } + + virtual void Free( void* mem ) { + if ( !mem ) { + return; + } + --_currentAllocs; + Item* item = static_cast( mem ); +#ifdef TINYXML2_DEBUG + memset( item, 0xfe, sizeof( *item ) ); +#endif + item->next = _root; + _root = item; + } + void Trace( const char* name ) { + printf( "Mempool %s watermark=%d [%dk] current=%d size=%d nAlloc=%d blocks=%d\n", + name, _maxAllocs, _maxAllocs * ITEM_SIZE / 1024, _currentAllocs, + ITEM_SIZE, _nAllocs, _blockPtrs.Size() ); + } + + void SetTracked() { + --_nUntracked; + } + + int Untracked() const { + return _nUntracked; + } + + // This number is perf sensitive. 4k seems like a good tradeoff on my machine. + // The test file is large, 170k. + // Release: VS2010 gcc(no opt) + // 1k: 4000 + // 2k: 4000 + // 4k: 3900 21000 + // 16k: 5200 + // 32k: 4300 + // 64k: 4000 21000 + // Declared public because some compilers do not accept to use ITEMS_PER_BLOCK + // in private part if ITEMS_PER_BLOCK is private + enum { ITEMS_PER_BLOCK = (4 * 1024) / ITEM_SIZE }; + +private: + MemPoolT( const MemPoolT& ); // not supported + void operator=( const MemPoolT& ); // not supported + + union Item { + Item* next; + char itemData[ITEM_SIZE]; + }; + struct Block { + Item items[ITEMS_PER_BLOCK]; + }; + DynArray< Block*, 10 > _blockPtrs; + Item* _root; + + int _currentAllocs; + int _nAllocs; + int _maxAllocs; + int _nUntracked; +}; + + + +/** + Implements the interface to the "Visitor pattern" (see the Accept() method.) + If you call the Accept() method, it requires being passed a XMLVisitor + class to handle callbacks. For nodes that contain other nodes (Document, Element) + you will get called with a VisitEnter/VisitExit pair. Nodes that are always leafs + are simply called with Visit(). + + If you return 'true' from a Visit method, recursive parsing will continue. If you return + false, no children of this node or its siblings will be visited. + + All flavors of Visit methods have a default implementation that returns 'true' (continue + visiting). You need to only override methods that are interesting to you. + + Generally Accept() is called on the XMLDocument, although all nodes support visiting. + + You should never change the document from a callback. + + @sa XMLNode::Accept() +*/ +class TINYXML2_LIB XMLVisitor +{ +public: + virtual ~XMLVisitor() {} + + /// Visit a document. + virtual bool VisitEnter( const XMLDocument& /*doc*/ ) { + return true; + } + /// Visit a document. + virtual bool VisitExit( const XMLDocument& /*doc*/ ) { + return true; + } + + /// Visit an element. + virtual bool VisitEnter( const XMLElement& /*element*/, const XMLAttribute* /*firstAttribute*/ ) { + return true; + } + /// Visit an element. + virtual bool VisitExit( const XMLElement& /*element*/ ) { + return true; + } + + /// Visit a declaration. + virtual bool Visit( const XMLDeclaration& /*declaration*/ ) { + return true; + } + /// Visit a text node. + virtual bool Visit( const XMLText& /*text*/ ) { + return true; + } + /// Visit a comment node. + virtual bool Visit( const XMLComment& /*comment*/ ) { + return true; + } + /// Visit an unknown node. + virtual bool Visit( const XMLUnknown& /*unknown*/ ) { + return true; + } +}; + +// WARNING: must match XMLDocument::_errorNames[] +enum XMLError { + XML_SUCCESS = 0, + XML_NO_ATTRIBUTE, + XML_WRONG_ATTRIBUTE_TYPE, + XML_ERROR_FILE_NOT_FOUND, + XML_ERROR_FILE_COULD_NOT_BE_OPENED, + XML_ERROR_FILE_READ_ERROR, + UNUSED_XML_ERROR_ELEMENT_MISMATCH, // remove at next major version + XML_ERROR_PARSING_ELEMENT, + XML_ERROR_PARSING_ATTRIBUTE, + UNUSED_XML_ERROR_IDENTIFYING_TAG, // remove at next major version + XML_ERROR_PARSING_TEXT, + XML_ERROR_PARSING_CDATA, + XML_ERROR_PARSING_COMMENT, + XML_ERROR_PARSING_DECLARATION, + XML_ERROR_PARSING_UNKNOWN, + XML_ERROR_EMPTY_DOCUMENT, + XML_ERROR_MISMATCHED_ELEMENT, + XML_ERROR_PARSING, + XML_CAN_NOT_CONVERT_TEXT, + XML_NO_TEXT_NODE, + XML_ELEMENT_DEPTH_EXCEEDED, + + XML_ERROR_COUNT +}; + + +/* + Utility functionality. +*/ +class TINYXML2_LIB XMLUtil +{ +public: + static const char* SkipWhiteSpace( const char* p, int* curLineNumPtr ) { + TIXMLASSERT( p ); + + while( IsWhiteSpace(*p) ) { + if (curLineNumPtr && *p == '\n') { + ++(*curLineNumPtr); + } + ++p; + } + TIXMLASSERT( p ); + return p; + } + static char* SkipWhiteSpace( char* p, int* curLineNumPtr ) { + return const_cast( SkipWhiteSpace( const_cast(p), curLineNumPtr ) ); + } + + // Anything in the high order range of UTF-8 is assumed to not be whitespace. This isn't + // correct, but simple, and usually works. + static bool IsWhiteSpace( char p ) { + return !IsUTF8Continuation(p) && isspace( static_cast(p) ); + } + + inline static bool IsNameStartChar( unsigned char ch ) { + if ( ch >= 128 ) { + // This is a heuristic guess in attempt to not implement Unicode-aware isalpha() + return true; + } + if ( isalpha( ch ) ) { + return true; + } + return ch == ':' || ch == '_'; + } + + inline static bool IsNameChar( unsigned char ch ) { + return IsNameStartChar( ch ) + || isdigit( ch ) + || ch == '.' + || ch == '-'; + } + + inline static bool StringEqual( const char* p, const char* q, int nChar=INT_MAX ) { + if ( p == q ) { + return true; + } + TIXMLASSERT( p ); + TIXMLASSERT( q ); + TIXMLASSERT( nChar >= 0 ); + return strncmp( p, q, nChar ) == 0; + } + + inline static bool IsUTF8Continuation( char p ) { + return ( p & 0x80 ) != 0; + } + + static const char* ReadBOM( const char* p, bool* hasBOM ); + // p is the starting location, + // the UTF-8 value of the entity will be placed in value, and length filled in. + static const char* GetCharacterRef( const char* p, char* value, int* length ); + static void ConvertUTF32ToUTF8( unsigned long input, char* output, int* length ); + + // converts primitive types to strings + static void ToStr( int v, char* buffer, int bufferSize ); + static void ToStr( unsigned v, char* buffer, int bufferSize ); + static void ToStr( bool v, char* buffer, int bufferSize ); + static void ToStr( float v, char* buffer, int bufferSize ); + static void ToStr( double v, char* buffer, int bufferSize ); + static void ToStr(int64_t v, char* buffer, int bufferSize); + + // converts strings to primitive types + static bool ToInt( const char* str, int* value ); + static bool ToUnsigned( const char* str, unsigned* value ); + static bool ToBool( const char* str, bool* value ); + static bool ToFloat( const char* str, float* value ); + static bool ToDouble( const char* str, double* value ); + static bool ToInt64(const char* str, int64_t* value); + + // Changes what is serialized for a boolean value. + // Default to "true" and "false". Shouldn't be changed + // unless you have a special testing or compatibility need. + // Be careful: static, global, & not thread safe. + // Be sure to set static const memory as parameters. + static void SetBoolSerialization(const char* writeTrue, const char* writeFalse); + +private: + static const char* writeBoolTrue; + static const char* writeBoolFalse; +}; + + +/** XMLNode is a base class for every object that is in the + XML Document Object Model (DOM), except XMLAttributes. + Nodes have siblings, a parent, and children which can + be navigated. A node is always in a XMLDocument. + The type of a XMLNode can be queried, and it can + be cast to its more defined type. + + A XMLDocument allocates memory for all its Nodes. + When the XMLDocument gets deleted, all its Nodes + will also be deleted. + + @verbatim + A Document can contain: Element (container or leaf) + Comment (leaf) + Unknown (leaf) + Declaration( leaf ) + + An Element can contain: Element (container or leaf) + Text (leaf) + Attributes (not on tree) + Comment (leaf) + Unknown (leaf) + + @endverbatim +*/ +class TINYXML2_LIB XMLNode +{ + friend class XMLDocument; + friend class XMLElement; +public: + + /// Get the XMLDocument that owns this XMLNode. + const XMLDocument* GetDocument() const { + TIXMLASSERT( _document ); + return _document; + } + /// Get the XMLDocument that owns this XMLNode. + XMLDocument* GetDocument() { + TIXMLASSERT( _document ); + return _document; + } + + /// Safely cast to an Element, or null. + virtual XMLElement* ToElement() { + return 0; + } + /// Safely cast to Text, or null. + virtual XMLText* ToText() { + return 0; + } + /// Safely cast to a Comment, or null. + virtual XMLComment* ToComment() { + return 0; + } + /// Safely cast to a Document, or null. + virtual XMLDocument* ToDocument() { + return 0; + } + /// Safely cast to a Declaration, or null. + virtual XMLDeclaration* ToDeclaration() { + return 0; + } + /// Safely cast to an Unknown, or null. + virtual XMLUnknown* ToUnknown() { + return 0; + } + + virtual const XMLElement* ToElement() const { + return 0; + } + virtual const XMLText* ToText() const { + return 0; + } + virtual const XMLComment* ToComment() const { + return 0; + } + virtual const XMLDocument* ToDocument() const { + return 0; + } + virtual const XMLDeclaration* ToDeclaration() const { + return 0; + } + virtual const XMLUnknown* ToUnknown() const { + return 0; + } + + /** The meaning of 'value' changes for the specific type. + @verbatim + Document: empty (NULL is returned, not an empty string) + Element: name of the element + Comment: the comment text + Unknown: the tag contents + Text: the text string + @endverbatim + */ + const char* Value() const; + + /** Set the Value of an XML node. + @sa Value() + */ + void SetValue( const char* val, bool staticMem=false ); + + /// Gets the line number the node is in, if the document was parsed from a file. + int GetLineNum() const { return _parseLineNum; } + + /// Get the parent of this node on the DOM. + const XMLNode* Parent() const { + return _parent; + } + + XMLNode* Parent() { + return _parent; + } + + /// Returns true if this node has no children. + bool NoChildren() const { + return !_firstChild; + } + + /// Get the first child node, or null if none exists. + const XMLNode* FirstChild() const { + return _firstChild; + } + + XMLNode* FirstChild() { + return _firstChild; + } + + /** Get the first child element, or optionally the first child + element with the specified name. + */ + const XMLElement* FirstChildElement( const char* name = 0 ) const; + + XMLElement* FirstChildElement( const char* name = 0 ) { + return const_cast(const_cast(this)->FirstChildElement( name )); + } + + /// Get the last child node, or null if none exists. + const XMLNode* LastChild() const { + return _lastChild; + } + + XMLNode* LastChild() { + return _lastChild; + } + + /** Get the last child element or optionally the last child + element with the specified name. + */ + const XMLElement* LastChildElement( const char* name = 0 ) const; + + XMLElement* LastChildElement( const char* name = 0 ) { + return const_cast(const_cast(this)->LastChildElement(name) ); + } + + /// Get the previous (left) sibling node of this node. + const XMLNode* PreviousSibling() const { + return _prev; + } + + XMLNode* PreviousSibling() { + return _prev; + } + + /// Get the previous (left) sibling element of this node, with an optionally supplied name. + const XMLElement* PreviousSiblingElement( const char* name = 0 ) const ; + + XMLElement* PreviousSiblingElement( const char* name = 0 ) { + return const_cast(const_cast(this)->PreviousSiblingElement( name ) ); + } + + /// Get the next (right) sibling node of this node. + const XMLNode* NextSibling() const { + return _next; + } + + XMLNode* NextSibling() { + return _next; + } + + /// Get the next (right) sibling element of this node, with an optionally supplied name. + const XMLElement* NextSiblingElement( const char* name = 0 ) const; + + XMLElement* NextSiblingElement( const char* name = 0 ) { + return const_cast(const_cast(this)->NextSiblingElement( name ) ); + } + + /** + Add a child node as the last (right) child. + If the child node is already part of the document, + it is moved from its old location to the new location. + Returns the addThis argument or 0 if the node does not + belong to the same document. + */ + XMLNode* InsertEndChild( XMLNode* addThis ); + + XMLNode* LinkEndChild( XMLNode* addThis ) { + return InsertEndChild( addThis ); + } + /** + Add a child node as the first (left) child. + If the child node is already part of the document, + it is moved from its old location to the new location. + Returns the addThis argument or 0 if the node does not + belong to the same document. + */ + XMLNode* InsertFirstChild( XMLNode* addThis ); + /** + Add a node after the specified child node. + If the child node is already part of the document, + it is moved from its old location to the new location. + Returns the addThis argument or 0 if the afterThis node + is not a child of this node, or if the node does not + belong to the same document. + */ + XMLNode* InsertAfterChild( XMLNode* afterThis, XMLNode* addThis ); + + /** + Delete all the children of this node. + */ + void DeleteChildren(); + + /** + Delete a child of this node. + */ + void DeleteChild( XMLNode* node ); + + /** + Make a copy of this node, but not its children. + You may pass in a Document pointer that will be + the owner of the new Node. If the 'document' is + null, then the node returned will be allocated + from the current Document. (this->GetDocument()) + + Note: if called on a XMLDocument, this will return null. + */ + virtual XMLNode* ShallowClone( XMLDocument* document ) const = 0; + + /** + Make a copy of this node and all its children. + + If the 'target' is null, then the nodes will + be allocated in the current document. If 'target' + is specified, the memory will be allocated is the + specified XMLDocument. + + NOTE: This is probably not the correct tool to + copy a document, since XMLDocuments can have multiple + top level XMLNodes. You probably want to use + XMLDocument::DeepCopy() + */ + XMLNode* DeepClone( XMLDocument* target ) const; + + /** + Test if 2 nodes are the same, but don't test children. + The 2 nodes do not need to be in the same Document. + + Note: if called on a XMLDocument, this will return false. + */ + virtual bool ShallowEqual( const XMLNode* compare ) const = 0; + + /** Accept a hierarchical visit of the nodes in the TinyXML-2 DOM. Every node in the + XML tree will be conditionally visited and the host will be called back + via the XMLVisitor interface. + + This is essentially a SAX interface for TinyXML-2. (Note however it doesn't re-parse + the XML for the callbacks, so the performance of TinyXML-2 is unchanged by using this + interface versus any other.) + + The interface has been based on ideas from: + + - http://www.saxproject.org/ + - http://c2.com/cgi/wiki?HierarchicalVisitorPattern + + Which are both good references for "visiting". + + An example of using Accept(): + @verbatim + XMLPrinter printer; + tinyxmlDoc.Accept( &printer ); + const char* xmlcstr = printer.CStr(); + @endverbatim + */ + virtual bool Accept( XMLVisitor* visitor ) const = 0; + + /** + Set user data into the XMLNode. TinyXML-2 in + no way processes or interprets user data. + It is initially 0. + */ + void SetUserData(void* userData) { _userData = userData; } + + /** + Get user data set into the XMLNode. TinyXML-2 in + no way processes or interprets user data. + It is initially 0. + */ + void* GetUserData() const { return _userData; } + +protected: + XMLNode( XMLDocument* ); + virtual ~XMLNode(); + + virtual char* ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr); + + XMLDocument* _document; + XMLNode* _parent; + mutable StrPair _value; + int _parseLineNum; + + XMLNode* _firstChild; + XMLNode* _lastChild; + + XMLNode* _prev; + XMLNode* _next; + + void* _userData; + +private: + MemPool* _memPool; + void Unlink( XMLNode* child ); + static void DeleteNode( XMLNode* node ); + void InsertChildPreamble( XMLNode* insertThis ) const; + const XMLElement* ToElementWithName( const char* name ) const; + + XMLNode( const XMLNode& ); // not supported + XMLNode& operator=( const XMLNode& ); // not supported +}; + + +/** XML text. + + Note that a text node can have child element nodes, for example: + @verbatim + This is bold + @endverbatim + + A text node can have 2 ways to output the next. "normal" output + and CDATA. It will default to the mode it was parsed from the XML file and + you generally want to leave it alone, but you can change the output mode with + SetCData() and query it with CData(). +*/ +class TINYXML2_LIB XMLText : public XMLNode +{ + friend class XMLDocument; +public: + virtual bool Accept( XMLVisitor* visitor ) const; + + virtual XMLText* ToText() { + return this; + } + virtual const XMLText* ToText() const { + return this; + } + + /// Declare whether this should be CDATA or standard text. + void SetCData( bool isCData ) { + _isCData = isCData; + } + /// Returns true if this is a CDATA text element. + bool CData() const { + return _isCData; + } + + virtual XMLNode* ShallowClone( XMLDocument* document ) const; + virtual bool ShallowEqual( const XMLNode* compare ) const; + +protected: + XMLText( XMLDocument* doc ) : XMLNode( doc ), _isCData( false ) {} + virtual ~XMLText() {} + + char* ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr ); + +private: + bool _isCData; + + XMLText( const XMLText& ); // not supported + XMLText& operator=( const XMLText& ); // not supported +}; + + +/** An XML Comment. */ +class TINYXML2_LIB XMLComment : public XMLNode +{ + friend class XMLDocument; +public: + virtual XMLComment* ToComment() { + return this; + } + virtual const XMLComment* ToComment() const { + return this; + } + + virtual bool Accept( XMLVisitor* visitor ) const; + + virtual XMLNode* ShallowClone( XMLDocument* document ) const; + virtual bool ShallowEqual( const XMLNode* compare ) const; + +protected: + XMLComment( XMLDocument* doc ); + virtual ~XMLComment(); + + char* ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr); + +private: + XMLComment( const XMLComment& ); // not supported + XMLComment& operator=( const XMLComment& ); // not supported +}; + + +/** In correct XML the declaration is the first entry in the file. + @verbatim + + @endverbatim + + TinyXML-2 will happily read or write files without a declaration, + however. + + The text of the declaration isn't interpreted. It is parsed + and written as a string. +*/ +class TINYXML2_LIB XMLDeclaration : public XMLNode +{ + friend class XMLDocument; +public: + virtual XMLDeclaration* ToDeclaration() { + return this; + } + virtual const XMLDeclaration* ToDeclaration() const { + return this; + } + + virtual bool Accept( XMLVisitor* visitor ) const; + + virtual XMLNode* ShallowClone( XMLDocument* document ) const; + virtual bool ShallowEqual( const XMLNode* compare ) const; + +protected: + XMLDeclaration( XMLDocument* doc ); + virtual ~XMLDeclaration(); + + char* ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr ); + +private: + XMLDeclaration( const XMLDeclaration& ); // not supported + XMLDeclaration& operator=( const XMLDeclaration& ); // not supported +}; + + +/** Any tag that TinyXML-2 doesn't recognize is saved as an + unknown. It is a tag of text, but should not be modified. + It will be written back to the XML, unchanged, when the file + is saved. + + DTD tags get thrown into XMLUnknowns. +*/ +class TINYXML2_LIB XMLUnknown : public XMLNode +{ + friend class XMLDocument; +public: + virtual XMLUnknown* ToUnknown() { + return this; + } + virtual const XMLUnknown* ToUnknown() const { + return this; + } + + virtual bool Accept( XMLVisitor* visitor ) const; + + virtual XMLNode* ShallowClone( XMLDocument* document ) const; + virtual bool ShallowEqual( const XMLNode* compare ) const; + +protected: + XMLUnknown( XMLDocument* doc ); + virtual ~XMLUnknown(); + + char* ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr ); + +private: + XMLUnknown( const XMLUnknown& ); // not supported + XMLUnknown& operator=( const XMLUnknown& ); // not supported +}; + + + +/** An attribute is a name-value pair. Elements have an arbitrary + number of attributes, each with a unique name. + + @note The attributes are not XMLNodes. You may only query the + Next() attribute in a list. +*/ +class TINYXML2_LIB XMLAttribute +{ + friend class XMLElement; +public: + /// The name of the attribute. + const char* Name() const; + + /// The value of the attribute. + const char* Value() const; + + /// Gets the line number the attribute is in, if the document was parsed from a file. + int GetLineNum() const { return _parseLineNum; } + + /// The next attribute in the list. + const XMLAttribute* Next() const { + return _next; + } + + /** IntValue interprets the attribute as an integer, and returns the value. + If the value isn't an integer, 0 will be returned. There is no error checking; + use QueryIntValue() if you need error checking. + */ + int IntValue() const { + int i = 0; + QueryIntValue(&i); + return i; + } + + int64_t Int64Value() const { + int64_t i = 0; + QueryInt64Value(&i); + return i; + } + + /// Query as an unsigned integer. See IntValue() + unsigned UnsignedValue() const { + unsigned i=0; + QueryUnsignedValue( &i ); + return i; + } + /// Query as a boolean. See IntValue() + bool BoolValue() const { + bool b=false; + QueryBoolValue( &b ); + return b; + } + /// Query as a double. See IntValue() + double DoubleValue() const { + double d=0; + QueryDoubleValue( &d ); + return d; + } + /// Query as a float. See IntValue() + float FloatValue() const { + float f=0; + QueryFloatValue( &f ); + return f; + } + + /** QueryIntValue interprets the attribute as an integer, and returns the value + in the provided parameter. The function will return XML_SUCCESS on success, + and XML_WRONG_ATTRIBUTE_TYPE if the conversion is not successful. + */ + XMLError QueryIntValue( int* value ) const; + /// See QueryIntValue + XMLError QueryUnsignedValue( unsigned int* value ) const; + /// See QueryIntValue + XMLError QueryInt64Value(int64_t* value) const; + /// See QueryIntValue + XMLError QueryBoolValue( bool* value ) const; + /// See QueryIntValue + XMLError QueryDoubleValue( double* value ) const; + /// See QueryIntValue + XMLError QueryFloatValue( float* value ) const; + + /// Set the attribute to a string value. + void SetAttribute( const char* value ); + /// Set the attribute to value. + void SetAttribute( int value ); + /// Set the attribute to value. + void SetAttribute( unsigned value ); + /// Set the attribute to value. + void SetAttribute(int64_t value); + /// Set the attribute to value. + void SetAttribute( bool value ); + /// Set the attribute to value. + void SetAttribute( double value ); + /// Set the attribute to value. + void SetAttribute( float value ); + +private: + enum { BUF_SIZE = 200 }; + + XMLAttribute() : _name(), _value(),_parseLineNum( 0 ), _next( 0 ), _memPool( 0 ) {} + virtual ~XMLAttribute() {} + + XMLAttribute( const XMLAttribute& ); // not supported + void operator=( const XMLAttribute& ); // not supported + void SetName( const char* name ); + + char* ParseDeep( char* p, bool processEntities, int* curLineNumPtr ); + + mutable StrPair _name; + mutable StrPair _value; + int _parseLineNum; + XMLAttribute* _next; + MemPool* _memPool; +}; + + +/** The element is a container class. It has a value, the element name, + and can contain other elements, text, comments, and unknowns. + Elements also contain an arbitrary number of attributes. +*/ +class TINYXML2_LIB XMLElement : public XMLNode +{ + friend class XMLDocument; +public: + /// Get the name of an element (which is the Value() of the node.) + const char* Name() const { + return Value(); + } + /// Set the name of the element. + void SetName( const char* str, bool staticMem=false ) { + SetValue( str, staticMem ); + } + + virtual XMLElement* ToElement() { + return this; + } + virtual const XMLElement* ToElement() const { + return this; + } + virtual bool Accept( XMLVisitor* visitor ) const; + + /** Given an attribute name, Attribute() returns the value + for the attribute of that name, or null if none + exists. For example: + + @verbatim + const char* value = ele->Attribute( "foo" ); + @endverbatim + + The 'value' parameter is normally null. However, if specified, + the attribute will only be returned if the 'name' and 'value' + match. This allow you to write code: + + @verbatim + if ( ele->Attribute( "foo", "bar" ) ) callFooIsBar(); + @endverbatim + + rather than: + @verbatim + if ( ele->Attribute( "foo" ) ) { + if ( strcmp( ele->Attribute( "foo" ), "bar" ) == 0 ) callFooIsBar(); + } + @endverbatim + */ + const char* Attribute( const char* name, const char* value=0 ) const; + + /** Given an attribute name, IntAttribute() returns the value + of the attribute interpreted as an integer. The default + value will be returned if the attribute isn't present, + or if there is an error. (For a method with error + checking, see QueryIntAttribute()). + */ + int IntAttribute(const char* name, int defaultValue = 0) const; + /// See IntAttribute() + unsigned UnsignedAttribute(const char* name, unsigned defaultValue = 0) const; + /// See IntAttribute() + int64_t Int64Attribute(const char* name, int64_t defaultValue = 0) const; + /// See IntAttribute() + bool BoolAttribute(const char* name, bool defaultValue = false) const; + /// See IntAttribute() + double DoubleAttribute(const char* name, double defaultValue = 0) const; + /// See IntAttribute() + float FloatAttribute(const char* name, float defaultValue = 0) const; + + /** Given an attribute name, QueryIntAttribute() returns + XML_SUCCESS, XML_WRONG_ATTRIBUTE_TYPE if the conversion + can't be performed, or XML_NO_ATTRIBUTE if the attribute + doesn't exist. If successful, the result of the conversion + will be written to 'value'. If not successful, nothing will + be written to 'value'. This allows you to provide default + value: + + @verbatim + int value = 10; + QueryIntAttribute( "foo", &value ); // if "foo" isn't found, value will still be 10 + @endverbatim + */ + XMLError QueryIntAttribute( const char* name, int* value ) const { + const XMLAttribute* a = FindAttribute( name ); + if ( !a ) { + return XML_NO_ATTRIBUTE; + } + return a->QueryIntValue( value ); + } + + /// See QueryIntAttribute() + XMLError QueryUnsignedAttribute( const char* name, unsigned int* value ) const { + const XMLAttribute* a = FindAttribute( name ); + if ( !a ) { + return XML_NO_ATTRIBUTE; + } + return a->QueryUnsignedValue( value ); + } + + /// See QueryIntAttribute() + XMLError QueryInt64Attribute(const char* name, int64_t* value) const { + const XMLAttribute* a = FindAttribute(name); + if (!a) { + return XML_NO_ATTRIBUTE; + } + return a->QueryInt64Value(value); + } + + /// See QueryIntAttribute() + XMLError QueryBoolAttribute( const char* name, bool* value ) const { + const XMLAttribute* a = FindAttribute( name ); + if ( !a ) { + return XML_NO_ATTRIBUTE; + } + return a->QueryBoolValue( value ); + } + /// See QueryIntAttribute() + XMLError QueryDoubleAttribute( const char* name, double* value ) const { + const XMLAttribute* a = FindAttribute( name ); + if ( !a ) { + return XML_NO_ATTRIBUTE; + } + return a->QueryDoubleValue( value ); + } + /// See QueryIntAttribute() + XMLError QueryFloatAttribute( const char* name, float* value ) const { + const XMLAttribute* a = FindAttribute( name ); + if ( !a ) { + return XML_NO_ATTRIBUTE; + } + return a->QueryFloatValue( value ); + } + + /// See QueryIntAttribute() + XMLError QueryStringAttribute(const char* name, const char** value) const { + const XMLAttribute* a = FindAttribute(name); + if (!a) { + return XML_NO_ATTRIBUTE; + } + *value = a->Value(); + return XML_SUCCESS; + } + + + + /** Given an attribute name, QueryAttribute() returns + XML_SUCCESS, XML_WRONG_ATTRIBUTE_TYPE if the conversion + can't be performed, or XML_NO_ATTRIBUTE if the attribute + doesn't exist. It is overloaded for the primitive types, + and is a generally more convenient replacement of + QueryIntAttribute() and related functions. + + If successful, the result of the conversion + will be written to 'value'. If not successful, nothing will + be written to 'value'. This allows you to provide default + value: + + @verbatim + int value = 10; + QueryAttribute( "foo", &value ); // if "foo" isn't found, value will still be 10 + @endverbatim + */ + int QueryAttribute( const char* name, int* value ) const { + return QueryIntAttribute( name, value ); + } + + int QueryAttribute( const char* name, unsigned int* value ) const { + return QueryUnsignedAttribute( name, value ); + } + + int QueryAttribute(const char* name, int64_t* value) const { + return QueryInt64Attribute(name, value); + } + + int QueryAttribute( const char* name, bool* value ) const { + return QueryBoolAttribute( name, value ); + } + + int QueryAttribute( const char* name, double* value ) const { + return QueryDoubleAttribute( name, value ); + } + + int QueryAttribute( const char* name, float* value ) const { + return QueryFloatAttribute( name, value ); + } + + /// Sets the named attribute to value. + void SetAttribute( const char* name, const char* value ) { + XMLAttribute* a = FindOrCreateAttribute( name ); + a->SetAttribute( value ); + } + /// Sets the named attribute to value. + void SetAttribute( const char* name, int value ) { + XMLAttribute* a = FindOrCreateAttribute( name ); + a->SetAttribute( value ); + } + /// Sets the named attribute to value. + void SetAttribute( const char* name, unsigned value ) { + XMLAttribute* a = FindOrCreateAttribute( name ); + a->SetAttribute( value ); + } + + /// Sets the named attribute to value. + void SetAttribute(const char* name, int64_t value) { + XMLAttribute* a = FindOrCreateAttribute(name); + a->SetAttribute(value); + } + + /// Sets the named attribute to value. + void SetAttribute( const char* name, bool value ) { + XMLAttribute* a = FindOrCreateAttribute( name ); + a->SetAttribute( value ); + } + /// Sets the named attribute to value. + void SetAttribute( const char* name, double value ) { + XMLAttribute* a = FindOrCreateAttribute( name ); + a->SetAttribute( value ); + } + /// Sets the named attribute to value. + void SetAttribute( const char* name, float value ) { + XMLAttribute* a = FindOrCreateAttribute( name ); + a->SetAttribute( value ); + } + + /** + Delete an attribute. + */ + void DeleteAttribute( const char* name ); + + /// Return the first attribute in the list. + const XMLAttribute* FirstAttribute() const { + return _rootAttribute; + } + /// Query a specific attribute in the list. + const XMLAttribute* FindAttribute( const char* name ) const; + + /** Convenience function for easy access to the text inside an element. Although easy + and concise, GetText() is limited compared to getting the XMLText child + and accessing it directly. + + If the first child of 'this' is a XMLText, the GetText() + returns the character string of the Text node, else null is returned. + + This is a convenient method for getting the text of simple contained text: + @verbatim + This is text + const char* str = fooElement->GetText(); + @endverbatim + + 'str' will be a pointer to "This is text". + + Note that this function can be misleading. If the element foo was created from + this XML: + @verbatim + This is text + @endverbatim + + then the value of str would be null. The first child node isn't a text node, it is + another element. From this XML: + @verbatim + This is text + @endverbatim + GetText() will return "This is ". + */ + const char* GetText() const; + + /** Convenience function for easy access to the text inside an element. Although easy + and concise, SetText() is limited compared to creating an XMLText child + and mutating it directly. + + If the first child of 'this' is a XMLText, SetText() sets its value to + the given string, otherwise it will create a first child that is an XMLText. + + This is a convenient method for setting the text of simple contained text: + @verbatim + This is text + fooElement->SetText( "Hullaballoo!" ); + Hullaballoo! + @endverbatim + + Note that this function can be misleading. If the element foo was created from + this XML: + @verbatim + This is text + @endverbatim + + then it will not change "This is text", but rather prefix it with a text element: + @verbatim + Hullaballoo!This is text + @endverbatim + + For this XML: + @verbatim + + @endverbatim + SetText() will generate + @verbatim + Hullaballoo! + @endverbatim + */ + void SetText( const char* inText ); + /// Convenience method for setting text inside an element. See SetText() for important limitations. + void SetText( int value ); + /// Convenience method for setting text inside an element. See SetText() for important limitations. + void SetText( unsigned value ); + /// Convenience method for setting text inside an element. See SetText() for important limitations. + void SetText(int64_t value); + /// Convenience method for setting text inside an element. See SetText() for important limitations. + void SetText( bool value ); + /// Convenience method for setting text inside an element. See SetText() for important limitations. + void SetText( double value ); + /// Convenience method for setting text inside an element. See SetText() for important limitations. + void SetText( float value ); + + /** + Convenience method to query the value of a child text node. This is probably best + shown by example. Given you have a document is this form: + @verbatim + + 1 + 1.4 + + @endverbatim + + The QueryIntText() and similar functions provide a safe and easier way to get to the + "value" of x and y. + + @verbatim + int x = 0; + float y = 0; // types of x and y are contrived for example + const XMLElement* xElement = pointElement->FirstChildElement( "x" ); + const XMLElement* yElement = pointElement->FirstChildElement( "y" ); + xElement->QueryIntText( &x ); + yElement->QueryFloatText( &y ); + @endverbatim + + @returns XML_SUCCESS (0) on success, XML_CAN_NOT_CONVERT_TEXT if the text cannot be converted + to the requested type, and XML_NO_TEXT_NODE if there is no child text to query. + + */ + XMLError QueryIntText( int* ival ) const; + /// See QueryIntText() + XMLError QueryUnsignedText( unsigned* uval ) const; + /// See QueryIntText() + XMLError QueryInt64Text(int64_t* uval) const; + /// See QueryIntText() + XMLError QueryBoolText( bool* bval ) const; + /// See QueryIntText() + XMLError QueryDoubleText( double* dval ) const; + /// See QueryIntText() + XMLError QueryFloatText( float* fval ) const; + + int IntText(int defaultValue = 0) const; + + /// See QueryIntText() + unsigned UnsignedText(unsigned defaultValue = 0) const; + /// See QueryIntText() + int64_t Int64Text(int64_t defaultValue = 0) const; + /// See QueryIntText() + bool BoolText(bool defaultValue = false) const; + /// See QueryIntText() + double DoubleText(double defaultValue = 0) const; + /// See QueryIntText() + float FloatText(float defaultValue = 0) const; + + // internal: + enum ElementClosingType { + OPEN, // + CLOSED, // + CLOSING // + }; + ElementClosingType ClosingType() const { + return _closingType; + } + virtual XMLNode* ShallowClone( XMLDocument* document ) const; + virtual bool ShallowEqual( const XMLNode* compare ) const; + +protected: + char* ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr ); + +private: + XMLElement( XMLDocument* doc ); + virtual ~XMLElement(); + XMLElement( const XMLElement& ); // not supported + void operator=( const XMLElement& ); // not supported + + XMLAttribute* FindAttribute( const char* name ) { + return const_cast(const_cast(this)->FindAttribute( name )); + } + XMLAttribute* FindOrCreateAttribute( const char* name ); + //void LinkAttribute( XMLAttribute* attrib ); + char* ParseAttributes( char* p, int* curLineNumPtr ); + static void DeleteAttribute( XMLAttribute* attribute ); + XMLAttribute* CreateAttribute(); + + enum { BUF_SIZE = 200 }; + ElementClosingType _closingType; + // The attribute list is ordered; there is no 'lastAttribute' + // because the list needs to be scanned for dupes before adding + // a new attribute. + XMLAttribute* _rootAttribute; +}; + + +enum Whitespace { + PRESERVE_WHITESPACE, + COLLAPSE_WHITESPACE +}; + + +/** A Document binds together all the functionality. + It can be saved, loaded, and printed to the screen. + All Nodes are connected and allocated to a Document. + If the Document is deleted, all its Nodes are also deleted. +*/ +class TINYXML2_LIB XMLDocument : public XMLNode +{ + friend class XMLElement; + // Gives access to SetError and Push/PopDepth, but over-access for everything else. + // Wishing C++ had "internal" scope. + friend class XMLNode; + friend class XMLText; + friend class XMLComment; + friend class XMLDeclaration; + friend class XMLUnknown; +public: + /// constructor + XMLDocument( bool processEntities = true, Whitespace whitespaceMode = PRESERVE_WHITESPACE ); + ~XMLDocument(); + + virtual XMLDocument* ToDocument() { + TIXMLASSERT( this == _document ); + return this; + } + virtual const XMLDocument* ToDocument() const { + TIXMLASSERT( this == _document ); + return this; + } + + /** + Parse an XML file from a character string. + Returns XML_SUCCESS (0) on success, or + an errorID. + + You may optionally pass in the 'nBytes', which is + the number of bytes which will be parsed. If not + specified, TinyXML-2 will assume 'xml' points to a + null terminated string. + */ + XMLError Parse( const char* xml, size_t nBytes=(size_t)(-1) ); + + /** + Load an XML file from disk. + Returns XML_SUCCESS (0) on success, or + an errorID. + */ + XMLError LoadFile( const char* filename ); + + /** + Load an XML file from disk. You are responsible + for providing and closing the FILE*. + + NOTE: The file should be opened as binary ("rb") + not text in order for TinyXML-2 to correctly + do newline normalization. + + Returns XML_SUCCESS (0) on success, or + an errorID. + */ + XMLError LoadFile( FILE* ); + + /** + Save the XML file to disk. + Returns XML_SUCCESS (0) on success, or + an errorID. + */ + XMLError SaveFile( const char* filename, bool compact = false ); + + /** + Save the XML file to disk. You are responsible + for providing and closing the FILE*. + + Returns XML_SUCCESS (0) on success, or + an errorID. + */ + XMLError SaveFile( FILE* fp, bool compact = false ); + + bool ProcessEntities() const { + return _processEntities; + } + Whitespace WhitespaceMode() const { + return _whitespaceMode; + } + + /** + Returns true if this document has a leading Byte Order Mark of UTF8. + */ + bool HasBOM() const { + return _writeBOM; + } + /** Sets whether to write the BOM when writing the file. + */ + void SetBOM( bool useBOM ) { + _writeBOM = useBOM; + } + + /** Return the root element of DOM. Equivalent to FirstChildElement(). + To get the first node, use FirstChild(). + */ + XMLElement* RootElement() { + return FirstChildElement(); + } + const XMLElement* RootElement() const { + return FirstChildElement(); + } + + /** Print the Document. If the Printer is not provided, it will + print to stdout. If you provide Printer, this can print to a file: + @verbatim + XMLPrinter printer( fp ); + doc.Print( &printer ); + @endverbatim + + Or you can use a printer to print to memory: + @verbatim + XMLPrinter printer; + doc.Print( &printer ); + // printer.CStr() has a const char* to the XML + @endverbatim + */ + void Print( XMLPrinter* streamer=0 ) const; + virtual bool Accept( XMLVisitor* visitor ) const; + + /** + Create a new Element associated with + this Document. The memory for the Element + is managed by the Document. + */ + XMLElement* NewElement( const char* name ); + /** + Create a new Comment associated with + this Document. The memory for the Comment + is managed by the Document. + */ + XMLComment* NewComment( const char* comment ); + /** + Create a new Text associated with + this Document. The memory for the Text + is managed by the Document. + */ + XMLText* NewText( const char* text ); + /** + Create a new Declaration associated with + this Document. The memory for the object + is managed by the Document. + + If the 'text' param is null, the standard + declaration is used.: + @verbatim + + @endverbatim + */ + XMLDeclaration* NewDeclaration( const char* text=0 ); + /** + Create a new Unknown associated with + this Document. The memory for the object + is managed by the Document. + */ + XMLUnknown* NewUnknown( const char* text ); + + /** + Delete a node associated with this document. + It will be unlinked from the DOM. + */ + void DeleteNode( XMLNode* node ); + + void ClearError() { + SetError(XML_SUCCESS, 0, 0); + } + + /// Return true if there was an error parsing the document. + bool Error() const { + return _errorID != XML_SUCCESS; + } + /// Return the errorID. + XMLError ErrorID() const { + return _errorID; + } + const char* ErrorName() const; + static const char* ErrorIDToName(XMLError errorID); + + /** Returns a "long form" error description. A hopefully helpful + diagnostic with location, line number, and/or additional info. + */ + const char* ErrorStr() const; + + /// A (trivial) utility function that prints the ErrorStr() to stdout. + void PrintError() const; + + /// Return the line where the error occured, or zero if unknown. + int ErrorLineNum() const + { + return _errorLineNum; + } + + /// Clear the document, resetting it to the initial state. + void Clear(); + + /** + Copies this document to a target document. + The target will be completely cleared before the copy. + If you want to copy a sub-tree, see XMLNode::DeepClone(). + + NOTE: that the 'target' must be non-null. + */ + void DeepCopy(XMLDocument* target) const; + + // internal + char* Identify( char* p, XMLNode** node ); + + // internal + void MarkInUse(XMLNode*); + + virtual XMLNode* ShallowClone( XMLDocument* /*document*/ ) const { + return 0; + } + virtual bool ShallowEqual( const XMLNode* /*compare*/ ) const { + return false; + } + +private: + XMLDocument( const XMLDocument& ); // not supported + void operator=( const XMLDocument& ); // not supported + + bool _writeBOM; + bool _processEntities; + XMLError _errorID; + Whitespace _whitespaceMode; + mutable StrPair _errorStr; + int _errorLineNum; + char* _charBuffer; + int _parseCurLineNum; + int _parsingDepth; + // Memory tracking does add some overhead. + // However, the code assumes that you don't + // have a bunch of unlinked nodes around. + // Therefore it takes less memory to track + // in the document vs. a linked list in the XMLNode, + // and the performance is the same. + DynArray _unlinked; + + MemPoolT< sizeof(XMLElement) > _elementPool; + MemPoolT< sizeof(XMLAttribute) > _attributePool; + MemPoolT< sizeof(XMLText) > _textPool; + MemPoolT< sizeof(XMLComment) > _commentPool; + + static const char* _errorNames[XML_ERROR_COUNT]; + + void Parse(); + + void SetError( XMLError error, int lineNum, const char* format, ... ); + + // Something of an obvious security hole, once it was discovered. + // Either an ill-formed XML or an excessively deep one can overflow + // the stack. Track stack depth, and error out if needed. + class DepthTracker { + public: + DepthTracker(XMLDocument * document) { + this->_document = document; + document->PushDepth(); + } + ~DepthTracker() { + _document->PopDepth(); + } + private: + XMLDocument * _document; + }; + void PushDepth(); + void PopDepth(); + + template + NodeType* CreateUnlinkedNode( MemPoolT& pool ); +}; + +template +inline NodeType* XMLDocument::CreateUnlinkedNode( MemPoolT& pool ) +{ + TIXMLASSERT( sizeof( NodeType ) == PoolElementSize ); + TIXMLASSERT( sizeof( NodeType ) == pool.ItemSize() ); + NodeType* returnNode = new (pool.Alloc()) NodeType( this ); + TIXMLASSERT( returnNode ); + returnNode->_memPool = &pool; + + _unlinked.Push(returnNode); + return returnNode; +} + +/** + A XMLHandle is a class that wraps a node pointer with null checks; this is + an incredibly useful thing. Note that XMLHandle is not part of the TinyXML-2 + DOM structure. It is a separate utility class. + + Take an example: + @verbatim + + + + + + + @endverbatim + + Assuming you want the value of "attributeB" in the 2nd "Child" element, it's very + easy to write a *lot* of code that looks like: + + @verbatim + XMLElement* root = document.FirstChildElement( "Document" ); + if ( root ) + { + XMLElement* element = root->FirstChildElement( "Element" ); + if ( element ) + { + XMLElement* child = element->FirstChildElement( "Child" ); + if ( child ) + { + XMLElement* child2 = child->NextSiblingElement( "Child" ); + if ( child2 ) + { + // Finally do something useful. + @endverbatim + + And that doesn't even cover "else" cases. XMLHandle addresses the verbosity + of such code. A XMLHandle checks for null pointers so it is perfectly safe + and correct to use: + + @verbatim + XMLHandle docHandle( &document ); + XMLElement* child2 = docHandle.FirstChildElement( "Document" ).FirstChildElement( "Element" ).FirstChildElement().NextSiblingElement(); + if ( child2 ) + { + // do something useful + @endverbatim + + Which is MUCH more concise and useful. + + It is also safe to copy handles - internally they are nothing more than node pointers. + @verbatim + XMLHandle handleCopy = handle; + @endverbatim + + See also XMLConstHandle, which is the same as XMLHandle, but operates on const objects. +*/ +class TINYXML2_LIB XMLHandle +{ +public: + /// Create a handle from any node (at any depth of the tree.) This can be a null pointer. + XMLHandle( XMLNode* node ) : _node( node ) { + } + /// Create a handle from a node. + XMLHandle( XMLNode& node ) : _node( &node ) { + } + /// Copy constructor + XMLHandle( const XMLHandle& ref ) : _node( ref._node ) { + } + /// Assignment + XMLHandle& operator=( const XMLHandle& ref ) { + _node = ref._node; + return *this; + } + + /// Get the first child of this handle. + XMLHandle FirstChild() { + return XMLHandle( _node ? _node->FirstChild() : 0 ); + } + /// Get the first child element of this handle. + XMLHandle FirstChildElement( const char* name = 0 ) { + return XMLHandle( _node ? _node->FirstChildElement( name ) : 0 ); + } + /// Get the last child of this handle. + XMLHandle LastChild() { + return XMLHandle( _node ? _node->LastChild() : 0 ); + } + /// Get the last child element of this handle. + XMLHandle LastChildElement( const char* name = 0 ) { + return XMLHandle( _node ? _node->LastChildElement( name ) : 0 ); + } + /// Get the previous sibling of this handle. + XMLHandle PreviousSibling() { + return XMLHandle( _node ? _node->PreviousSibling() : 0 ); + } + /// Get the previous sibling element of this handle. + XMLHandle PreviousSiblingElement( const char* name = 0 ) { + return XMLHandle( _node ? _node->PreviousSiblingElement( name ) : 0 ); + } + /// Get the next sibling of this handle. + XMLHandle NextSibling() { + return XMLHandle( _node ? _node->NextSibling() : 0 ); + } + /// Get the next sibling element of this handle. + XMLHandle NextSiblingElement( const char* name = 0 ) { + return XMLHandle( _node ? _node->NextSiblingElement( name ) : 0 ); + } + + /// Safe cast to XMLNode. This can return null. + XMLNode* ToNode() { + return _node; + } + /// Safe cast to XMLElement. This can return null. + XMLElement* ToElement() { + return ( _node ? _node->ToElement() : 0 ); + } + /// Safe cast to XMLText. This can return null. + XMLText* ToText() { + return ( _node ? _node->ToText() : 0 ); + } + /// Safe cast to XMLUnknown. This can return null. + XMLUnknown* ToUnknown() { + return ( _node ? _node->ToUnknown() : 0 ); + } + /// Safe cast to XMLDeclaration. This can return null. + XMLDeclaration* ToDeclaration() { + return ( _node ? _node->ToDeclaration() : 0 ); + } + +private: + XMLNode* _node; +}; + + +/** + A variant of the XMLHandle class for working with const XMLNodes and Documents. It is the + same in all regards, except for the 'const' qualifiers. See XMLHandle for API. +*/ +class TINYXML2_LIB XMLConstHandle +{ +public: + XMLConstHandle( const XMLNode* node ) : _node( node ) { + } + XMLConstHandle( const XMLNode& node ) : _node( &node ) { + } + XMLConstHandle( const XMLConstHandle& ref ) : _node( ref._node ) { + } + + XMLConstHandle& operator=( const XMLConstHandle& ref ) { + _node = ref._node; + return *this; + } + + const XMLConstHandle FirstChild() const { + return XMLConstHandle( _node ? _node->FirstChild() : 0 ); + } + const XMLConstHandle FirstChildElement( const char* name = 0 ) const { + return XMLConstHandle( _node ? _node->FirstChildElement( name ) : 0 ); + } + const XMLConstHandle LastChild() const { + return XMLConstHandle( _node ? _node->LastChild() : 0 ); + } + const XMLConstHandle LastChildElement( const char* name = 0 ) const { + return XMLConstHandle( _node ? _node->LastChildElement( name ) : 0 ); + } + const XMLConstHandle PreviousSibling() const { + return XMLConstHandle( _node ? _node->PreviousSibling() : 0 ); + } + const XMLConstHandle PreviousSiblingElement( const char* name = 0 ) const { + return XMLConstHandle( _node ? _node->PreviousSiblingElement( name ) : 0 ); + } + const XMLConstHandle NextSibling() const { + return XMLConstHandle( _node ? _node->NextSibling() : 0 ); + } + const XMLConstHandle NextSiblingElement( const char* name = 0 ) const { + return XMLConstHandle( _node ? _node->NextSiblingElement( name ) : 0 ); + } + + + const XMLNode* ToNode() const { + return _node; + } + const XMLElement* ToElement() const { + return ( _node ? _node->ToElement() : 0 ); + } + const XMLText* ToText() const { + return ( _node ? _node->ToText() : 0 ); + } + const XMLUnknown* ToUnknown() const { + return ( _node ? _node->ToUnknown() : 0 ); + } + const XMLDeclaration* ToDeclaration() const { + return ( _node ? _node->ToDeclaration() : 0 ); + } + +private: + const XMLNode* _node; +}; + + +/** + Printing functionality. The XMLPrinter gives you more + options than the XMLDocument::Print() method. + + It can: + -# Print to memory. + -# Print to a file you provide. + -# Print XML without a XMLDocument. + + Print to Memory + + @verbatim + XMLPrinter printer; + doc.Print( &printer ); + SomeFunction( printer.CStr() ); + @endverbatim + + Print to a File + + You provide the file pointer. + @verbatim + XMLPrinter printer( fp ); + doc.Print( &printer ); + @endverbatim + + Print without a XMLDocument + + When loading, an XML parser is very useful. However, sometimes + when saving, it just gets in the way. The code is often set up + for streaming, and constructing the DOM is just overhead. + + The Printer supports the streaming case. The following code + prints out a trivially simple XML file without ever creating + an XML document. + + @verbatim + XMLPrinter printer( fp ); + printer.OpenElement( "foo" ); + printer.PushAttribute( "foo", "bar" ); + printer.CloseElement(); + @endverbatim +*/ +class TINYXML2_LIB XMLPrinter : public XMLVisitor +{ +public: + /** Construct the printer. If the FILE* is specified, + this will print to the FILE. Else it will print + to memory, and the result is available in CStr(). + If 'compact' is set to true, then output is created + with only required whitespace and newlines. + */ + XMLPrinter( FILE* file=0, bool compact = false, int depth = 0 ); + virtual ~XMLPrinter() {} + + /** If streaming, write the BOM and declaration. */ + void PushHeader( bool writeBOM, bool writeDeclaration ); + /** If streaming, start writing an element. + The element must be closed with CloseElement() + */ + void OpenElement( const char* name, bool compactMode=false ); + /// If streaming, add an attribute to an open element. + void PushAttribute( const char* name, const char* value ); + void PushAttribute( const char* name, int value ); + void PushAttribute( const char* name, unsigned value ); + void PushAttribute(const char* name, int64_t value); + void PushAttribute( const char* name, bool value ); + void PushAttribute( const char* name, double value ); + /// If streaming, close the Element. + virtual void CloseElement( bool compactMode=false ); + + /// Add a text node. + void PushText( const char* text, bool cdata=false ); + /// Add a text node from an integer. + void PushText( int value ); + /// Add a text node from an unsigned. + void PushText( unsigned value ); + /// Add a text node from an unsigned. + void PushText(int64_t value); + /// Add a text node from a bool. + void PushText( bool value ); + /// Add a text node from a float. + void PushText( float value ); + /// Add a text node from a double. + void PushText( double value ); + + /// Add a comment + void PushComment( const char* comment ); + + void PushDeclaration( const char* value ); + void PushUnknown( const char* value ); + + virtual bool VisitEnter( const XMLDocument& /*doc*/ ); + virtual bool VisitExit( const XMLDocument& /*doc*/ ) { + return true; + } + + virtual bool VisitEnter( const XMLElement& element, const XMLAttribute* attribute ); + virtual bool VisitExit( const XMLElement& element ); + + virtual bool Visit( const XMLText& text ); + virtual bool Visit( const XMLComment& comment ); + virtual bool Visit( const XMLDeclaration& declaration ); + virtual bool Visit( const XMLUnknown& unknown ); + + /** + If in print to memory mode, return a pointer to + the XML file in memory. + */ + const char* CStr() const { + return _buffer.Mem(); + } + /** + If in print to memory mode, return the size + of the XML file in memory. (Note the size returned + includes the terminating null.) + */ + int CStrSize() const { + return _buffer.Size(); + } + /** + If in print to memory mode, reset the buffer to the + beginning. + */ + void ClearBuffer() { + _buffer.Clear(); + _buffer.Push(0); + _firstElement = true; + } + +protected: + virtual bool CompactMode( const XMLElement& ) { return _compactMode; } + + /** Prints out the space before an element. You may override to change + the space and tabs used. A PrintSpace() override should call Print(). + */ + virtual void PrintSpace( int depth ); + void Print( const char* format, ... ); + void Write( const char* data, size_t size ); + inline void Write( const char* data ) { Write( data, strlen( data ) ); } + void Putc( char ch ); + + void SealElementIfJustOpened(); + bool _elementJustOpened; + DynArray< const char*, 10 > _stack; + +private: + void PrintString( const char*, bool restrictedEntitySet ); // prints out, after detecting entities. + + bool _firstElement; + FILE* _fp; + int _depth; + int _textDepth; + bool _processEntities; + bool _compactMode; + + enum { + ENTITY_RANGE = 64, + BUF_SIZE = 200 + }; + bool _entityFlag[ENTITY_RANGE]; + bool _restrictedEntityFlag[ENTITY_RANGE]; + + DynArray< char, 20 > _buffer; + + // Prohibit cloning, intentionally not implemented + XMLPrinter( const XMLPrinter& ); + XMLPrinter& operator=( const XMLPrinter& ); +}; + + +} // tinyxml2 + +#if defined(_MSC_VER) +# pragma warning(pop) +#endif + +#endif // TINYXML2_INCLUDED diff --git a/CMakeLists.txt b/CMakeLists.txt index 19eb8db92..470b43d1c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -38,6 +38,9 @@ endif(catkin_FOUND) set(BT_Source src/action_node.cpp src/decorator_node.cpp + src/decorator_negation_node.cpp + src/decorator_repeat_node.cpp + src/decorator_retry_node.cpp src/condition_node.cpp src/control_node.cpp src/exceptions.cpp @@ -50,8 +53,12 @@ set(BT_Source src/sequence_node_with_memory.cpp src/tree_node.cpp src/bt_factory.cpp + src/behavior_tree.cpp + + src/xml_parsing.cpp + 3rdparty/tinyXML2/tinyxml2.cpp ) -include_directories(include) +include_directories(include 3rdparty/) ###################################################### @@ -67,6 +74,7 @@ set(BT_Tests gtest/src/action_test_node.cpp gtest/src/condition_test_node.cpp gtest/gtest_tree.cpp + gtest/gtest_factory.cpp ) if(catkin_FOUND AND CATKIN_ENABLE_TESTING) diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp new file mode 100644 index 000000000..cd4e45737 --- /dev/null +++ b/gtest/gtest_factory.cpp @@ -0,0 +1,184 @@ +#include +#include "action_test_node.h" +#include "condition_test_node.h" +#include "behavior_tree_core/xml_parsing.h" +#include "crossdoor_dummy_nodes.h" + +// clang-format off + +const std::string xml_text = R"( + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + )"; + +const std::string xml_text_subtree = R"( + + + + + + + + + + + + + + + + + + + + + + + + )"; +// clang-format on + + +TEST(BehaviorTreeFactory, VerifyLargeTree) +{ + BT::XMLParser parser; + parser.loadFromText(xml_text); + std::vector errors; + bool res = parser.verifyXML(errors); + + for (const std::string& str : errors) + { + std::cout << str << std::endl; + } + + ASSERT_EQ(res, true); + ASSERT_EQ(errors.size(), 0); + + std::vector nodes; + BT::BehaviorTreeFactory factory; + + CrossDoor cross_door(factory); + + BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); + + BT::PrintTreeRecursively(root_node.get()); + + ASSERT_EQ(root_node->name(), "root_selector"); + + auto fallback = dynamic_cast(root_node.get()); + ASSERT_TRUE(fallback != nullptr); + + ASSERT_EQ(fallback->children().size(), 3); + ASSERT_EQ(fallback->child(0)->name(), "door_open_sequence"); + ASSERT_EQ(fallback->child(1)->name(), "door_closed_sequence"); + ASSERT_EQ(fallback->child(2)->name(), "PassThroughWindow"); + + auto sequence_open = dynamic_cast(fallback->child(0)); + ASSERT_TRUE(sequence_open != nullptr); + + ASSERT_EQ(sequence_open->children().size(), 2); + ASSERT_EQ(sequence_open->child(0)->name(), "IsDoorOpen"); + ASSERT_EQ(sequence_open->child(1)->name(), "PassThroughDoor"); + + auto sequence_closed = dynamic_cast(fallback->child(1)); + ASSERT_TRUE(sequence_closed != nullptr); + + ASSERT_EQ(sequence_closed->children().size(), 4); + ASSERT_EQ(sequence_closed->child(0)->name(), "Negation"); + ASSERT_EQ(sequence_closed->child(1)->name(), "OpenDoor"); + ASSERT_EQ(sequence_closed->child(2)->name(), "PassThroughDoor"); + ASSERT_EQ(sequence_closed->child(3)->name(), "CloseDoor"); + + auto decorator = dynamic_cast(sequence_closed->child(0)); + ASSERT_TRUE(decorator != nullptr); + + ASSERT_EQ(decorator->child()->name(), "IsDoorOpen"); +} + +TEST(BehaviorTreeFactory, Subtree) +{ + BT::XMLParser parser; + parser.loadFromText(xml_text_subtree); + std::vector errors; + bool res = parser.verifyXML(errors); + + for (const std::string& str : errors) + { + std::cout << str << std::endl; + } + + ASSERT_EQ(res, true); + ASSERT_EQ(errors.size(), 0); + + std::vector nodes; + BT::BehaviorTreeFactory factory; + + CrossDoor cross_door(factory); + + BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); + BT::PrintTreeRecursively(root_node.get()); + + ASSERT_EQ(root_node->name(), "root_selector"); + + auto root_selector = dynamic_cast(root_node.get()); + ASSERT_TRUE( root_selector != nullptr); + ASSERT_EQ(root_selector->children().size(), 2); + ASSERT_EQ(root_selector->child(0)->name(), "CrossDoorSubtree"); + ASSERT_EQ(root_selector->child(1)->name(), "PassThroughWindow"); + + auto subtree = dynamic_cast(root_selector->child(0)); + ASSERT_TRUE( subtree != nullptr); + + auto sequence = dynamic_cast(subtree->child()); + ASSERT_TRUE(sequence != nullptr); + + ASSERT_EQ(sequence->children().size(), 4); + ASSERT_EQ(sequence->child(0)->name(), "Negation"); + ASSERT_EQ(sequence->child(1)->name(), "OpenDoor"); + ASSERT_EQ(sequence->child(2)->name(), "PassThroughDoor"); + ASSERT_EQ(sequence->child(3)->name(), "CloseDoor"); + + auto decorator = dynamic_cast(sequence->child(0)); + ASSERT_TRUE(decorator != nullptr); + + ASSERT_EQ(decorator->child()->name(), "IsDoorLocked"); +} diff --git a/gtest/include/crossdoor_dummy_nodes.h b/gtest/include/crossdoor_dummy_nodes.h new file mode 100644 index 000000000..e5844a9c4 --- /dev/null +++ b/gtest/include/crossdoor_dummy_nodes.h @@ -0,0 +1,70 @@ +#include "behavior_tree_core/bt_factory.h" + +class CrossDoor +{ + public: + CrossDoor(BT::BehaviorTreeFactory& factory) + { + door_open_ = true; + door_locked_ = false; + + factory.registerSimpleAction("IsDoorOpen", [this]() { return IsDoorOpen(); }); + factory.registerSimpleAction("PassThroughDoor", [this]() { return PassThroughDoor(); }); + factory.registerSimpleAction("PassThroughWindow", [this]() { return PassThroughWindow(); }); + factory.registerSimpleAction("OpenDoor", [this]() { return OpenDoor(); }); + factory.registerSimpleAction("CloseDoor", [this]() { return CloseDoor(); }); + factory.registerSimpleAction("IsDoorLocked", [this]() { return IsDoorLocked(); }); + factory.registerSimpleAction("UnlockDoor", [this]() { return UnlockDoor(); }); + } + + BT::NodeStatus IsDoorOpen() + { + return door_open_ ? BT::SUCCESS : BT::FAILURE; + } + + BT::NodeStatus IsDoorLocked() + { + return door_locked_ ? BT::SUCCESS : BT::FAILURE; + } + + BT::NodeStatus UnlockDoor() + { + door_locked_ = false; + return BT::SUCCESS; + } + + BT::NodeStatus PassThroughDoor() + { + return door_open_ ? BT::SUCCESS : BT::FAILURE; + } + + BT::NodeStatus PassThroughWindow() + { + return BT::SUCCESS; + } + + BT::NodeStatus OpenDoor() + { + if (door_locked_) + return BT::FAILURE; + door_open_ = true; + return BT::SUCCESS; + } + + BT::NodeStatus CloseDoor() + { + if (door_open_) + { + door_open_ = false; + return BT::SUCCESS; + } + else + { + return BT::FAILURE; + } + } + + private: + bool door_open_; + bool door_locked_; +}; diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index 17afb3973..5e641e821 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -26,7 +26,17 @@ #include "behavior_tree_core/decorator_negation_node.h" #include "behavior_tree_core/decorator_retry_node.h" +#include "behavior_tree_core/decorator_repeat_node.h" +#include "behavior_tree_core/decorator_subtree_node.h" -#include "behavior_tree_core/exceptions.h" +namespace BT +{ +void RecursiveVisitor(const TreeNode *node, const std::function visitor); + +/** + * Debug function to print on a stream + */ +void PrintTreeRecursively(const TreeNode* root_node); +} #endif // BEHAVIOR_TREE_H diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 116c5dac5..5ae8f02b7 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -19,22 +19,12 @@ #include #include -#include "behavior_tree_core/action_node.h" -#include "behavior_tree_core/control_node.h" -#include "behavior_tree_core/condition_node.h" -#include "behavior_tree_core/decorator_node.h" +#include "behavior_tree_core/behavior_tree.h" namespace BT { typedef std::set RequiredParameters; -// We call Parameters the set of Key/Values that canbe read from file and are -// used to parametrize an object. it is up to the user's code to parse the string. -typedef std::map NodeParameters; - -// The term "Builder" refers to the Builder Ppattern (https://en.wikipedia.org/wiki/Builder_pattern) -typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; - class BehaviorTreeFactory { public: @@ -42,66 +32,75 @@ class BehaviorTreeFactory bool unregisterBuilder(const std::string& ID); - template - void registerBuilder(const std::string& ID); - - void registerSimpleAction(const std::string& ID, std::function tick_functor); + void registerBuilder(const std::string& ID, NodeBuilder builder); - void registerSimpleDecorator(const std::string& ID, std::function tick_functor); + void registerSimpleAction(const std::string& ID, std::function tick_functor); - std::unique_ptr instantiateTreeNode(const std::string& ID, const NodeParameters& params); + std::unique_ptr instantiateTreeNode(const std::string& ID, const std::string& name, + const NodeParameters& params) const; const std::map& builders() const { return builders_; } - private: - std::map builders_; -}; + template + void registerNodeType(const std::string& ID) + { + static_assert(std::is_base_of::value || std::is_base_of::value || + std::is_base_of::value || std::is_base_of::value, + "[registerBuilder]: accepts only classed derived from either ActionNode, DecoratorNode, " + "ControlNode " + "or ConditionNode"); -//----------------------------------------------- + constexpr bool default_constructable = std::is_constructible::value; + constexpr bool param_constructable = std::is_constructible::value; -template -inline void BehaviorTreeFactory::registerBuilder(const std::string& ID) -{ - static_assert(std::is_base_of::value || std::is_base_of::value || - std::is_base_of::value || std::is_base_of::value, - "[registerBuilder]: accepts only classed derived from either ActionNode, DecoratorNode, ControlNode " - "or ConditionNode"); - - constexpr bool default_constructable = std::is_constructible::value; - constexpr bool param_constructable = std::is_constructible::value; - - static_assert(param_constructable || param_constructable, - "[registerBuilder]: the registered class must have a Constructor with signature:\n\n" - " (const std::string&, const NodeParameters&)\n" - " or\n" - " (const std::string&)"); - - auto it = builders_.find(ID); - if (it != builders_.end()) - { - throw BehaviorTreeException("ID '" + ID + "' already registered"); + static_assert(default_constructable || param_constructable, + "[registerBuilder]: the registered class must have a Constructor with signature: " + " (const std::string&, const NodeParameters&) or (const std::string&)"); + + registerNodeTypeImpl(ID); } - NodeBuilder builder = [default_constructable, ID](const std::string& name, const NodeParameters& params) { - if (default_constructable && params.empty()) - { - return std::unique_ptr(new T(name)); - } - if (!param_constructable && !params.empty()) - { - throw BehaviorTreeException("Trying to instantiate a TreeNode that can NOT accept NodeParameters in the " - "Constructor: [" + - ID + " / " + name + "]"); - } - return std::unique_ptr(new T(name, params)); + private: + std::map builders_; + // template specialization + SFINAE + black magic + struct default_constructable + { + }; + struct param_constructable + { }; - builders_.insert(std::make_pair(ID, builder)); -} + template + using enable_if_default_constructable = + typename std::enable_if::value, struct default_constructable>; + + template + using enable_if_param_constructable = + typename std::enable_if::value, + struct param_constructable>; + + template ::type* = nullptr> + void registerNodeTypeImpl(const std::string& ID) + { + NodeBuilder builder = [](const std::string& name, const NodeParameters&) { + return std::unique_ptr(new T(name)); + }; + registerBuilder(ID, builder); + } + + template ::type* = nullptr> + void registerNodeTypeImpl(const std::string& ID) + { + NodeBuilder builder = [](const std::string& name, const NodeParameters& params) { + return std::unique_ptr(new T(name, params)); + }; + registerBuilder(ID, builder); + } +}; } // end namespace #endif // BT_FACTORY_H diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index 8735a348d..e0b905ca7 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -19,6 +19,7 @@ class DecoratorNode : public TreeNode void setChild(TreeNode* child); const TreeNode* child() const; + TreeNode* child(); // The method used to interrupt the execution of the node virtual void halt() override; diff --git a/include/behavior_tree_core/decorator_repeat_node.h b/include/behavior_tree_core/decorator_repeat_node.h index 85569c6db..0b25a644f 100644 --- a/include/behavior_tree_core/decorator_repeat_node.h +++ b/include/behavior_tree_core/decorator_repeat_node.h @@ -24,6 +24,8 @@ class DecoratorRepeatNode : public DecoratorNode // Constructor DecoratorRepeatNode(std::string name, unsigned int NTries); + DecoratorRepeatNode(std::string name, const NodeParameters& params); + ~DecoratorRepeatNode() = default; private: diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h index 7d6db98c0..1db56a38d 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -23,6 +23,9 @@ class DecoratorRetryNode : public DecoratorNode public: // Constructor DecoratorRetryNode(std::string name, unsigned int NTries); + + DecoratorRetryNode(std::string name, const NodeParameters& params); + ~DecoratorRetryNode() = default; diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index b3f66c2a0..052ca4c43 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -28,6 +28,7 @@ #include #include +#include #include "behavior_tree_core/tick_engine.h" #include "behavior_tree_core/exceptions.h" @@ -42,9 +43,34 @@ enum NodeType ACTION_NODE, CONDITION_NODE, CONTROL_NODE, - DECORATOR_NODE + DECORATOR_NODE, + SUBTREE_NODE, + UNDEFINED }; +inline const char* toStr(const BT::NodeType& type) +{ + switch (type) + { + case NodeType::ACTION_NODE: + return "Action"; + case NodeType::DECORATOR_NODE: + return "Decorator"; + case NodeType::CONTROL_NODE: + return "Control"; + case NodeType::SUBTREE_NODE: + return "SubTree"; + default: + return "Undefined"; + } +} + +inline std::ostream& operator<<(std::ostream& os, const BT::NodeType& type) +{ + os << toStr(type); + return os; +} + // Enumerates the states every node can be in after execution during a particular // time step: // - "Success" indicates that the node has completed running during this time step; @@ -63,6 +89,32 @@ enum NodeStatus EXIT }; +inline const char* toStr(const BT::NodeStatus& status) +{ + switch (status) + { + case NodeStatus::SUCCESS: + return "SUCCESS"; + case NodeStatus::FAILURE: + return "FAILURE"; + case NodeStatus::RUNNING: + return "RUNNING"; + case NodeStatus::IDLE: + return "IDLE"; + case NodeStatus::HALTED: + return "HALTED"; + default: + return "Undefined"; + } +} + + +inline std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status) +{ + os << toStr(status); + return os; +} + // Enumerates the options for when a parallel node is considered to have failed: // - "FAIL_ON_ONE" indicates that the node will return failure as soon as one of // its children fails; @@ -94,6 +146,10 @@ enum SuccessPolicy // If "BT::FAIL_ON_ONE" and "BT::SUCCEED_ON_ONE" are both active and are both trigerred in the // same time step, failure will take precedence. +// We call Parameters the set of Key/Values that can be read from file and are +// used to parametrize an object. It is up to the user's code to parse the string. +typedef std::map NodeParameters; + // Abstract base class for Behavior Tree Nodes class TreeNode { @@ -152,6 +208,11 @@ class TreeNode StatusChangeSignal state_change_signal_; }; + +typedef std::shared_ptr TreeNodePtr; + +// The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) +typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; } #endif diff --git a/include/behavior_tree_core/xml_parsing.h b/include/behavior_tree_core/xml_parsing.h new file mode 100644 index 000000000..29eaa52d2 --- /dev/null +++ b/include/behavior_tree_core/xml_parsing.h @@ -0,0 +1,104 @@ +#ifndef XML_PARSING_BT_H +#define XML_PARSING_BT_H + +#include "behavior_tree_core/bt_factory.h" +#include "tinyXML2/tinyxml2.h" + +namespace BT +{ +class XMLParser +{ + public: + XMLParser() = default; + + void loadFromFile(const std::string& filename) noexcept(false); + + void loadFromText(const std::string& xml_text) noexcept(false); + + bool verifyXML(std::vector& error_messages) const noexcept(false); + + template + using NodeBuilder = + std::function; + + // general and reusable method to visit each node of a tree + template + NodePtr treeParsing(const tinyxml2::XMLElement* root_element, const NodeBuilder& node_builder, + std::vector& nodes, NodePtr root_parent); + + TreeNodePtr instantiateTree(const BehaviorTreeFactory& factory, std::vector& nodes); + + private: + tinyxml2::XMLDocument doc_; +}; + +//--------------------------------------------- + +template +inline NodePtr XMLParser::treeParsing(const tinyxml2::XMLElement* root_element, + const NodeBuilder& node_builder, std::vector& nodes, + NodePtr root_parent) +{ + using namespace tinyxml2; + + std::function RecursiveVisitor; + + RecursiveVisitor = [&](NodePtr parent, const tinyxml2::XMLElement* element) -> NodePtr { + const std::string element_name = element->Name(); + std::string node_ID; + std::string node_alias; + NodeParameters node_params; + + // Actions and Decorators have their own ID + if (element_name == "Action" || element_name == "Decorator") + { + node_ID = element->Attribute("ID"); + } + else + { + node_ID = element_name; + } + + const char* attr_alias = element->Attribute("name"); + if (attr_alias) + { + node_alias = attr_alias; + } + else + { + node_alias = node_ID; + } + + if (element_name == "SubTree") + { + node_alias = element->Attribute("ID"); + } + + for (const XMLAttribute* att = element->FirstAttribute(); att; att = att->Next()) + { + const std::string attribute_name = att->Name(); + if (attribute_name != "ID" && attribute_name != "name") + { + node_params[attribute_name] = att->Value(); + } + } + + NodePtr node = node_builder(node_ID, node_alias, node_params, parent); + nodes.push_back(node); + + for (auto child_element = element->FirstChildElement(); child_element; + child_element = child_element->NextSiblingElement()) + { + RecursiveVisitor(node, child_element); + } + + return node; + }; + + // start recursion + NodePtr root = RecursiveVisitor(root_parent, root_element); + return root; +} +} + +#endif // XML_PARSING_BT_H diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp new file mode 100644 index 000000000..961797f09 --- /dev/null +++ b/src/behavior_tree.cpp @@ -0,0 +1,64 @@ +#include "behavior_tree_core/behavior_tree.h" + +namespace BT +{ +void RecursiveVisitor(const TreeNode* node, const std::function visitor) +{ + if (!node) + { + throw std::runtime_error("One of the children of a DecoratorNode or ControlNode is nulltr"); + } + + visitor(node); + + auto control = dynamic_cast(node); + if (control) + { + for (const auto& child : control->children()) + { + RecursiveVisitor(child, visitor); + } + } + auto decorator = dynamic_cast(node); + if (decorator) + { + RecursiveVisitor(decorator->child(), visitor); + } +} + +void PrintTreeRecursively(const TreeNode* root_node) +{ + std::function recursivePrint; + + recursivePrint = [&recursivePrint](unsigned indent, const BT::TreeNode* node) { + for (unsigned i = 0; i < indent; i++) + { + std::cout << " "; + } + if (!node) + { + std::cout << "!nullptr!" << std::endl; + return; + } + std::cout << node->name() << std::endl; + indent++; + auto control = dynamic_cast(node); + if (control) + { + for (const auto& child : control->children()) + { + recursivePrint(indent, child); + } + } + auto decorator = dynamic_cast(node); + if (decorator) + { + recursivePrint(indent, decorator->child()); + } + }; + + std::cout << "----------------" << std::endl; + recursivePrint(0, root_node); + std::cout << "----------------" << std::endl; +} +} diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 63806433b..bee438df6 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -17,6 +17,16 @@ namespace BT { BehaviorTreeFactory::BehaviorTreeFactory() { + registerNodeType("Fallback"); + registerNodeType("FallbackStar"); + registerNodeType("Sequence"); + registerNodeType("SequenceStar"); + + registerNodeType("Negation"); + registerNodeType("RetryUntilSuccesful"); + registerNodeType("Repeat"); + + registerNodeType("SubTree"); } bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID) @@ -30,23 +40,35 @@ bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID) return true; } -void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, std::function tick_functor) +void BehaviorTreeFactory::registerBuilder(const std::string& ID, NodeBuilder builder) { + auto it = builders_.find(ID); + if (it != builders_.end()) + { + throw BehaviorTreeException("ID '" + ID + "' already registered"); + } + + builders_.insert(std::make_pair(ID, builder)); } -void BehaviorTreeFactory::registerSimpleDecorator(const std::string& ID, - std::function tick_functor) +void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, std::function tick_functor) { + NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeParameters&) { + return std::unique_ptr(new SimpleActionNode(name, tick_functor)); + }; + + registerBuilder(ID, builder); } -std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::string& ID, const NodeParameters& params) +std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::string& ID, const std::string& name, + const NodeParameters& params) const { auto it = builders_.find(ID); if (it == builders_.end()) { throw BehaviorTreeException("ID '" + ID + "' not registered"); } - return it->second(ID, params); + return it->second(name, params); } } // end namespace diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index 3c96efe69..184e942a5 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -20,7 +20,7 @@ BT::DecoratorNegationNode::DecoratorNegationNode(std::string name) : DecoratorNo BT::NodeStatus BT::DecoratorNegationNode::tick() { setStatus(BT::RUNNING); - const NodeStatus child_state = child_node_->tick(); + const NodeStatus child_state = child_node_->executeTick(); switch (child_state) { diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 2aeb73696..76cc68250 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -41,6 +41,7 @@ const BT::TreeNode* BT::DecoratorNode::child() const return child_node_; } + void BT::DecoratorNode::haltChild() { if (child_node_->status() == BT::RUNNING) diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index 523e3b0cc..0ccf4283a 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -18,11 +18,21 @@ BT::DecoratorRetryNode::DecoratorRetryNode(std::string name, unsigned int NTries { } +BT::DecoratorRetryNode::DecoratorRetryNode(std::string name, const BT::NodeParameters& params) + : DecoratorNode(name), NTries_(1), TryIndx_(0) +{ + auto it = params.find("num_attempts"); + if (it == params.end()) + { + throw std::runtime_error("[DecoratorRetryNode] requires a parameter callen 'num_attempts'"); + } + NTries_ = std::stoul(it->second); +} BT::NodeStatus BT::DecoratorRetryNode::tick() { setStatus(BT::RUNNING); - BT::NodeStatus child_state = child_node_->tick(); + BT::NodeStatus child_state = child_node_->executeTick(); switch (child_state) { diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp new file mode 100644 index 000000000..3299ccd59 --- /dev/null +++ b/src/xml_parsing.cpp @@ -0,0 +1,241 @@ +#include "behavior_tree_core/xml_parsing.h" +#include + +namespace BT +{ +using namespace tinyxml2; + +void XMLParser::loadFromFile(const std::string& filename) +{ + XMLError err = doc_.LoadFile(filename.c_str()); + + if (err) + { + char buffer[200]; + sprintf(buffer, "Error parsing the XML: %s", XMLDocument::ErrorIDToName(err)); + throw std::runtime_error(buffer); + } +} + +void XMLParser::loadFromText(const std::string& xml_text) +{ + XMLError err = doc_.Parse(xml_text.c_str(), xml_text.size()); + + if (err) + { + char buffer[200]; + sprintf(buffer, "Error parsing the XML: %s", XMLDocument::ErrorIDToName(err)); + throw std::runtime_error(buffer); + } +} + +bool XMLParser::verifyXML(std::vector& error_messages) const +{ + error_messages.clear(); + + if (doc_.Error()) + { + error_messages.emplace_back("The XML was not correctly loaded"); + return false; + } + bool is_valid = true; + + //-------- Helper functions (lambdas) ----------------- + auto strEqual = [](const char* str1, const char* str2) -> bool { return strcmp(str1, str2) == 0; }; + + auto AppendError = [&](int line_num, const char* text) { + char buffer[256]; + sprintf(buffer, "Error at line %d: -> %s", line_num, text); + error_messages.emplace_back(buffer); + is_valid = false; + }; + + auto ChildrenCount = [](const XMLElement* parent_node) { + int count = 0; + for (auto node = parent_node->FirstChildElement(); node != nullptr; node = node->NextSiblingElement()) + { + count++; + } + return count; + }; + + //----------------------------- + + const XMLElement* xml_root = doc_.RootElement(); + + if (!xml_root || !strEqual(xml_root->Name(), "root")) + { + error_messages.emplace_back("The XML must have a root node called "); + return false; + } + //------------------------------------------------- + auto meta_root = xml_root->FirstChildElement("BehaviorTreeMetaModel"); + auto meta_sibling = meta_root ? meta_root->NextSiblingElement("BehaviorTreeMetaModel") : nullptr; + + if (meta_sibling) + { + AppendError(meta_sibling->GetLineNum(), " Only a single node is supported"); + } + if (meta_root) + { + // not having a MetaModel is not an error. But consider that the + // Graphical editor needs it. + for (auto node = xml_root->FirstChildElement(); node != nullptr; node = node->NextSiblingElement()) + { + const char* name = node->Name(); + if (strEqual(name, "Action") || strEqual(name, "Decorator") || strEqual(name, "SubTree")) + { + const char* ID = node->Attribute("ID"); + if (!ID) + { + AppendError(node->GetLineNum(), "Error at line %d: -> The attribute [ID] is mandatory"); + } + for (auto param_node = xml_root->FirstChildElement("Parameter"); param_node != nullptr; + param_node = param_node->NextSiblingElement("Parameter")) + { + const char* label = node->Attribute("label"); + const char* type = node->Attribute("type"); + if (!label || !type) + { + AppendError(node->GetLineNum(), "The node requires the attributes [type] and " + "[label]"); + } + } + } + } + } + + //------------------------------------------------- + + // function to be called recursively + std::function recursiveStep; + + recursiveStep = [&](const XMLElement* node) { + const int children_count = ChildrenCount(node); + const char* name = node->Name(); + if (strEqual(name, "Decorator")) + { + if (children_count != 1) + { + AppendError(node->GetLineNum(), "The node must have exactly 1 child"); + } + if (!node->Attribute("ID")) + { + AppendError(node->GetLineNum(), "The node must have the attribute [ID]"); + } + } + else if (strEqual(name, "Action")) + { + if (children_count != 0) + { + AppendError(node->GetLineNum(), "The node must not have any child"); + } + if (!node->Attribute("ID")) + { + AppendError(node->GetLineNum(), "The node must have the attribute [ID]"); + } + } + else if (strEqual(name, "Sequence") || strEqual(name, "SequenceStar") || strEqual(name, "Fallback") || + strEqual(name, "FallbackStar")) + { + if (children_count == 0) + { + AppendError(node->GetLineNum(), "A Control node must have at least 1 child"); + } + } + else if (strEqual(name, "SubTree")) + { + if (children_count > 0) + { + AppendError(node->GetLineNum(), "The node must have no children"); + } + if (!node->Attribute("ID")) + { + AppendError(node->GetLineNum(), "The node must have the attribute [ID]"); + } + } + else + { + AppendError(node->GetLineNum(), "Node not recognized"); + } + //recursion + for (auto child = node->FirstChildElement(); child != nullptr; child = child->NextSiblingElement()) + { + recursiveStep(child); + } + }; + + for (auto bt_root = xml_root->FirstChildElement("BehaviorTree"); bt_root != nullptr; + bt_root = bt_root->NextSiblingElement("BehaviorTree")) + { + if (ChildrenCount(bt_root) != 1) + { + AppendError(bt_root->GetLineNum(), "The node must have exactly 1 child"); + } + else + { + recursiveStep(bt_root->FirstChildElement()); + } + } + return is_valid; +} + +TreeNodePtr XMLParser::instantiateTree(const BehaviorTreeFactory& factory, std::vector& nodes) +{ + std::vector error_messages; + this->verifyXML(error_messages); + + if (error_messages.size() > 0) + { + for (const std::string& str : error_messages) + { + std::cerr << str << std::endl; + } + throw std::runtime_error("verifyXML failed"); + } + + //-------------------------------------- + XMLElement* xml_root = doc_.RootElement(); + const std::string main_tree_ID = xml_root->Attribute("main_tree_to_execute"); + + std::map bt_roots; + + for (auto node = xml_root->FirstChildElement("BehaviorTree"); node != nullptr; + node = node->NextSiblingElement("BehaviorTree")) + { + bt_roots[node->Attribute("ID")] = node; + } + + //-------------------------------------- + NodeBuilder node_builder = [&](const std::string& ID, const std::string& name, + const NodeParameters& params, TreeNodePtr parent) -> TreeNodePtr { + TreeNodePtr child_node = factory.instantiateTreeNode(ID, name, params); + nodes.push_back(child_node); + if (parent) + { + ControlNode* control_parent = dynamic_cast(parent.get()); + if (control_parent) + { + control_parent->addChild(child_node.get()); + } + DecoratorNode* decorator_parent = dynamic_cast(parent.get()); + if (decorator_parent) + { + decorator_parent->setChild(child_node.get()); + } + } + DecoratorSubtreeNode* subtree_node = dynamic_cast(child_node.get()); + + if (subtree_node) + { + auto subtree_elem = bt_roots[name]->FirstChildElement(); + treeParsing(subtree_elem, node_builder, nodes, child_node); + } + return child_node; + }; + //-------------------------------------- + + auto root_element = bt_roots[main_tree_ID]->FirstChildElement(); + return treeParsing(root_element, node_builder, nodes, TreeNodePtr()); +} +} From 7a3560c3c5e3f3bc9167e6745ed0d2ad186d107d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 7 May 2018 12:57:56 +0200 Subject: [PATCH 051/125] Nodes with memory are now parametrized --- include/behavior_tree_core/bt_factory.h | 58 ++++++++++++++----- .../fallback_node_with_memory.h | 3 + .../sequence_node_with_memory.h | 3 + src/fallback_node_with_memory.cpp | 28 +++++++++ src/sequence_node_with_memory.cpp | 27 +++++++++ 5 files changed, 103 insertions(+), 16 deletions(-) diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 5ae8f02b7..2310ade63 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -48,7 +48,7 @@ class BehaviorTreeFactory void registerNodeType(const std::string& ID) { static_assert(std::is_base_of::value || std::is_base_of::value || - std::is_base_of::value || std::is_base_of::value, + std::is_base_of::value || std::is_base_of::value, "[registerBuilder]: accepts only classed derived from either ActionNode, DecoratorNode, " "ControlNode " "or ConditionNode"); @@ -67,39 +67,65 @@ class BehaviorTreeFactory std::map builders_; // template specialization + SFINAE + black magic - struct default_constructable - { - }; - struct param_constructable - { - }; + + // clang-format off + template + using has_default_constructor = typename std::is_constructible; + + template + using has_params_constructor = typename std::is_constructible; + + struct default_constructable{}; + struct param_constructable{}; + struct both_constructable{}; + + template + using enable_if_default_constructable_only = + typename std::enable_if::value && !has_params_constructor::value, struct default_constructable>; template - using enable_if_default_constructable = - typename std::enable_if::value, struct default_constructable>; + using enable_if_param_constructable_only = + typename std::enable_if::value && has_params_constructor::value, struct param_constructable>; template - using enable_if_param_constructable = - typename std::enable_if::value, - struct param_constructable>; + using enable_if_has_both_constructors = + typename std::enable_if::value && has_params_constructor::value, struct both_constructable>; - template ::type* = nullptr> + + template ::type* = nullptr> void registerNodeTypeImpl(const std::string& ID) { - NodeBuilder builder = [](const std::string& name, const NodeParameters&) { + NodeBuilder builder = [](const std::string& name, const NodeParameters&) + { return std::unique_ptr(new T(name)); }; registerBuilder(ID, builder); } - template ::type* = nullptr> + template ::type* = nullptr> + void registerNodeTypeImpl(const std::string& ID) + { + NodeBuilder builder = [](const std::string& name, const NodeParameters& params) + { + return std::unique_ptr(new T(name, params)); + }; + registerBuilder(ID, builder); + } + + template ::type* = nullptr> void registerNodeTypeImpl(const std::string& ID) { - NodeBuilder builder = [](const std::string& name, const NodeParameters& params) { + NodeBuilder builder = [](const std::string& name, const NodeParameters& params) + { + if( params.empty() ) + { + return std::unique_ptr(new T(name)); + } return std::unique_ptr(new T(name, params)); }; registerBuilder(ID, builder); } + // clang-format on }; } // end namespace diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index dcc82f30b..da166d1ff 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -23,6 +23,9 @@ class FallbackNodeWithMemory : public ControlNode public: FallbackNodeWithMemory(std::string name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); + // Reset policy passed by parameter [reset_policy] + FallbackNodeWithMemory(std::string name, const NodeParameters& params); + ~FallbackNodeWithMemory() = default; virtual void halt() override; diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index 6b5db0acc..b05fcf9ba 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -23,6 +23,9 @@ class SequenceNodeWithMemory : public ControlNode public: SequenceNodeWithMemory(std::string name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); + // Reset policy passed by parameter [reset_policy] + SequenceNodeWithMemory(std::string name, const NodeParameters& params); + ~SequenceNodeWithMemory() = default; virtual void halt() override; diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 148f5afcf..c5bc15180 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -18,6 +18,34 @@ BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, ResetPolicy { } +BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, const NodeParameters& params) + : ControlNode::ControlNode(name), current_child_idx_(0) +{ + auto it = params.find("reset_policy"); + if( it == params.end()) + { + throw std::runtime_error("FallbackNodeWithMemory requires the parameter [reset_policy]"); + } + const std::string& policy = it->second; + + if(policy == "ON_SUCCESS_OR_FAILURE") + { + reset_policy_ = ON_SUCCESS_OR_FAILURE; + } + else if(policy == "ON_SUCCESS") + { + reset_policy_ = ON_SUCCESS; + } + else if(policy == "ON_FAILURE") + { + reset_policy_ = ON_FAILURE; + } + else{ + throw std::runtime_error("FallbackNodeWithMemory has a [reset_policy] that doesn't match."); + } +} + + BT::NodeStatus BT::FallbackNodeWithMemory::tick() { DEBUG_STDOUT(name() << " ticked, memory counter: " << current_child_idx_); diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index af5fc41c5..c585e29cb 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -18,6 +18,33 @@ BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolicy { } +BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, const NodeParameters& params) + : ControlNode::ControlNode(name), current_child_idx_(0) +{ + auto it = params.find("reset_policy"); + if( it == params.end()) + { + throw std::runtime_error("SequenceNodeWithMemory requires the parameter [reset_policy]"); + } + const std::string& policy = it->second; + + if(policy == "ON_SUCCESS_OR_FAILURE") + { + reset_policy_ = ON_SUCCESS_OR_FAILURE; + } + else if(policy == "ON_SUCCESS") + { + reset_policy_ = ON_SUCCESS; + } + else if(policy == "ON_FAILURE") + { + reset_policy_ = ON_FAILURE; + } + else{ + throw std::runtime_error("SequenceNodeWithMemory has a [reset_policy] that doesn't match."); + } +} + BT::NodeStatus BT::SequenceNodeWithMemory::tick() { // Vector size initialization. N_of_children_ could change at runtime if you edit the tree From e2c43d9dcec47140b66874b36d336fe9f40aaf32 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 7 May 2018 13:15:17 +0200 Subject: [PATCH 052/125] fix style --- gtest/gtest_factory.cpp | 4 ++-- include/behavior_tree_core/behavior_tree.h | 4 ++-- include/behavior_tree_core/tree_node.h | 2 ++ 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp index cd4e45737..bc5590e24 100644 --- a/gtest/gtest_factory.cpp +++ b/gtest/gtest_factory.cpp @@ -100,7 +100,7 @@ TEST(BehaviorTreeFactory, VerifyLargeTree) BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); - BT::PrintTreeRecursively(root_node.get()); + BT::printTreeRecursively(root_node.get()); ASSERT_EQ(root_node->name(), "root_selector"); @@ -155,7 +155,7 @@ TEST(BehaviorTreeFactory, Subtree) CrossDoor cross_door(factory); BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); - BT::PrintTreeRecursively(root_node.get()); + BT::printTreeRecursively(root_node.get()); ASSERT_EQ(root_node->name(), "root_selector"); diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index 5e641e821..a6e125dfa 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -31,12 +31,12 @@ namespace BT { -void RecursiveVisitor(const TreeNode *node, const std::function visitor); +void recursiveVisitor(const TreeNode *node, const std::function visitor); /** * Debug function to print on a stream */ -void PrintTreeRecursively(const TreeNode* root_node); +void printTreeRecursively(const TreeNode* root_node); } #endif // BEHAVIOR_TREE_H diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 052ca4c43..4f4c3f91a 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -54,6 +54,8 @@ inline const char* toStr(const BT::NodeType& type) { case NodeType::ACTION_NODE: return "Action"; + case NodeType::CONDITION_NODE: + return "Condition"; case NodeType::DECORATOR_NODE: return "Decorator"; case NodeType::CONTROL_NODE: From 0b7977dc4dd06db15cd069e0d6ac555e39a2d28e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 7 May 2018 13:17:03 +0200 Subject: [PATCH 053/125] fix --- src/behavior_tree.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index 961797f09..a1c2d45e9 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -2,7 +2,7 @@ namespace BT { -void RecursiveVisitor(const TreeNode* node, const std::function visitor) +void recursiveVisitor(const TreeNode* node, const std::function visitor) { if (!node) { @@ -16,17 +16,17 @@ void RecursiveVisitor(const TreeNode* node, const std::functionchildren()) { - RecursiveVisitor(child, visitor); + recursiveVisitor(child, visitor); } } auto decorator = dynamic_cast(node); if (decorator) { - RecursiveVisitor(decorator->child(), visitor); + recursiveVisitor(decorator->child(), visitor); } } -void PrintTreeRecursively(const TreeNode* root_node) +void printTreeRecursively(const TreeNode* root_node) { std::function recursivePrint; From 35b0ae581b54778bcd12d9c7db58cd1670faa1b7 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 8 May 2018 11:33:29 +0200 Subject: [PATCH 054/125] XML tag BehaviorTreeMetaModel renamed to TreeNodesModel It was neither a BehaviorTree itself nor a MetaModel... --- gtest/gtest_factory.cpp | 6 +++--- src/xml_parsing.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp index bc5590e24..171406ebb 100644 --- a/gtest/gtest_factory.cpp +++ b/gtest/gtest_factory.cpp @@ -32,8 +32,8 @@ const std::string xml_text = R"( - - + + @@ -46,7 +46,7 @@ const std::string xml_text = R"( - + )"; diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 3299ccd59..019ad8fb5 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -69,12 +69,12 @@ bool XMLParser::verifyXML(std::vector& error_messages) const return false; } //------------------------------------------------- - auto meta_root = xml_root->FirstChildElement("BehaviorTreeMetaModel"); - auto meta_sibling = meta_root ? meta_root->NextSiblingElement("BehaviorTreeMetaModel") : nullptr; + auto meta_root = xml_root->FirstChildElement("TreeNodesModel"); + auto meta_sibling = meta_root ? meta_root->NextSiblingElement("TreeNodesModel") : nullptr; if (meta_sibling) { - AppendError(meta_sibling->GetLineNum(), " Only a single node is supported"); + AppendError(meta_sibling->GetLineNum(), " Only a single node is supported"); } if (meta_root) { From 1d5b179a4e57d80ece4f0bb44678940623c4a929 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 11 May 2018 15:56:37 +0200 Subject: [PATCH 055/125] rebase fix --- include/behavior_tree_core/decorator_subtree_node.h | 2 +- include/behavior_tree_core/tree_node.h | 2 -- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/include/behavior_tree_core/decorator_subtree_node.h b/include/behavior_tree_core/decorator_subtree_node.h index b00b6461c..0756c3638 100644 --- a/include/behavior_tree_core/decorator_subtree_node.h +++ b/include/behavior_tree_core/decorator_subtree_node.h @@ -19,7 +19,7 @@ class DecoratorSubtreeNode : public DecoratorNode virtual BT::NodeStatus tick() { NodeStatus prev_status = status(); - if ( prev_status== BT::IDLE || prev_status == BT::HALTED) + if ( prev_status== BT::IDLE) { setStatus(BT::RUNNING); } diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 4f4c3f91a..adefa4777 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -103,8 +103,6 @@ inline const char* toStr(const BT::NodeStatus& status) return "RUNNING"; case NodeStatus::IDLE: return "IDLE"; - case NodeStatus::HALTED: - return "HALTED"; default: return "Undefined"; } From a1521549501c30701e70c6dcf284fc47f620e590 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 15 May 2018 16:40:36 +0200 Subject: [PATCH 056/125] UID added --- include/behavior_tree_core/tree_node.h | 6 ++++++ src/tree_node.cpp | 13 ++++++++++++- 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index adefa4777..5dea635a3 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -29,6 +29,7 @@ #include #include #include +#include #include "behavior_tree_core/tick_engine.h" #include "behavior_tree_core/exceptions.h" @@ -203,10 +204,15 @@ class TreeNode */ StatusChangeSubscriber subscribeToStatusChange(StatusChangeCallback callback); + // get an unique identifier of this instance of treeNode + uint16_t UID() const; + private: StatusChangeSignal state_change_signal_; + const uint16_t _uid; + }; typedef std::shared_ptr TreeNodePtr; diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 9a68a46e8..0afac7358 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -13,7 +13,13 @@ #include "behavior_tree_core/tree_node.h" -BT::TreeNode::TreeNode(std::string name) : name_(name), status_(BT::IDLE) +static uint8_t getUID() +{ + static uint8_t uid = 0; + return uid++; +} + +BT::TreeNode::TreeNode(std::string name) : name_(name), status_(BT::IDLE), _uid( getUID() ) { } @@ -73,3 +79,8 @@ BT::TreeNode::StatusChangeSubscriber BT::TreeNode::subscribeToStatusChange(BT::T { return state_change_signal_.subscribe(callback); } + +uint16_t BT::TreeNode::UID() const +{ + return _uid; +} From e3d8ab30ca925dbf84de9a7cc52562469587a9e9 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 15 May 2018 17:52:57 +0200 Subject: [PATCH 057/125] adding buildSerializedStatusSnapshot --- include/behavior_tree_core/behavior_tree.h | 16 +++++++++++++ src/behavior_tree.cpp | 28 +++++++++++++++------- 2 files changed, 36 insertions(+), 8 deletions(-) diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index a6e125dfa..a41b6363d 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -37,6 +37,22 @@ void recursiveVisitor(const TreeNode *node, const std::function> SerializedTreeStatus; + +void buildSerializedStatusSnapshot(const TreeNode *root_node, SerializedTreeStatus& serialized_buffer); + + } #endif // BEHAVIOR_TREE_H diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index a1c2d45e9..682547117 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -1,4 +1,5 @@ #include "behavior_tree_core/behavior_tree.h" +#include namespace BT { @@ -11,16 +12,14 @@ void recursiveVisitor(const TreeNode* node, const std::function(node); - if (control) + if (auto control = dynamic_cast(node)) { for (const auto& child : control->children()) { recursiveVisitor(child, visitor); } } - auto decorator = dynamic_cast(node); - if (decorator) + else if (auto decorator = dynamic_cast(node)) { recursiveVisitor(decorator->child(), visitor); } @@ -42,16 +41,15 @@ void printTreeRecursively(const TreeNode* root_node) } std::cout << node->name() << std::endl; indent++; - auto control = dynamic_cast(node); - if (control) + + if (auto control = dynamic_cast(node)) { for (const auto& child : control->children()) { recursivePrint(indent, child); } } - auto decorator = dynamic_cast(node); - if (decorator) + else if (auto decorator = dynamic_cast(node)) { recursivePrint(indent, decorator->child()); } @@ -61,4 +59,18 @@ void printTreeRecursively(const TreeNode* root_node) recursivePrint(0, root_node); std::cout << "----------------" << std::endl; } + +void buildSerializedStatusSnapshot(const TreeNode *root_node, SerializedTreeStatus& serialized_buffer) +{ + serialized_buffer.clear(); + + auto visitor = [ &serialized_buffer ](const TreeNode *node) + { + serialized_buffer.push_back( std::make_pair( node->UID(), + static_cast( node->status()) ) ); + }; + + recursiveVisitor(root_node, visitor); +} + } From 93ac32c5ec98ca3038f7024c78c56bf8242d8c65 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 18 May 2018 12:20:48 +0200 Subject: [PATCH 058/125] initial version of the serialization file --- include/behavior_tree_logger/BT_logger.fbs | 62 +++ .../BT_logger_generated.h | 445 ++++++++++++++++++ 2 files changed, 507 insertions(+) create mode 100644 include/behavior_tree_logger/BT_logger.fbs create mode 100644 include/behavior_tree_logger/BT_logger_generated.h diff --git a/include/behavior_tree_logger/BT_logger.fbs b/include/behavior_tree_logger/BT_logger.fbs new file mode 100644 index 000000000..2fbbcba77 --- /dev/null +++ b/include/behavior_tree_logger/BT_logger.fbs @@ -0,0 +1,62 @@ +namespace BT_Serialization; + +enum Status : byte { + IDLE = 0, + RUNNING, + SUCCESS, + FAILURE +} + +enum NodeType : byte { + UNDEFINED = 0, + ACTION, + CONDITION, + CONTROL, + DECORATOR, + SUBTREE +} + +struct Timestamp +{ + sec : uint32; + usec : uint32; +} + +table TreeNode +{ + uid : uint16; + parend_uid : uint16; + type : NodeType; + name : string (required); +} + +table BehaviorTree +{ + root_uid : uint16; + nodes : [TreeNode]; +} + +struct Status +{ + uid : uint16; + status : Status; +} + +struct StatusChange +{ + uid : uint16; + prev_status : Status; + status : Status; + usec_delta : uint32; +} + + +table StatusChangeLog +{ + behavior_tree : BehaviorTree; + initial_status : [Status]; + initial_time : Timestamp; + state_changes : [StatusChange]; +} + +root_type StatusChangeLog; diff --git a/include/behavior_tree_logger/BT_logger_generated.h b/include/behavior_tree_logger/BT_logger_generated.h new file mode 100644 index 000000000..7600111d4 --- /dev/null +++ b/include/behavior_tree_logger/BT_logger_generated.h @@ -0,0 +1,445 @@ +// automatically generated by the FlatBuffers compiler, do not modify + + +#ifndef FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ +#define FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ + +#include "flatbuffers/flatbuffers.h" + +namespace BT_Serialization { + +struct Timestamp; + +struct TreeNode; + +struct BehaviorTree; + +struct Status; + +struct StatusChange; + +struct StatusChangeLog; + +enum class Status : int8_t { + IDLE = 0, + RUNNING = 1, + SUCCESS = 2, + FAILURE = 3, + MIN = IDLE, + MAX = FAILURE +}; + +inline const Status (&EnumValuesStatus())[4] { + static const Status values[] = { + Status::IDLE, + Status::RUNNING, + Status::SUCCESS, + Status::FAILURE + }; + return values; +} + +inline const char * const *EnumNamesStatus() { + static const char * const names[] = { + "IDLE", + "RUNNING", + "SUCCESS", + "FAILURE", + nullptr + }; + return names; +} + +inline const char *EnumNameStatus(Status e) { + const size_t index = static_cast(e); + return EnumNamesStatus()[index]; +} + +enum class NodeType : int8_t { + UNDEFINED = 0, + ACTION = 1, + CONDITION = 2, + CONTROL = 3, + DECORATOR = 4, + SUBTREE = 5, + MIN = UNDEFINED, + MAX = SUBTREE +}; + +inline const NodeType (&EnumValuesNodeType())[6] { + static const NodeType values[] = { + NodeType::UNDEFINED, + NodeType::ACTION, + NodeType::CONDITION, + NodeType::CONTROL, + NodeType::DECORATOR, + NodeType::SUBTREE + }; + return values; +} + +inline const char * const *EnumNamesNodeType() { + static const char * const names[] = { + "UNDEFINED", + "ACTION", + "CONDITION", + "CONTROL", + "DECORATOR", + "SUBTREE", + nullptr + }; + return names; +} + +inline const char *EnumNameNodeType(NodeType e) { + const size_t index = static_cast(e); + return EnumNamesNodeType()[index]; +} + +FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(4) Timestamp FLATBUFFERS_FINAL_CLASS { + private: + uint32_t sec_; + uint32_t usec_; + + public: + Timestamp() { + memset(this, 0, sizeof(Timestamp)); + } + Timestamp(uint32_t _sec, uint32_t _usec) + : sec_(flatbuffers::EndianScalar(_sec)), + usec_(flatbuffers::EndianScalar(_usec)) { + } + uint32_t sec() const { + return flatbuffers::EndianScalar(sec_); + } + uint32_t usec() const { + return flatbuffers::EndianScalar(usec_); + } +}; +FLATBUFFERS_STRUCT_END(Timestamp, 8); + +FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(2) Status FLATBUFFERS_FINAL_CLASS { + private: + uint16_t uid_; + int8_t status_; + int8_t padding0__; + + public: + Status() { + memset(this, 0, sizeof(Status)); + } + Status(uint16_t _uid, Status _status) + : uid_(flatbuffers::EndianScalar(_uid)), + status_(flatbuffers::EndianScalar(static_cast(_status))), + padding0__(0) { + (void)padding0__; + } + uint16_t uid() const { + return flatbuffers::EndianScalar(uid_); + } + Status status() const { + return static_cast(flatbuffers::EndianScalar(status_)); + } +}; +FLATBUFFERS_STRUCT_END(Status, 4); + +FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(4) StatusChange FLATBUFFERS_FINAL_CLASS { + private: + uint16_t uid_; + int8_t prev_status_; + int8_t status_; + uint32_t usec_delta_; + + public: + StatusChange() { + memset(this, 0, sizeof(StatusChange)); + } + StatusChange(uint16_t _uid, Status _prev_status, Status _status, uint32_t _usec_delta) + : uid_(flatbuffers::EndianScalar(_uid)), + prev_status_(flatbuffers::EndianScalar(static_cast(_prev_status))), + status_(flatbuffers::EndianScalar(static_cast(_status))), + usec_delta_(flatbuffers::EndianScalar(_usec_delta)) { + } + uint16_t uid() const { + return flatbuffers::EndianScalar(uid_); + } + Status prev_status() const { + return static_cast(flatbuffers::EndianScalar(prev_status_)); + } + Status status() const { + return static_cast(flatbuffers::EndianScalar(status_)); + } + uint32_t usec_delta() const { + return flatbuffers::EndianScalar(usec_delta_); + } +}; +FLATBUFFERS_STRUCT_END(StatusChange, 8); + +struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + enum { + VT_UID = 4, + VT_PAREND_UID = 6, + VT_TYPE = 8, + VT_NAME = 10 + }; + uint16_t uid() const { + return GetField(VT_UID, 0); + } + uint16_t parend_uid() const { + return GetField(VT_PAREND_UID, 0); + } + NodeType type() const { + return static_cast(GetField(VT_TYPE, 0)); + } + const flatbuffers::String *name() const { + return GetPointer(VT_NAME); + } + bool Verify(flatbuffers::Verifier &verifier) const { + return VerifyTableStart(verifier) && + VerifyField(verifier, VT_UID) && + VerifyField(verifier, VT_PAREND_UID) && + VerifyField(verifier, VT_TYPE) && + VerifyOffsetRequired(verifier, VT_NAME) && + verifier.Verify(name()) && + verifier.EndTable(); + } +}; + +struct TreeNodeBuilder { + flatbuffers::FlatBufferBuilder &fbb_; + flatbuffers::uoffset_t start_; + void add_uid(uint16_t uid) { + fbb_.AddElement(TreeNode::VT_UID, uid, 0); + } + void add_parend_uid(uint16_t parend_uid) { + fbb_.AddElement(TreeNode::VT_PAREND_UID, parend_uid, 0); + } + void add_type(NodeType type) { + fbb_.AddElement(TreeNode::VT_TYPE, static_cast(type), 0); + } + void add_name(flatbuffers::Offset name) { + fbb_.AddOffset(TreeNode::VT_NAME, name); + } + explicit TreeNodeBuilder(flatbuffers::FlatBufferBuilder &_fbb) + : fbb_(_fbb) { + start_ = fbb_.StartTable(); + } + TreeNodeBuilder &operator=(const TreeNodeBuilder &); + flatbuffers::Offset Finish() { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + fbb_.Required(o, TreeNode::VT_NAME); + return o; + } +}; + +inline flatbuffers::Offset CreateTreeNode( + flatbuffers::FlatBufferBuilder &_fbb, + uint16_t uid = 0, + uint16_t parend_uid = 0, + NodeType type = NodeType::UNDEFINED, + flatbuffers::Offset name = 0) { + TreeNodeBuilder builder_(_fbb); + builder_.add_name(name); + builder_.add_parend_uid(parend_uid); + builder_.add_uid(uid); + builder_.add_type(type); + return builder_.Finish(); +} + +inline flatbuffers::Offset CreateTreeNodeDirect( + flatbuffers::FlatBufferBuilder &_fbb, + uint16_t uid = 0, + uint16_t parend_uid = 0, + NodeType type = NodeType::UNDEFINED, + const char *name = nullptr) { + return BT_Serialization::CreateTreeNode( + _fbb, + uid, + parend_uid, + type, + name ? _fbb.CreateString(name) : 0); +} + +struct BehaviorTree FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + enum { + VT_ROOT_UID = 4, + VT_NODES = 6 + }; + uint16_t root_uid() const { + return GetField(VT_ROOT_UID, 0); + } + const flatbuffers::Vector> *nodes() const { + return GetPointer> *>(VT_NODES); + } + bool Verify(flatbuffers::Verifier &verifier) const { + return VerifyTableStart(verifier) && + VerifyField(verifier, VT_ROOT_UID) && + VerifyOffset(verifier, VT_NODES) && + verifier.Verify(nodes()) && + verifier.VerifyVectorOfTables(nodes()) && + verifier.EndTable(); + } +}; + +struct BehaviorTreeBuilder { + flatbuffers::FlatBufferBuilder &fbb_; + flatbuffers::uoffset_t start_; + void add_root_uid(uint16_t root_uid) { + fbb_.AddElement(BehaviorTree::VT_ROOT_UID, root_uid, 0); + } + void add_nodes(flatbuffers::Offset>> nodes) { + fbb_.AddOffset(BehaviorTree::VT_NODES, nodes); + } + explicit BehaviorTreeBuilder(flatbuffers::FlatBufferBuilder &_fbb) + : fbb_(_fbb) { + start_ = fbb_.StartTable(); + } + BehaviorTreeBuilder &operator=(const BehaviorTreeBuilder &); + flatbuffers::Offset Finish() { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + return o; + } +}; + +inline flatbuffers::Offset CreateBehaviorTree( + flatbuffers::FlatBufferBuilder &_fbb, + uint16_t root_uid = 0, + flatbuffers::Offset>> nodes = 0) { + BehaviorTreeBuilder builder_(_fbb); + builder_.add_nodes(nodes); + builder_.add_root_uid(root_uid); + return builder_.Finish(); +} + +inline flatbuffers::Offset CreateBehaviorTreeDirect( + flatbuffers::FlatBufferBuilder &_fbb, + uint16_t root_uid = 0, + const std::vector> *nodes = nullptr) { + return BT_Serialization::CreateBehaviorTree( + _fbb, + root_uid, + nodes ? _fbb.CreateVector>(*nodes) : 0); +} + +struct StatusChangeLog FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + enum { + VT_BEHAVIOR_TREE = 4, + VT_INITIAL_STATUS = 6, + VT_INITIAL_TIME = 8, + VT_STATE_CHANGES = 10 + }; + const BehaviorTree *behavior_tree() const { + return GetPointer(VT_BEHAVIOR_TREE); + } + const flatbuffers::Vector *initial_status() const { + return GetPointer *>(VT_INITIAL_STATUS); + } + const Timestamp *initial_time() const { + return GetStruct(VT_INITIAL_TIME); + } + const flatbuffers::Vector *state_changes() const { + return GetPointer *>(VT_STATE_CHANGES); + } + bool Verify(flatbuffers::Verifier &verifier) const { + return VerifyTableStart(verifier) && + VerifyOffset(verifier, VT_BEHAVIOR_TREE) && + verifier.VerifyTable(behavior_tree()) && + VerifyOffset(verifier, VT_INITIAL_STATUS) && + verifier.Verify(initial_status()) && + VerifyField(verifier, VT_INITIAL_TIME) && + VerifyOffset(verifier, VT_STATE_CHANGES) && + verifier.Verify(state_changes()) && + verifier.EndTable(); + } +}; + +struct StatusChangeLogBuilder { + flatbuffers::FlatBufferBuilder &fbb_; + flatbuffers::uoffset_t start_; + void add_behavior_tree(flatbuffers::Offset behavior_tree) { + fbb_.AddOffset(StatusChangeLog::VT_BEHAVIOR_TREE, behavior_tree); + } + void add_initial_status(flatbuffers::Offset> initial_status) { + fbb_.AddOffset(StatusChangeLog::VT_INITIAL_STATUS, initial_status); + } + void add_initial_time(const Timestamp *initial_time) { + fbb_.AddStruct(StatusChangeLog::VT_INITIAL_TIME, initial_time); + } + void add_state_changes(flatbuffers::Offset> state_changes) { + fbb_.AddOffset(StatusChangeLog::VT_STATE_CHANGES, state_changes); + } + explicit StatusChangeLogBuilder(flatbuffers::FlatBufferBuilder &_fbb) + : fbb_(_fbb) { + start_ = fbb_.StartTable(); + } + StatusChangeLogBuilder &operator=(const StatusChangeLogBuilder &); + flatbuffers::Offset Finish() { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + return o; + } +}; + +inline flatbuffers::Offset CreateStatusChangeLog( + flatbuffers::FlatBufferBuilder &_fbb, + flatbuffers::Offset behavior_tree = 0, + flatbuffers::Offset> initial_status = 0, + const Timestamp *initial_time = 0, + flatbuffers::Offset> state_changes = 0) { + StatusChangeLogBuilder builder_(_fbb); + builder_.add_state_changes(state_changes); + builder_.add_initial_time(initial_time); + builder_.add_initial_status(initial_status); + builder_.add_behavior_tree(behavior_tree); + return builder_.Finish(); +} + +inline flatbuffers::Offset CreateStatusChangeLogDirect( + flatbuffers::FlatBufferBuilder &_fbb, + flatbuffers::Offset behavior_tree = 0, + const std::vector *initial_status = nullptr, + const Timestamp *initial_time = 0, + const std::vector *state_changes = nullptr) { + return BT_Serialization::CreateStatusChangeLog( + _fbb, + behavior_tree, + initial_status ? _fbb.CreateVector(*initial_status) : 0, + initial_time, + state_changes ? _fbb.CreateVectorOfStructs(*state_changes) : 0); +} + +inline const BT_Serialization::StatusChangeLog *GetStatusChangeLog(const void *buf) { + return flatbuffers::GetRoot(buf); +} + +inline const BT_Serialization::StatusChangeLog *GetSizePrefixedStatusChangeLog(const void *buf) { + return flatbuffers::GetSizePrefixedRoot(buf); +} + +inline bool VerifyStatusChangeLogBuffer( + flatbuffers::Verifier &verifier) { + return verifier.VerifyBuffer(nullptr); +} + +inline bool VerifySizePrefixedStatusChangeLogBuffer( + flatbuffers::Verifier &verifier) { + return verifier.VerifySizePrefixedBuffer(nullptr); +} + +inline void FinishStatusChangeLogBuffer( + flatbuffers::FlatBufferBuilder &fbb, + flatbuffers::Offset root) { + fbb.Finish(root); +} + +inline void FinishSizePrefixedStatusChangeLogBuffer( + flatbuffers::FlatBufferBuilder &fbb, + flatbuffers::Offset root) { + fbb.FinishSizePrefixed(root); +} + +} // namespace BT_Serialization + +#endif // FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ From 6bdd8389f53745a9f9c368a7e02ed918510b3617 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 18 May 2018 14:03:29 +0200 Subject: [PATCH 059/125] flatbuffers added --- 3rdparty/flatbuffers/flatbuffers.h | 2302 ++++++++++++++++++++++++++++ 1 file changed, 2302 insertions(+) create mode 100644 3rdparty/flatbuffers/flatbuffers.h diff --git a/3rdparty/flatbuffers/flatbuffers.h b/3rdparty/flatbuffers/flatbuffers.h new file mode 100644 index 000000000..e513e7938 --- /dev/null +++ b/3rdparty/flatbuffers/flatbuffers.h @@ -0,0 +1,2302 @@ +/* + * Copyright 2014 Google Inc. All rights reserved. + * + * 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. + */ + +#ifndef FLATBUFFERS_H_ +#define FLATBUFFERS_H_ + +#include "flatbuffers/base.h" + +namespace flatbuffers { +// Wrapper for uoffset_t to allow safe template specialization. +// Value is allowed to be 0 to indicate a null object (see e.g. AddOffset). +template struct Offset { + uoffset_t o; + Offset() : o(0) {} + Offset(uoffset_t _o) : o(_o) {} + Offset Union() const { return Offset(o); } + bool IsNull() const { return !o; } +}; + +inline void EndianCheck() { + int endiantest = 1; + // If this fails, see FLATBUFFERS_LITTLEENDIAN above. + FLATBUFFERS_ASSERT(*reinterpret_cast(&endiantest) == + FLATBUFFERS_LITTLEENDIAN); + (void)endiantest; +} + +template FLATBUFFERS_CONSTEXPR size_t AlignOf() { + // clang-format off + #ifdef _MSC_VER + return __alignof(T); + #else + #ifndef alignof + return __alignof__(T); + #else + return alignof(T); + #endif + #endif + // clang-format on +} + +// When we read serialized data from memory, in the case of most scalars, +// we want to just read T, but in the case of Offset, we want to actually +// perform the indirection and return a pointer. +// The template specialization below does just that. +// It is wrapped in a struct since function templates can't overload on the +// return type like this. +// The typedef is for the convenience of callers of this function +// (avoiding the need for a trailing return decltype) +template struct IndirectHelper { + typedef T return_type; + typedef T mutable_return_type; + static const size_t element_stride = sizeof(T); + static return_type Read(const uint8_t *p, uoffset_t i) { + return EndianScalar((reinterpret_cast(p))[i]); + } +}; +template struct IndirectHelper> { + typedef const T *return_type; + typedef T *mutable_return_type; + static const size_t element_stride = sizeof(uoffset_t); + static return_type Read(const uint8_t *p, uoffset_t i) { + p += i * sizeof(uoffset_t); + return reinterpret_cast(p + ReadScalar(p)); + } +}; +template struct IndirectHelper { + typedef const T *return_type; + typedef T *mutable_return_type; + static const size_t element_stride = sizeof(T); + static return_type Read(const uint8_t *p, uoffset_t i) { + return reinterpret_cast(p + i * sizeof(T)); + } +}; + +// An STL compatible iterator implementation for Vector below, effectively +// calling Get() for every element. +template struct VectorIterator { + typedef std::random_access_iterator_tag iterator_category; + typedef IT value_type; + typedef uoffset_t difference_type; + typedef IT *pointer; + typedef IT &reference; + + VectorIterator(const uint8_t *data, uoffset_t i) + : data_(data + IndirectHelper::element_stride * i) {} + VectorIterator(const VectorIterator &other) : data_(other.data_) {} + + VectorIterator &operator=(const VectorIterator &other) { + data_ = other.data_; + return *this; + } + + VectorIterator &operator=(VectorIterator &&other) { + data_ = other.data_; + return *this; + } + + bool operator==(const VectorIterator &other) const { + return data_ == other.data_; + } + + bool operator<(const VectorIterator &other) const { + return data_ < other.data_; + } + + bool operator!=(const VectorIterator &other) const { + return data_ != other.data_; + } + + ptrdiff_t operator-(const VectorIterator &other) const { + return (data_ - other.data_) / IndirectHelper::element_stride; + } + + IT operator*() const { return IndirectHelper::Read(data_, 0); } + + IT operator->() const { return IndirectHelper::Read(data_, 0); } + + VectorIterator &operator++() { + data_ += IndirectHelper::element_stride; + return *this; + } + + VectorIterator operator++(int) { + VectorIterator temp(data_, 0); + data_ += IndirectHelper::element_stride; + return temp; + } + + VectorIterator operator+(const uoffset_t &offset) const { + return VectorIterator(data_ + offset * IndirectHelper::element_stride, + 0); + } + + VectorIterator &operator+=(const uoffset_t &offset) { + data_ += offset * IndirectHelper::element_stride; + return *this; + } + + VectorIterator &operator--() { + data_ -= IndirectHelper::element_stride; + return *this; + } + + VectorIterator operator--(int) { + VectorIterator temp(data_, 0); + data_ -= IndirectHelper::element_stride; + return temp; + } + + VectorIterator operator-(const uoffset_t &offset) { + return VectorIterator(data_ - offset * IndirectHelper::element_stride, + 0); + } + + VectorIterator &operator-=(const uoffset_t &offset) { + data_ -= offset * IndirectHelper::element_stride; + return *this; + } + + private: + const uint8_t *data_; +}; + +struct String; + +// This is used as a helper type for accessing vectors. +// Vector::data() assumes the vector elements start after the length field. +template class Vector { + public: + typedef VectorIterator::mutable_return_type> + iterator; + typedef VectorIterator::return_type> + const_iterator; + + uoffset_t size() const { return EndianScalar(length_); } + + // Deprecated: use size(). Here for backwards compatibility. + uoffset_t Length() const { return size(); } + + typedef typename IndirectHelper::return_type return_type; + typedef typename IndirectHelper::mutable_return_type mutable_return_type; + + return_type Get(uoffset_t i) const { + FLATBUFFERS_ASSERT(i < size()); + return IndirectHelper::Read(Data(), i); + } + + return_type operator[](uoffset_t i) const { return Get(i); } + + // If this is a Vector of enums, T will be its storage type, not the enum + // type. This function makes it convenient to retrieve value with enum + // type E. + template E GetEnum(uoffset_t i) const { + return static_cast(Get(i)); + } + + // If this a vector of unions, this does the cast for you. There's no check + // to make sure this is the right type! + template const U *GetAs(uoffset_t i) const { + return reinterpret_cast(Get(i)); + } + + // If this a vector of unions, this does the cast for you. There's no check + // to make sure this is actually a string! + const String *GetAsString(uoffset_t i) const { + return reinterpret_cast(Get(i)); + } + + const void *GetStructFromOffset(size_t o) const { + return reinterpret_cast(Data() + o); + } + + iterator begin() { return iterator(Data(), 0); } + const_iterator begin() const { return const_iterator(Data(), 0); } + + iterator end() { return iterator(Data(), size()); } + const_iterator end() const { return const_iterator(Data(), size()); } + + // Change elements if you have a non-const pointer to this object. + // Scalars only. See reflection.h, and the documentation. + void Mutate(uoffset_t i, const T &val) { + FLATBUFFERS_ASSERT(i < size()); + WriteScalar(data() + i, val); + } + + // Change an element of a vector of tables (or strings). + // "val" points to the new table/string, as you can obtain from + // e.g. reflection::AddFlatBuffer(). + void MutateOffset(uoffset_t i, const uint8_t *val) { + FLATBUFFERS_ASSERT(i < size()); + static_assert(sizeof(T) == sizeof(uoffset_t), "Unrelated types"); + WriteScalar(data() + i, + static_cast(val - (Data() + i * sizeof(uoffset_t)))); + } + + // Get a mutable pointer to tables/strings inside this vector. + mutable_return_type GetMutableObject(uoffset_t i) const { + FLATBUFFERS_ASSERT(i < size()); + return const_cast(IndirectHelper::Read(Data(), i)); + } + + // The raw data in little endian format. Use with care. + const uint8_t *Data() const { + return reinterpret_cast(&length_ + 1); + } + + uint8_t *Data() { return reinterpret_cast(&length_ + 1); } + + // Similarly, but typed, much like std::vector::data + const T *data() const { return reinterpret_cast(Data()); } + T *data() { return reinterpret_cast(Data()); } + + template return_type LookupByKey(K key) const { + void *search_result = std::bsearch( + &key, Data(), size(), IndirectHelper::element_stride, KeyCompare); + + if (!search_result) { + return nullptr; // Key not found. + } + + const uint8_t *element = reinterpret_cast(search_result); + + return IndirectHelper::Read(element, 0); + } + + protected: + // This class is only used to access pre-existing data. Don't ever + // try to construct these manually. + Vector(); + + uoffset_t length_; + + private: + // This class is a pointer. Copying will therefore create an invalid object. + // Private and unimplemented copy constructor. + Vector(const Vector &); + + template static int KeyCompare(const void *ap, const void *bp) { + const K *key = reinterpret_cast(ap); + const uint8_t *data = reinterpret_cast(bp); + auto table = IndirectHelper::Read(data, 0); + + // std::bsearch compares with the operands transposed, so we negate the + // result here. + return -table->KeyCompareWithValue(*key); + } +}; + +// Represent a vector much like the template above, but in this case we +// don't know what the element types are (used with reflection.h). +class VectorOfAny { + public: + uoffset_t size() const { return EndianScalar(length_); } + + const uint8_t *Data() const { + return reinterpret_cast(&length_ + 1); + } + uint8_t *Data() { return reinterpret_cast(&length_ + 1); } + + protected: + VectorOfAny(); + + uoffset_t length_; + + private: + VectorOfAny(const VectorOfAny &); +}; + +#ifndef FLATBUFFERS_CPP98_STL +template +Vector> *VectorCast(Vector> *ptr) { + static_assert(std::is_base_of::value, "Unrelated types"); + return reinterpret_cast> *>(ptr); +} + +template +const Vector> *VectorCast(const Vector> *ptr) { + static_assert(std::is_base_of::value, "Unrelated types"); + return reinterpret_cast> *>(ptr); +} +#endif + +// Convenient helper function to get the length of any vector, regardless +// of wether it is null or not (the field is not set). +template static inline size_t VectorLength(const Vector *v) { + return v ? v->Length() : 0; +} + +struct String : public Vector { + const char *c_str() const { return reinterpret_cast(Data()); } + std::string str() const { return std::string(c_str(), Length()); } + + // clang-format off + #ifdef FLATBUFFERS_HAS_STRING_VIEW + flatbuffers::string_view string_view() const { + return flatbuffers::string_view(c_str(), Length()); + } + #endif // FLATBUFFERS_HAS_STRING_VIEW + // clang-format on + + bool operator<(const String &o) const { + return strcmp(c_str(), o.c_str()) < 0; + } +}; + +// Allocator interface. This is flatbuffers-specific and meant only for +// `vector_downward` usage. +class Allocator { + public: + virtual ~Allocator() {} + + // Allocate `size` bytes of memory. + virtual uint8_t *allocate(size_t size) = 0; + + // Deallocate `size` bytes of memory at `p` allocated by this allocator. + virtual void deallocate(uint8_t *p, size_t size) = 0; + + // Reallocate `new_size` bytes of memory, replacing the old region of size + // `old_size` at `p`. In contrast to a normal realloc, this grows downwards, + // and is intended specifcally for `vector_downward` use. + // `in_use_back` and `in_use_front` indicate how much of `old_size` is + // actually in use at each end, and needs to be copied. + virtual uint8_t *reallocate_downward(uint8_t *old_p, size_t old_size, + size_t new_size, size_t in_use_back, + size_t in_use_front) { + FLATBUFFERS_ASSERT(new_size > old_size); // vector_downward only grows + uint8_t *new_p = allocate(new_size); + memcpy_downward(old_p, old_size, new_p, new_size, in_use_back, + in_use_front); + deallocate(old_p, old_size); + return new_p; + } + + protected: + // Called by `reallocate_downward` to copy memory from `old_p` of `old_size` + // to `new_p` of `new_size`. Only memory of size `in_use_front` and + // `in_use_back` will be copied from the front and back of the old memory + // allocation. + void memcpy_downward(uint8_t *old_p, size_t old_size, + uint8_t *new_p, size_t new_size, + size_t in_use_back, size_t in_use_front) { + memcpy(new_p + new_size - in_use_back, old_p + old_size - in_use_back, + in_use_back); + memcpy(new_p, old_p, in_use_front); + } +}; + +// DefaultAllocator uses new/delete to allocate memory regions +class DefaultAllocator : public Allocator { + public: + virtual uint8_t *allocate(size_t size) FLATBUFFERS_OVERRIDE { + return new uint8_t[size]; + } + + virtual void deallocate(uint8_t *p, size_t) FLATBUFFERS_OVERRIDE { + delete[] p; + } + + static DefaultAllocator &instance() { + static DefaultAllocator inst; + return inst; + } +}; + +// DetachedBuffer is a finished flatbuffer memory region, detached from its +// builder. The original memory region and allocator are also stored so that +// the DetachedBuffer can manage the memory lifetime. +class DetachedBuffer { + public: + DetachedBuffer() + : allocator_(nullptr), + own_allocator_(false), + buf_(nullptr), + reserved_(0), + cur_(nullptr), + size_(0) {} + + DetachedBuffer(Allocator *allocator, bool own_allocator, uint8_t *buf, + size_t reserved, uint8_t *cur, size_t sz) + : allocator_(allocator), + own_allocator_(own_allocator), + buf_(buf), + reserved_(reserved), + cur_(cur), + size_(sz) { + FLATBUFFERS_ASSERT(allocator_); + } + + DetachedBuffer(DetachedBuffer &&other) + : allocator_(other.allocator_), + own_allocator_(other.own_allocator_), + buf_(other.buf_), + reserved_(other.reserved_), + cur_(other.cur_), + size_(other.size_) { + other.reset(); + } + + DetachedBuffer &operator=(DetachedBuffer &&other) { + destroy(); + + allocator_ = other.allocator_; + own_allocator_ = other.own_allocator_; + buf_ = other.buf_; + reserved_ = other.reserved_; + cur_ = other.cur_; + size_ = other.size_; + + other.reset(); + + return *this; + } + + ~DetachedBuffer() { destroy(); } + + const uint8_t *data() const { return cur_; } + + uint8_t *data() { return cur_; } + + size_t size() const { return size_; } + + // clang-format off + #if 0 // disabled for now due to the ordering of classes in this header + template + bool Verify() const { + Verifier verifier(data(), size()); + return verifier.Verify(nullptr); + } + + template + const T* GetRoot() const { + return flatbuffers::GetRoot(data()); + } + + template + T* GetRoot() { + return flatbuffers::GetRoot(data()); + } + #endif + // clang-format on + + // These may change access mode, leave these at end of public section + FLATBUFFERS_DELETE_FUNC(DetachedBuffer(const DetachedBuffer &other)) + FLATBUFFERS_DELETE_FUNC( + DetachedBuffer &operator=(const DetachedBuffer &other)) + + protected: + Allocator *allocator_; + bool own_allocator_; + uint8_t *buf_; + size_t reserved_; + uint8_t *cur_; + size_t size_; + + inline void destroy() { + if (buf_) { + FLATBUFFERS_ASSERT(allocator_); + allocator_->deallocate(buf_, reserved_); + } + if (own_allocator_ && allocator_) { delete allocator_; } + + reset(); + } + + inline void reset() { + allocator_ = nullptr; + own_allocator_ = false; + buf_ = nullptr; + reserved_ = 0; + cur_ = nullptr; + size_ = 0; + } +}; + +// This is a minimal replication of std::vector functionality, +// except growing from higher to lower addresses. i.e push_back() inserts data +// in the lowest address in the vector. +// Since this vector leaves the lower part unused, we support a "scratch-pad" +// that can be stored there for temporary data, to share the allocated space. +// Essentially, this supports 2 std::vectors in a single buffer. +class vector_downward { + public: + explicit vector_downward(size_t initial_size, + Allocator *allocator, + bool own_allocator, + size_t buffer_minalign) + : allocator_(allocator ? allocator : &DefaultAllocator::instance()), + own_allocator_(own_allocator), + initial_size_(initial_size), + buffer_minalign_(buffer_minalign), + reserved_(0), + buf_(nullptr), + cur_(nullptr), + scratch_(nullptr) { + FLATBUFFERS_ASSERT(allocator_); + } + + ~vector_downward() { + if (buf_) { + FLATBUFFERS_ASSERT(allocator_); + allocator_->deallocate(buf_, reserved_); + } + if (own_allocator_ && allocator_) { delete allocator_; } + } + + void reset() { + if (buf_) { + FLATBUFFERS_ASSERT(allocator_); + allocator_->deallocate(buf_, reserved_); + buf_ = nullptr; + } + clear(); + } + + void clear() { + if (buf_) { + cur_ = buf_ + reserved_; + } else { + reserved_ = 0; + cur_ = nullptr; + } + clear_scratch(); + } + + void clear_scratch() { + scratch_ = buf_; + } + + // Relinquish the pointer to the caller. + DetachedBuffer release() { + DetachedBuffer fb(allocator_, own_allocator_, buf_, reserved_, cur_, + size()); + allocator_ = nullptr; + own_allocator_ = false; + buf_ = nullptr; + clear(); + return fb; + } + + size_t ensure_space(size_t len) { + FLATBUFFERS_ASSERT(cur_ >= scratch_ && scratch_ >= buf_); + if (len > static_cast(cur_ - scratch_)) { reallocate(len); } + // Beyond this, signed offsets may not have enough range: + // (FlatBuffers > 2GB not supported). + FLATBUFFERS_ASSERT(size() < FLATBUFFERS_MAX_BUFFER_SIZE); + return len; + } + + inline uint8_t *make_space(size_t len) { + cur_ -= ensure_space(len); + return cur_; + } + + Allocator &get_allocator() { return *allocator_; } + + uoffset_t size() const { + return static_cast(reserved_ - (cur_ - buf_)); + } + + uoffset_t scratch_size() const { + return static_cast(scratch_ - buf_); + } + + size_t capacity() const { return reserved_; } + + uint8_t *data() const { + FLATBUFFERS_ASSERT(cur_); + return cur_; + } + + uint8_t *scratch_data() const { + FLATBUFFERS_ASSERT(buf_); + return buf_; + } + + uint8_t *scratch_end() const { + FLATBUFFERS_ASSERT(scratch_); + return scratch_; + } + + uint8_t *data_at(size_t offset) const { return buf_ + reserved_ - offset; } + + void push(const uint8_t *bytes, size_t num) { + memcpy(make_space(num), bytes, num); + } + + // Specialized version of push() that avoids memcpy call for small data. + template void push_small(const T &little_endian_t) { + make_space(sizeof(T)); + *reinterpret_cast(cur_) = little_endian_t; + } + + template void scratch_push_small(const T &t) { + ensure_space(sizeof(T)); + *reinterpret_cast(scratch_) = t; + scratch_ += sizeof(T); + } + + // fill() is most frequently called with small byte counts (<= 4), + // which is why we're using loops rather than calling memset. + void fill(size_t zero_pad_bytes) { + make_space(zero_pad_bytes); + for (size_t i = 0; i < zero_pad_bytes; i++) cur_[i] = 0; + } + + // Version for when we know the size is larger. + void fill_big(size_t zero_pad_bytes) { + memset(make_space(zero_pad_bytes), 0, zero_pad_bytes); + } + + void pop(size_t bytes_to_remove) { cur_ += bytes_to_remove; } + void scratch_pop(size_t bytes_to_remove) { scratch_ -= bytes_to_remove; } + + private: + // You shouldn't really be copying instances of this class. + FLATBUFFERS_DELETE_FUNC(vector_downward(const vector_downward &)) + FLATBUFFERS_DELETE_FUNC(vector_downward &operator=(const vector_downward &)) + + Allocator *allocator_; + bool own_allocator_; + size_t initial_size_; + size_t buffer_minalign_; + size_t reserved_; + uint8_t *buf_; + uint8_t *cur_; // Points at location between empty (below) and used (above). + uint8_t *scratch_; // Points to the end of the scratchpad in use. + + void reallocate(size_t len) { + FLATBUFFERS_ASSERT(allocator_); + auto old_reserved = reserved_; + auto old_size = size(); + auto old_scratch_size = scratch_size(); + reserved_ += (std::max)(len, + old_reserved ? old_reserved / 2 : initial_size_); + reserved_ = (reserved_ + buffer_minalign_ - 1) & ~(buffer_minalign_ - 1); + if (buf_) { + buf_ = allocator_->reallocate_downward(buf_, old_reserved, reserved_, + old_size, old_scratch_size); + } else { + buf_ = allocator_->allocate(reserved_); + } + cur_ = buf_ + reserved_ - old_size; + scratch_ = buf_ + old_scratch_size; + } +}; + +// Converts a Field ID to a virtual table offset. +inline voffset_t FieldIndexToOffset(voffset_t field_id) { + // Should correspond to what EndTable() below builds up. + const int fixed_fields = 2; // Vtable size and Object Size. + return static_cast((field_id + fixed_fields) * sizeof(voffset_t)); +} + +template +const T *data(const std::vector &v) { + return v.empty() ? nullptr : &v.front(); +} +template T *data(std::vector &v) { + return v.empty() ? nullptr : &v.front(); +} + +/// @endcond + +/// @addtogroup flatbuffers_cpp_api +/// @{ +/// @class FlatBufferBuilder +/// @brief Helper class to hold data needed in creation of a FlatBuffer. +/// To serialize data, you typically call one of the `Create*()` functions in +/// the generated code, which in turn call a sequence of `StartTable`/ +/// `PushElement`/`AddElement`/`EndTable`, or the builtin `CreateString`/ +/// `CreateVector` functions. Do this is depth-first order to build up a tree to +/// the root. `Finish()` wraps up the buffer ready for transport. +class FlatBufferBuilder { + public: + /// @brief Default constructor for FlatBufferBuilder. + /// @param[in] initial_size The initial size of the buffer, in bytes. Defaults + /// to `1024`. + /// @param[in] allocator An `Allocator` to use. Defaults to a new instance of + /// a `DefaultAllocator`. + /// @param[in] own_allocator Whether the builder/vector should own the + /// allocator. Defaults to / `false`. + /// @param[in] buffer_minalign Force the buffer to be aligned to the given + /// minimum alignment upon reallocation. Only needed if you intend to store + /// types with custom alignment AND you wish to read the buffer in-place + /// directly after creation. + explicit FlatBufferBuilder(size_t initial_size = 1024, + Allocator *allocator = nullptr, + bool own_allocator = false, + size_t buffer_minalign = + AlignOf()) + : buf_(initial_size, allocator, own_allocator, buffer_minalign), + num_field_loc(0), + max_voffset_(0), + nested(false), + finished(false), + minalign_(1), + force_defaults_(false), + dedup_vtables_(true), + string_pool(nullptr) { + EndianCheck(); + } + + ~FlatBufferBuilder() { + if (string_pool) delete string_pool; + } + + void Reset() { + Clear(); // clear builder state + buf_.reset(); // deallocate buffer + } + + /// @brief Reset all the state in this FlatBufferBuilder so it can be reused + /// to construct another buffer. + void Clear() { + ClearOffsets(); + buf_.clear(); + nested = false; + finished = false; + minalign_ = 1; + if (string_pool) string_pool->clear(); + } + + /// @brief The current size of the serialized buffer, counting from the end. + /// @return Returns an `uoffset_t` with the current size of the buffer. + uoffset_t GetSize() const { return buf_.size(); } + + /// @brief Get the serialized buffer (after you call `Finish()`). + /// @return Returns an `uint8_t` pointer to the FlatBuffer data inside the + /// buffer. + uint8_t *GetBufferPointer() const { + Finished(); + return buf_.data(); + } + + /// @brief Get a pointer to an unfinished buffer. + /// @return Returns a `uint8_t` pointer to the unfinished buffer. + uint8_t *GetCurrentBufferPointer() const { return buf_.data(); } + + /// @brief Get the released pointer to the serialized buffer. + /// @warning Do NOT attempt to use this FlatBufferBuilder afterwards! + /// @return A `FlatBuffer` that owns the buffer and its allocator and + /// behaves similar to a `unique_ptr` with a deleter. + /// Deprecated: use Release() instead + DetachedBuffer ReleaseBufferPointer() { + Finished(); + return buf_.release(); + } + + /// @brief Get the released DetachedBuffer. + /// @return A `DetachedBuffer` that owns the buffer and its allocator. + DetachedBuffer Release() { + Finished(); + return buf_.release(); + } + + /// @brief get the minimum alignment this buffer needs to be accessed + /// properly. This is only known once all elements have been written (after + /// you call Finish()). You can use this information if you need to embed + /// a FlatBuffer in some other buffer, such that you can later read it + /// without first having to copy it into its own buffer. + size_t GetBufferMinAlignment() { + Finished(); + return minalign_; + } + + /// @cond FLATBUFFERS_INTERNAL + void Finished() const { + // If you get this assert, you're attempting to get access a buffer + // which hasn't been finished yet. Be sure to call + // FlatBufferBuilder::Finish with your root table. + // If you really need to access an unfinished buffer, call + // GetCurrentBufferPointer instead. + FLATBUFFERS_ASSERT(finished); + } + /// @endcond + + /// @brief In order to save space, fields that are set to their default value + /// don't get serialized into the buffer. + /// @param[in] bool fd When set to `true`, always serializes default values. + void ForceDefaults(bool fd) { force_defaults_ = fd; } + + /// @brief By default vtables are deduped in order to save space. + /// @param[in] bool dedup When set to `true`, dedup vtables. + void DedupVtables(bool dedup) { dedup_vtables_ = dedup; } + + /// @cond FLATBUFFERS_INTERNAL + void Pad(size_t num_bytes) { buf_.fill(num_bytes); } + + void TrackMinAlign(size_t elem_size) { + if (elem_size > minalign_) minalign_ = elem_size; + } + + void Align(size_t elem_size) { + TrackMinAlign(elem_size); + buf_.fill(PaddingBytes(buf_.size(), elem_size)); + } + + void PushFlatBuffer(const uint8_t *bytes, size_t size) { + PushBytes(bytes, size); + finished = true; + } + + void PushBytes(const uint8_t *bytes, size_t size) { buf_.push(bytes, size); } + + void PopBytes(size_t amount) { buf_.pop(amount); } + + template void AssertScalarT() { + // The code assumes power of 2 sizes and endian-swap-ability. + static_assert(flatbuffers::is_scalar::value, "T must be a scalar type"); + } + + // Write a single aligned scalar to the buffer + template uoffset_t PushElement(T element) { + AssertScalarT(); + T litle_endian_element = EndianScalar(element); + Align(sizeof(T)); + buf_.push_small(litle_endian_element); + return GetSize(); + } + + template uoffset_t PushElement(Offset off) { + // Special case for offsets: see ReferTo below. + return PushElement(ReferTo(off.o)); + } + + // When writing fields, we track where they are, so we can create correct + // vtables later. + void TrackField(voffset_t field, uoffset_t off) { + FieldLoc fl = { off, field }; + buf_.scratch_push_small(fl); + num_field_loc++; + max_voffset_ = (std::max)(max_voffset_, field); + } + + // Like PushElement, but additionally tracks the field this represents. + template void AddElement(voffset_t field, T e, T def) { + // We don't serialize values equal to the default. + if (e == def && !force_defaults_) return; + auto off = PushElement(e); + TrackField(field, off); + } + + template void AddOffset(voffset_t field, Offset off) { + if (off.IsNull()) return; // Don't store. + AddElement(field, ReferTo(off.o), static_cast(0)); + } + + template void AddStruct(voffset_t field, const T *structptr) { + if (!structptr) return; // Default, don't store. + Align(AlignOf()); + buf_.push_small(*structptr); + TrackField(field, GetSize()); + } + + void AddStructOffset(voffset_t field, uoffset_t off) { + TrackField(field, off); + } + + // Offsets initially are relative to the end of the buffer (downwards). + // This function converts them to be relative to the current location + // in the buffer (when stored here), pointing upwards. + uoffset_t ReferTo(uoffset_t off) { + // Align to ensure GetSize() below is correct. + Align(sizeof(uoffset_t)); + // Offset must refer to something already in buffer. + FLATBUFFERS_ASSERT(off && off <= GetSize()); + return GetSize() - off + static_cast(sizeof(uoffset_t)); + } + + void NotNested() { + // If you hit this, you're trying to construct a Table/Vector/String + // during the construction of its parent table (between the MyTableBuilder + // and table.Finish(). + // Move the creation of these sub-objects to above the MyTableBuilder to + // not get this assert. + // Ignoring this assert may appear to work in simple cases, but the reason + // it is here is that storing objects in-line may cause vtable offsets + // to not fit anymore. It also leads to vtable duplication. + FLATBUFFERS_ASSERT(!nested); + // If you hit this, fields were added outside the scope of a table. + FLATBUFFERS_ASSERT(!num_field_loc); + } + + // From generated code (or from the parser), we call StartTable/EndTable + // with a sequence of AddElement calls in between. + uoffset_t StartTable() { + NotNested(); + nested = true; + return GetSize(); + } + + // This finishes one serialized object by generating the vtable if it's a + // table, comparing it against existing vtables, and writing the + // resulting vtable offset. + uoffset_t EndTable(uoffset_t start) { + // If you get this assert, a corresponding StartTable wasn't called. + FLATBUFFERS_ASSERT(nested); + // Write the vtable offset, which is the start of any Table. + // We fill it's value later. + auto vtableoffsetloc = PushElement(0); + // Write a vtable, which consists entirely of voffset_t elements. + // It starts with the number of offsets, followed by a type id, followed + // by the offsets themselves. In reverse: + // Include space for the last offset and ensure empty tables have a + // minimum size. + max_voffset_ = + (std::max)(static_cast(max_voffset_ + sizeof(voffset_t)), + FieldIndexToOffset(0)); + buf_.fill_big(max_voffset_); + auto table_object_size = vtableoffsetloc - start; + // Vtable use 16bit offsets. + FLATBUFFERS_ASSERT(table_object_size < 0x10000); + WriteScalar(buf_.data() + sizeof(voffset_t), + static_cast(table_object_size)); + WriteScalar(buf_.data(), max_voffset_); + // Write the offsets into the table + for (auto it = buf_.scratch_end() - num_field_loc * sizeof(FieldLoc); + it < buf_.scratch_end(); it += sizeof(FieldLoc)) { + auto field_location = reinterpret_cast(it); + auto pos = static_cast(vtableoffsetloc - field_location->off); + // If this asserts, it means you've set a field twice. + FLATBUFFERS_ASSERT( + !ReadScalar(buf_.data() + field_location->id)); + WriteScalar(buf_.data() + field_location->id, pos); + } + ClearOffsets(); + auto vt1 = reinterpret_cast(buf_.data()); + auto vt1_size = ReadScalar(vt1); + auto vt_use = GetSize(); + // See if we already have generated a vtable with this exact same + // layout before. If so, make it point to the old one, remove this one. + if (dedup_vtables_) { + for (auto it = buf_.scratch_data(); it < buf_.scratch_end(); + it += sizeof(uoffset_t)) { + auto vt_offset_ptr = reinterpret_cast(it); + auto vt2 = reinterpret_cast(buf_.data_at(*vt_offset_ptr)); + auto vt2_size = *vt2; + if (vt1_size != vt2_size || memcmp(vt2, vt1, vt1_size)) continue; + vt_use = *vt_offset_ptr; + buf_.pop(GetSize() - vtableoffsetloc); + break; + } + } + // If this is a new vtable, remember it. + if (vt_use == GetSize()) { buf_.scratch_push_small(vt_use); } + // Fill the vtable offset we created above. + // The offset points from the beginning of the object to where the + // vtable is stored. + // Offsets default direction is downward in memory for future format + // flexibility (storing all vtables at the start of the file). + WriteScalar(buf_.data_at(vtableoffsetloc), + static_cast(vt_use) - + static_cast(vtableoffsetloc)); + + nested = false; + return vtableoffsetloc; + } + + // DEPRECATED: call the version above instead. + uoffset_t EndTable(uoffset_t start, voffset_t /*numfields*/) { + return EndTable(start); + } + + // This checks a required field has been set in a given table that has + // just been constructed. + template void Required(Offset table, voffset_t field) { + auto table_ptr = buf_.data_at(table.o); + auto vtable_ptr = table_ptr - ReadScalar(table_ptr); + bool ok = ReadScalar(vtable_ptr + field) != 0; + // If this fails, the caller will show what field needs to be set. + FLATBUFFERS_ASSERT(ok); + (void)ok; + } + + uoffset_t StartStruct(size_t alignment) { + Align(alignment); + return GetSize(); + } + + uoffset_t EndStruct() { return GetSize(); } + + void ClearOffsets() { + buf_.scratch_pop(num_field_loc * sizeof(FieldLoc)); + num_field_loc = 0; + max_voffset_ = 0; + } + + // Aligns such that when "len" bytes are written, an object can be written + // after it with "alignment" without padding. + void PreAlign(size_t len, size_t alignment) { + TrackMinAlign(alignment); + buf_.fill(PaddingBytes(GetSize() + len, alignment)); + } + template void PreAlign(size_t len) { + AssertScalarT(); + PreAlign(len, sizeof(T)); + } + /// @endcond + + /// @brief Store a string in the buffer, which can contain any binary data. + /// @param[in] str A const char pointer to the data to be stored as a string. + /// @param[in] len The number of bytes that should be stored from `str`. + /// @return Returns the offset in the buffer where the string starts. + Offset CreateString(const char *str, size_t len) { + NotNested(); + PreAlign(len + 1); // Always 0-terminated. + buf_.fill(1); + PushBytes(reinterpret_cast(str), len); + PushElement(static_cast(len)); + return Offset(GetSize()); + } + + /// @brief Store a string in the buffer, which is null-terminated. + /// @param[in] str A const char pointer to a C-string to add to the buffer. + /// @return Returns the offset in the buffer where the string starts. + Offset CreateString(const char *str) { + return CreateString(str, strlen(str)); + } + + /// @brief Store a string in the buffer, which is null-terminated. + /// @param[in] str A char pointer to a C-string to add to the buffer. + /// @return Returns the offset in the buffer where the string starts. + Offset CreateString(char *str) { + return CreateString(str, strlen(str)); + } + + /// @brief Store a string in the buffer, which can contain any binary data. + /// @param[in] str A const reference to a std::string to store in the buffer. + /// @return Returns the offset in the buffer where the string starts. + Offset CreateString(const std::string &str) { + return CreateString(str.c_str(), str.length()); + } + + // clang-format off + #ifdef FLATBUFFERS_HAS_STRING_VIEW + /// @brief Store a string in the buffer, which can contain any binary data. + /// @param[in] str A const string_view to copy in to the buffer. + /// @return Returns the offset in the buffer where the string starts. + Offset CreateString(flatbuffers::string_view str) { + return CreateString(str.data(), str.size()); + } + #endif // FLATBUFFERS_HAS_STRING_VIEW + // clang-format on + + /// @brief Store a string in the buffer, which can contain any binary data. + /// @param[in] str A const pointer to a `String` struct to add to the buffer. + /// @return Returns the offset in the buffer where the string starts + Offset CreateString(const String *str) { + return str ? CreateString(str->c_str(), str->Length()) : 0; + } + + /// @brief Store a string in the buffer, which can contain any binary data. + /// @param[in] str A const reference to a std::string like type with support + /// of T::c_str() and T::length() to store in the buffer. + /// @return Returns the offset in the buffer where the string starts. + template Offset CreateString(const T &str) { + return CreateString(str.c_str(), str.length()); + } + + /// @brief Store a string in the buffer, which can contain any binary data. + /// If a string with this exact contents has already been serialized before, + /// instead simply returns the offset of the existing string. + /// @param[in] str A const char pointer to the data to be stored as a string. + /// @param[in] len The number of bytes that should be stored from `str`. + /// @return Returns the offset in the buffer where the string starts. + Offset CreateSharedString(const char *str, size_t len) { + if (!string_pool) + string_pool = new StringOffsetMap(StringOffsetCompare(buf_)); + auto size_before_string = buf_.size(); + // Must first serialize the string, since the set is all offsets into + // buffer. + auto off = CreateString(str, len); + auto it = string_pool->find(off); + // If it exists we reuse existing serialized data! + if (it != string_pool->end()) { + // We can remove the string we serialized. + buf_.pop(buf_.size() - size_before_string); + return *it; + } + // Record this string for future use. + string_pool->insert(off); + return off; + } + + /// @brief Store a string in the buffer, which null-terminated. + /// If a string with this exact contents has already been serialized before, + /// instead simply returns the offset of the existing string. + /// @param[in] str A const char pointer to a C-string to add to the buffer. + /// @return Returns the offset in the buffer where the string starts. + Offset CreateSharedString(const char *str) { + return CreateSharedString(str, strlen(str)); + } + + /// @brief Store a string in the buffer, which can contain any binary data. + /// If a string with this exact contents has already been serialized before, + /// instead simply returns the offset of the existing string. + /// @param[in] str A const reference to a std::string to store in the buffer. + /// @return Returns the offset in the buffer where the string starts. + Offset CreateSharedString(const std::string &str) { + return CreateSharedString(str.c_str(), str.length()); + } + + /// @brief Store a string in the buffer, which can contain any binary data. + /// If a string with this exact contents has already been serialized before, + /// instead simply returns the offset of the existing string. + /// @param[in] str A const pointer to a `String` struct to add to the buffer. + /// @return Returns the offset in the buffer where the string starts + Offset CreateSharedString(const String *str) { + return CreateSharedString(str->c_str(), str->Length()); + } + + /// @cond FLATBUFFERS_INTERNAL + uoffset_t EndVector(size_t len) { + FLATBUFFERS_ASSERT(nested); // Hit if no corresponding StartVector. + nested = false; + return PushElement(static_cast(len)); + } + + void StartVector(size_t len, size_t elemsize) { + NotNested(); + nested = true; + PreAlign(len * elemsize); + PreAlign(len * elemsize, elemsize); // Just in case elemsize > uoffset_t. + } + + // Call this right before StartVector/CreateVector if you want to force the + // alignment to be something different than what the element size would + // normally dictate. + // This is useful when storing a nested_flatbuffer in a vector of bytes, + // or when storing SIMD floats, etc. + void ForceVectorAlignment(size_t len, size_t elemsize, size_t alignment) { + PreAlign(len * elemsize, alignment); + } + + /// @endcond + + /// @brief Serialize an array into a FlatBuffer `vector`. + /// @tparam T The data type of the array elements. + /// @param[in] v A pointer to the array of type `T` to serialize into the + /// buffer as a `vector`. + /// @param[in] len The number of elements to serialize. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template Offset> CreateVector(const T *v, size_t len) { + // If this assert hits, you're specifying a template argument that is + // causing the wrong overload to be selected, remove it. + AssertScalarT(); + StartVector(len, sizeof(T)); + // clang-format off + #if FLATBUFFERS_LITTLEENDIAN + PushBytes(reinterpret_cast(v), len * sizeof(T)); + #else + if (sizeof(T) == 1) { + PushBytes(reinterpret_cast(v), len); + } else { + for (auto i = len; i > 0; ) { + PushElement(v[--i]); + } + } + #endif + // clang-format on + return Offset>(EndVector(len)); + } + + template + Offset>> CreateVector(const Offset *v, size_t len) { + StartVector(len, sizeof(Offset)); + for (auto i = len; i > 0;) { PushElement(v[--i]); } + return Offset>>(EndVector(len)); + } + + /// @brief Serialize a `std::vector` into a FlatBuffer `vector`. + /// @tparam T The data type of the `std::vector` elements. + /// @param v A const reference to the `std::vector` to serialize into the + /// buffer as a `vector`. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template Offset> CreateVector(const std::vector &v) { + return CreateVector(data(v), v.size()); + } + + // vector may be implemented using a bit-set, so we can't access it as + // an array. Instead, read elements manually. + // Background: https://isocpp.org/blog/2012/11/on-vectorbool + Offset> CreateVector(const std::vector &v) { + StartVector(v.size(), sizeof(uint8_t)); + for (auto i = v.size(); i > 0;) { + PushElement(static_cast(v[--i])); + } + return Offset>(EndVector(v.size())); + } + + // clang-format off + #ifndef FLATBUFFERS_CPP98_STL + /// @brief Serialize values returned by a function into a FlatBuffer `vector`. + /// This is a convenience function that takes care of iteration for you. + /// @tparam T The data type of the `std::vector` elements. + /// @param f A function that takes the current iteration 0..vector_size-1 and + /// returns any type that you can construct a FlatBuffers vector out of. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template Offset> CreateVector(size_t vector_size, + const std::function &f) { + std::vector elems(vector_size); + for (size_t i = 0; i < vector_size; i++) elems[i] = f(i); + return CreateVector(elems); + } + #endif + // clang-format on + + /// @brief Serialize values returned by a function into a FlatBuffer `vector`. + /// This is a convenience function that takes care of iteration for you. + /// @tparam T The data type of the `std::vector` elements. + /// @param f A function that takes the current iteration 0..vector_size-1, + /// and the state parameter returning any type that you can construct a + /// FlatBuffers vector out of. + /// @param state State passed to f. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVector(size_t vector_size, F f, S *state) { + std::vector elems(vector_size); + for (size_t i = 0; i < vector_size; i++) elems[i] = f(i, state); + return CreateVector(elems); + } + + /// @brief Serialize a `std::vector` into a FlatBuffer `vector`. + /// This is a convenience function for a common case. + /// @param v A const reference to the `std::vector` to serialize into the + /// buffer as a `vector`. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + Offset>> CreateVectorOfStrings( + const std::vector &v) { + std::vector> offsets(v.size()); + for (size_t i = 0; i < v.size(); i++) offsets[i] = CreateString(v[i]); + return CreateVector(offsets); + } + + /// @brief Serialize an array of structs into a FlatBuffer `vector`. + /// @tparam T The data type of the struct array elements. + /// @param[in] v A pointer to the array of type `T` to serialize into the + /// buffer as a `vector`. + /// @param[in] len The number of elements to serialize. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfStructs(const T *v, size_t len) { + StartVector(len * sizeof(T) / AlignOf(), AlignOf()); + PushBytes(reinterpret_cast(v), sizeof(T) * len); + return Offset>(EndVector(len)); + } + + /// @brief Serialize an array of native structs into a FlatBuffer `vector`. + /// @tparam T The data type of the struct array elements. + /// @tparam S The data type of the native struct array elements. + /// @param[in] v A pointer to the array of type `S` to serialize into the + /// buffer as a `vector`. + /// @param[in] len The number of elements to serialize. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfNativeStructs(const S *v, + size_t len) { + extern T Pack(const S &); + typedef T (*Pack_t)(const S &); + std::vector vv(len); + std::transform(v, v + len, vv.begin(), *(Pack_t)&Pack); + return CreateVectorOfStructs(vv.data(), vv.size()); + } + + // clang-format off + #ifndef FLATBUFFERS_CPP98_STL + /// @brief Serialize an array of structs into a FlatBuffer `vector`. + /// @tparam T The data type of the struct array elements. + /// @param[in] f A function that takes the current iteration 0..vector_size-1 + /// and a pointer to the struct that must be filled. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + /// This is mostly useful when flatbuffers are generated with mutation + /// accessors. + template Offset> CreateVectorOfStructs( + size_t vector_size, const std::function &filler) { + T* structs = StartVectorOfStructs(vector_size); + for (size_t i = 0; i < vector_size; i++) { + filler(i, structs); + structs++; + } + return EndVectorOfStructs(vector_size); + } + #endif + // clang-format on + + /// @brief Serialize an array of structs into a FlatBuffer `vector`. + /// @tparam T The data type of the struct array elements. + /// @param[in] f A function that takes the current iteration 0..vector_size-1, + /// a pointer to the struct that must be filled and the state argument. + /// @param[in] state Arbitrary state to pass to f. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + /// This is mostly useful when flatbuffers are generated with mutation + /// accessors. + template + Offset> CreateVectorOfStructs(size_t vector_size, F f, + S *state) { + T *structs = StartVectorOfStructs(vector_size); + for (size_t i = 0; i < vector_size; i++) { + f(i, structs, state); + structs++; + } + return EndVectorOfStructs(vector_size); + } + + /// @brief Serialize a `std::vector` of structs into a FlatBuffer `vector`. + /// @tparam T The data type of the `std::vector` struct elements. + /// @param[in]] v A const reference to the `std::vector` of structs to + /// serialize into the buffer as a `vector`. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfStructs( + const std::vector &v) { + return CreateVectorOfStructs(data(v), v.size()); + } + + /// @brief Serialize a `std::vector` of native structs into a FlatBuffer + /// `vector`. + /// @tparam T The data type of the `std::vector` struct elements. + /// @tparam S The data type of the `std::vector` native struct elements. + /// @param[in]] v A const reference to the `std::vector` of structs to + /// serialize into the buffer as a `vector`. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfNativeStructs( + const std::vector &v) { + return CreateVectorOfNativeStructs(data(v), v.size()); + } + + /// @cond FLATBUFFERS_INTERNAL + template struct StructKeyComparator { + bool operator()(const T &a, const T &b) const { + return a.KeyCompareLessThan(&b); + } + + private: + StructKeyComparator &operator=(const StructKeyComparator &); + }; + /// @endcond + + /// @brief Serialize a `std::vector` of structs into a FlatBuffer `vector` + /// in sorted order. + /// @tparam T The data type of the `std::vector` struct elements. + /// @param[in]] v A const reference to the `std::vector` of structs to + /// serialize into the buffer as a `vector`. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfSortedStructs(std::vector *v) { + return CreateVectorOfSortedStructs(data(*v), v->size()); + } + + /// @brief Serialize a `std::vector` of native structs into a FlatBuffer + /// `vector` in sorted order. + /// @tparam T The data type of the `std::vector` struct elements. + /// @tparam S The data type of the `std::vector` native struct elements. + /// @param[in]] v A const reference to the `std::vector` of structs to + /// serialize into the buffer as a `vector`. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfSortedNativeStructs( + std::vector *v) { + return CreateVectorOfSortedNativeStructs(data(*v), v->size()); + } + + /// @brief Serialize an array of structs into a FlatBuffer `vector` in sorted + /// order. + /// @tparam T The data type of the struct array elements. + /// @param[in] v A pointer to the array of type `T` to serialize into the + /// buffer as a `vector`. + /// @param[in] len The number of elements to serialize. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfSortedStructs(T *v, size_t len) { + std::sort(v, v + len, StructKeyComparator()); + return CreateVectorOfStructs(v, len); + } + + /// @brief Serialize an array of native structs into a FlatBuffer `vector` in + /// sorted order. + /// @tparam T The data type of the struct array elements. + /// @tparam S The data type of the native struct array elements. + /// @param[in] v A pointer to the array of type `S` to serialize into the + /// buffer as a `vector`. + /// @param[in] len The number of elements to serialize. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfSortedNativeStructs(S *v, + size_t len) { + extern T Pack(const S &); + typedef T (*Pack_t)(const S &); + std::vector vv(len); + std::transform(v, v + len, vv.begin(), *(Pack_t)&Pack); + return CreateVectorOfSortedStructs(vv, len); + } + + /// @cond FLATBUFFERS_INTERNAL + template struct TableKeyComparator { + TableKeyComparator(vector_downward &buf) : buf_(buf) {} + bool operator()(const Offset &a, const Offset &b) const { + auto table_a = reinterpret_cast(buf_.data_at(a.o)); + auto table_b = reinterpret_cast(buf_.data_at(b.o)); + return table_a->KeyCompareLessThan(table_b); + } + vector_downward &buf_; + + private: + TableKeyComparator &operator=(const TableKeyComparator &); + }; + /// @endcond + + /// @brief Serialize an array of `table` offsets as a `vector` in the buffer + /// in sorted order. + /// @tparam T The data type that the offset refers to. + /// @param[in] v An array of type `Offset` that contains the `table` + /// offsets to store in the buffer in sorted order. + /// @param[in] len The number of elements to store in the `vector`. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset>> CreateVectorOfSortedTables(Offset *v, + size_t len) { + std::sort(v, v + len, TableKeyComparator(buf_)); + return CreateVector(v, len); + } + + /// @brief Serialize an array of `table` offsets as a `vector` in the buffer + /// in sorted order. + /// @tparam T The data type that the offset refers to. + /// @param[in] v An array of type `Offset` that contains the `table` + /// offsets to store in the buffer in sorted order. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset>> CreateVectorOfSortedTables( + std::vector> *v) { + return CreateVectorOfSortedTables(data(*v), v->size()); + } + + /// @brief Specialized version of `CreateVector` for non-copying use cases. + /// Write the data any time later to the returned buffer pointer `buf`. + /// @param[in] len The number of elements to store in the `vector`. + /// @param[in] elemsize The size of each element in the `vector`. + /// @param[out] buf A pointer to a `uint8_t` pointer that can be + /// written to at a later time to serialize the data into a `vector` + /// in the buffer. + uoffset_t CreateUninitializedVector(size_t len, size_t elemsize, + uint8_t **buf) { + NotNested(); + StartVector(len, elemsize); + buf_.make_space(len * elemsize); + auto vec_start = GetSize(); + auto vec_end = EndVector(len); + *buf = buf_.data_at(vec_start); + return vec_end; + } + + /// @brief Specialized version of `CreateVector` for non-copying use cases. + /// Write the data any time later to the returned buffer pointer `buf`. + /// @tparam T The data type of the data that will be stored in the buffer + /// as a `vector`. + /// @param[in] len The number of elements to store in the `vector`. + /// @param[out] buf A pointer to a pointer of type `T` that can be + /// written to at a later time to serialize the data into a `vector` + /// in the buffer. + template + Offset> CreateUninitializedVector(size_t len, T **buf) { + return CreateUninitializedVector(len, sizeof(T), + reinterpret_cast(buf)); + } + + /// @brief Write a struct by itself, typically to be part of a union. + template Offset CreateStruct(const T &structobj) { + NotNested(); + Align(AlignOf()); + buf_.push_small(structobj); + return Offset(GetSize()); + } + + /// @brief The length of a FlatBuffer file header. + static const size_t kFileIdentifierLength = 4; + + /// @brief Finish serializing a buffer by writing the root offset. + /// @param[in] file_identifier If a `file_identifier` is given, the buffer + /// will be prefixed with a standard FlatBuffers file header. + template + void Finish(Offset root, const char *file_identifier = nullptr) { + Finish(root.o, file_identifier, false); + } + + /// @brief Finish a buffer with a 32 bit size field pre-fixed (size of the + /// buffer following the size field). These buffers are NOT compatible + /// with standard buffers created by Finish, i.e. you can't call GetRoot + /// on them, you have to use GetSizePrefixedRoot instead. + /// All >32 bit quantities in this buffer will be aligned when the whole + /// size pre-fixed buffer is aligned. + /// These kinds of buffers are useful for creating a stream of FlatBuffers. + template + void FinishSizePrefixed(Offset root, + const char *file_identifier = nullptr) { + Finish(root.o, file_identifier, true); + } + + protected: + // You shouldn't really be copying instances of this class. + FlatBufferBuilder(const FlatBufferBuilder &); + FlatBufferBuilder &operator=(const FlatBufferBuilder &); + + void Finish(uoffset_t root, const char *file_identifier, bool size_prefix) { + NotNested(); + buf_.clear_scratch(); + // This will cause the whole buffer to be aligned. + PreAlign((size_prefix ? sizeof(uoffset_t) : 0) + sizeof(uoffset_t) + + (file_identifier ? kFileIdentifierLength : 0), + minalign_); + if (file_identifier) { + FLATBUFFERS_ASSERT(strlen(file_identifier) == kFileIdentifierLength); + PushBytes(reinterpret_cast(file_identifier), + kFileIdentifierLength); + } + PushElement(ReferTo(root)); // Location of root. + if (size_prefix) { PushElement(GetSize()); } + finished = true; + } + + struct FieldLoc { + uoffset_t off; + voffset_t id; + }; + + vector_downward buf_; + + // Accumulating offsets of table members while it is being built. + // We store these in the scratch pad of buf_, after the vtable offsets. + uoffset_t num_field_loc; + // Track how much of the vtable is in use, so we can output the most compact + // possible vtable. + voffset_t max_voffset_; + + // Ensure objects are not nested. + bool nested; + + // Ensure the buffer is finished before it is being accessed. + bool finished; + + size_t minalign_; + + bool force_defaults_; // Serialize values equal to their defaults anyway. + + bool dedup_vtables_; + + struct StringOffsetCompare { + StringOffsetCompare(const vector_downward &buf) : buf_(&buf) {} + bool operator()(const Offset &a, const Offset &b) const { + auto stra = reinterpret_cast(buf_->data_at(a.o)); + auto strb = reinterpret_cast(buf_->data_at(b.o)); + return strncmp(stra->c_str(), strb->c_str(), + (std::min)(stra->size(), strb->size()) + 1) < 0; + } + const vector_downward *buf_; + }; + + // For use with CreateSharedString. Instantiated on first use only. + typedef std::set, StringOffsetCompare> StringOffsetMap; + StringOffsetMap *string_pool; + + private: + // Allocates space for a vector of structures. + // Must be completed with EndVectorOfStructs(). + template T *StartVectorOfStructs(size_t vector_size) { + StartVector(vector_size * sizeof(T) / AlignOf(), AlignOf()); + return reinterpret_cast(buf_.make_space(vector_size * sizeof(T))); + } + + // End the vector of structues in the flatbuffers. + // Vector should have previously be started with StartVectorOfStructs(). + template + Offset> EndVectorOfStructs(size_t vector_size) { + return Offset>(EndVector(vector_size)); + } +}; +/// @} + +/// @cond FLATBUFFERS_INTERNAL +// Helpers to get a typed pointer to the root object contained in the buffer. +template T *GetMutableRoot(void *buf) { + EndianCheck(); + return reinterpret_cast( + reinterpret_cast(buf) + + EndianScalar(*reinterpret_cast(buf))); +} + +template const T *GetRoot(const void *buf) { + return GetMutableRoot(const_cast(buf)); +} + +template const T *GetSizePrefixedRoot(const void *buf) { + return GetRoot(reinterpret_cast(buf) + sizeof(uoffset_t)); +} + +/// Helpers to get a typed pointer to objects that are currently being built. +/// @warning Creating new objects will lead to reallocations and invalidates +/// the pointer! +template +T *GetMutableTemporaryPointer(FlatBufferBuilder &fbb, Offset offset) { + return reinterpret_cast(fbb.GetCurrentBufferPointer() + fbb.GetSize() - + offset.o); +} + +template +const T *GetTemporaryPointer(FlatBufferBuilder &fbb, Offset offset) { + return GetMutableTemporaryPointer(fbb, offset); +} + +/// @brief Get a pointer to the the file_identifier section of the buffer. +/// @return Returns a const char pointer to the start of the file_identifier +/// characters in the buffer. The returned char * has length +/// 'flatbuffers::FlatBufferBuilder::kFileIdentifierLength'. +/// This function is UNDEFINED for FlatBuffers whose schema does not include +/// a file_identifier (likely points at padding or the start of a the root +/// vtable). +inline const char *GetBufferIdentifier(const void *buf, bool size_prefixed = false) { + return reinterpret_cast(buf) + + ((size_prefixed) ? 2 * sizeof(uoffset_t) : sizeof(uoffset_t)); +} + +// Helper to see if the identifier in a buffer has the expected value. +inline bool BufferHasIdentifier(const void *buf, const char *identifier, bool size_prefixed = false) { + return strncmp(GetBufferIdentifier(buf, size_prefixed), identifier, + FlatBufferBuilder::kFileIdentifierLength) == 0; +} + +// Helper class to verify the integrity of a FlatBuffer +class Verifier FLATBUFFERS_FINAL_CLASS { + public: + Verifier(const uint8_t *buf, size_t buf_len, uoffset_t _max_depth = 64, + uoffset_t _max_tables = 1000000) + : buf_(buf), + end_(buf + buf_len), + depth_(0), + max_depth_(_max_depth), + num_tables_(0), + max_tables_(_max_tables) + // clang-format off + #ifdef FLATBUFFERS_TRACK_VERIFIER_BUFFER_SIZE + , upper_bound_(buf) + #endif + // clang-format on + { + } + + // Central location where any verification failures register. + bool Check(bool ok) const { + // clang-format off + #ifdef FLATBUFFERS_DEBUG_VERIFICATION_FAILURE + FLATBUFFERS_ASSERT(ok); + #endif + #ifdef FLATBUFFERS_TRACK_VERIFIER_BUFFER_SIZE + if (!ok) + upper_bound_ = buf_; + #endif + // clang-format on + return ok; + } + + // Verify any range within the buffer. + bool Verify(const void *elem, size_t elem_len) const { + // clang-format off + #ifdef FLATBUFFERS_TRACK_VERIFIER_BUFFER_SIZE + auto upper_bound = reinterpret_cast(elem) + elem_len; + if (upper_bound_ < upper_bound) + upper_bound_ = upper_bound; + #endif + // clang-format on + return Check(elem_len <= (size_t)(end_ - buf_) && elem >= buf_ && + elem <= end_ - elem_len); + } + + // Verify a range indicated by sizeof(T). + template bool Verify(const void *elem) const { + return Verify(elem, sizeof(T)); + } + + // Verify a pointer (may be NULL) of a table type. + template bool VerifyTable(const T *table) { + return !table || table->Verify(*this); + } + + // Verify a pointer (may be NULL) of any vector type. + template bool Verify(const Vector *vec) const { + const uint8_t *end; + return !vec || VerifyVector(reinterpret_cast(vec), + sizeof(T), &end); + } + + // Verify a pointer (may be NULL) of a vector to struct. + template bool Verify(const Vector *vec) const { + return Verify(reinterpret_cast *>(vec)); + } + + // Verify a pointer (may be NULL) to string. + bool Verify(const String *str) const { + const uint8_t *end; + return !str || + (VerifyVector(reinterpret_cast(str), 1, &end) && + Verify(end, 1) && // Must have terminator + Check(*end == '\0')); // Terminating byte must be 0. + } + + // Common code between vectors and strings. + bool VerifyVector(const uint8_t *vec, size_t elem_size, + const uint8_t **end) const { + // Check we can read the size field. + if (!Verify(vec)) return false; + // Check the whole array. If this is a string, the byte past the array + // must be 0. + auto size = ReadScalar(vec); + auto max_elems = FLATBUFFERS_MAX_BUFFER_SIZE / elem_size; + if (!Check(size < max_elems)) + return false; // Protect against byte_size overflowing. + auto byte_size = sizeof(size) + elem_size * size; + *end = vec + byte_size; + return Verify(vec, byte_size); + } + + // Special case for string contents, after the above has been called. + bool VerifyVectorOfStrings(const Vector> *vec) const { + if (vec) { + for (uoffset_t i = 0; i < vec->size(); i++) { + if (!Verify(vec->Get(i))) return false; + } + } + return true; + } + + // Special case for table contents, after the above has been called. + template bool VerifyVectorOfTables(const Vector> *vec) { + if (vec) { + for (uoffset_t i = 0; i < vec->size(); i++) { + if (!vec->Get(i)->Verify(*this)) return false; + } + } + return true; + } + + template + bool VerifyBufferFromStart(const char *identifier, const uint8_t *start) { + if (identifier && + (size_t(end_ - start) < 2 * sizeof(flatbuffers::uoffset_t) || + !BufferHasIdentifier(start, identifier))) { + return false; + } + + // Call T::Verify, which must be in the generated code for this type. + auto o = VerifyOffset(start); + return o && reinterpret_cast(start + o)->Verify(*this) +#ifdef FLATBUFFERS_TRACK_VERIFIER_BUFFER_SIZE + && GetComputedSize() +#endif + ; + } + + // Verify this whole buffer, starting with root type T. + template bool VerifyBuffer() { return VerifyBuffer(nullptr); } + + template bool VerifyBuffer(const char *identifier) { + return VerifyBufferFromStart(identifier, buf_); + } + + template bool VerifySizePrefixedBuffer(const char *identifier) { + return Verify(buf_) && + ReadScalar(buf_) == end_ - buf_ - sizeof(uoffset_t) && + VerifyBufferFromStart(identifier, buf_ + sizeof(uoffset_t)); + } + + uoffset_t VerifyOffset(const uint8_t *start) const { + if (!Verify(start)) return false; + auto o = ReadScalar(start); + Check(o != 0); + return o; + } + + // Called at the start of a table to increase counters measuring data + // structure depth and amount, and possibly bails out with false if + // limits set by the constructor have been hit. Needs to be balanced + // with EndTable(). + bool VerifyComplexity() { + depth_++; + num_tables_++; + return Check(depth_ <= max_depth_ && num_tables_ <= max_tables_); + } + + // Called at the end of a table to pop the depth count. + bool EndTable() { + depth_--; + return true; + } + + // clang-format off + #ifdef FLATBUFFERS_TRACK_VERIFIER_BUFFER_SIZE + // Returns the message size in bytes + size_t GetComputedSize() const { + uintptr_t size = upper_bound_ - buf_; + // Align the size to uoffset_t + size = (size - 1 + sizeof(uoffset_t)) & ~(sizeof(uoffset_t) - 1); + return (buf_ + size > end_) ? 0 : size; + } + #endif + // clang-format on + + private: + const uint8_t *buf_; + const uint8_t *end_; + uoffset_t depth_; + uoffset_t max_depth_; + uoffset_t num_tables_; + uoffset_t max_tables_; + // clang-format off + #ifdef FLATBUFFERS_TRACK_VERIFIER_BUFFER_SIZE + mutable const uint8_t *upper_bound_; + #endif + // clang-format on +}; + +// Convenient way to bundle a buffer and its length, to pass it around +// typed by its root. +// A BufferRef does not own its buffer. +struct BufferRefBase {}; // for std::is_base_of +template struct BufferRef : BufferRefBase { + BufferRef() : buf(nullptr), len(0), must_free(false) {} + BufferRef(uint8_t *_buf, uoffset_t _len) + : buf(_buf), len(_len), must_free(false) {} + + ~BufferRef() { + if (must_free) free(buf); + } + + const T *GetRoot() const { return flatbuffers::GetRoot(buf); } + + bool Verify() { + Verifier verifier(buf, len); + return verifier.VerifyBuffer(nullptr); + } + + uint8_t *buf; + uoffset_t len; + bool must_free; +}; + +// "structs" are flat structures that do not have an offset table, thus +// always have all members present and do not support forwards/backwards +// compatible extensions. + +class Struct FLATBUFFERS_FINAL_CLASS { + public: + template T GetField(uoffset_t o) const { + return ReadScalar(&data_[o]); + } + + template T GetStruct(uoffset_t o) const { + return reinterpret_cast(&data_[o]); + } + + const uint8_t *GetAddressOf(uoffset_t o) const { return &data_[o]; } + uint8_t *GetAddressOf(uoffset_t o) { return &data_[o]; } + + private: + uint8_t data_[1]; +}; + +// "tables" use an offset table (possibly shared) that allows fields to be +// omitted and added at will, but uses an extra indirection to read. +class Table { + public: + const uint8_t *GetVTable() const { + return data_ - ReadScalar(data_); + } + + // This gets the field offset for any of the functions below it, or 0 + // if the field was not present. + voffset_t GetOptionalFieldOffset(voffset_t field) const { + // The vtable offset is always at the start. + auto vtable = GetVTable(); + // The first element is the size of the vtable (fields + type id + itself). + auto vtsize = ReadScalar(vtable); + // If the field we're accessing is outside the vtable, we're reading older + // data, so it's the same as if the offset was 0 (not present). + return field < vtsize ? ReadScalar(vtable + field) : 0; + } + + template T GetField(voffset_t field, T defaultval) const { + auto field_offset = GetOptionalFieldOffset(field); + return field_offset ? ReadScalar(data_ + field_offset) : defaultval; + } + + template P GetPointer(voffset_t field) { + auto field_offset = GetOptionalFieldOffset(field); + auto p = data_ + field_offset; + return field_offset ? reinterpret_cast

(p + ReadScalar(p)) + : nullptr; + } + template P GetPointer(voffset_t field) const { + return const_cast(this)->GetPointer

(field); + } + + template P GetStruct(voffset_t field) const { + auto field_offset = GetOptionalFieldOffset(field); + auto p = const_cast(data_ + field_offset); + return field_offset ? reinterpret_cast

(p) : nullptr; + } + + template bool SetField(voffset_t field, T val, T def) { + auto field_offset = GetOptionalFieldOffset(field); + if (!field_offset) return val == def; + WriteScalar(data_ + field_offset, val); + return true; + } + + bool SetPointer(voffset_t field, const uint8_t *val) { + auto field_offset = GetOptionalFieldOffset(field); + if (!field_offset) return false; + WriteScalar(data_ + field_offset, + static_cast(val - (data_ + field_offset))); + return true; + } + + uint8_t *GetAddressOf(voffset_t field) { + auto field_offset = GetOptionalFieldOffset(field); + return field_offset ? data_ + field_offset : nullptr; + } + const uint8_t *GetAddressOf(voffset_t field) const { + return const_cast

(this)->GetAddressOf(field); + } + + bool CheckField(voffset_t field) const { + return GetOptionalFieldOffset(field) != 0; + } + + // Verify the vtable of this table. + // Call this once per table, followed by VerifyField once per field. + bool VerifyTableStart(Verifier &verifier) const { + // Check the vtable offset. + if (!verifier.Verify(data_)) return false; + auto vtable = GetVTable(); + // Check the vtable size field, then check vtable fits in its entirety. + return verifier.VerifyComplexity() && verifier.Verify(vtable) && + (ReadScalar(vtable) & (sizeof(voffset_t) - 1)) == 0 && + verifier.Verify(vtable, ReadScalar(vtable)); + } + + // Verify a particular field. + template + bool VerifyField(const Verifier &verifier, voffset_t field) const { + // Calling GetOptionalFieldOffset should be safe now thanks to + // VerifyTable(). + auto field_offset = GetOptionalFieldOffset(field); + // Check the actual field. + return !field_offset || verifier.Verify(data_ + field_offset); + } + + // VerifyField for required fields. + template + bool VerifyFieldRequired(const Verifier &verifier, voffset_t field) const { + auto field_offset = GetOptionalFieldOffset(field); + return verifier.Check(field_offset != 0) && + verifier.Verify(data_ + field_offset); + } + + // Versions for offsets. + bool VerifyOffset(const Verifier &verifier, voffset_t field) const { + auto field_offset = GetOptionalFieldOffset(field); + return !field_offset || verifier.VerifyOffset(data_ + field_offset); + } + + bool VerifyOffsetRequired(const Verifier &verifier, voffset_t field) const { + auto field_offset = GetOptionalFieldOffset(field); + return verifier.Check(field_offset != 0) && + verifier.VerifyOffset(data_ + field_offset); + } + + private: + // private constructor & copy constructor: you obtain instances of this + // class by pointing to existing data only + Table(); + Table(const Table &other); + + uint8_t data_[1]; +}; + +/// @brief This can compute the start of a FlatBuffer from a root pointer, i.e. +/// it is the opposite transformation of GetRoot(). +/// This may be useful if you want to pass on a root and have the recipient +/// delete the buffer afterwards. +inline const uint8_t *GetBufferStartFromRootPointer(const void *root) { + auto table = reinterpret_cast(root); + auto vtable = table->GetVTable(); + // Either the vtable is before the root or after the root. + auto start = (std::min)(vtable, reinterpret_cast(root)); + // Align to at least sizeof(uoffset_t). + start = reinterpret_cast(reinterpret_cast(start) & + ~(sizeof(uoffset_t) - 1)); + // Additionally, there may be a file_identifier in the buffer, and the root + // offset. The buffer may have been aligned to any size between + // sizeof(uoffset_t) and FLATBUFFERS_MAX_ALIGNMENT (see "force_align"). + // Sadly, the exact alignment is only known when constructing the buffer, + // since it depends on the presence of values with said alignment properties. + // So instead, we simply look at the next uoffset_t values (root, + // file_identifier, and alignment padding) to see which points to the root. + // None of the other values can "impersonate" the root since they will either + // be 0 or four ASCII characters. + static_assert(FlatBufferBuilder::kFileIdentifierLength == sizeof(uoffset_t), + "file_identifier is assumed to be the same size as uoffset_t"); + for (auto possible_roots = FLATBUFFERS_MAX_ALIGNMENT / sizeof(uoffset_t) + 1; + possible_roots; possible_roots--) { + start -= sizeof(uoffset_t); + if (ReadScalar(start) + start == + reinterpret_cast(root)) + return start; + } + // We didn't find the root, either the "root" passed isn't really a root, + // or the buffer is corrupt. + // Assert, because calling this function with bad data may cause reads + // outside of buffer boundaries. + FLATBUFFERS_ASSERT(false); + return nullptr; +} + +/// @brief This return the prefixed size of a FlatBuffer. +inline uoffset_t GetPrefixedSize(const uint8_t* buf){ return ReadScalar(buf); } + +// Base class for native objects (FlatBuffer data de-serialized into native +// C++ data structures). +// Contains no functionality, purely documentative. +struct NativeTable {}; + +/// @brief Function types to be used with resolving hashes into objects and +/// back again. The resolver gets a pointer to a field inside an object API +/// object that is of the type specified in the schema using the attribute +/// `cpp_type` (it is thus important whatever you write to this address +/// matches that type). The value of this field is initially null, so you +/// may choose to implement a delayed binding lookup using this function +/// if you wish. The resolver does the opposite lookup, for when the object +/// is being serialized again. +typedef uint64_t hash_value_t; +// clang-format off +#ifdef FLATBUFFERS_CPP98_STL + typedef void (*resolver_function_t)(void **pointer_adr, hash_value_t hash); + typedef hash_value_t (*rehasher_function_t)(void *pointer); +#else + typedef std::function + resolver_function_t; + typedef std::function rehasher_function_t; +#endif +// clang-format on + +// Helper function to test if a field is present, using any of the field +// enums in the generated code. +// `table` must be a generated table type. Since this is a template parameter, +// this is not typechecked to be a subclass of Table, so beware! +// Note: this function will return false for fields equal to the default +// value, since they're not stored in the buffer (unless force_defaults was +// used). +template bool IsFieldPresent(const T *table, voffset_t field) { + // Cast, since Table is a private baseclass of any table types. + return reinterpret_cast(table)->CheckField(field); +} + +// Utility function for reverse lookups on the EnumNames*() functions +// (in the generated C++ code) +// names must be NULL terminated. +inline int LookupEnum(const char **names, const char *name) { + for (const char **p = names; *p; p++) + if (!strcmp(*p, name)) return static_cast(p - names); + return -1; +} + +// These macros allow us to layout a struct with a guarantee that they'll end +// up looking the same on different compilers and platforms. +// It does this by disallowing the compiler to do any padding, and then +// does padding itself by inserting extra padding fields that make every +// element aligned to its own size. +// Additionally, it manually sets the alignment of the struct as a whole, +// which is typically its largest element, or a custom size set in the schema +// by the force_align attribute. +// These are used in the generated code only. + +// clang-format off +#if defined(_MSC_VER) + #define FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(alignment) \ + __pragma(pack(1)); \ + struct __declspec(align(alignment)) + #define FLATBUFFERS_STRUCT_END(name, size) \ + __pragma(pack()); \ + static_assert(sizeof(name) == size, "compiler breaks packing rules") +#elif defined(__GNUC__) || defined(__clang__) + #define FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(alignment) \ + _Pragma("pack(1)") \ + struct __attribute__((aligned(alignment))) + #define FLATBUFFERS_STRUCT_END(name, size) \ + _Pragma("pack()") \ + static_assert(sizeof(name) == size, "compiler breaks packing rules") +#else + #error Unknown compiler, please define structure alignment macros +#endif +// clang-format on + +// Minimal reflection via code generation. +// Besides full-fat reflection (see reflection.h) and parsing/printing by +// loading schemas (see idl.h), we can also have code generation for mimimal +// reflection data which allows pretty-printing and other uses without needing +// a schema or a parser. +// Generate code with --reflect-types (types only) or --reflect-names (names +// also) to enable. +// See minireflect.h for utilities using this functionality. + +// These types are organized slightly differently as the ones in idl.h. +enum SequenceType { ST_TABLE, ST_STRUCT, ST_UNION, ST_ENUM }; + +// Scalars have the same order as in idl.h +// clang-format off +#define FLATBUFFERS_GEN_ELEMENTARY_TYPES(ET) \ + ET(ET_UTYPE) \ + ET(ET_BOOL) \ + ET(ET_CHAR) \ + ET(ET_UCHAR) \ + ET(ET_SHORT) \ + ET(ET_USHORT) \ + ET(ET_INT) \ + ET(ET_UINT) \ + ET(ET_LONG) \ + ET(ET_ULONG) \ + ET(ET_FLOAT) \ + ET(ET_DOUBLE) \ + ET(ET_STRING) \ + ET(ET_SEQUENCE) // See SequenceType. + +enum ElementaryType { + #define FLATBUFFERS_ET(E) E, + FLATBUFFERS_GEN_ELEMENTARY_TYPES(FLATBUFFERS_ET) + #undef FLATBUFFERS_ET +}; + +inline const char * const *ElementaryTypeNames() { + static const char * const names[] = { + #define FLATBUFFERS_ET(E) #E, + FLATBUFFERS_GEN_ELEMENTARY_TYPES(FLATBUFFERS_ET) + #undef FLATBUFFERS_ET + }; + return names; +} +// clang-format on + +// Basic type info cost just 16bits per field! +struct TypeCode { + uint16_t base_type : 4; // ElementaryType + uint16_t is_vector : 1; + int16_t sequence_ref : 11; // Index into type_refs below, or -1 for none. +}; + +static_assert(sizeof(TypeCode) == 2, "TypeCode"); + +struct TypeTable; + +// Signature of the static method present in each type. +typedef const TypeTable *(*TypeFunction)(); + +struct TypeTable { + SequenceType st; + size_t num_elems; // of each of the arrays below. + const TypeCode *type_codes; + const TypeFunction *type_refs; + const int32_t *values; // Only set for non-consecutive enum/union or structs. + const char * const *names; // Only set if compiled with --reflect-names. +}; + +// String which identifies the current version of FlatBuffers. +// flatbuffer_version_string is used by Google developers to identify which +// applications uploaded to Google Play are using this library. This allows +// the development team at Google to determine the popularity of the library. +// How it works: Applications that are uploaded to the Google Play Store are +// scanned for this version string. We track which applications are using it +// to measure popularity. You are free to remove it (of course) but we would +// appreciate if you left it in. + +// Weak linkage is culled by VS & doesn't work on cygwin. +// clang-format off +#if !defined(_WIN32) && !defined(__CYGWIN__) + +extern volatile __attribute__((weak)) const char *flatbuffer_version_string; +volatile __attribute__((weak)) const char *flatbuffer_version_string = + "FlatBuffers " + FLATBUFFERS_STRING(FLATBUFFERS_VERSION_MAJOR) "." + FLATBUFFERS_STRING(FLATBUFFERS_VERSION_MINOR) "." + FLATBUFFERS_STRING(FLATBUFFERS_VERSION_REVISION); + +#endif // !defined(_WIN32) && !defined(__CYGWIN__) + +#define FLATBUFFERS_DEFINE_BITMASK_OPERATORS(E, T)\ + inline E operator | (E lhs, E rhs){\ + return E(T(lhs) | T(rhs));\ + }\ + inline E operator & (E lhs, E rhs){\ + return E(T(lhs) & T(rhs));\ + }\ + inline E operator ^ (E lhs, E rhs){\ + return E(T(lhs) ^ T(rhs));\ + }\ + inline E operator ~ (E lhs){\ + return E(~T(lhs));\ + }\ + inline E operator |= (E &lhs, E rhs){\ + lhs = lhs | rhs;\ + return lhs;\ + }\ + inline E operator &= (E &lhs, E rhs){\ + lhs = lhs & rhs;\ + return lhs;\ + }\ + inline E operator ^= (E &lhs, E rhs){\ + lhs = lhs ^ rhs;\ + return lhs;\ + }\ + inline bool operator !(E rhs) \ + {\ + return !bool(T(rhs)); \ + } +/// @endcond +} // namespace flatbuffers + +#if defined(_MSC_VER) + #pragma warning(pop) +#endif +// clang-format on + +#endif // FLATBUFFERS_H_ From 3e0021840d79ffc460277b42dd68c75d2ce5d3a3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 18 May 2018 14:03:47 +0200 Subject: [PATCH 060/125] using enum class --- gtest/include/crossdoor_dummy_nodes.h | 20 ++++++------ gtest/src/action_test_node.cpp | 8 ++--- gtest/src/condition_test_node.cpp | 8 ++--- include/behavior_tree_core/action_node.h | 6 ++-- include/behavior_tree_core/condition_node.h | 2 +- include/behavior_tree_core/control_node.h | 2 +- include/behavior_tree_core/decorator_node.h | 2 +- .../decorator_subtree_node.h | 4 +-- include/behavior_tree_core/tree_node.h | 31 +++++++++---------- src/action_node.cpp | 14 ++++----- src/control_node.cpp | 6 ++-- src/decorator_negation_node.cpp | 14 ++++----- src/decorator_node.cpp | 6 ++-- src/decorator_repeat_node.cpp | 14 ++++----- src/decorator_retry_node.cpp | 14 ++++----- src/example.cpp | 10 +++--- src/fallback_node.cpp | 12 +++---- src/fallback_node_with_memory.cpp | 12 +++---- src/parallel_node.cpp | 12 +++---- src/sequence_node.cpp | 12 +++---- src/sequence_node_with_memory.cpp | 12 +++---- src/tree_node.cpp | 6 ++-- templates/action_node_template.cpp | 10 +++--- templates/condition_node_template.cpp | 8 ++--- 24 files changed, 123 insertions(+), 122 deletions(-) diff --git a/gtest/include/crossdoor_dummy_nodes.h b/gtest/include/crossdoor_dummy_nodes.h index e5844a9c4..d520aabec 100644 --- a/gtest/include/crossdoor_dummy_nodes.h +++ b/gtest/include/crossdoor_dummy_nodes.h @@ -1,5 +1,7 @@ #include "behavior_tree_core/bt_factory.h" +using namespace BT; + class CrossDoor { public: @@ -19,36 +21,36 @@ class CrossDoor BT::NodeStatus IsDoorOpen() { - return door_open_ ? BT::SUCCESS : BT::FAILURE; + return door_open_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } BT::NodeStatus IsDoorLocked() { - return door_locked_ ? BT::SUCCESS : BT::FAILURE; + return door_locked_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } BT::NodeStatus UnlockDoor() { door_locked_ = false; - return BT::SUCCESS; + return NodeStatus::SUCCESS; } BT::NodeStatus PassThroughDoor() { - return door_open_ ? BT::SUCCESS : BT::FAILURE; + return door_open_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } BT::NodeStatus PassThroughWindow() { - return BT::SUCCESS; + return NodeStatus::SUCCESS; } BT::NodeStatus OpenDoor() { if (door_locked_) - return BT::FAILURE; + return NodeStatus::FAILURE; door_open_ = true; - return BT::SUCCESS; + return NodeStatus::SUCCESS; } BT::NodeStatus CloseDoor() @@ -56,11 +58,11 @@ class CrossDoor if (door_open_) { door_open_ = false; - return BT::SUCCESS; + return NodeStatus::SUCCESS; } else { - return BT::FAILURE; + return NodeStatus::FAILURE; } } diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 668347217..07c832409 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -41,24 +41,24 @@ BT::NodeStatus BT::ActionTestNode::tick() if (boolean_value_) { DEBUG_STDOUT(" Action " << name() << " Done!"); - return BT::SUCCESS; + return NodeStatus::SUCCESS; } else { DEBUG_STDOUT(" Action " << name() << " FAILED!"); - return BT::FAILURE; + return NodeStatus::FAILURE; } } else { - return BT::IDLE; + return NodeStatus::IDLE; } } void BT::ActionTestNode::halt() { stop_loop_ = true; - setStatus(BT::IDLE); + setStatus(NodeStatus::IDLE); DEBUG_STDOUT("HALTED state set!"); } diff --git a/gtest/src/condition_test_node.cpp b/gtest/src/condition_test_node.cpp index 2c295c6e3..8c343dab2 100644 --- a/gtest/src/condition_test_node.cpp +++ b/gtest/src/condition_test_node.cpp @@ -28,13 +28,13 @@ BT::NodeStatus BT::ConditionTestNode::tick() if (boolean_value_) { - setStatus(BT::SUCCESS); - return BT::SUCCESS; + setStatus(NodeStatus::SUCCESS); + return NodeStatus::SUCCESS; } else { - setStatus(BT::FAILURE); - return BT::FAILURE; + setStatus(NodeStatus::FAILURE); + return NodeStatus::FAILURE; } } diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 98d519a9c..9833527b8 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -28,7 +28,7 @@ class ActionNodeBase : public LeafNode virtual NodeType type() const override final { - return ACTION_NODE; + return NodeType::ACTION; } }; @@ -94,13 +94,13 @@ class ActionNode : public ActionNodeBase // This method MUST to be overriden by the user. virtual NodeStatus tick() override { - return BT::IDLE; + return NodeStatus::IDLE; } // This method MUST to be overriden by the user. virtual void halt() override { - setStatus(BT::IDLE); + setStatus(NodeStatus::IDLE); } void stopAndJoinThread(); diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index 79ba1e2dc..2309dff43 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -30,7 +30,7 @@ class ConditionNode : public LeafNode virtual NodeType type() const override final { - return CONDITION_NODE; + return NodeType::CONDITION; } }; } diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index c43de191f..9aa138353 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -50,7 +50,7 @@ class ControlNode : public TreeNode virtual NodeType type() const override final { - return CONTROL_NODE; + return NodeType::CONTROL; } }; } diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index e0b905ca7..59b9a4ff3 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -28,7 +28,7 @@ class DecoratorNode : public TreeNode virtual NodeType type() const override final { - return DECORATOR_NODE; + return NodeType::DECORATOR; } }; diff --git a/include/behavior_tree_core/decorator_subtree_node.h b/include/behavior_tree_core/decorator_subtree_node.h index 0756c3638..be5f8d11c 100644 --- a/include/behavior_tree_core/decorator_subtree_node.h +++ b/include/behavior_tree_core/decorator_subtree_node.h @@ -19,9 +19,9 @@ class DecoratorSubtreeNode : public DecoratorNode virtual BT::NodeStatus tick() { NodeStatus prev_status = status(); - if ( prev_status== BT::IDLE) + if ( prev_status== NodeStatus::IDLE) { - setStatus(BT::RUNNING); + setStatus(NodeStatus::RUNNING); } auto status = child_node_->executeTick(); setStatus(status); diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 5dea635a3..e7c53958e 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -39,29 +39,29 @@ namespace BT { // Enumerates the possible types of a node, for drawinf we have do discriminate whoich control node it is: -enum NodeType +enum class NodeType { - ACTION_NODE, - CONDITION_NODE, - CONTROL_NODE, - DECORATOR_NODE, - SUBTREE_NODE, - UNDEFINED + UNDEFINED = 0, + ACTION, + CONDITION, + CONTROL, + DECORATOR, + SUBTREE }; inline const char* toStr(const BT::NodeType& type) { switch (type) { - case NodeType::ACTION_NODE: + case NodeType::ACTION: return "Action"; - case NodeType::CONDITION_NODE: + case NodeType::CONDITION: return "Condition"; - case NodeType::DECORATOR_NODE: + case NodeType::DECORATOR: return "Decorator"; - case NodeType::CONTROL_NODE: + case NodeType::CONTROL: return "Control"; - case NodeType::SUBTREE_NODE: + case NodeType::SUBTREE: return "SubTree"; default: return "Undefined"; @@ -83,13 +83,12 @@ inline std::ostream& operator<<(std::ostream& os, const BT::NodeType& type) // time step, but the task is not yet complete; // - "Idle" indicates that the node hasn't run yet. // - "Halted" indicates that the node has been halted by its father. -enum NodeStatus +enum class NodeStatus { - IDLE, + IDLE = 0, RUNNING, SUCCESS, - FAILURE, - EXIT + FAILURE }; inline const char* toStr(const BT::NodeStatus& status) diff --git a/src/action_node.cpp b/src/action_node.cpp index a88732f67..e02f51bc0 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -28,10 +28,10 @@ BT::NodeStatus BT::SimpleActionNode::tick() { NodeStatus prev_status = status(); - if (prev_status == BT::IDLE) + if (prev_status == NodeStatus::IDLE) { - setStatus(BT::RUNNING); - prev_status = BT::RUNNING; + setStatus(NodeStatus::RUNNING); + prev_status = NodeStatus::RUNNING; } NodeStatus status = tick_functor_(); @@ -69,9 +69,9 @@ void BT::ActionNode::waitForTick() // notified from the method stopAndJoinThread if (loop_.load()) { - if (status() == BT::IDLE) + if (status() == NodeStatus::IDLE) { - setStatus(BT::RUNNING); + setStatus(NodeStatus::RUNNING); } setStatus( tick() ); } @@ -82,12 +82,12 @@ BT::NodeStatus BT::ActionNode::executeTick() { //send signal to other thread. // The other thread is in charge for changing the status - if (status() == BT::IDLE) + if (status() == NodeStatus::IDLE) { tick_engine_.notify(); } - // block as long as the state is BT::IDLE + // block as long as the state is NodeStatus::IDLE const NodeStatus stat = waitValidStatus(); return stat; } diff --git a/src/control_node.cpp b/src/control_node.cpp index 307219090..6032f740c 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -17,7 +17,7 @@ BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable - // ReturnStatus const NodeStatus child_status = BT::IDLE; // commented out as unused + // ReturnStatus const NodeStatus child_status = NodeStatus::IDLE; // commented out as unused } void BT::ControlNode::addChild(TreeNode* child) @@ -43,7 +43,7 @@ void BT::ControlNode::halt() { DEBUG_STDOUT("HALTING: " << name()); haltChildren(0); - setStatus(BT::IDLE); + setStatus(NodeStatus::IDLE); } const std::vector& BT::ControlNode::children() const @@ -55,7 +55,7 @@ void BT::ControlNode::haltChildren(int i) { for (unsigned int j = i; j < children_nodes_.size(); j++) { - if (children_nodes_[j]->status() == BT::RUNNING) + if (children_nodes_[j]->status() == NodeStatus::RUNNING) { DEBUG_STDOUT("SENDING HALT TO CHILD " << children_nodes_[j]->name()); children_nodes_[j]->halt(); diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index 184e942a5..e20cdcf7e 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -19,26 +19,26 @@ BT::DecoratorNegationNode::DecoratorNegationNode(std::string name) : DecoratorNo BT::NodeStatus BT::DecoratorNegationNode::tick() { - setStatus(BT::RUNNING); + setStatus(NodeStatus::RUNNING); const NodeStatus child_state = child_node_->executeTick(); switch (child_state) { - case BT::SUCCESS: + case NodeStatus::SUCCESS: { - setStatus(BT::FAILURE); + setStatus(NodeStatus::FAILURE); } break; - case BT::FAILURE: + case NodeStatus::FAILURE: { - setStatus(BT::SUCCESS); + setStatus(NodeStatus::SUCCESS); } break; - case BT::RUNNING: + case NodeStatus::RUNNING: { - setStatus(BT::RUNNING); + setStatus(NodeStatus::RUNNING); } break; diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 76cc68250..12e48e8e2 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -16,7 +16,7 @@ BT::DecoratorNode::DecoratorNode(std::string name) : TreeNode::TreeNode(name), c { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable - // ReturnStatus const NodeStatus child_status = BT::IDLE; // commented out as unused + // ReturnStatus const NodeStatus child_status = NodeStatus::IDLE; // commented out as unused } void BT::DecoratorNode::setChild(TreeNode* child) @@ -33,7 +33,7 @@ void BT::DecoratorNode::halt() { DEBUG_STDOUT("HALTING: " << name()); haltChild(); - setStatus(BT::IDLE); + setStatus(NodeStatus::IDLE); } const BT::TreeNode* BT::DecoratorNode::child() const @@ -44,7 +44,7 @@ const BT::TreeNode* BT::DecoratorNode::child() const void BT::DecoratorNode::haltChild() { - if (child_node_->status() == BT::RUNNING) + if (child_node_->status() == NodeStatus::RUNNING) { DEBUG_STDOUT("SENDING HALT TO CHILD " << child_node_->name()); child_node_->halt(); diff --git a/src/decorator_repeat_node.cpp b/src/decorator_repeat_node.cpp index 063d92cf2..031f54151 100644 --- a/src/decorator_repeat_node.cpp +++ b/src/decorator_repeat_node.cpp @@ -31,31 +31,31 @@ BT::DecoratorRepeatNode::DecoratorRepeatNode(std::string name, const BT::NodePar BT::NodeStatus BT::DecoratorRepeatNode::tick() { - setStatus(BT::RUNNING); + setStatus(NodeStatus::RUNNING); BT::NodeStatus child_state = child_node_->executeTick(); switch (child_state) { - case BT::SUCCESS: + case NodeStatus::SUCCESS: { TryIndx_++; if (TryIndx_ >= NTries_) { - setStatus(BT::SUCCESS); + setStatus(NodeStatus::SUCCESS); } } break; - case BT::FAILURE: + case NodeStatus::FAILURE: { TryIndx_ = 0; - setStatus(BT::FAILURE); + setStatus(NodeStatus::FAILURE); } break; - case BT::RUNNING: + case NodeStatus::RUNNING: { - setStatus(BT::RUNNING); + setStatus(NodeStatus::RUNNING); } break; diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index 0ccf4283a..915e7d1e2 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -31,32 +31,32 @@ BT::DecoratorRetryNode::DecoratorRetryNode(std::string name, const BT::NodeParam BT::NodeStatus BT::DecoratorRetryNode::tick() { - setStatus(BT::RUNNING); + setStatus(NodeStatus::RUNNING); BT::NodeStatus child_state = child_node_->executeTick(); switch (child_state) { - case BT::SUCCESS: + case NodeStatus::SUCCESS: { TryIndx_ = 0; - setStatus(BT::SUCCESS); + setStatus(NodeStatus::SUCCESS); } break; - case BT::FAILURE: + case NodeStatus::FAILURE: { TryIndx_++; if (TryIndx_ >= NTries_) { TryIndx_ = 0; - setStatus(BT::FAILURE); + setStatus(NodeStatus::FAILURE); } } break; - case BT::RUNNING: + case NodeStatus::RUNNING: { - setStatus(BT::RUNNING); + setStatus(NodeStatus::RUNNING); } break; diff --git a/src/example.cpp b/src/example.cpp index 44414f12d..f177d3384 100644 --- a/src/example.cpp +++ b/src/example.cpp @@ -17,7 +17,7 @@ BT::ReturnStatus MyCondition::Tick() { std::cout << "The Condition is true" << std::endl; - return BT::SUCCESS; + return NodeStatus::SUCCESS; } class MyAction : public BT::ActionNode @@ -39,25 +39,25 @@ BT::ReturnStatus MyAction::Tick() std::this_thread::sleep_for(std::chrono::milliseconds(500)); if (is_halted()) { - return BT::IDLE; + return NodeStatus::IDLE; } std::cout << "The Action is doing some others operations" << std::endl; std::this_thread::sleep_for(std::chrono::milliseconds(500)); if (is_halted()) { - return BT::IDLE; + return NodeStatus::IDLE; } std::cout << "The Action is doing more operations" << std::endl; std::this_thread::sleep_for(std::chrono::milliseconds(500)); if (is_halted()) { - return BT::IDLE; + return NodeStatus::IDLE; } std::cout << "The Action has succeeded" << std::endl; - return BT::SUCCESS; + return NodeStatus::SUCCESS; } void MyAction::Halt() diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 40786e630..fca5f8cb1 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -31,13 +31,13 @@ BT::NodeStatus BT::FallbackNode::tick() const NodeStatus child_status = child_node->executeTick(); // Ponderate on which status to send to the parent - if (child_status != BT::FAILURE) + if (child_status != NodeStatus::FAILURE) { - if (child_status == BT::SUCCESS) + if (child_status == NodeStatus::SUCCESS) { for (unsigned t=0; t<=i; t++) { - children_nodes_[t]->setStatus(BT::IDLE); + children_nodes_[t]->setStatus(NodeStatus::IDLE); } } // If the child status is not failure, halt the next children and return the status to your parent. @@ -54,11 +54,11 @@ BT::NodeStatus BT::FallbackNode::tick() // then the sequence has failed. for (unsigned t=0; t<=i; t++) { - children_nodes_[t]->setStatus(BT::IDLE); + children_nodes_[t]->setStatus(NodeStatus::IDLE); } - return BT::FAILURE; + return NodeStatus::FAILURE; } } } - return BT::EXIT; + throw std::runtime_error("This is not supposed to happen"); } diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index c5bc15180..34c0bc005 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -60,15 +60,15 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() const NodeStatus child_status = current_child_node->executeTick(); - if (child_status != BT::FAILURE) + if (child_status != NodeStatus::FAILURE) { // If the child status is not success, return the status DEBUG_STDOUT("the status of: " << name() << " becomes " << child_status); - if (child_status == BT::SUCCESS && reset_policy_ != BT::ON_FAILURE) + if (child_status == NodeStatus::SUCCESS && reset_policy_ != BT::ON_FAILURE) { for (unsigned t=0; t<=current_child_idx_; t++) { - children_nodes_[t]->setStatus(BT::IDLE); + children_nodes_[t]->setStatus(NodeStatus::IDLE); } current_child_idx_ = 0; } @@ -83,11 +83,11 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() else { // If it the last child. - if (child_status == BT::FAILURE && reset_policy_ != BT::ON_SUCCESS ) + if (child_status == NodeStatus::FAILURE && reset_policy_ != BT::ON_SUCCESS ) { for (unsigned t=0; t<=current_child_idx_; t++) { - children_nodes_[t]->setStatus(BT::IDLE); + children_nodes_[t]->setStatus(NodeStatus::IDLE); } // if it the last child and it has returned failure, reset the memory current_child_idx_ = 0; @@ -95,7 +95,7 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() return child_status; } } - return BT::EXIT; + throw std::runtime_error("This is not supposed to happen"); } void BT::FallbackNodeWithMemory::halt() diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 15fd1a781..9fbbf3305 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -36,8 +36,8 @@ BT::NodeStatus BT::ParallelNode::tick() switch (child_status) { - case BT::SUCCESS: - child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned success. + case NodeStatus::SUCCESS: + child_node->setStatus(NodeStatus::IDLE); // the child goes in idle if it has returned success. if (++success_childred_num_ == threshold_M_) { success_childred_num_ = 0; @@ -46,8 +46,8 @@ BT::NodeStatus BT::ParallelNode::tick() return child_status; } break; - case BT::FAILURE: - child_node->setStatus(BT::IDLE); // the child goes in idle if it has returned failure. + case NodeStatus::FAILURE: + child_node->setStatus(NodeStatus::IDLE); // the child goes in idle if it has returned failure. if (++failure_childred_num_ > N_of_children - threshold_M_) { DEBUG_STDOUT("*******PARALLEL" << name() @@ -59,14 +59,14 @@ BT::NodeStatus BT::ParallelNode::tick() return child_status; } break; - case BT::RUNNING: + case NodeStatus::RUNNING: setStatus(child_status); break; default: break; } } - return BT::RUNNING; + return NodeStatus::RUNNING; } void BT::ParallelNode::halt() diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 51e4d0f3f..fdd8b8c1a 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -31,14 +31,14 @@ BT::NodeStatus BT::SequenceNode::tick() const NodeStatus child_status = child_node->executeTick(); // Ponderate on which status to send to the parent - if (child_status != BT::SUCCESS) + if (child_status != NodeStatus::SUCCESS) { // If the child status is not success, halt the next children and return the status to your parent. - if (child_status == BT::FAILURE) + if (child_status == NodeStatus::FAILURE) { for(unsigned t=0; t<=i; t++) { - children_nodes_[t]->setStatus( BT::IDLE ); + children_nodes_[t]->setStatus( NodeStatus::IDLE ); } } @@ -54,11 +54,11 @@ BT::NodeStatus BT::SequenceNode::tick() // then the sequence has succeeded. for(auto &ch: children_nodes_) { - ch->setStatus( BT::IDLE ); + ch->setStatus( NodeStatus::IDLE ); } - return BT::SUCCESS; + return NodeStatus::SUCCESS; } } } - return BT::EXIT; + throw std::runtime_error("This is not supposed to happen"); } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index c585e29cb..838de7533 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -64,16 +64,16 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() const NodeStatus child_status = current_child_node->executeTick(); - if (child_status != BT::SUCCESS) + if (child_status != NodeStatus::SUCCESS) { // If the child status is not success, return the status DEBUG_STDOUT("the status of: " << name() << " becomes " << child_status); - if (child_status == BT::FAILURE && reset_policy_ != BT::ON_SUCCESS ) + if (child_status == NodeStatus::FAILURE && reset_policy_ != BT::ON_SUCCESS ) { for (unsigned t=0; t<=current_child_idx_; t++) { - children_nodes_[t]->setStatus(BT::IDLE); + children_nodes_[t]->setStatus(NodeStatus::IDLE); } current_child_idx_ = 0; } @@ -88,19 +88,19 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() else { // if it the last child. - if (child_status == BT::SUCCESS || reset_policy_ != BT::ON_FAILURE) + if (child_status == NodeStatus::SUCCESS || reset_policy_ != BT::ON_FAILURE) { // if it the last child and it has returned SUCCESS, reset the memory for (unsigned t=0; t<=current_child_idx_; t++) { - children_nodes_[t]->setStatus(BT::IDLE); + children_nodes_[t]->setStatus(NodeStatus::IDLE); } current_child_idx_ = 0; } return child_status; } } - return BT::EXIT; + throw std::runtime_error("This is not supposed to happen"); } void BT::SequenceNodeWithMemory::halt() diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 0afac7358..1e12f23e6 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -19,7 +19,7 @@ static uint8_t getUID() return uid++; } -BT::TreeNode::TreeNode(std::string name) : name_(name), status_(BT::IDLE), _uid( getUID() ) +BT::TreeNode::TreeNode(std::string name) : name_(name), status_(NodeStatus::IDLE), _uid( getUID() ) { } @@ -61,7 +61,7 @@ BT::NodeStatus BT::TreeNode::waitValidStatus() std::unique_lock lk(state_mutex_); state_condition_variable_.wait( - lk, [&]() { return (status_ == BT::RUNNING || status_ == BT::SUCCESS || status_ == BT::FAILURE); }); + lk, [&]() { return (status_ == NodeStatus::RUNNING || status_ == NodeStatus::SUCCESS || status_ == NodeStatus::FAILURE); }); return status_; } @@ -72,7 +72,7 @@ const std::string& BT::TreeNode::name() const bool BT::TreeNode::isHalted() const { - return status() == BT::IDLE; + return status() == NodeStatus::IDLE; } BT::TreeNode::StatusChangeSubscriber BT::TreeNode::subscribeToStatusChange(BT::TreeNode::StatusChangeCallback callback) diff --git a/templates/action_node_template.cpp b/templates/action_node_template.cpp index ea5316ced..83a426950 100644 --- a/templates/action_node_template.cpp +++ b/templates/action_node_template.cpp @@ -21,14 +21,14 @@ void BT::CLASSNAME::WaitForTick() DEBUG_STDOUT(name() << " TICK RECEIVED"); // Running state - SetStatus(BT::RUNNING); + SetStatus(NodeStatus::RUNNING); // Perform action... - while (Status() != BT::IDLE) + while (Status() != NodeStatus::IDLE) { /*HERE THE CODE TO EXECUTE FOR THE ACTION. - wHEN THE ACTION HAS FINISHED CORRECLTY, CALL set_status(BT::SUCCESS) - IF THE ACTION FAILS, CALL set_status(BT::FAILURE)*/ + wHEN THE ACTION HAS FINISHED CORRECLTY, CALL set_status(NodeStatus::SUCCESS) + IF THE ACTION FAILS, CALL set_status(NodeStatus::FAILURE)*/ } } } @@ -36,6 +36,6 @@ void BT::CLASSNAME::WaitForTick() void BT::CLASSNAME::Halt() { /*HERE THE CODE TO PERFORM WHEN THE ACTION IS HALTED*/ - SetStatus(BT::IDLE); + SetStatus(NodeStatus::IDLE); DEBUG_STDOUT("HALTED state set!"); } diff --git a/templates/condition_node_template.cpp b/templates/condition_node_template.cpp index 7c8b4eaa8..423b60154 100644 --- a/templates/condition_node_template.cpp +++ b/templates/condition_node_template.cpp @@ -14,12 +14,12 @@ BT::ReturnStatus BT::CLASSNAME::Tick() if (/*CONDITION TO CHECK*/) { - SetStatus(BT::SUCCESS); - return BT::SUCCESS; + SetStatus(NodeStatus::SUCCESS); + return NodeStatus::SUCCESS; } else { - SetStatus(BT::FAILURE); - return BT::FAILURE; + SetStatus(NodeStatus::FAILURE); + return NodeStatus::FAILURE; } } From f1c91dd927deba9b4f466f265943b85d0bff648b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 21 May 2018 09:21:37 +0200 Subject: [PATCH 061/125] moved functions --- include/behavior_tree_core/behavior_tree.h | 26 +++++++++- include/behavior_tree_core/tree_node.h | 48 ------------------ src/behavior_tree.cpp | 58 ++++++++++++++++++++-- src/decorator_node.cpp | 4 ++ 4 files changed, 83 insertions(+), 53 deletions(-) diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index a41b6363d..f4e1e3c23 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -31,7 +31,7 @@ namespace BT { -void recursiveVisitor(const TreeNode *node, const std::function visitor); +void recursiveVisitor(TreeNode *node, std::function visitor); /** * Debug function to print on a stream @@ -53,6 +53,30 @@ typedef std::vector> SerializedTreeStatus; void buildSerializedStatusSnapshot(const TreeNode *root_node, SerializedTreeStatus& serialized_buffer); +/** + * @brief toStr converts NodeStatus to string. Optionally colored. + */ +const char* toStr(const BT::NodeStatus& status, bool colored = false); + + +inline std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status) +{ + os << toStr(status); + return os; +} + +/** + * @brief toStr converts NodeType to string. + */ +const char* toStr(const BT::NodeType& type); + +inline std::ostream& operator<<(std::ostream& os, const BT::NodeType& type) +{ + os << toStr(type); + return os; +} + + } #endif // BEHAVIOR_TREE_H diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index e7c53958e..f2b28bfc2 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -49,31 +49,6 @@ enum class NodeType SUBTREE }; -inline const char* toStr(const BT::NodeType& type) -{ - switch (type) - { - case NodeType::ACTION: - return "Action"; - case NodeType::CONDITION: - return "Condition"; - case NodeType::DECORATOR: - return "Decorator"; - case NodeType::CONTROL: - return "Control"; - case NodeType::SUBTREE: - return "SubTree"; - default: - return "Undefined"; - } -} - -inline std::ostream& operator<<(std::ostream& os, const BT::NodeType& type) -{ - os << toStr(type); - return os; -} - // Enumerates the states every node can be in after execution during a particular // time step: // - "Success" indicates that the node has completed running during this time step; @@ -91,29 +66,6 @@ enum class NodeStatus FAILURE }; -inline const char* toStr(const BT::NodeStatus& status) -{ - switch (status) - { - case NodeStatus::SUCCESS: - return "SUCCESS"; - case NodeStatus::FAILURE: - return "FAILURE"; - case NodeStatus::RUNNING: - return "RUNNING"; - case NodeStatus::IDLE: - return "IDLE"; - default: - return "Undefined"; - } -} - - -inline std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status) -{ - os << toStr(status); - return os; -} // Enumerates the options for when a parallel node is considered to have failed: // - "FAIL_ON_ONE" indicates that the node will return failure as soon as one of diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index 682547117..4c9b555e4 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -3,7 +3,7 @@ namespace BT { -void recursiveVisitor(const TreeNode* node, const std::function visitor) +void recursiveVisitor(TreeNode* node, std::function visitor) { if (!node) { @@ -12,14 +12,14 @@ void recursiveVisitor(const TreeNode* node, const std::function(node)) + if (auto control = dynamic_cast(node)) { for (const auto& child : control->children()) { recursiveVisitor(child, visitor); } } - else if (auto decorator = dynamic_cast(node)) + else if (auto decorator = dynamic_cast(node)) { recursiveVisitor(decorator->child(), visitor); } @@ -60,7 +60,7 @@ void printTreeRecursively(const TreeNode* root_node) std::cout << "----------------" << std::endl; } -void buildSerializedStatusSnapshot(const TreeNode *root_node, SerializedTreeStatus& serialized_buffer) +void buildSerializedStatusSnapshot(TreeNode *root_node, SerializedTreeStatus& serialized_buffer) { serialized_buffer.clear(); @@ -73,4 +73,54 @@ void buildSerializedStatusSnapshot(const TreeNode *root_node, SerializedTreeStat recursiveVisitor(root_node, visitor); } +const char *toStr(const NodeStatus &status, bool colored) +{ + if( ! colored ){ + switch (status) + { + case NodeStatus::SUCCESS: + return "SUCCESS"; + case NodeStatus::FAILURE: + return "FAILURE"; + case NodeStatus::RUNNING: + return "RUNNING"; + case NodeStatus::IDLE: + return "IDLE"; + } + } + else{ + switch (status) + { + case NodeStatus::SUCCESS: + return ( "\x1b[32m" "SUCCESS" "\x1b[0m"); // RED + case NodeStatus::FAILURE: + return ( "\x1b[31m" "FAILURE" "\x1b[0m"); // GREEN + case NodeStatus::RUNNING: + return ( "\x1b[33m" "RUNNING" "\x1b[0m"); // YELLOW + case NodeStatus::IDLE: + return ( "\x1b[36m" "IDLE" "\x1b[0m"); // CYAN + } + } + return "Undefined"; +} + +const char *toStr(const NodeType &type) +{ + switch (type) + { + case NodeType::ACTION: + return "Action"; + case NodeType::CONDITION: + return "Condition"; + case NodeType::DECORATOR: + return "Decorator"; + case NodeType::CONTROL: + return "Control"; + case NodeType::SUBTREE: + return "SubTree"; + default: + return "Undefined"; + } +} + } diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 12e48e8e2..d27770de9 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -41,6 +41,10 @@ const BT::TreeNode* BT::DecoratorNode::child() const return child_node_; } +BT::TreeNode* BT::DecoratorNode::child() +{ + return child_node_; +} void BT::DecoratorNode::haltChild() { From 2d6f0487b21ad874f15f4b7a28569b3ccf42af37 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 21 May 2018 09:50:18 +0200 Subject: [PATCH 062/125] first example of logger --- CMakeLists.txt | 4 +- gtest/crossdoor_example.cpp | 59 +++++++++++++++++++ .../behavior_tree_logger/abstract_logger.h | 51 ++++++++++++++++ include/behavior_tree_logger/bt_cout_logger.h | 55 +++++++++++++++++ 4 files changed, 168 insertions(+), 1 deletion(-) create mode 100644 gtest/crossdoor_example.cpp create mode 100644 include/behavior_tree_logger/abstract_logger.h create mode 100644 include/behavior_tree_logger/bt_cout_logger.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 470b43d1c..c9935e434 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -100,8 +100,10 @@ endif() # COMPILING EXAMPLES ###################################################### -#TODO +add_executable(crossdoor_example gtest/crossdoor_example.cpp ) +target_link_libraries(crossdoor_example + behavior_tree_core ) ###################################################### # INSTALLATION OF LIBRARY AND EXECUTABLE diff --git a/gtest/crossdoor_example.cpp b/gtest/crossdoor_example.cpp new file mode 100644 index 000000000..ef40cb20c --- /dev/null +++ b/gtest/crossdoor_example.cpp @@ -0,0 +1,59 @@ +#include "crossdoor_dummy_nodes.h" +#include "behavior_tree_core/xml_parsing.h" +#include "behavior_tree_logger/bt_cout_logger.h" + +// clang-format off + +const std::string xml_text = R"( + + + + + + + + + + + + + + + + + + + + + + + + + + + )"; + +// clang-format on + +int main(int argc, char** argv) +{ + using namespace BT; + + BT::BehaviorTreeFactory factory; + + // register all the actions into the factory + CrossDoor cross_door(factory); + + XMLParser parser; + parser.loadFromText(xml_text); + + std::vector nodes; + BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); + + StdCoutLogger logger(root_node.get()); + + std::cout << "---------------" << std::endl; + root_node->executeTick(); + std::cout << "---------------" << std::endl; + return 0; +} diff --git a/include/behavior_tree_logger/abstract_logger.h b/include/behavior_tree_logger/abstract_logger.h new file mode 100644 index 000000000..0936d2489 --- /dev/null +++ b/include/behavior_tree_logger/abstract_logger.h @@ -0,0 +1,51 @@ +#ifndef ABSTRACT_LOGGER_H +#define ABSTRACT_LOGGER_H + +#include "behavior_tree_core/behavior_tree.h" + + +namespace BT{ + +class StatusChangeLogger { + +public: + StatusChangeLogger(TreeNode* root_node); + virtual ~StatusChangeLogger() = default; + + virtual void callback(const TreeNode& node, + NodeStatus prev_status, + NodeStatus status) = 0; + + void setEnabled(bool enabled) { _enabled = enabled; } + + bool enabled() const { return _enabled; } + +private: + bool _enabled; + std::vector _subscribers; +}; + +//-------------------------------------------- + +StatusChangeLogger::StatusChangeLogger(TreeNode *root_node): + _enabled(true) +{ + recursiveVisitor(root_node, [this](TreeNode* node) + { + _subscribers.push_back( node->subscribeToStatusChange( + [this](const TreeNode& node, + NodeStatus prev, + NodeStatus status) + { + if(_enabled) + { + this->callback(node,prev,status); + } + })); + }); +} + + +} + +#endif // ABSTRACT_LOGGER_H diff --git a/include/behavior_tree_logger/bt_cout_logger.h b/include/behavior_tree_logger/bt_cout_logger.h new file mode 100644 index 000000000..dcaa1d081 --- /dev/null +++ b/include/behavior_tree_logger/bt_cout_logger.h @@ -0,0 +1,55 @@ +#ifndef BT_COUT_LOGGER_H +#define BT_COUT_LOGGER_H + +#include +#include "abstract_logger.h" + + +namespace BT{ + + + +/** + * @brief AddStdCoutLoggerToTree. Give the root node of a tree, + * a simple callback is subscribed to any status change of each node. + * + * + * @param root_node + * @return Important: the returned shared_ptr must not go out of scope, + * otherwise the logger is removed. + */ + +class StdCoutLogger: public StatusChangeLogger { + +public: + StdCoutLogger(TreeNode* root_node): + StatusChangeLogger(root_node) + {} + + virtual ~StdCoutLogger() = default; + + virtual void callback(const TreeNode& node, + NodeStatus prev_status, + NodeStatus status) + { + using namespace std::chrono; + auto now = high_resolution_clock::now(); + + constexpr const char* whitespaces = " "; + constexpr const size_t ws_count = 20; + + double since_epoch = duration( now.time_since_epoch() ).count(); + printf("[%.3f]: %s%s %s -> %s\n", + since_epoch, + node.name().c_str(), + &whitespaces[ std::min( ws_count, node.name().size()) ], + toStr(prev_status, true), + toStr(status, true) ); + } +}; + + +} // end namespace + + +#endif // BT_COUT_LOGGER_H From 4a51d3b956fad58d7f6b7042ec49388e4e76bd46 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 21 May 2018 10:09:15 +0200 Subject: [PATCH 063/125] fixed issue in decorators --- src/decorator_negation_node.cpp | 3 ++- src/decorator_repeat_node.cpp | 2 ++ src/decorator_retry_node.cpp | 2 ++ 3 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index e20cdcf7e..fd59ecff8 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -19,7 +19,6 @@ BT::DecoratorNegationNode::DecoratorNegationNode(std::string name) : DecoratorNo BT::NodeStatus BT::DecoratorNegationNode::tick() { - setStatus(NodeStatus::RUNNING); const NodeStatus child_state = child_node_->executeTick(); switch (child_state) @@ -27,12 +26,14 @@ BT::NodeStatus BT::DecoratorNegationNode::tick() case NodeStatus::SUCCESS: { setStatus(NodeStatus::FAILURE); + child_node_->setStatus(NodeStatus::IDLE); } break; case NodeStatus::FAILURE: { setStatus(NodeStatus::SUCCESS); + child_node_->setStatus(NodeStatus::IDLE); } break; diff --git a/src/decorator_repeat_node.cpp b/src/decorator_repeat_node.cpp index 031f54151..1a1f10b1e 100644 --- a/src/decorator_repeat_node.cpp +++ b/src/decorator_repeat_node.cpp @@ -42,6 +42,7 @@ BT::NodeStatus BT::DecoratorRepeatNode::tick() if (TryIndx_ >= NTries_) { setStatus(NodeStatus::SUCCESS); + child_node_->setStatus(NodeStatus::IDLE); } } break; @@ -50,6 +51,7 @@ BT::NodeStatus BT::DecoratorRepeatNode::tick() { TryIndx_ = 0; setStatus(NodeStatus::FAILURE); + child_node_->setStatus(NodeStatus::IDLE); } break; diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index 915e7d1e2..4ef4e361a 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -40,6 +40,7 @@ BT::NodeStatus BT::DecoratorRetryNode::tick() { TryIndx_ = 0; setStatus(NodeStatus::SUCCESS); + child_node_->setStatus(NodeStatus::IDLE); } break; @@ -50,6 +51,7 @@ BT::NodeStatus BT::DecoratorRetryNode::tick() { TryIndx_ = 0; setStatus(NodeStatus::FAILURE); + child_node_->setStatus(NodeStatus::IDLE); } } break; From 6666f6dbea2b5764fc9a5866570ab5c5655df6f5 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 21 May 2018 10:09:47 +0200 Subject: [PATCH 064/125] added RUNNING status to control nodes for debuggability --- src/fallback_node.cpp | 2 ++ src/fallback_node_with_memory.cpp | 2 ++ src/sequence_node.cpp | 2 ++ src/sequence_node_with_memory.cpp | 2 ++ 4 files changed, 8 insertions(+) diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index fca5f8cb1..d6e58ccf6 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -24,6 +24,8 @@ BT::NodeStatus BT::FallbackNode::tick() // Routing the ticks according to the fallback node's logic: + setStatus(NodeStatus::RUNNING); + for (unsigned i = 0; i < N_of_children; i++) { TreeNode* child_node = children_nodes_[i]; diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 34c0bc005..0cd9b21fa 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -53,6 +53,8 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children = children_nodes_.size(); + setStatus(NodeStatus::RUNNING); + // Routing the ticks according to the fallback node's (with memory) logic: while (current_child_idx_ < N_of_children) { diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index fdd8b8c1a..91b0fb608 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -24,6 +24,8 @@ BT::NodeStatus BT::SequenceNode::tick() // Routing the ticks according to the sequence node's logic: + setStatus(NodeStatus::RUNNING); + for (unsigned int i = 0; i < N_of_children; i++) { TreeNode* child_node = children_nodes_[i]; diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 838de7533..d9833233b 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -50,6 +50,8 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children = children_nodes_.size(); + setStatus(NodeStatus::RUNNING); + // Routing the ticks according to the sequence node's (with memory) logic: while (current_child_idx_ < N_of_children) { From 608c28b234f8afeec5c96e424441dea042918498 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 21 May 2018 10:11:41 +0200 Subject: [PATCH 065/125] removed RUNNING for simplicity (user provided tick() might be "atomic") --- src/action_node.cpp | 8 +------- src/tree_node.cpp | 2 +- 2 files changed, 2 insertions(+), 8 deletions(-) diff --git a/src/action_node.cpp b/src/action_node.cpp index e02f51bc0..c9bbfdb35 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -26,13 +26,7 @@ BT::SimpleActionNode::SimpleActionNode(std::string name, BT::SimpleActionNode::T BT::NodeStatus BT::SimpleActionNode::tick() { - NodeStatus prev_status = status(); - - if (prev_status == NodeStatus::IDLE) - { - setStatus(NodeStatus::RUNNING); - prev_status = NodeStatus::RUNNING; - } + const NodeStatus prev_status = status(); NodeStatus status = tick_functor_(); if (status != prev_status) diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 1e12f23e6..957269aff 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -42,7 +42,7 @@ void BT::TreeNode::setStatus(NodeStatus new_status) { state_condition_variable_.notify_all(); state_change_signal_.notify(*this, prev_status, new_status); -} + } } BT::NodeStatus BT::TreeNode::status() const From 1dd7fb530f849c25d8f06329686d7799870c2844 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 21 May 2018 10:11:56 +0200 Subject: [PATCH 066/125] added option to make the output less verbose --- gtest/crossdoor_example.cpp | 4 ++++ include/behavior_tree_logger/abstract_logger.h | 11 +++++++++-- 2 files changed, 13 insertions(+), 2 deletions(-) diff --git a/gtest/crossdoor_example.cpp b/gtest/crossdoor_example.cpp index ef40cb20c..26c0af9fc 100644 --- a/gtest/crossdoor_example.cpp +++ b/gtest/crossdoor_example.cpp @@ -52,6 +52,10 @@ int main(int argc, char** argv) StdCoutLogger logger(root_node.get()); + cross_door.CloseDoor(); + + std::cout << "---------------" << std::endl; + root_node->executeTick(); std::cout << "---------------" << std::endl; root_node->executeTick(); std::cout << "---------------" << std::endl; diff --git a/include/behavior_tree_logger/abstract_logger.h b/include/behavior_tree_logger/abstract_logger.h index 0936d2489..b35de7097 100644 --- a/include/behavior_tree_logger/abstract_logger.h +++ b/include/behavior_tree_logger/abstract_logger.h @@ -20,15 +20,22 @@ class StatusChangeLogger { bool enabled() const { return _enabled; } + // false by default. + bool showsTransitionToIdle() const { return _show_transition_to_idle; } + + void enableTransitionToIdle(bool enable ) { _show_transition_to_idle = enable; } + private: bool _enabled; + bool _show_transition_to_idle; std::vector _subscribers; }; //-------------------------------------------- StatusChangeLogger::StatusChangeLogger(TreeNode *root_node): - _enabled(true) + _enabled(true), + _show_transition_to_idle(false) { recursiveVisitor(root_node, [this](TreeNode* node) { @@ -37,7 +44,7 @@ StatusChangeLogger::StatusChangeLogger(TreeNode *root_node): NodeStatus prev, NodeStatus status) { - if(_enabled) + if(_enabled && ( status != NodeStatus::IDLE || _show_transition_to_idle)) { this->callback(node,prev,status); } From e95a27ddbb66637ca425fbc0515999d0e8a2b637 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 21 May 2018 10:26:44 +0200 Subject: [PATCH 067/125] removed DEBUG_STDOUT --- gtest/src/action_test_node.cpp | 13 +------------ include/behavior_tree_core/tree_node.h | 14 +------------- src/action_node.cpp | 2 -- src/control_node.cpp | 6 ------ src/decorator_node.cpp | 6 ------ src/fallback_node.cpp | 1 - src/fallback_node_with_memory.cpp | 3 --- src/parallel_node.cpp | 5 ----- src/sequence_node.cpp | 1 - src/sequence_node_with_memory.cpp | 4 ---- 10 files changed, 2 insertions(+), 53 deletions(-) diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index 07c832409..f65fe044f 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -32,22 +32,12 @@ BT::NodeStatus BT::ActionTestNode::tick() int i = 0; while ( !stop_loop_ && i++ < time_) { - DEBUG_STDOUT(" Action " << name() << "running! Thread id:" << std::this_thread::get_id()); std::this_thread::sleep_for(std::chrono::milliseconds(100)); } if ( !stop_loop_ ) { - if (boolean_value_) - { - DEBUG_STDOUT(" Action " << name() << " Done!"); - return NodeStatus::SUCCESS; - } - else - { - DEBUG_STDOUT(" Action " << name() << " FAILED!"); - return NodeStatus::FAILURE; - } + return boolean_value_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } else { @@ -59,7 +49,6 @@ void BT::ActionTestNode::halt() { stop_loop_ = true; setStatus(NodeStatus::IDLE); - DEBUG_STDOUT("HALTED state set!"); } void BT::ActionTestNode::set_time(int time) diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index f2b28bfc2..dd366ce53 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -14,18 +14,6 @@ #ifndef BEHAVIORTREECORE_TREENODE_H #define BEHAVIORTREECORE_TREENODE_H -#ifdef DEBUG -// #define DEBUG_STDERR(x) (std::cerr << (x)) -#define DEBUG_STDOUT(str) \ - do \ - { \ - std::cout << str << std::endl; \ - } while (false) - -#else -#define DEBUG_STDOUT(str) -#endif - #include #include #include @@ -95,7 +83,7 @@ enum SuccessPolicy SUCCEED_ON_ALL }; -// If "BT::FAIL_ON_ONE" and "BT::SUCCEED_ON_ONE" are both active and are both trigerred in the +// If "BT::FAIL_vON_ONE" and "BT::SUCCEED_ON_ONE" are both active and are both trigerred in the // same time step, failure will take precedence. // We call Parameters the set of Key/Values that can be read from file and are diff --git a/src/action_node.cpp b/src/action_node.cpp index c9bbfdb35..eb8b0d170 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -55,9 +55,7 @@ void BT::ActionNode::waitForTick() { while (loop_.load()) { - DEBUG_STDOUT(name() << " WAIT FOR TICK"); tick_engine_.wait(); - DEBUG_STDOUT(name() << " TICK RECEIVED"); // check this again because the tick_engine_ could be // notified from the method stopAndJoinThread diff --git a/src/control_node.cpp b/src/control_node.cpp index 6032f740c..b4eb3012c 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -41,7 +41,6 @@ unsigned int BT::ControlNode::childrenCount() const void BT::ControlNode::halt() { - DEBUG_STDOUT("HALTING: " << name()); haltChildren(0); setStatus(NodeStatus::IDLE); } @@ -57,12 +56,7 @@ void BT::ControlNode::haltChildren(int i) { if (children_nodes_[j]->status() == NodeStatus::RUNNING) { - DEBUG_STDOUT("SENDING HALT TO CHILD " << children_nodes_[j]->name()); children_nodes_[j]->halt(); } - else - { - DEBUG_STDOUT("NO NEED TO HALT " << children_nodes_[j]->name() << "STATUS" << children_nodes_[j]->status()); - } } } diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index d27770de9..dbd4dbc03 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -31,7 +31,6 @@ void BT::DecoratorNode::setChild(TreeNode* child) void BT::DecoratorNode::halt() { - DEBUG_STDOUT("HALTING: " << name()); haltChild(); setStatus(NodeStatus::IDLE); } @@ -50,11 +49,6 @@ void BT::DecoratorNode::haltChild() { if (child_node_->status() == NodeStatus::RUNNING) { - DEBUG_STDOUT("SENDING HALT TO CHILD " << child_node_->name()); child_node_->halt(); } - else - { - DEBUG_STDOUT("NO NEED TO HALT " << child_node_->name() << "STATUS" << child_node_->status()); - } } diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index d6e58ccf6..774183bc7 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -43,7 +43,6 @@ BT::NodeStatus BT::FallbackNode::tick() } } // If the child status is not failure, halt the next children and return the status to your parent. - DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); haltChildren(i + 1); return child_status; } diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 0cd9b21fa..cd62895c8 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -48,8 +48,6 @@ BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, const NodeP BT::NodeStatus BT::FallbackNodeWithMemory::tick() { - DEBUG_STDOUT(name() << " ticked, memory counter: " << current_child_idx_); - // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children = children_nodes_.size(); @@ -65,7 +63,6 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() if (child_status != NodeStatus::FAILURE) { // If the child status is not success, return the status - DEBUG_STDOUT("the status of: " << name() << " becomes " << child_status); if (child_status == NodeStatus::SUCCESS && reset_policy_ != BT::ON_FAILURE) { for (unsigned t=0; t<=current_child_idx_; t++) diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index 9fbbf3305..b97734c47 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -30,8 +30,6 @@ BT::NodeStatus BT::ParallelNode::tick() { TreeNode* child_node = children_nodes_[i]; - DEBUG_STDOUT(name() << "TICKING " << child_node); - NodeStatus child_status = child_node->executeTick(); switch (child_status) @@ -50,9 +48,6 @@ BT::NodeStatus BT::ParallelNode::tick() child_node->setStatus(NodeStatus::IDLE); // the child goes in idle if it has returned failure. if (++failure_childred_num_ > N_of_children - threshold_M_) { - DEBUG_STDOUT("*******PARALLEL" << name() - << " FAILED****** failure_childred_num_:" << failure_childred_num_); - success_childred_num_ = 0; failure_childred_num_ = 0; haltChildren(0); // halts all running children. The execution is hopeless. diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 91b0fb608..15768447a 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -44,7 +44,6 @@ BT::NodeStatus BT::SequenceNode::tick() } } - DEBUG_STDOUT(name() << " is HALTING children from " << (i + 1)); haltChildren(i + 1); return child_status; } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index d9833233b..a389e9611 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -55,8 +55,6 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() // Routing the ticks according to the sequence node's (with memory) logic: while (current_child_idx_ < N_of_children) { - DEBUG_STDOUT(name() << " ticked, memory counter: " << current_child_idx_); - /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. We want this thread detached so we can cancel its execution (when the action no longer receive ticks). Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. @@ -69,8 +67,6 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() if (child_status != NodeStatus::SUCCESS) { // If the child status is not success, return the status - DEBUG_STDOUT("the status of: " << name() << " becomes " << child_status); - if (child_status == NodeStatus::FAILURE && reset_policy_ != BT::ON_SUCCESS ) { for (unsigned t=0; t<=current_child_idx_; t++) From e06aa6da5bb4f1fa3cb0d9ef13f6c5ddf99a5b6e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 21 May 2018 12:32:55 +0200 Subject: [PATCH 068/125] REVERTED change. It was a bad idea --- src/action_node.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/action_node.cpp b/src/action_node.cpp index eb8b0d170..ae49cbfef 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -26,7 +26,13 @@ BT::SimpleActionNode::SimpleActionNode(std::string name, BT::SimpleActionNode::T BT::NodeStatus BT::SimpleActionNode::tick() { - const NodeStatus prev_status = status(); + NodeStatus prev_status = status(); + + if ( prev_status == NodeStatus::IDLE) + { + setStatus(NodeStatus::RUNNING); + prev_status = NodeStatus::RUNNING; + } NodeStatus status = tick_functor_(); if (status != prev_status) From 11a42583b08fa9c115e3415bbb5040a3f704ef69 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 30 May 2018 15:14:01 +0200 Subject: [PATCH 069/125] third party libraries --- 3rdparty/flatbuffers/LICENSE.txt | 202 +++++++++++ 3rdparty/flatbuffers/base.h | 267 ++++++++++++++ 3rdparty/flatbuffers/readme.md | 59 +++ 3rdparty/flatbuffers/stl_emulation.h | 228 ++++++++++++ 3rdparty/flatbuffers/util.h | 515 +++++++++++++++++++++++++++ 3rdparty/minitrace/LICENSE | 21 ++ 3rdparty/minitrace/README.md | 103 ++++++ 3rdparty/minitrace/minitrace.cpp | 378 ++++++++++++++++++++ 3rdparty/minitrace/minitrace.h | 267 ++++++++++++++ cmake/FindZMQ.cmake | 59 +++ 10 files changed, 2099 insertions(+) create mode 100644 3rdparty/flatbuffers/LICENSE.txt create mode 100644 3rdparty/flatbuffers/base.h create mode 100644 3rdparty/flatbuffers/readme.md create mode 100644 3rdparty/flatbuffers/stl_emulation.h create mode 100644 3rdparty/flatbuffers/util.h create mode 100644 3rdparty/minitrace/LICENSE create mode 100644 3rdparty/minitrace/README.md create mode 100644 3rdparty/minitrace/minitrace.cpp create mode 100644 3rdparty/minitrace/minitrace.h create mode 100644 cmake/FindZMQ.cmake diff --git a/3rdparty/flatbuffers/LICENSE.txt b/3rdparty/flatbuffers/LICENSE.txt new file mode 100644 index 000000000..a4c5efd82 --- /dev/null +++ b/3rdparty/flatbuffers/LICENSE.txt @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright 2014 Google Inc. + + 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. diff --git a/3rdparty/flatbuffers/base.h b/3rdparty/flatbuffers/base.h new file mode 100644 index 000000000..5fe501779 --- /dev/null +++ b/3rdparty/flatbuffers/base.h @@ -0,0 +1,267 @@ +#ifndef FLATBUFFERS_BASE_H_ +#define FLATBUFFERS_BASE_H_ + +// clang-format off +#if defined(FLATBUFFERS_MEMORY_LEAK_TRACKING) && \ + defined(_MSC_VER) && defined(_DEBUG) + #define _CRTDBG_MAP_ALLOC +#endif + +#include + +#if !defined(FLATBUFFERS_ASSERT) +#define FLATBUFFERS_ASSERT assert +#endif + +#ifndef ARDUINO +#include +#endif + +#include +#include +#include + +#if defined(FLATBUFFERS_MEMORY_LEAK_TRACKING) && \ + defined(_MSC_VER) && defined(_DEBUG) + #include + #define DEBUG_NEW new(_NORMAL_BLOCK, __FILE__, __LINE__) + #define new DEBUG_NEW +#endif + +#if defined(ARDUINO) && !defined(ARDUINOSTL_M_H) + #include +#else + #include +#endif + +#include +#include +#include +#include +#include +#include +#include + +#ifdef _STLPORT_VERSION + #define FLATBUFFERS_CPP98_STL +#endif +#ifndef FLATBUFFERS_CPP98_STL + #include +#endif + +#include "flatbuffers/stl_emulation.h" + +/// @cond FLATBUFFERS_INTERNAL +#if __cplusplus <= 199711L && \ + (!defined(_MSC_VER) || _MSC_VER < 1600) && \ + (!defined(__GNUC__) || \ + (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__ < 40400)) + #error A C++11 compatible compiler with support for the auto typing is \ + required for FlatBuffers. + #error __cplusplus _MSC_VER __GNUC__ __GNUC_MINOR__ __GNUC_PATCHLEVEL__ +#endif + +#if !defined(__clang__) && \ + defined(__GNUC__) && \ + (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__ < 40600) + // Backwards compatability for g++ 4.4, and 4.5 which don't have the nullptr + // and constexpr keywords. Note the __clang__ check is needed, because clang + // presents itself as an older GNUC compiler. + #ifndef nullptr_t + const class nullptr_t { + public: + template inline operator T*() const { return 0; } + private: + void operator&() const; + } nullptr = {}; + #endif + #ifndef constexpr + #define constexpr const + #endif +#endif + +// The wire format uses a little endian encoding (since that's efficient for +// the common platforms). +#if defined(__s390x__) + #define FLATBUFFERS_LITTLEENDIAN 0 +#endif // __s390x__ +#if !defined(FLATBUFFERS_LITTLEENDIAN) + #if defined(__GNUC__) || defined(__clang__) + #ifdef __BIG_ENDIAN__ + #define FLATBUFFERS_LITTLEENDIAN 0 + #else + #define FLATBUFFERS_LITTLEENDIAN 1 + #endif // __BIG_ENDIAN__ + #elif defined(_MSC_VER) + #if defined(_M_PPC) + #define FLATBUFFERS_LITTLEENDIAN 0 + #else + #define FLATBUFFERS_LITTLEENDIAN 1 + #endif + #else + #error Unable to determine endianness, define FLATBUFFERS_LITTLEENDIAN. + #endif +#endif // !defined(FLATBUFFERS_LITTLEENDIAN) + +#define FLATBUFFERS_VERSION_MAJOR 1 +#define FLATBUFFERS_VERSION_MINOR 9 +#define FLATBUFFERS_VERSION_REVISION 0 +#define FLATBUFFERS_STRING_EXPAND(X) #X +#define FLATBUFFERS_STRING(X) FLATBUFFERS_STRING_EXPAND(X) + +#if (!defined(_MSC_VER) || _MSC_VER > 1600) && \ + (!defined(__GNUC__) || (__GNUC__ * 100 + __GNUC_MINOR__ >= 407)) + #define FLATBUFFERS_FINAL_CLASS final + #define FLATBUFFERS_OVERRIDE override +#else + #define FLATBUFFERS_FINAL_CLASS + #define FLATBUFFERS_OVERRIDE +#endif + +#if (!defined(_MSC_VER) || _MSC_VER >= 1900) && \ + (!defined(__GNUC__) || (__GNUC__ * 100 + __GNUC_MINOR__ >= 406)) + #define FLATBUFFERS_CONSTEXPR constexpr +#else + #define FLATBUFFERS_CONSTEXPR +#endif + +#if (defined(__cplusplus) && __cplusplus >= 201402L) || \ + (defined(__cpp_constexpr) && __cpp_constexpr >= 201304) + #define FLATBUFFERS_CONSTEXPR_CPP14 FLATBUFFERS_CONSTEXPR +#else + #define FLATBUFFERS_CONSTEXPR_CPP14 +#endif + +#if defined(__GXX_EXPERIMENTAL_CXX0X__) && __GNUC__ * 10 + __GNUC_MINOR__ >= 46 || \ + defined(_MSC_FULL_VER) && _MSC_FULL_VER >= 190023026 + #define FLATBUFFERS_NOEXCEPT noexcept +#else + #define FLATBUFFERS_NOEXCEPT +#endif + +// NOTE: the FLATBUFFERS_DELETE_FUNC macro may change the access mode to +// private, so be sure to put it at the end or reset access mode explicitly. +#if (!defined(_MSC_VER) || _MSC_FULL_VER >= 180020827) && \ + (!defined(__GNUC__) || (__GNUC__ * 100 + __GNUC_MINOR__ >= 404)) + #define FLATBUFFERS_DELETE_FUNC(func) func = delete; +#else + #define FLATBUFFERS_DELETE_FUNC(func) private: func; +#endif + +#if defined(_MSC_VER) + #pragma warning(push) + #pragma warning(disable: 4127) // C4127: conditional expression is constant +#endif + +#ifndef FLATBUFFERS_HAS_STRING_VIEW + // Only provide flatbuffers::string_view if __has_include can be used + // to detect a header that provides an implementation + #if defined(__has_include) + // Check for std::string_view (in c++17) + #if __has_include() && (__cplusplus > 201402) + #include + namespace flatbuffers { + typedef std::string_view string_view; + } + #define FLATBUFFERS_HAS_STRING_VIEW 1 + // Check for std::experimental::string_view (in c++14, compiler-dependent) + #elif __has_include() && (__cplusplus > 201103) + #include + namespace flatbuffers { + typedef std::experimental::string_view string_view; + } + #define FLATBUFFERS_HAS_STRING_VIEW 1 + #endif + #endif // __has_include +#endif // !FLATBUFFERS_HAS_STRING_VIEW + +/// @endcond + +/// @file +namespace flatbuffers { + +/// @cond FLATBUFFERS_INTERNAL +// Our default offset / size type, 32bit on purpose on 64bit systems. +// Also, using a consistent offset type maintains compatibility of serialized +// offset values between 32bit and 64bit systems. +typedef uint32_t uoffset_t; + +// Signed offsets for references that can go in both directions. +typedef int32_t soffset_t; + +// Offset/index used in v-tables, can be changed to uint8_t in +// format forks to save a bit of space if desired. +typedef uint16_t voffset_t; + +typedef uintmax_t largest_scalar_t; + +// In 32bits, this evaluates to 2GB - 1 +#define FLATBUFFERS_MAX_BUFFER_SIZE ((1ULL << (sizeof(soffset_t) * 8 - 1)) - 1) + +// We support aligning the contents of buffers up to this size. +#define FLATBUFFERS_MAX_ALIGNMENT 16 + +template T EndianSwap(T t) { + #if defined(_MSC_VER) + #define FLATBUFFERS_BYTESWAP16 _byteswap_ushort + #define FLATBUFFERS_BYTESWAP32 _byteswap_ulong + #define FLATBUFFERS_BYTESWAP64 _byteswap_uint64 + #else + #if defined(__GNUC__) && __GNUC__ * 100 + __GNUC_MINOR__ < 408 && !defined(__clang__) + // __builtin_bswap16 was missing prior to GCC 4.8. + #define FLATBUFFERS_BYTESWAP16(x) \ + static_cast(__builtin_bswap32(static_cast(x) << 16)) + #else + #define FLATBUFFERS_BYTESWAP16 __builtin_bswap16 + #endif + #define FLATBUFFERS_BYTESWAP32 __builtin_bswap32 + #define FLATBUFFERS_BYTESWAP64 __builtin_bswap64 + #endif + if (sizeof(T) == 1) { // Compile-time if-then's. + return t; + } else if (sizeof(T) == 2) { + union { T t; uint16_t i; } u; + u.t = t; + u.i = FLATBUFFERS_BYTESWAP16(u.i); + return u.t; + } else if (sizeof(T) == 4) { + union { T t; uint32_t i; } u; + u.t = t; + u.i = FLATBUFFERS_BYTESWAP32(u.i); + return u.t; + } else if (sizeof(T) == 8) { + union { T t; uint64_t i; } u; + u.t = t; + u.i = FLATBUFFERS_BYTESWAP64(u.i); + return u.t; + } else { + FLATBUFFERS_ASSERT(0); + } +} + + +template T EndianScalar(T t) { + #if FLATBUFFERS_LITTLEENDIAN + return t; + #else + return EndianSwap(t); + #endif +} + +template T ReadScalar(const void *p) { + return EndianScalar(*reinterpret_cast(p)); +} + +template void WriteScalar(void *p, T t) { + *reinterpret_cast(p) = EndianScalar(t); +} + +// Computes how many bytes you'd have to pad to be able to write an +// "scalar_size" scalar if the buffer had grown to "buf_size" (downwards in +// memory). +inline size_t PaddingBytes(size_t buf_size, size_t scalar_size) { + return ((~buf_size) + 1) & (scalar_size - 1); +} + +} // namespace flatbuffers +#endif // FLATBUFFERS_BASE_H_ diff --git a/3rdparty/flatbuffers/readme.md b/3rdparty/flatbuffers/readme.md new file mode 100644 index 000000000..a7c0e93fd --- /dev/null +++ b/3rdparty/flatbuffers/readme.md @@ -0,0 +1,59 @@ +![logo](http://google.github.io/flatbuffers/fpl_logo_small.png) FlatBuffers +=========== + +[![Join the chat at https://gitter.im/google/flatbuffers](https://badges.gitter.im/google/flatbuffers.svg)](https://gitter.im/google/flatbuffers?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge) +[![Build Status](https://travis-ci.org/google/flatbuffers.svg?branch=master)](https://travis-ci.org/google/flatbuffers) [![Build status](https://ci.appveyor.com/api/projects/status/yg5idd2fnusv1n10?svg=true)](https://ci.appveyor.com/project/gwvo/flatbuffers) + +**FlatBuffers** is an efficient cross platform serialization library for games and +other memory constrained apps. It allows you to directly access serialized data without +unpacking/parsing it first, while still having great forwards/backwards compatibility. + +**Go to our [landing page][] to browse our documentation.** + +## Supported operating systems +* Android +* Windows +* MacOS X +* Linux + +## Supported programming languages +* C++ +* C# +* C +* Go +* Java +* JavaScript +* PHP +* Python + +*and many more in progress...* + +## Contribution +* [FlatBuffers Google Group][] to discuss FlatBuffers with other developers and users. +* [FlatBuffers Issues Tracker][] to submit an issue. +* [stackoverflow.com][] with [`flatbuffers` tag][] for any questions regarding FlatBuffers. + +*To contribute to this project,* see [CONTRIBUTING][]. + +## Integration +For applications on Google Play that integrate this tool, usage is tracked. +This tracking is done automatically using the embedded version string +(**`flatbuffer_version_string`**), and helps us continue to optimize it. Aside from +consuming a few extra bytes in your application binary, it shouldn't affect +your application at all. We use this information to let us know if FlatBuffers +is useful and if we should continue to invest in it. Since this is open +source, you are free to remove the version string but we would appreciate if +you would leave it in. + +## Licensing +*Flatbuffers* is licensed under the Apache License, Version 2.0. See [LICENSE][] for the full license text. + +
+ + [CONTRIBUTING]: http://github.com/google/flatbuffers/blob/master/CONTRIBUTING.md + [`flatbuffers` tag]: https://stackoverflow.com/questions/tagged/flatbuffers + [FlatBuffers Google Group]: https://groups.google.com/forum/#!forum/flatbuffers + [FlatBuffers Issues Tracker]: http://github.com/google/flatbuffers/issues + [stackoverflow.com]: http://stackoverflow.com/search?q=flatbuffers + [landing page]: http://google.github.io/flatbuffers + [LICENSE]: https://github.com/google/flatbuffers/blob/master/LICENSE.txt diff --git a/3rdparty/flatbuffers/stl_emulation.h b/3rdparty/flatbuffers/stl_emulation.h new file mode 100644 index 000000000..7e7e978a4 --- /dev/null +++ b/3rdparty/flatbuffers/stl_emulation.h @@ -0,0 +1,228 @@ +/* + * Copyright 2017 Google Inc. All rights reserved. + * + * 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. + */ + +#ifndef FLATBUFFERS_STL_EMULATION_H_ +#define FLATBUFFERS_STL_EMULATION_H_ + +// clang-format off + +#include +#include +#include +#include +#include + +#if defined(_STLPORT_VERSION) && !defined(FLATBUFFERS_CPP98_STL) + #define FLATBUFFERS_CPP98_STL +#endif // defined(_STLPORT_VERSION) && !defined(FLATBUFFERS_CPP98_STL) + +#if defined(FLATBUFFERS_CPP98_STL) + #include +#endif // defined(FLATBUFFERS_CPP98_STL) + +// This header provides backwards compatibility for C++98 STLs like stlport. +namespace flatbuffers { + +// Retrieve ::back() from a string in a way that is compatible with pre C++11 +// STLs (e.g stlport). +inline char& string_back(std::string &value) { + return value[value.length() - 1]; +} + +inline char string_back(const std::string &value) { + return value[value.length() - 1]; +} + +// Helper method that retrieves ::data() from a vector in a way that is +// compatible with pre C++11 STLs (e.g stlport). +template inline T *vector_data(std::vector &vector) { + // In some debug environments, operator[] does bounds checking, so &vector[0] + // can't be used. + return vector.empty() ? nullptr : &vector[0]; +} + +template inline const T *vector_data( + const std::vector &vector) { + return vector.empty() ? nullptr : &vector[0]; +} + +template +inline void vector_emplace_back(std::vector *vector, V &&data) { + #if defined(FLATBUFFERS_CPP98_STL) + vector->push_back(data); + #else + vector->emplace_back(std::forward(data)); + #endif // defined(FLATBUFFERS_CPP98_STL) +} + +#ifndef FLATBUFFERS_CPP98_STL + #if !(defined(_MSC_VER) && _MSC_VER <= 1700 /* MSVC2012 */) + template + using numeric_limits = std::numeric_limits; + #else + template class numeric_limits : + public std::numeric_limits {}; + #endif // !(defined(_MSC_VER) && _MSC_VER <= 1700 /* MSVC2012 */) +#else + template class numeric_limits : + public std::numeric_limits {}; + + template <> class numeric_limits { + public: + static unsigned long long min() { return 0ULL; } + static unsigned long long max() { return ~0ULL; } + }; + + template <> class numeric_limits { + public: + static long long min() { + return static_cast(1ULL << ((sizeof(long long) << 3) - 1)); + } + static long long max() { + return static_cast( + (1ULL << ((sizeof(long long) << 3) - 1)) - 1); + } + }; +#endif // FLATBUFFERS_CPP98_STL + +#if !(defined(_MSC_VER) && _MSC_VER <= 1700 /* MSVC2012 */) + #ifndef FLATBUFFERS_CPP98_STL + template using is_scalar = std::is_scalar; + template using is_same = std::is_same; + template using is_floating_point = std::is_floating_point; + template using is_unsigned = std::is_unsigned; + #else + // Map C++ TR1 templates defined by stlport. + template using is_scalar = std::tr1::is_scalar; + template using is_same = std::tr1::is_same; + template using is_floating_point = + std::tr1::is_floating_point; + template using is_unsigned = std::tr1::is_unsigned; + #endif // !FLATBUFFERS_CPP98_STL +#else + // MSVC 2010 doesn't support C++11 aliases. + template struct is_scalar : public std::is_scalar {}; + template struct is_same : public std::is_same {}; + template struct is_floating_point : + public std::is_floating_point {}; + template struct is_unsigned : public std::is_unsigned {}; +#endif // !(defined(_MSC_VER) && _MSC_VER <= 1700 /* MSVC2012 */) + +#ifndef FLATBUFFERS_CPP98_STL + #if !(defined(_MSC_VER) && _MSC_VER <= 1700 /* MSVC2012 */) + template using unique_ptr = std::unique_ptr; + #else + // MSVC 2010 doesn't support C++11 aliases. + // We're manually "aliasing" the class here as we want to bring unique_ptr + // into the flatbuffers namespace. We have unique_ptr in the flatbuffers + // namespace we have a completely independent implemenation (see below) + // for C++98 STL implementations. + template class unique_ptr : public std::unique_ptr { + public: + unique_ptr() {} + explicit unique_ptr(T* p) : std::unique_ptr(p) {} + unique_ptr(std::unique_ptr&& u) { *this = std::move(u); } + unique_ptr(unique_ptr&& u) { *this = std::move(u); } + unique_ptr& operator=(std::unique_ptr&& u) { + std::unique_ptr::reset(u.release()); + return *this; + } + unique_ptr& operator=(unique_ptr&& u) { + std::unique_ptr::reset(u.release()); + return *this; + } + unique_ptr& operator=(T* p) { + return std::unique_ptr::operator=(p); + } + }; + #endif // !(defined(_MSC_VER) && _MSC_VER <= 1700 /* MSVC2012 */) +#else + // Very limited implementation of unique_ptr. + // This is provided simply to allow the C++ code generated from the default + // settings to function in C++98 environments with no modifications. + template class unique_ptr { + public: + typedef T element_type; + + unique_ptr() : ptr_(nullptr) {} + explicit unique_ptr(T* p) : ptr_(p) {} + unique_ptr(unique_ptr&& u) : ptr_(nullptr) { reset(u.release()); } + unique_ptr(const unique_ptr& u) : ptr_(nullptr) { + reset(const_cast(&u)->release()); + } + ~unique_ptr() { reset(); } + + unique_ptr& operator=(const unique_ptr& u) { + reset(const_cast(&u)->release()); + return *this; + } + + unique_ptr& operator=(unique_ptr&& u) { + reset(u.release()); + return *this; + } + + unique_ptr& operator=(T* p) { + reset(p); + return *this; + } + + const T& operator*() const { return *ptr_; } + T* operator->() const { return ptr_; } + T* get() const noexcept { return ptr_; } + explicit operator bool() const { return ptr_ != nullptr; } + + // modifiers + T* release() { + T* value = ptr_; + ptr_ = nullptr; + return value; + } + + void reset(T* p = nullptr) { + T* value = ptr_; + ptr_ = p; + if (value) delete value; + } + + void swap(unique_ptr& u) { + T* temp_ptr = ptr_; + ptr_ = u.ptr_; + u.ptr_ = temp_ptr; + } + + private: + T* ptr_; + }; + + template bool operator==(const unique_ptr& x, + const unique_ptr& y) { + return x.get() == y.get(); + } + + template bool operator==(const unique_ptr& x, + const D* y) { + return static_cast(x.get()) == y; + } + + template bool operator==(const unique_ptr& x, intptr_t y) { + return reinterpret_cast(x.get()) == y; + } +#endif // !FLATBUFFERS_CPP98_STL + +} // namespace flatbuffers + +#endif // FLATBUFFERS_STL_EMULATION_H_ diff --git a/3rdparty/flatbuffers/util.h b/3rdparty/flatbuffers/util.h new file mode 100644 index 000000000..cf2949a20 --- /dev/null +++ b/3rdparty/flatbuffers/util.h @@ -0,0 +1,515 @@ +/* + * Copyright 2014 Google Inc. All rights reserved. + * + * 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. + */ + +#ifndef FLATBUFFERS_UTIL_H_ +#define FLATBUFFERS_UTIL_H_ + +#include +#include +#include +#include +#include +#ifndef FLATBUFFERS_PREFER_PRINTF +# include +#else // FLATBUFFERS_PREFER_PRINTF +# include +# include +#endif // FLATBUFFERS_PREFER_PRINTF +#include +#ifdef _WIN32 +# ifndef WIN32_LEAN_AND_MEAN +# define WIN32_LEAN_AND_MEAN +# endif +# ifndef NOMINMAX +# define NOMINMAX +# endif +# include // Must be included before +# include +# include +# undef interface // This is also important because of reasons +#else +# include +#endif +#include +#include + +#include "flatbuffers/base.h" + +namespace flatbuffers { + +#ifdef FLATBUFFERS_PREFER_PRINTF +template size_t IntToDigitCount(T t) { + size_t digit_count = 0; + // Count the sign for negative numbers + if (t < 0) digit_count++; + // Count a single 0 left of the dot for fractional numbers + if (-1 < t && t < 1) digit_count++; + // Count digits until fractional part + T eps = std::numeric_limits::epsilon(); + while (t <= (-1 + eps) || (1 - eps) <= t) { + t /= 10; + digit_count++; + } + return digit_count; +} + +template size_t NumToStringWidth(T t, int precision = 0) { + size_t string_width = IntToDigitCount(t); + // Count the dot for floating point numbers + if (precision) string_width += (precision + 1); + return string_width; +} + +template std::string NumToStringImplWrapper(T t, const char* fmt, + int precision = 0) { + size_t string_width = NumToStringWidth(t, precision); + std::string s(string_width, 0x00); + // Allow snprintf to use std::string trailing null to detect buffer overflow + snprintf(const_cast(s.data()), (s.size()+1), fmt, precision, t); + return s; +} +#endif // FLATBUFFERS_PREFER_PRINTF + +// Convert an integer or floating point value to a string. +// In contrast to std::stringstream, "char" values are +// converted to a string of digits, and we don't use scientific notation. +template std::string NumToString(T t) { + // clang-format off + #ifndef FLATBUFFERS_PREFER_PRINTF + std::stringstream ss; + ss << t; + return ss.str(); + #else // FLATBUFFERS_PREFER_PRINTF + auto v = static_cast(t); + return NumToStringImplWrapper(v, "%.*lld"); + #endif // FLATBUFFERS_PREFER_PRINTF + // clang-format on +} +// Avoid char types used as character data. +template<> inline std::string NumToString(signed char t) { + return NumToString(static_cast(t)); +} +template<> inline std::string NumToString(unsigned char t) { + return NumToString(static_cast(t)); +} +#if defined(FLATBUFFERS_CPP98_STL) +template<> inline std::string NumToString(long long t) { + char buf[21]; // (log((1 << 63) - 1) / log(10)) + 2 + snprintf(buf, sizeof(buf), "%lld", t); + return std::string(buf); +} + +template<> +inline std::string NumToString(unsigned long long t) { + char buf[22]; // (log((1 << 63) - 1) / log(10)) + 1 + snprintf(buf, sizeof(buf), "%llu", t); + return std::string(buf); +} +#endif // defined(FLATBUFFERS_CPP98_STL) + +// Special versions for floats/doubles. +template std::string FloatToString(T t, int precision) { + // clang-format off + #ifndef FLATBUFFERS_PREFER_PRINTF + // to_string() prints different numbers of digits for floats depending on + // platform and isn't available on Android, so we use stringstream + std::stringstream ss; + // Use std::fixed to suppress scientific notation. + ss << std::fixed; + // Default precision is 6, we want that to be higher for doubles. + ss << std::setprecision(precision); + ss << t; + auto s = ss.str(); + #else // FLATBUFFERS_PREFER_PRINTF + auto v = static_cast(t); + auto s = NumToStringImplWrapper(v, "%0.*f", precision); + #endif // FLATBUFFERS_PREFER_PRINTF + // clang-format on + // Sadly, std::fixed turns "1" into "1.00000", so here we undo that. + auto p = s.find_last_not_of('0'); + if (p != std::string::npos) { + // Strip trailing zeroes. If it is a whole number, keep one zero. + s.resize(p + (s[p] == '.' ? 2 : 1)); + } + return s; +} + +template<> inline std::string NumToString(double t) { + return FloatToString(t, 12); +} +template<> inline std::string NumToString(float t) { + return FloatToString(t, 6); +} + +// Convert an integer value to a hexadecimal string. +// The returned string length is always xdigits long, prefixed by 0 digits. +// For example, IntToStringHex(0x23, 8) returns the string "00000023". +inline std::string IntToStringHex(int i, int xdigits) { + // clang-format off + #ifndef FLATBUFFERS_PREFER_PRINTF + std::stringstream ss; + ss << std::setw(xdigits) << std::setfill('0') << std::hex << std::uppercase + << i; + return ss.str(); + #else // FLATBUFFERS_PREFER_PRINTF + return NumToStringImplWrapper(i, "%.*X", xdigits); + #endif // FLATBUFFERS_PREFER_PRINTF + // clang-format on +} + +// Portable implementation of strtoll(). +inline int64_t StringToInt(const char *str, char **endptr = nullptr, + int base = 10) { + // clang-format off + #ifdef _MSC_VER + return _strtoi64(str, endptr, base); + #else + return strtoll(str, endptr, base); + #endif + // clang-format on +} + +// Portable implementation of strtoull(). +inline uint64_t StringToUInt(const char *str, char **endptr = nullptr, + int base = 10) { + // clang-format off + #ifdef _MSC_VER + return _strtoui64(str, endptr, base); + #else + return strtoull(str, endptr, base); + #endif + // clang-format on +} + +typedef bool (*LoadFileFunction)(const char *filename, bool binary, + std::string *dest); +typedef bool (*FileExistsFunction)(const char *filename); + +LoadFileFunction SetLoadFileFunction(LoadFileFunction load_file_function); + +FileExistsFunction SetFileExistsFunction( + FileExistsFunction file_exists_function); + +// Check if file "name" exists. +bool FileExists(const char *name); + +// Check if "name" exists and it is also a directory. +bool DirExists(const char *name); + +// Load file "name" into "buf" returning true if successful +// false otherwise. If "binary" is false data is read +// using ifstream's text mode, otherwise data is read with +// no transcoding. +bool LoadFile(const char *name, bool binary, std::string *buf); + +// Save data "buf" of length "len" bytes into a file +// "name" returning true if successful, false otherwise. +// If "binary" is false data is written using ifstream's +// text mode, otherwise data is written with no +// transcoding. +inline bool SaveFile(const char *name, const char *buf, size_t len, + bool binary) { + std::ofstream ofs(name, binary ? std::ofstream::binary : std::ofstream::out); + if (!ofs.is_open()) return false; + ofs.write(buf, len); + return !ofs.bad(); +} + +// Save data "buf" into file "name" returning true if +// successful, false otherwise. If "binary" is false +// data is written using ifstream's text mode, otherwise +// data is written with no transcoding. +inline bool SaveFile(const char *name, const std::string &buf, bool binary) { + return SaveFile(name, buf.c_str(), buf.size(), binary); +} + +// Functionality for minimalistic portable path handling. + +// The functions below behave correctly regardless of whether posix ('/') or +// Windows ('/' or '\\') separators are used. + +// Any new separators inserted are always posix. + +// We internally store paths in posix format ('/'). Paths supplied +// by the user should go through PosixPath to ensure correct behavior +// on Windows when paths are string-compared. + +static const char kPathSeparator = '/'; +static const char kPathSeparatorWindows = '\\'; +static const char *PathSeparatorSet = "\\/"; // Intentionally no ':' + +// Returns the path with the extension, if any, removed. +inline std::string StripExtension(const std::string &filepath) { + size_t i = filepath.find_last_of("."); + return i != std::string::npos ? filepath.substr(0, i) : filepath; +} + +// Returns the extension, if any. +inline std::string GetExtension(const std::string &filepath) { + size_t i = filepath.find_last_of("."); + return i != std::string::npos ? filepath.substr(i + 1) : ""; +} + +// Return the last component of the path, after the last separator. +inline std::string StripPath(const std::string &filepath) { + size_t i = filepath.find_last_of(PathSeparatorSet); + return i != std::string::npos ? filepath.substr(i + 1) : filepath; +} + +// Strip the last component of the path + separator. +inline std::string StripFileName(const std::string &filepath) { + size_t i = filepath.find_last_of(PathSeparatorSet); + return i != std::string::npos ? filepath.substr(0, i) : ""; +} + +// Concatenates a path with a filename, regardless of wether the path +// ends in a separator or not. +inline std::string ConCatPathFileName(const std::string &path, + const std::string &filename) { + std::string filepath = path; + if (filepath.length()) { + char &filepath_last_character = string_back(filepath); + if (filepath_last_character == kPathSeparatorWindows) { + filepath_last_character = kPathSeparator; + } else if (filepath_last_character != kPathSeparator) { + filepath += kPathSeparator; + } + } + filepath += filename; + // Ignore './' at the start of filepath. + if (filepath[0] == '.' && filepath[1] == kPathSeparator) { + filepath.erase(0, 2); + } + return filepath; +} + +// Replaces any '\\' separators with '/' +inline std::string PosixPath(const char *path) { + std::string p = path; + std::replace(p.begin(), p.end(), '\\', '/'); + return p; +} + +// This function ensure a directory exists, by recursively +// creating dirs for any parts of the path that don't exist yet. +inline void EnsureDirExists(const std::string &filepath) { + auto parent = StripFileName(filepath); + if (parent.length()) EnsureDirExists(parent); + // clang-format off + #ifdef _WIN32 + (void)_mkdir(filepath.c_str()); + #else + mkdir(filepath.c_str(), S_IRWXU|S_IRGRP|S_IXGRP); + #endif + // clang-format on +} + +// Obtains the absolute path from any other path. +// Returns the input path if the absolute path couldn't be resolved. +inline std::string AbsolutePath(const std::string &filepath) { + // clang-format off + #ifdef FLATBUFFERS_NO_ABSOLUTE_PATH_RESOLUTION + return filepath; + #else + #ifdef _WIN32 + char abs_path[MAX_PATH]; + return GetFullPathNameA(filepath.c_str(), MAX_PATH, abs_path, nullptr) + #else + char abs_path[PATH_MAX]; + return realpath(filepath.c_str(), abs_path) + #endif + ? abs_path + : filepath; + #endif // FLATBUFFERS_NO_ABSOLUTE_PATH_RESOLUTION + // clang-format on +} + +// To and from UTF-8 unicode conversion functions + +// Convert a unicode code point into a UTF-8 representation by appending it +// to a string. Returns the number of bytes generated. +inline int ToUTF8(uint32_t ucc, std::string *out) { + FLATBUFFERS_ASSERT(!(ucc & 0x80000000)); // Top bit can't be set. + // 6 possible encodings: http://en.wikipedia.org/wiki/UTF-8 + for (int i = 0; i < 6; i++) { + // Max bits this encoding can represent. + uint32_t max_bits = 6 + i * 5 + static_cast(!i); + if (ucc < (1u << max_bits)) { // does it fit? + // Remaining bits not encoded in the first byte, store 6 bits each + uint32_t remain_bits = i * 6; + // Store first byte: + (*out) += static_cast((0xFE << (max_bits - remain_bits)) | + (ucc >> remain_bits)); + // Store remaining bytes: + for (int j = i - 1; j >= 0; j--) { + (*out) += static_cast(((ucc >> (j * 6)) & 0x3F) | 0x80); + } + return i + 1; // Return the number of bytes added. + } + } + FLATBUFFERS_ASSERT(0); // Impossible to arrive here. + return -1; +} + +// Converts whatever prefix of the incoming string corresponds to a valid +// UTF-8 sequence into a unicode code. The incoming pointer will have been +// advanced past all bytes parsed. +// returns -1 upon corrupt UTF-8 encoding (ignore the incoming pointer in +// this case). +inline int FromUTF8(const char **in) { + int len = 0; + // Count leading 1 bits. + for (int mask = 0x80; mask >= 0x04; mask >>= 1) { + if (**in & mask) { + len++; + } else { + break; + } + } + if ((static_cast(**in) << len) & 0x80) return -1; // Bit after leading 1's must be 0. + if (!len) return *(*in)++; + // UTF-8 encoded values with a length are between 2 and 4 bytes. + if (len < 2 || len > 4) { return -1; } + // Grab initial bits of the code. + int ucc = *(*in)++ & ((1 << (7 - len)) - 1); + for (int i = 0; i < len - 1; i++) { + if ((**in & 0xC0) != 0x80) return -1; // Upper bits must 1 0. + ucc <<= 6; + ucc |= *(*in)++ & 0x3F; // Grab 6 more bits of the code. + } + // UTF-8 cannot encode values between 0xD800 and 0xDFFF (reserved for + // UTF-16 surrogate pairs). + if (ucc >= 0xD800 && ucc <= 0xDFFF) { return -1; } + // UTF-8 must represent code points in their shortest possible encoding. + switch (len) { + case 2: + // Two bytes of UTF-8 can represent code points from U+0080 to U+07FF. + if (ucc < 0x0080 || ucc > 0x07FF) { return -1; } + break; + case 3: + // Three bytes of UTF-8 can represent code points from U+0800 to U+FFFF. + if (ucc < 0x0800 || ucc > 0xFFFF) { return -1; } + break; + case 4: + // Four bytes of UTF-8 can represent code points from U+10000 to U+10FFFF. + if (ucc < 0x10000 || ucc > 0x10FFFF) { return -1; } + break; + } + return ucc; +} + +#ifndef FLATBUFFERS_PREFER_PRINTF +// Wraps a string to a maximum length, inserting new lines where necessary. Any +// existing whitespace will be collapsed down to a single space. A prefix or +// suffix can be provided, which will be inserted before or after a wrapped +// line, respectively. +inline std::string WordWrap(const std::string in, size_t max_length, + const std::string wrapped_line_prefix, + const std::string wrapped_line_suffix) { + std::istringstream in_stream(in); + std::string wrapped, line, word; + + in_stream >> word; + line = word; + + while (in_stream >> word) { + if ((line.length() + 1 + word.length() + wrapped_line_suffix.length()) < + max_length) { + line += " " + word; + } else { + wrapped += line + wrapped_line_suffix + "\n"; + line = wrapped_line_prefix + word; + } + } + wrapped += line; + + return wrapped; +} +#endif // !FLATBUFFERS_PREFER_PRINTF + +inline bool EscapeString(const char *s, size_t length, std::string *_text, + bool allow_non_utf8, bool natural_utf8) { + std::string &text = *_text; + text += "\""; + for (uoffset_t i = 0; i < length; i++) { + char c = s[i]; + switch (c) { + case '\n': text += "\\n"; break; + case '\t': text += "\\t"; break; + case '\r': text += "\\r"; break; + case '\b': text += "\\b"; break; + case '\f': text += "\\f"; break; + case '\"': text += "\\\""; break; + case '\\': text += "\\\\"; break; + default: + if (c >= ' ' && c <= '~') { + text += c; + } else { + // Not printable ASCII data. Let's see if it's valid UTF-8 first: + const char *utf8 = s + i; + int ucc = FromUTF8(&utf8); + if (ucc < 0) { + if (allow_non_utf8) { + text += "\\x"; + text += IntToStringHex(static_cast(c), 2); + } else { + // There are two cases here: + // + // 1) We reached here by parsing an IDL file. In that case, + // we previously checked for non-UTF-8, so we shouldn't reach + // here. + // + // 2) We reached here by someone calling GenerateText() + // on a previously-serialized flatbuffer. The data might have + // non-UTF-8 Strings, or might be corrupt. + // + // In both cases, we have to give up and inform the caller + // they have no JSON. + return false; + } + } else { + if (natural_utf8) { + // utf8 points to past all utf-8 bytes parsed + text.append(s + i, static_cast(utf8 - s - i)); + } else if (ucc <= 0xFFFF) { + // Parses as Unicode within JSON's \uXXXX range, so use that. + text += "\\u"; + text += IntToStringHex(ucc, 4); + } else if (ucc <= 0x10FFFF) { + // Encode Unicode SMP values to a surrogate pair using two \u + // escapes. + uint32_t base = ucc - 0x10000; + auto high_surrogate = (base >> 10) + 0xD800; + auto low_surrogate = (base & 0x03FF) + 0xDC00; + text += "\\u"; + text += IntToStringHex(high_surrogate, 4); + text += "\\u"; + text += IntToStringHex(low_surrogate, 4); + } + // Skip past characters recognized. + i = static_cast(utf8 - s - 1); + } + } + break; + } + } + text += "\""; + return true; +} + +} // namespace flatbuffers + +#endif // FLATBUFFERS_UTIL_H_ diff --git a/3rdparty/minitrace/LICENSE b/3rdparty/minitrace/LICENSE new file mode 100644 index 000000000..f7469311e --- /dev/null +++ b/3rdparty/minitrace/LICENSE @@ -0,0 +1,21 @@ +The MIT License (MIT) + +Copyright (c) 2014 Henrik RydgÃ¥rd + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, 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: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. \ No newline at end of file diff --git a/3rdparty/minitrace/README.md b/3rdparty/minitrace/README.md new file mode 100644 index 000000000..70e7179ef --- /dev/null +++ b/3rdparty/minitrace/README.md @@ -0,0 +1,103 @@ +minitrace +========= +by Henrik RydgÃ¥rd 2014 (hrydgard+minitrace@gmail.com) + +MIT licensed, feel free to use however you want. If you use it for something cool, I'd love to hear about it! + +This is a C library with C++ helpers for producing JSON traces suitable for Chrome's excellent built-in trace viewer (chrome://tracing). + +Extremely simple to build and use. Tested on Mac and Windows, but should compile anywhere you can use ANSI C with few or no changes. + +Sample output (see example code below): + +![minitrace](http://www.ppsspp.org/img/minitrace.png) + +Remember to be careful when interpreting the output. This is not a sampling profiler, so it only records start and stop times for blocks. This means that blocks grow even when the CPU is off running another thread, and that it can look like work is being done on more blocks at a time than you have CPUs. + + +How to use +---------- + + 1. Include minitrace.c and minitrace.h in your project. #include minitrace.h in some common header. + + 2. In your initialization code: + + mtr_init("trace.json"); + + 3. In your exit code: + + mtr_shutdown(); + + 4. In all functions you want to profile: + + // C + MTR_BEGIN("GFX", "RasterizeTriangle") + ... + MTR_END("GFX", "RasterizeTriangle") + + // C++ + MTR_SCOPE("GFX", "RasterizeTriangle") + + 5. In Google Chrome open "about:tracing" + + 6. Click Open, and choose your trace.json + + 7. Navigate the trace view using the WASD keys, and Look for bottlenecks and optimize your application. + + 8. In your final release build, build with + + -DMTR_DISABLE + + +By default, it will collect 1 million tracepoints and then stop. You can change this behaviour, see the +top of the header file. + +Note: Please only use string literals in MTR statements. + +Example code +------------ + + int main(int argc, const char *argv[]) { + int i; + mtr_init("trace.json"); + + MTR_META_PROCESS_NAME("minitrace_test"); + MTR_META_THREAD_NAME("main thread"); + + int long_running_thing_1; + int long_running_thing_2; + + MTR_START("background", "long_running", &long_running_thing_1); + MTR_START("background", "long_running", &long_running_thing_2); + + MTR_BEGIN("main", "outer"); + usleep(80000); + for (i = 0; i < 3; i++) { + MTR_BEGIN("main", "inner"); + usleep(40000); + MTR_END("main", "inner"); + usleep(10000); + } + MTR_STEP("background", "long_running", &long_running_thing_1, "middle step"); + usleep(80000); + MTR_END("main", "outer"); + + usleep(50000); + MTR_INSTANT("main", "the end"); + usleep(10000); + MTR_FINISH("background", "long_running", &long_running_thing_1); + MTR_FINISH("background", "long_running", &long_running_thing_2); + + mtr_flush(); + mtr_shutdown(); + return 0; + } + +The output will result in something looking a little like the picture at the top of this readme. + +Future plans: + + * Builtin background flush thread support with better synchronization, no more fixed limit + * Support for more trace arguments, more tracing types + +If you use this, feel free to tell me how, and what issues you may have had. hrydgard+minitrace@gmail.com diff --git a/3rdparty/minitrace/minitrace.cpp b/3rdparty/minitrace/minitrace.cpp new file mode 100644 index 000000000..73b46a608 --- /dev/null +++ b/3rdparty/minitrace/minitrace.cpp @@ -0,0 +1,378 @@ +// minitrace +// Copyright 2014 by Henrik RydgÃ¥rd +// http://www.github.com/hrydgard/minitrace +// Released under the MIT license. + +// See minitrace.h for basic documentation. + +#include +#include +#include + +#ifdef _WIN32 +#pragma warning (disable:4996) +#define WIN32_LEAN_AND_MEAN +#include +#define __thread __declspec(thread) +#define pthread_mutex_t CRITICAL_SECTION +#define pthread_mutex_init(a, b) InitializeCriticalSection(a) +#define pthread_mutex_lock(a) EnterCriticalSection(a) +#define pthread_mutex_unlock(a) LeaveCriticalSection(a) +#define pthread_mutex_destroy(a) DeleteCriticalSection(a) +#else +#include +#include +#include +#include +#endif + +#include "minitrace.h" + +#define ARRAY_SIZE(x) sizeof(x)/sizeof(x[0]) + +namespace minitrace { + +// Ugh, this struct is already pretty heavy. +// Will probably need to move arguments to a second buffer to support more than one. +typedef struct raw_event { + const char *name; + const char *cat; + void *id; + int64_t ts; + uint32_t pid; + uint32_t tid; + char ph; + mtr_arg_type arg_type; + const char *arg_name; + union { + const char *a_str; + int a_int; + double a_double; + }; +} raw_event_t; + +static raw_event_t *buffer; +static volatile int count; +static int is_tracing = 0; +static int64_t time_offset; +static int first_line = 1; +static FILE *f; +static __thread int cur_thread_id; // Thread local storage +static pthread_mutex_t mutex; + +#define STRING_POOL_SIZE 100 +static char *str_pool[100]; + +// Tiny portability layer. +// Exposes: +// get_cur_thread_id() +// mtr_time_s() +// pthread basics +#ifdef _WIN32 +static int get_cur_thread_id() { + return (int)GetCurrentThreadId(); +} + +static uint64_t _frequency = 0; +static uint64_t _starttime = 0; + +inline int64_t mtr_time_usec(){ + static int64_t prev = 0; + if (_frequency == 0) { + QueryPerformanceFrequency((LARGE_INTEGER*)&_frequency); + QueryPerformanceCounter((LARGE_INTEGER*)&_starttime); + } + __int64 time; + QueryPerformanceCounter((LARGE_INTEGER*)&time); + int64_t now = 1.0e6 * ((double) (time - _starttime) / (double) _frequency); + if( now <= prev) now = prev + 1; + prev = now; + return now; +} + +// Ctrl+C handling for Windows console apps +static BOOL WINAPI CtrlHandler(DWORD fdwCtrlType) { + if (is_tracing && fdwCtrlType == CTRL_C_EVENT) { + printf("Ctrl-C detected! Flushing trace and shutting down.\n\n"); + mtr_flush(); + mtr_shutdown(); + } + ExitProcess(1); +} + +void mtr_register_sigint_handler() { + // For console apps: + SetConsoleCtrlHandler(&CtrlHandler, TRUE); +} + +#else + +static inline int get_cur_thread_id() { + return (int)(intptr_t)pthread_self(); +} + +#if defined(BLACKBERRY) +inline int64_t mtr_time_usec(){ + static int64_t prev = 0; + struct timespec time; + clock_gettime(CLOCK_MONOTONIC, &time); // Linux must use CLOCK_MONOTONIC_RAW due to time warps + int64_t now = time.tv_sec*1000000 + time.tv_nsec / 1000; + if( now <= prev) now = prev + 1; + prev = now; + return now; +} +#else +int64_t mtr_time_usec() +{ + static int64_t prev = 0; + struct timeval tv; + gettimeofday(&tv, NULL); + int64_t now = 1000000*tv.tv_sec + tv.tv_usec; + if( now <= prev) now = prev + 1; + prev = now; + return now; +} +#endif // !BLACKBERRY + +static void termination_handler(int signum) { + if (is_tracing) { + printf("Ctrl-C detected! Flushing trace and shutting down.\n\n"); + mtr_flush(); + fwrite("\n]}\n", 1, 4, f); + fclose(f); + } + exit(1); +} + +void mtr_register_sigint_handler() { +#ifndef MTR_ENABLED + return; +#endif + // Avoid altering set-to-be-ignored handlers while registering. + if (signal(SIGINT, &termination_handler) == SIG_IGN) + signal(SIGINT, SIG_IGN); +} + +#endif + +void mtr_init(const char *json_file) { +#ifndef MTR_ENABLED + return; +#endif + buffer = (raw_event_t *)malloc(INTERNAL_MINITRACE_BUFFER_SIZE * sizeof(raw_event_t)); + is_tracing = 1; + count = 0; + f = fopen(json_file, "wb"); + const char *header = "{\"traceEvents\":[\n"; + fwrite(header, 1, strlen(header), f); + time_offset = mtr_time_usec(); + first_line = 1; + pthread_mutex_init(&mutex, 0); +} + +void mtr_shutdown() { + int i; +#ifndef MTR_ENABLED + return; +#endif + is_tracing = 0; + mtr_flush(); + fwrite("\n]}\n", 1, 4, f); + fclose(f); + pthread_mutex_destroy(&mutex); + f = 0; + free(buffer); + buffer = 0; + for (i = 0; i < STRING_POOL_SIZE; i++) { + if (str_pool[i]) { + free(str_pool[i]); + str_pool[i] = 0; + } + } +} + +const char *mtr_pool_string(const char *str) { + int i; + for (i = 0; i < STRING_POOL_SIZE; i++) { + if (!str_pool[i]) { + str_pool[i] = (char *)malloc(strlen(str) + 1); + strcpy(str_pool[i], str); + return str_pool[i]; + } else { + if (!strcmp(str, str_pool[i])) + return str_pool[i]; + } + } + return "string pool full"; +} + +void mtr_start() { +#ifndef MTR_ENABLED + return; +#endif + is_tracing = 1; +} + +void mtr_stop() { +#ifndef MTR_ENABLED + return; +#endif + is_tracing = 0; +} + +// TODO: fwrite more than one line at a time. +void mtr_flush() { +#ifndef MTR_ENABLED + return; +#endif + int i = 0; + char linebuf[1024]; + char arg_buf[256]; + char id_buf[256]; + // We have to lock while flushing. So we really should avoid flushing as much as possible. + + + pthread_mutex_lock(&mutex); + int old_tracing = is_tracing; + is_tracing = 0; // Stop logging even if using interlocked increments instead of the mutex. Can cause data loss. + + for (i = 0; i < count; i++) { + raw_event_t *raw = &buffer[i]; + int len; + switch (raw->arg_type) { + case MTR_ARG_TYPE_INT: + snprintf(arg_buf, ARRAY_SIZE(arg_buf), "\"%s\":%i", raw->arg_name, raw->a_int); + break; + case MTR_ARG_TYPE_STRING_CONST: + snprintf(arg_buf, ARRAY_SIZE(arg_buf), "\"%s\":\"%s\"", raw->arg_name, raw->a_str); + break; + case MTR_ARG_TYPE_STRING_COPY: + if (strlen(raw->a_str) > 700) { + ((char*)raw->a_str)[700] = 0; + } + snprintf(arg_buf, ARRAY_SIZE(arg_buf), "\"%s\":\"%s\"", raw->arg_name, raw->a_str); + break; + case MTR_ARG_TYPE_NONE: + default: + arg_buf[0] = '\0'; + break; + } + if (raw->id) { + switch (raw->ph) { + case 'S': + case 'T': + case 'F': + // TODO: Support full 64-bit pointers + snprintf(id_buf, ARRAY_SIZE(id_buf), ",\"id\":\"0x%08x\"", (uint32_t)(uintptr_t)raw->id); + break; + case 'X': + snprintf(id_buf, ARRAY_SIZE(id_buf), ",\"dur\":%i", (int)raw->a_double); + break; + } + } else { + id_buf[0] = 0; + } + const char *cat = raw->cat; +#ifdef _WIN32 + // On Windows, we often end up with backslashes in category. + { + char temp[256]; + int len = (int)strlen(cat); + int i; + if (len > 255) len = 255; + for (i = 0; i < len; i++) { + temp[i] = cat[i] == '\\' ? '/' : cat[i]; + } + temp[len] = 0; + cat = temp; + } +#endif + + len = snprintf(linebuf, ARRAY_SIZE(linebuf), "%s{\"cat\":\"%s\",\"pid\":%i,\"tid\":%i,\"ts\":%" PRId64 ",\"ph\":\"%c\",\"name\":\"%s\",\"args\":{%s}%s}", + first_line ? "" : ",\n", + cat, raw->pid, raw->tid, raw->ts - time_offset, raw->ph, raw->name, arg_buf, id_buf); + fwrite(linebuf, 1, len, f); + first_line = 0; + } + count = 0; + is_tracing = old_tracing; + pthread_mutex_unlock(&mutex); +} + +void internal_mtr_raw_event(const char *category, const char *name, char ph, void *id) { +#ifndef MTR_ENABLED + return; +#endif + if (!is_tracing || count >= INTERNAL_MINITRACE_BUFFER_SIZE) + return; + int64_t ts = mtr_time_usec(); + if (!cur_thread_id) { + cur_thread_id = get_cur_thread_id(); + } + +#if 0 && _WIN32 // TODO: This needs testing + int bufPos = InterlockedIncrement(&count); + raw_event_t *ev = &buffer[count - 1]; +#else + pthread_mutex_lock(&mutex); + raw_event_t *ev = &buffer[count]; + count++; + pthread_mutex_unlock(&mutex); +#endif + + ev->cat = category; + ev->name = name; + ev->id = id; + ev->ph = ph; + if (ev->ph == 'X') { + int64_t x; + memcpy(&x, id, sizeof(int64_t)); + ev->ts = x; + ev->a_double = (ts - x); + } else { + ev->ts = ts; + } + ev->tid = cur_thread_id; + ev->pid = 0; +} + +void internal_mtr_raw_event_arg(const char *category, const char *name, char ph, void *id, mtr_arg_type arg_type, const char *arg_name, void *arg_value) { +#ifndef MTR_ENABLED + return; +#endif + if (!is_tracing || count >= INTERNAL_MINITRACE_BUFFER_SIZE) + return; + if (!cur_thread_id) { + cur_thread_id = get_cur_thread_id(); + } + int64_t ts = mtr_time_usec(); + +#if 0 && _WIN32 // TODO: This needs testing + int bufPos = InterlockedIncrement(&count); + raw_event_t *ev = &buffer[count - 1]; +#else + pthread_mutex_lock(&mutex); + raw_event_t *ev = &buffer[count]; + count++; + pthread_mutex_unlock(&mutex); +#endif + + ev->cat = category; + ev->name = name; + ev->id = id; + ev->ts = ts; + ev->ph = ph; + ev->tid = cur_thread_id; + ev->pid = 0; + ev->arg_type = arg_type; + ev->arg_name = arg_name; + switch (arg_type) { + case MTR_ARG_TYPE_INT: ev->a_int = (int)(uintptr_t)arg_value; break; + case MTR_ARG_TYPE_STRING_CONST: ev->a_str = (const char*)arg_value; break; + case MTR_ARG_TYPE_STRING_COPY: ev->a_str = strdup((const char*)arg_value); break; + default: + break; + } +} + +} diff --git a/3rdparty/minitrace/minitrace.h b/3rdparty/minitrace/minitrace.h new file mode 100644 index 000000000..628b16119 --- /dev/null +++ b/3rdparty/minitrace/minitrace.h @@ -0,0 +1,267 @@ +#ifndef MINITRACE_H +#define MINITRACE_H + +// Minitrace +// +// Copyright 2014 by Henrik RydgÃ¥rd +// http://www.github.com/hrydgard/minitrace +// Released under the MIT license. +// +// Ultra-light dependency free library for performance tracing C/C++ applications. +// Produces traces compatible with Google Chrome's trace viewer. +// Simply open "about:tracing" in Chrome and load the produced JSON. +// +// This contains far less template magic than the original libraries from Chrome +// because this is meant to be usable from C. +// +// See README.md for a tutorial. +// +// The trace format is documented here: +// https://docs.google.com/document/d/1CvAClvFfyA5R-PhYUmn5OOQtYMH4h6I0nSsKchNAySU/edit +// More: +// http://www.altdevblogaday.com/2012/08/21/using-chrometracing-to-view-your-inline-profiling-data/ + +#include + +#define MTR_ENABLED + +// If MTR_ENABLED is not defined, Minitrace does nothing and has near zero overhead. +// Preferably, set this flag in your build system. If you can't just uncomment this line. +// #define MTR_ENABLED + +// By default, will collect up to 1000000 events, then you must flush. +// It's recommended that you simply call mtr_flush on a background thread +// occasionally. It's safe...ish. +#define INTERNAL_MINITRACE_BUFFER_SIZE 1000000 + +//#define MTR_ENABLED + +namespace minitrace { + +// Initializes Minitrace. Must be called very early during startup of your executable, +// before any MTR_ statements.. +void mtr_init(const char *json_file); + +// Shuts down minitrace cleanly, flushing the trace buffer. +void mtr_shutdown(); + +// Lets you enable and disable Minitrace at runtime. +// May cause strange discontinuities in the output. +// Minitrace is enabled on startup by default. +void mtr_start(); +void mtr_stop(); + +// Flushes the collected data to disk, clearing the buffer for new data. +void mtr_flush(); + +// Returns the current time in seconds. Used internally by Minitrace. No caching. +int64_t mtr_time_usec(); + +// Registers a handler that will flush the trace on Ctrl+C. +// Works on Linux and MacOSX, and in Win32 console applications. +void mtr_register_sigint_handler(); + +// Utility function that should rarely be used. +// If str is semi dynamic, store it permanently in a small pool so we don't need to malloc it. +// The pool fills up fast though and performance isn't great. +// Returns a fixed string if the pool is full. +const char *mtr_pool_string(const char *str); + +// Commented-out types will be supported in the future. +typedef enum { + MTR_ARG_TYPE_NONE = 0, + MTR_ARG_TYPE_INT = 1, // I + // MTR_ARG_TYPE_FLOAT = 2, // TODO + // MTR_ARG_TYPE_DOUBLE = 3, // TODO + MTR_ARG_TYPE_STRING_CONST = 8, // C + MTR_ARG_TYPE_STRING_COPY = 9, + // MTR_ARG_TYPE_JSON_COPY = 10, +} mtr_arg_type; + +// TODO: Add support for more than one argument (metadata) per event +// Having more costs speed and memory. +#define MTR_MAX_ARGS 1 + +// Only use the macros to call these. +void internal_mtr_raw_event(const char *category, const char *name, char ph, void *id); +void internal_mtr_raw_event_arg(const char *category, const char *name, char ph, void *id, mtr_arg_type arg_type, const char *arg_name, void *arg_value); + +#ifdef MTR_ENABLED + +// c - category. Can be filtered by in trace viewer (or at least that's the intention). +// A good use is to pass __FILE__, there are macros further below that will do it for you. +// n - name. Pass __FUNCTION__ in most cases, unless you are marking up parts of one. + +// Scopes. In C++, use MTR_SCOPE. In C, always match them within the same scope. +#define MTR_BEGIN(c, n) internal_mtr_raw_event(c, n, 'B', 0) +#define MTR_END(c, n) internal_mtr_raw_event(c, n, 'E', 0) +#define MTR_SCOPE(c, n) MTRScopedTrace ____mtr_scope(c, n) +#define MTR_SCOPE_LIMIT(c, n, l) MTRScopedTraceLimit ____mtr_scope(c, n, l) + +// Async events. Can span threads. ID identifies which events to connect in the view. +#define MTR_START(c, n, id) internal_mtr_raw_event(c, n, 'S', (void *)(id)) +#define MTR_STEP(c, n, id, step) internal_mtr_raw_event_arg(c, n, 'T', (void *)(id), MTR_ARG_TYPE_STRING_CONST, "step", (void *)(step)) +#define MTR_FINISH(c, n, id) internal_mtr_raw_event(c, n, 'F', (void *)(id)) + +// Flow events. Like async events, but displayed in a more fancy way in the viewer. +#define MTR_FLOW_START(c, n, id) internal_mtr_raw_event(c, n, 's', (void *)(id)) +#define MTR_FLOW_STEP(c, n, id, step) internal_mtr_raw_event_arg(c, n, 't', (void *)(id), MTR_ARG_TYPE_STRING_CONST, "step", (void *)(step)) +#define MTR_FLOW_FINISH(c, n, id) internal_mtr_raw_event(c, n, 'f', (void *)(id)) + +// The same macros, but with a single named argument which shows up as metadata in the viewer. +// _I for int. +// _C is for a const string arg. +// _S will copy the string, freeing on flush (expensive but sometimes necessary). +// but required if the string was generated dynamically. + +// Note that it's fine to match BEGIN_S with END and BEGIN with END_S, etc. +#define MTR_BEGIN_C(c, n, aname, astrval) internal_mtr_raw_event_arg(c, n, 'B', 0, MTR_ARG_TYPE_STRING_CONST, aname, (void *)(astrval)) +#define MTR_END_C(c, n, aname, astrval) internal_mtr_raw_event_arg(c, n, 'E', 0, MTR_ARG_TYPE_STRING_CONST, aname, (void *)(astrval)) +#define MTR_SCOPE_C(c, n, aname, astrval) MTRScopedTraceArg ____mtr_scope(c, n, MTR_ARG_TYPE_STRING_CONST, aname, (void *)(astrval)) + +#define MTR_BEGIN_S(c, n, aname, astrval) internal_mtr_raw_event_arg(c, n, 'B', 0, MTR_ARG_TYPE_STRING_COPY, aname, (void *)(astrval)) +#define MTR_END_S(c, n, aname, astrval) internal_mtr_raw_event_arg(c, n, 'E', 0, MTR_ARG_TYPE_STRING_COPY, aname, (void *)(astrval)) +#define MTR_SCOPE_S(c, n, aname, astrval) MTRScopedTraceArg ____mtr_scope(c, n, MTR_ARG_TYPE_STRING_COPY, aname, (void *)(astrval)) + +#define MTR_BEGIN_I(c, n, aname, aintval) internal_mtr_raw_event_arg(c, n, 'B', 0, MTR_ARG_TYPE_INT, aname, (void*)(intptr_t)(aintval)) +#define MTR_END_I(c, n, aname, aintval) internal_mtr_raw_event_arg(c, n, 'E', 0, MTR_ARG_TYPE_INT, aname, (void*)(intptr_t)(aintval)) +#define MTR_SCOPE_I(c, n, aname, aintval) MTRScopedTraceArg ____mtr_scope(c, n, MTR_ARG_TYPE_INT, aname, (void*)(intptr_t)(aintval)) + +// Instant events. For things with no duration. +#define MTR_INSTANT(c, n) internal_mtr_raw_event(c, n, 'I', 0) +#define MTR_INSTANT_C(c, n, aname, astrval) internal_mtr_raw_event(c, n, 'I', 0, MTR_ARG_TYPE_STRING_CONST, aname, (void *)(astrval)) +#define MTR_INSTANT_I(c, n, aname, aintval) internal_mtr_raw_event(c, n, 'I', 0, MTR_ARG_TYPE_INT, aname, (void *)(aintval)) + +// Counters (can't do multi-value counters yet) +#define MTR_COUNTER(c, n, val) internal_mtr_raw_event_arg(c, n, 'C', 0, MTR_ARG_TYPE_INT, n, (void *)(intptr_t)(val)) + +// Metadata. Call at the start preferably. Must be const strings. + +#define MTR_META_PROCESS_NAME(n) internal_mtr_raw_event_arg("", "process_name", 'M', 0, MTR_ARG_TYPE_STRING_COPY, "name", (void *)(n)) +#define MTR_META_THREAD_NAME(n) internal_mtr_raw_event_arg("", "thread_name", 'M', 0, MTR_ARG_TYPE_STRING_COPY, "name", (void *)(n)) +#define MTR_META_THREAD_SORT_INDEX(i) internal_mtr_raw_event_arg("", "thread_sort_index", 'M', 0, MTR_ARG_TYPE_INT, "sort_index", (void *)(i)) + +#else + +#define MTR_BEGIN(c, n) +#define MTR_END(c, n) +#define MTR_SCOPE(c, n) +#define MTR_START(c, n, id) +#define MTR_STEP(c, n, id, step) +#define MTR_FINISH(c, n, id) +#define MTR_FLOW_START(c, n, id) +#define MTR_FLOW_STEP(c, n, id, step) +#define MTR_FLOW_FINISH(c, n, id) +#define MTR_INSTANT(c, n) + +#define MTR_BEGIN_C(c, n, aname, astrval) +#define MTR_END_C(c, n, aname, astrval) +#define MTR_SCOPE_C(c, n, aname, astrval) + +#define MTR_BEGIN_S(c, n, aname, astrval) +#define MTR_END_S(c, n, aname, astrval) +#define MTR_SCOPE_S(c, n, aname, astrval) + +#define MTR_BEGIN_I(c, n, aname, aintval) +#define MTR_END_I(c, n, aname, aintval) +#define MTR_SCOPE_I(c, n, aname, aintval) + +#define MTR_INSTANT(c, n) +#define MTR_INSTANT_C(c, n, aname, astrval) +#define MTR_INSTANT_I(c, n, aname, aintval) + +// Counters (can't do multi-value counters yet) +#define MTR_COUNTER(c, n, val) + +// Metadata. Call at the start preferably. Must be const strings. + +#define MTR_META_PROCESS_NAME(n) + +#define MTR_META_THREAD_NAME(n) +#define MTR_META_THREAD_SORT_INDEX(i) + +#endif + +// Shortcuts for simple function timing with automatic categories and names. + +#define MTR_BEGIN_FUNC() MTR_BEGIN(__FILE__, __FUNCTION__) +#define MTR_END_FUNC() MTR_END(__FILE__, __FUNCTION__) +#define MTR_SCOPE_FUNC() MTR_SCOPE(__FILE__, __FUNCTION__) +#define MTR_INSTANT_FUNC() MTR_INSTANT(__FILE__, __FUNCTION__) +#define MTR_SCOPE_FUNC_LIMIT_S(l) MTRScopedTraceLimit ____mtr_scope(__FILE__, __FUNCTION__, l) +#define MTR_SCOPE_FUNC_LIMIT_MS(l) MTRScopedTraceLimit ____mtr_scope(__FILE__, __FUNCTION__, 1) + +// Same, but with a single argument of the usual types. +#define MTR_BEGIN_FUNC_S(aname, arg) MTR_BEGIN_S(__FILE__, __FUNCTION__, aname, arg) +#define MTR_END_FUNC_S(aname, arg) MTR_END_S(__FILE__, __FUNCTION__, aname, arg) +#define MTR_SCOPE_FUNC_S(aname, arg) MTR_SCOPE_S(__FILE__, __FUNCTION__, aname, arg) + +#define MTR_BEGIN_FUNC_C(aname, arg) MTR_BEGIN_C(__FILE__, __FUNCTION__, aname, arg) +#define MTR_END_FUNC_C(aname, arg) MTR_END_C(__FILE__, __FUNCTION__, aname, arg) +#define MTR_SCOPE_FUNC_C(aname, arg) MTR_SCOPE_C(__FILE__, __FUNCTION__, aname, arg) + +#define MTR_BEGIN_FUNC_I(aname, arg) MTR_BEGIN_I(__FILE__, __FUNCTION__, aname, arg) +#define MTR_END_FUNC_I(aname, arg) MTR_END_I(__FILE__, __FUNCTION__, aname, arg) +#define MTR_SCOPE_FUNC_I(aname, arg) MTR_SCOPE_I(__FILE__, __FUNCTION__, aname, arg) + + +#ifdef MTR_ENABLED +// These are optimized to use X events (combined B and E). Much easier to do in C++ than in C. +class MTRScopedTrace { +public: + MTRScopedTrace(const char *category, const char *name) + : category_(category), name_(name) { + start_time_ = mtr_time_usec(); + } + ~MTRScopedTrace() { + internal_mtr_raw_event(category_, name_, 'X', &start_time_); + } + +private: + const char *category_; + const char *name_; + int64_t start_time_; +}; + +// Only outputs a block if execution time exceeded the limit. +// TODO: This will effectively call mtr_time_usec twice at the end, which is bad. +class MTRScopedTraceLimit { +public: + MTRScopedTraceLimit(const char *category, const char *name, double limit_s) + : category_(category), name_(name), limit_(limit_s) { + start_time_ = mtr_time_usec(); + } + ~MTRScopedTraceLimit() { + int64_t end_time = mtr_time_usec(); + if (end_time - start_time_ >= limit_) { + internal_mtr_raw_event(category_, name_, 'X', &start_time_); + } + } + +private: + const char *category_; + const char *name_; + double start_time_; + double limit_; +}; + +class MTRScopedTraceArg { +public: + MTRScopedTraceArg(const char *category, const char *name, mtr_arg_type arg_type, const char *arg_name, void *arg_value) + : category_(category), name_(name) { + internal_mtr_raw_event_arg(category, name, 'B', 0, arg_type, arg_name, arg_value); + } + ~MTRScopedTraceArg() { + internal_mtr_raw_event(category_, name_, 'E', 0); + } + +private: + const char *category_; + const char *name_; +}; + +#endif + +} //end namespace + +#endif diff --git a/cmake/FindZMQ.cmake b/cmake/FindZMQ.cmake new file mode 100644 index 000000000..b0ae5dda9 --- /dev/null +++ b/cmake/FindZMQ.cmake @@ -0,0 +1,59 @@ +# - Try to find ZMQ +# Once done this will define +# +# ZMQ_FOUND - system has ZMQ +# ZMQ_INCLUDE_DIRS - the ZMQ include directory +# ZMQ_LIBRARIES - Link these to use ZMQ +# ZMQ_DEFINITIONS - Compiler switches required for using ZMQ +# +# Copyright (c) 2011 Lee Hambley +# +# Redistribution and use is allowed according to the terms of the New +# BSD license. +# For details see the accompanying COPYING-CMAKE-SCRIPTS file. +# + +if (ZMQ_LIBRARIES AND ZMQ_INCLUDE_DIRS) + # in cache already + set(ZMQ_FOUND TRUE) +else (ZMQ_LIBRARIES AND ZMQ_INCLUDE_DIRS) + + find_path(ZMQ_INCLUDE_DIR + NAMES + zmq.h + PATHS + /usr/include + /usr/local/include + /opt/local/include + /sw/include + ) + + find_library(ZMQ_LIBRARY + NAMES + zmq + PATHS + /usr/lib + /usr/local/lib + /opt/local/lib + /sw/lib + ) + + set(ZMQ_INCLUDE_DIRS + ${ZMQ_INCLUDE_DIR} + ) + + if (ZMQ_LIBRARY) + set(ZMQ_LIBRARIES + ${ZMQ_LIBRARIES} + ${ZMQ_LIBRARY} + ) + endif (ZMQ_LIBRARY) + + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(ZMQ DEFAULT_MSG ZMQ_LIBRARIES ZMQ_INCLUDE_DIRS) + + # show the ZMQ_INCLUDE_DIRS and ZMQ_LIBRARIES variables only in the advanced view + mark_as_advanced(ZMQ_INCLUDE_DIRS ZMQ_LIBRARIES) + +endif (ZMQ_LIBRARIES AND ZMQ_INCLUDE_DIRS) + From ab678f5d4f1b7b75da4c0fc0af982f928a202efa Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 30 May 2018 15:14:37 +0200 Subject: [PATCH 070/125] xml parsing didn't handle Conditions --- include/behavior_tree_core/xml_parsing.h | 2 +- src/xml_parsing.cpp | 16 +++++++++++++++- 2 files changed, 16 insertions(+), 2 deletions(-) diff --git a/include/behavior_tree_core/xml_parsing.h b/include/behavior_tree_core/xml_parsing.h index 29eaa52d2..a9ba06e78 100644 --- a/include/behavior_tree_core/xml_parsing.h +++ b/include/behavior_tree_core/xml_parsing.h @@ -50,7 +50,7 @@ inline NodePtr XMLParser::treeParsing(const tinyxml2::XMLElement* root_element, NodeParameters node_params; // Actions and Decorators have their own ID - if (element_name == "Action" || element_name == "Decorator") + if (element_name == "Action" || element_name == "Decorator" || element_name == "Condition") { node_ID = element->Attribute("ID"); } diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 019ad8fb5..041bcd1ab 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -83,7 +83,10 @@ bool XMLParser::verifyXML(std::vector& error_messages) const for (auto node = xml_root->FirstChildElement(); node != nullptr; node = node->NextSiblingElement()) { const char* name = node->Name(); - if (strEqual(name, "Action") || strEqual(name, "Decorator") || strEqual(name, "SubTree")) + if (strEqual(name, "Action") || + strEqual(name, "Decorator") || + strEqual(name, "SubTree") || + strEqual(name, "Condition")) { const char* ID = node->Attribute("ID"); if (!ID) @@ -135,6 +138,17 @@ bool XMLParser::verifyXML(std::vector& error_messages) const AppendError(node->GetLineNum(), "The node must have the attribute [ID]"); } } + else if (strEqual(name, "Condition")) + { + if (children_count != 0) + { + AppendError(node->GetLineNum(), "The node must not have any child"); + } + if (!node->Attribute("ID")) + { + AppendError(node->GetLineNum(), "The node must have the attribute [ID]"); + } + } else if (strEqual(name, "Sequence") || strEqual(name, "SequenceStar") || strEqual(name, "Fallback") || strEqual(name, "FallbackStar")) { From 1eebb19feca351d65225c3b16badd0f4e4712bc4 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 30 May 2018 15:45:18 +0200 Subject: [PATCH 071/125] loggers cornucopia --- 3rdparty/minitrace/minitrace.cpp | 21 +- CMakeLists.txt | 37 ++- gtest/crossdoor_example.cpp | 61 +++-- gtest/gtest_tree.cpp | 6 +- gtest/include/crossdoor_dummy_nodes.h | 12 +- gtest/simple_example.cpp | 104 +++++++++ include/behavior_tree_core/tree_node.h | 12 +- include/behavior_tree_logger/BT_logger.fbs | 42 ++-- .../BT_logger_generated.h | 217 ++++++++---------- .../behavior_tree_logger/abstract_logger.h | 15 +- include/behavior_tree_logger/bt_cout_logger.h | 26 ++- include/behavior_tree_logger/bt_file_logger.h | 40 ++++ .../bt_flatbuffer_helper.h | 107 +++++++++ .../bt_minitrace_logger.h | 73 ++++++ .../behavior_tree_logger/bt_zmq_publisher.h | 46 ++++ src/bt_factory.cpp | 4 +- src/bt_file_logger.cpp | 73 ++++++ src/bt_zmq_publisher.cpp | 127 ++++++++++ src/decorator_negation_node.cpp | 2 + src/tree_node.cpp | 15 +- tools/bt_log_cat.cpp | 99 ++++++++ tools/bt_recorder.cpp | 99 ++++++++ 22 files changed, 1035 insertions(+), 203 deletions(-) create mode 100644 gtest/simple_example.cpp create mode 100644 include/behavior_tree_logger/bt_file_logger.h create mode 100644 include/behavior_tree_logger/bt_flatbuffer_helper.h create mode 100644 include/behavior_tree_logger/bt_minitrace_logger.h create mode 100644 include/behavior_tree_logger/bt_zmq_publisher.h create mode 100644 src/bt_file_logger.cpp create mode 100644 src/bt_zmq_publisher.cpp create mode 100644 tools/bt_log_cat.cpp create mode 100644 tools/bt_recorder.cpp diff --git a/3rdparty/minitrace/minitrace.cpp b/3rdparty/minitrace/minitrace.cpp index 73b46a608..d3c832207 100644 --- a/3rdparty/minitrace/minitrace.cpp +++ b/3rdparty/minitrace/minitrace.cpp @@ -56,7 +56,7 @@ static volatile int count; static int is_tracing = 0; static int64_t time_offset; static int first_line = 1; -static FILE *f; +static FILE *file; static __thread int cur_thread_id; // Thread local storage static pthread_mutex_t mutex; @@ -138,8 +138,8 @@ static void termination_handler(int signum) { if (is_tracing) { printf("Ctrl-C detected! Flushing trace and shutting down.\n\n"); mtr_flush(); - fwrite("\n]}\n", 1, 4, f); - fclose(f); + fwrite("\n]}\n", 1, 4, file); + fclose(file); } exit(1); } @@ -162,10 +162,10 @@ void mtr_init(const char *json_file) { buffer = (raw_event_t *)malloc(INTERNAL_MINITRACE_BUFFER_SIZE * sizeof(raw_event_t)); is_tracing = 1; count = 0; - f = fopen(json_file, "wb"); + file = fopen(json_file, "wb"); const char *header = "{\"traceEvents\":[\n"; - fwrite(header, 1, strlen(header), f); - time_offset = mtr_time_usec(); + fwrite(header, 1, strlen(header), file); + time_offset = mtr_time_usec(); first_line = 1; pthread_mutex_init(&mutex, 0); } @@ -177,10 +177,10 @@ void mtr_shutdown() { #endif is_tracing = 0; mtr_flush(); - fwrite("\n]}\n", 1, 4, f); - fclose(f); + fwrite("\n]}\n", 1, 4, file); + fclose(file); pthread_mutex_destroy(&mutex); - f = 0; + file = 0; free(buffer); buffer = 0; for (i = 0; i < STRING_POOL_SIZE; i++) { @@ -291,7 +291,8 @@ void mtr_flush() { len = snprintf(linebuf, ARRAY_SIZE(linebuf), "%s{\"cat\":\"%s\",\"pid\":%i,\"tid\":%i,\"ts\":%" PRId64 ",\"ph\":\"%c\",\"name\":\"%s\",\"args\":{%s}%s}", first_line ? "" : ",\n", cat, raw->pid, raw->tid, raw->ts - time_offset, raw->ph, raw->name, arg_buf, id_buf); - fwrite(linebuf, 1, len, f); + fwrite(linebuf, 1, len, file); + fflush(file); first_line = 0; } count = 0; diff --git a/CMakeLists.txt b/CMakeLists.txt index c9935e434..42b349885 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,9 +2,13 @@ cmake_minimum_required(VERSION 2.8) project(behavior_tree_core) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11 -pthread -Werror=return-type") +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake") ############################################################# # http://answers.ros.org/question/230877/optionally-build-a-package-with-catkin/ +# +# This variable MUST NOT be set by the user manually, it will be detected +# automatically if you compile using catkin if( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) set(catkin_FOUND 1) add_definitions( -DUSING_ROS ) @@ -56,10 +60,26 @@ set(BT_Source src/behavior_tree.cpp src/xml_parsing.cpp + src/bt_file_logger.cpp 3rdparty/tinyXML2/tinyxml2.cpp + + 3rdparty/minitrace/minitrace.cpp ) include_directories(include 3rdparty/) +set(BEHAVIOR_TRE_LIBRARIES behavior_tree_core) + +find_package(ZMQ) + +if( ZMQ_FOUND ) + message(STATUS "ZeroMQ found.") + add_definitions( -DZMQ_FOUND ) + set(BT_Source ${BT_Source} src/bt_zmq_publisher.cpp ) + + set(BEHAVIOR_TRE_LIBRARIES behavior_tree_core zmq) +else() + message(WARNING "ZeroMQ NOT found. Skipping the build of [PublisherZMQ] and [bt_recorder].") +endif() ###################################################### # COMPILING LIBRARY @@ -97,13 +117,24 @@ elseif(GTEST_FOUND) endif() ###################################################### -# COMPILING EXAMPLES +# COMPILING EXAMPLES and TOOLS ###################################################### add_executable(crossdoor_example gtest/crossdoor_example.cpp ) -target_link_libraries(crossdoor_example - behavior_tree_core ) +target_link_libraries(crossdoor_example ${BEHAVIOR_TRE_LIBRARIES} ) + +add_executable(bt_log_cat tools/bt_log_cat.cpp ) +target_link_libraries(bt_log_cat behavior_tree_core ) + +if( ZMQ_FOUND ) + add_executable(bt_recorder tools/bt_recorder.cpp ) + target_link_libraries(bt_recorder ${BEHAVIOR_TRE_LIBRARIES} ) +endif() + +add_executable(simple_example gtest/simple_example.cpp ) +target_link_libraries(simple_example ${BEHAVIOR_TRE_LIBRARIES} ) + ###################################################### # INSTALLATION OF LIBRARY AND EXECUTABLE diff --git a/gtest/crossdoor_example.cpp b/gtest/crossdoor_example.cpp index 26c0af9fc..8b79519cf 100644 --- a/gtest/crossdoor_example.cpp +++ b/gtest/crossdoor_example.cpp @@ -1,37 +1,43 @@ #include "crossdoor_dummy_nodes.h" #include "behavior_tree_core/xml_parsing.h" #include "behavior_tree_logger/bt_cout_logger.h" +#include "behavior_tree_logger/bt_minitrace_logger.h" +#include "behavior_tree_logger/bt_file_logger.h" + +#ifdef ZMQ_FOUND + #include "behavior_tree_logger/bt_zmq_publisher.h" +#endif // clang-format off const std::string xml_text = R"( - + - - + + - - - - + + + + - - - - - - - - + + + + + + + + - + - - + + - - )"; + + )"; // clang-format on @@ -42,7 +48,7 @@ int main(int argc, char** argv) BT::BehaviorTreeFactory factory; // register all the actions into the factory - CrossDoor cross_door(factory); + CrossDoor cross_door(factory, false); XMLParser parser; parser.loadFromText(xml_text); @@ -50,14 +56,23 @@ int main(int argc, char** argv) std::vector nodes; BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); - StdCoutLogger logger(root_node.get()); + StdCoutLogger logger_cout(root_node.get()); + MinitraceLogger logger_minitrace(root_node.get(), "bt_trace.json"); + FileLogger logger_file( root_node.get(), "bt_trace.fbl", 32 ); + +#ifdef ZMQ_FOUND + PublisherZMQ publisher_zmq(root_node.get()); +#endif cross_door.CloseDoor(); std::cout << "---------------" << std::endl; root_node->executeTick(); + + std::this_thread::sleep_for( std::chrono::milliseconds(100) ); + std::cout << "---------------" << std::endl; - root_node->executeTick(); + while(1) root_node->executeTick(); std::cout << "---------------" << std::endl; return 0; } diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 34a3867a4..54f77a440 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -396,19 +396,19 @@ TEST_F(SequenceTripleActionTest, TripleAction) bool done_1 = false, done_2 = false, done_3 = false; auto sub1 = action_1.subscribeToStatusChange( - [&done_1](const TreeNode& , NodeStatus,NodeStatus status) + [&done_1](TimePoint, const TreeNode& , NodeStatus,NodeStatus status) { if( status == NodeStatus::SUCCESS) done_1 = true; }); auto sub2 = action_2.subscribeToStatusChange( - [&done_2](const TreeNode& , NodeStatus,NodeStatus status) + [&done_2](TimePoint, const TreeNode& , NodeStatus,NodeStatus status) { if( status == NodeStatus::SUCCESS) done_2 = true; }); auto sub3 = action_3.subscribeToStatusChange( - [&done_3](const TreeNode& , NodeStatus,NodeStatus status) + [&done_3](TimePoint, const TreeNode& , NodeStatus,NodeStatus status) { if( status == NodeStatus::SUCCESS) done_3 = true; }); diff --git a/gtest/include/crossdoor_dummy_nodes.h b/gtest/include/crossdoor_dummy_nodes.h index d520aabec..159bf0078 100644 --- a/gtest/include/crossdoor_dummy_nodes.h +++ b/gtest/include/crossdoor_dummy_nodes.h @@ -4,8 +4,9 @@ using namespace BT; class CrossDoor { + int _multiplier; public: - CrossDoor(BT::BehaviorTreeFactory& factory) + CrossDoor(BT::BehaviorTreeFactory& factory, bool fast = true) { door_open_ = true; door_locked_ = false; @@ -17,36 +18,44 @@ class CrossDoor factory.registerSimpleAction("CloseDoor", [this]() { return CloseDoor(); }); factory.registerSimpleAction("IsDoorLocked", [this]() { return IsDoorLocked(); }); factory.registerSimpleAction("UnlockDoor", [this]() { return UnlockDoor(); }); + + _multiplier = fast ? 1 : 10; } BT::NodeStatus IsDoorOpen() { + std::this_thread::sleep_for( std::chrono::milliseconds(50) * _multiplier ); return door_open_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } BT::NodeStatus IsDoorLocked() { + std::this_thread::sleep_for( std::chrono::milliseconds(50) * _multiplier ); return door_locked_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } BT::NodeStatus UnlockDoor() { + std::this_thread::sleep_for( std::chrono::milliseconds(200) * _multiplier ); door_locked_ = false; return NodeStatus::SUCCESS; } BT::NodeStatus PassThroughDoor() { + std::this_thread::sleep_for( std::chrono::milliseconds(100) * _multiplier ); return door_open_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } BT::NodeStatus PassThroughWindow() { + std::this_thread::sleep_for( std::chrono::milliseconds(100) * _multiplier ); return NodeStatus::SUCCESS; } BT::NodeStatus OpenDoor() { + std::this_thread::sleep_for( std::chrono::milliseconds(200) * _multiplier ); if (door_locked_) return NodeStatus::FAILURE; door_open_ = true; @@ -55,6 +64,7 @@ class CrossDoor BT::NodeStatus CloseDoor() { + std::this_thread::sleep_for( std::chrono::milliseconds(150) * _multiplier ); if (door_open_) { door_open_ = false; diff --git a/gtest/simple_example.cpp b/gtest/simple_example.cpp new file mode 100644 index 000000000..c5bcbfb88 --- /dev/null +++ b/gtest/simple_example.cpp @@ -0,0 +1,104 @@ +#include "behavior_tree_core/xml_parsing.h" +#include "behavior_tree_logger/bt_cout_logger.h" +#include "behavior_tree_logger/bt_file_logger.h" + +// clang-format off + +class BatteryCondition: public BT::ConditionNode +{ +public: + BatteryCondition(const std::string& name): BT::ConditionNode(name) {} + BT::NodeStatus tick() override { + std::cout << "[ Battery: OK ]" << std::endl; + return BT::NodeStatus::SUCCESS; } +}; + +class TemperatureCondition: public BT::ConditionNode +{ +public: + TemperatureCondition(const std::string& name): BT::ConditionNode(name) {} + BT::NodeStatus tick() override { + std::cout << "[ Temperature: OK ]" << std::endl; + return BT::NodeStatus::SUCCESS; } +}; + +class MoveAction: public BT::ActionNode +{ +public: + MoveAction(const std::string& name): BT::ActionNode(name) {} + BT::NodeStatus tick() override { + std::cout << "[ Move: started ]" << std::endl; + std::this_thread::sleep_for( std::chrono::milliseconds(80) ); + std::cout << "[ Move: finished ]" << std::endl; + return BT::NodeStatus::SUCCESS; + } +}; + + +const std::string xml_text_A = R"( + + + + + + + + + + + + + + + )"; + +const std::string xml_text_B = R"( + + + + + + + + + + + + + )"; + + +// clang-format on + +int main(int argc, char** argv) +{ + using namespace BT; + + BT::BehaviorTreeFactory factory; + factory.registerNodeType("TemperatureOK"); + factory.registerNodeType("BatteryOK"); + factory.registerNodeType("Move"); + + XMLParser parser; + parser.loadFromText(xml_text_A); + + std::vector nodes; + BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); + + StdCoutLogger logger_cout(root_node.get()); + FileLogger file_file( root_node.get(), "simple_trace.fbl", 32 ); + + + std::cout << "\n------- First executeTick() --------" << std::endl; + root_node->executeTick(); + std::cout << "\n------- sleep --------" << std::endl; + std::this_thread::sleep_for( std::chrono::milliseconds(50) ); + std::cout << "\n------- Second executeTick() --------" << std::endl; + root_node->executeTick(); + std::cout << "\n------- sleep --------" << std::endl; + std::this_thread::sleep_for( std::chrono::milliseconds(50) ); + std::cout << "\n------- Third executeTick() --------" << std::endl; + root_node->executeTick(); + std::cout << std::endl; + return 0; +} diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index dd366ce53..39f903af8 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -90,6 +90,8 @@ enum SuccessPolicy // used to parametrize an object. It is up to the user's code to parse the string. typedef std::map NodeParameters; +typedef std::chrono::high_resolution_clock::time_point TimePoint; + // Abstract base class for Behavior Tree Nodes class TreeNode { @@ -106,7 +108,7 @@ class TreeNode virtual BT::NodeStatus tick() = 0; public: - // The constructor and the distructor + // The constructor and the destructor TreeNode(std::string name); virtual ~TreeNode() = default; @@ -128,7 +130,7 @@ class TreeNode virtual NodeType type() const = 0; - using StatusChangeSignal = Signal; + using StatusChangeSignal = Signal; using StatusChangeSubscriber = StatusChangeSignal::Subscriber; using StatusChangeCallback = StatusChangeSignal::CallableFunction; @@ -146,12 +148,18 @@ class TreeNode // get an unique identifier of this instance of treeNode uint16_t UID() const; + void setRegistrationName(const std::string& registration_name); + + const std::string& registrationName() const; + private: StatusChangeSignal state_change_signal_; const uint16_t _uid; + std::string _registration_name; + }; typedef std::shared_ptr TreeNodePtr; diff --git a/include/behavior_tree_logger/BT_logger.fbs b/include/behavior_tree_logger/BT_logger.fbs index 2fbbcba77..523f1d2cc 100644 --- a/include/behavior_tree_logger/BT_logger.fbs +++ b/include/behavior_tree_logger/BT_logger.fbs @@ -1,33 +1,34 @@ namespace BT_Serialization; -enum Status : byte { +enum Status : byte { IDLE = 0, RUNNING, SUCCESS, FAILURE } -enum NodeType : byte { - UNDEFINED = 0, - ACTION, - CONDITION, - CONTROL, +enum Type : byte { + UNDEFINED = 0, + ACTION, + CONDITION, + CONTROL, DECORATOR, SUBTREE } struct Timestamp { - sec : uint32; - usec : uint32; + usec_since_epoch : uint64; } table TreeNode { - uid : uint16; - parend_uid : uint16; - type : NodeType; - name : string (required); + uid : uint16; + children_uid : [uint16]; + type : Type; + status : Status; + instance_name : string (required); + registration_name : string (required); } table BehaviorTree @@ -36,27 +37,20 @@ table BehaviorTree nodes : [TreeNode]; } -struct Status -{ - uid : uint16; - status : Status; -} - struct StatusChange { uid : uint16; prev_status : Status; status : Status; - usec_delta : uint32; + timestamp : Timestamp; } - table StatusChangeLog { - behavior_tree : BehaviorTree; - initial_status : [Status]; - initial_time : Timestamp; - state_changes : [StatusChange]; + behavior_tree : BehaviorTree; + state_changes : [StatusChange]; } root_type StatusChangeLog; + +root_type BehaviorTree; diff --git a/include/behavior_tree_logger/BT_logger_generated.h b/include/behavior_tree_logger/BT_logger_generated.h index 7600111d4..7c6630dab 100644 --- a/include/behavior_tree_logger/BT_logger_generated.h +++ b/include/behavior_tree_logger/BT_logger_generated.h @@ -14,8 +14,6 @@ struct TreeNode; struct BehaviorTree; -struct Status; - struct StatusChange; struct StatusChangeLog; @@ -55,7 +53,7 @@ inline const char *EnumNameStatus(Status e) { return EnumNamesStatus()[index]; } -enum class NodeType : int8_t { +enum class Type : int8_t { UNDEFINED = 0, ACTION = 1, CONDITION = 2, @@ -66,19 +64,19 @@ enum class NodeType : int8_t { MAX = SUBTREE }; -inline const NodeType (&EnumValuesNodeType())[6] { - static const NodeType values[] = { - NodeType::UNDEFINED, - NodeType::ACTION, - NodeType::CONDITION, - NodeType::CONTROL, - NodeType::DECORATOR, - NodeType::SUBTREE +inline const Type (&EnumValuesType())[6] { + static const Type values[] = { + Type::UNDEFINED, + Type::ACTION, + Type::CONDITION, + Type::CONTROL, + Type::DECORATOR, + Type::SUBTREE }; return values; } -inline const char * const *EnumNamesNodeType() { +inline const char * const *EnumNamesType() { static const char * const names[] = { "UNDEFINED", "ACTION", @@ -91,74 +89,47 @@ inline const char * const *EnumNamesNodeType() { return names; } -inline const char *EnumNameNodeType(NodeType e) { +inline const char *EnumNameType(Type e) { const size_t index = static_cast(e); - return EnumNamesNodeType()[index]; + return EnumNamesType()[index]; } -FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(4) Timestamp FLATBUFFERS_FINAL_CLASS { +FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) Timestamp FLATBUFFERS_FINAL_CLASS { private: - uint32_t sec_; - uint32_t usec_; + uint64_t usec_since_epoch_; public: Timestamp() { memset(this, 0, sizeof(Timestamp)); } - Timestamp(uint32_t _sec, uint32_t _usec) - : sec_(flatbuffers::EndianScalar(_sec)), - usec_(flatbuffers::EndianScalar(_usec)) { - } - uint32_t sec() const { - return flatbuffers::EndianScalar(sec_); + Timestamp(uint64_t _usec_since_epoch) + : usec_since_epoch_(flatbuffers::EndianScalar(_usec_since_epoch)) { } - uint32_t usec() const { - return flatbuffers::EndianScalar(usec_); + uint64_t usec_since_epoch() const { + return flatbuffers::EndianScalar(usec_since_epoch_); } }; FLATBUFFERS_STRUCT_END(Timestamp, 8); -FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(2) Status FLATBUFFERS_FINAL_CLASS { - private: - uint16_t uid_; - int8_t status_; - int8_t padding0__; - - public: - Status() { - memset(this, 0, sizeof(Status)); - } - Status(uint16_t _uid, Status _status) - : uid_(flatbuffers::EndianScalar(_uid)), - status_(flatbuffers::EndianScalar(static_cast(_status))), - padding0__(0) { - (void)padding0__; - } - uint16_t uid() const { - return flatbuffers::EndianScalar(uid_); - } - Status status() const { - return static_cast(flatbuffers::EndianScalar(status_)); - } -}; -FLATBUFFERS_STRUCT_END(Status, 4); - -FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(4) StatusChange FLATBUFFERS_FINAL_CLASS { +FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) StatusChange FLATBUFFERS_FINAL_CLASS { private: uint16_t uid_; int8_t prev_status_; int8_t status_; - uint32_t usec_delta_; + int32_t padding0__; + Timestamp timestamp_; public: StatusChange() { memset(this, 0, sizeof(StatusChange)); } - StatusChange(uint16_t _uid, Status _prev_status, Status _status, uint32_t _usec_delta) + StatusChange(uint16_t _uid, Status _prev_status, Status _status, const Timestamp &_timestamp) : uid_(flatbuffers::EndianScalar(_uid)), prev_status_(flatbuffers::EndianScalar(static_cast(_prev_status))), status_(flatbuffers::EndianScalar(static_cast(_status))), - usec_delta_(flatbuffers::EndianScalar(_usec_delta)) { + padding0__(0), + timestamp_(_timestamp) { + (void)padding0__; } uint16_t uid() const { return flatbuffers::EndianScalar(uid_); @@ -169,38 +140,50 @@ FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(4) StatusChange FLATBUFFERS_FINAL_CLASS { Status status() const { return static_cast(flatbuffers::EndianScalar(status_)); } - uint32_t usec_delta() const { - return flatbuffers::EndianScalar(usec_delta_); + const Timestamp ×tamp() const { + return timestamp_; } }; -FLATBUFFERS_STRUCT_END(StatusChange, 8); +FLATBUFFERS_STRUCT_END(StatusChange, 16); struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { enum { VT_UID = 4, - VT_PAREND_UID = 6, + VT_CHILDREN_UID = 6, VT_TYPE = 8, - VT_NAME = 10 + VT_STATUS = 10, + VT_INSTANCE_NAME = 12, + VT_REGISTRATION_NAME = 14 }; uint16_t uid() const { return GetField(VT_UID, 0); } - uint16_t parend_uid() const { - return GetField(VT_PAREND_UID, 0); + const flatbuffers::Vector *children_uid() const { + return GetPointer *>(VT_CHILDREN_UID); } - NodeType type() const { - return static_cast(GetField(VT_TYPE, 0)); + Type type() const { + return static_cast(GetField(VT_TYPE, 0)); + } + Status status() const { + return static_cast(GetField(VT_STATUS, 0)); } - const flatbuffers::String *name() const { - return GetPointer(VT_NAME); + const flatbuffers::String *instance_name() const { + return GetPointer(VT_INSTANCE_NAME); + } + const flatbuffers::String *registration_name() const { + return GetPointer(VT_REGISTRATION_NAME); } bool Verify(flatbuffers::Verifier &verifier) const { return VerifyTableStart(verifier) && VerifyField(verifier, VT_UID) && - VerifyField(verifier, VT_PAREND_UID) && + VerifyOffset(verifier, VT_CHILDREN_UID) && + verifier.Verify(children_uid()) && VerifyField(verifier, VT_TYPE) && - VerifyOffsetRequired(verifier, VT_NAME) && - verifier.Verify(name()) && + VerifyField(verifier, VT_STATUS) && + VerifyOffsetRequired(verifier, VT_INSTANCE_NAME) && + verifier.Verify(instance_name()) && + VerifyOffsetRequired(verifier, VT_REGISTRATION_NAME) && + verifier.Verify(registration_name()) && verifier.EndTable(); } }; @@ -211,14 +194,20 @@ struct TreeNodeBuilder { void add_uid(uint16_t uid) { fbb_.AddElement(TreeNode::VT_UID, uid, 0); } - void add_parend_uid(uint16_t parend_uid) { - fbb_.AddElement(TreeNode::VT_PAREND_UID, parend_uid, 0); + void add_children_uid(flatbuffers::Offset> children_uid) { + fbb_.AddOffset(TreeNode::VT_CHILDREN_UID, children_uid); } - void add_type(NodeType type) { + void add_type(Type type) { fbb_.AddElement(TreeNode::VT_TYPE, static_cast(type), 0); } - void add_name(flatbuffers::Offset name) { - fbb_.AddOffset(TreeNode::VT_NAME, name); + void add_status(Status status) { + fbb_.AddElement(TreeNode::VT_STATUS, static_cast(status), 0); + } + void add_instance_name(flatbuffers::Offset instance_name) { + fbb_.AddOffset(TreeNode::VT_INSTANCE_NAME, instance_name); + } + void add_registration_name(flatbuffers::Offset registration_name) { + fbb_.AddOffset(TreeNode::VT_REGISTRATION_NAME, registration_name); } explicit TreeNodeBuilder(flatbuffers::FlatBufferBuilder &_fbb) : fbb_(_fbb) { @@ -228,7 +217,8 @@ struct TreeNodeBuilder { flatbuffers::Offset Finish() { const auto end = fbb_.EndTable(start_); auto o = flatbuffers::Offset(end); - fbb_.Required(o, TreeNode::VT_NAME); + fbb_.Required(o, TreeNode::VT_INSTANCE_NAME); + fbb_.Required(o, TreeNode::VT_REGISTRATION_NAME); return o; } }; @@ -236,13 +226,17 @@ struct TreeNodeBuilder { inline flatbuffers::Offset CreateTreeNode( flatbuffers::FlatBufferBuilder &_fbb, uint16_t uid = 0, - uint16_t parend_uid = 0, - NodeType type = NodeType::UNDEFINED, - flatbuffers::Offset name = 0) { + flatbuffers::Offset> children_uid = 0, + Type type = Type::UNDEFINED, + Status status = Status::IDLE, + flatbuffers::Offset instance_name = 0, + flatbuffers::Offset registration_name = 0) { TreeNodeBuilder builder_(_fbb); - builder_.add_name(name); - builder_.add_parend_uid(parend_uid); + builder_.add_registration_name(registration_name); + builder_.add_instance_name(instance_name); + builder_.add_children_uid(children_uid); builder_.add_uid(uid); + builder_.add_status(status); builder_.add_type(type); return builder_.Finish(); } @@ -250,15 +244,19 @@ inline flatbuffers::Offset CreateTreeNode( inline flatbuffers::Offset CreateTreeNodeDirect( flatbuffers::FlatBufferBuilder &_fbb, uint16_t uid = 0, - uint16_t parend_uid = 0, - NodeType type = NodeType::UNDEFINED, - const char *name = nullptr) { + const std::vector *children_uid = nullptr, + Type type = Type::UNDEFINED, + Status status = Status::IDLE, + const char *instance_name = nullptr, + const char *registration_name = nullptr) { return BT_Serialization::CreateTreeNode( _fbb, uid, - parend_uid, + children_uid ? _fbb.CreateVector(*children_uid) : 0, type, - name ? _fbb.CreateString(name) : 0); + status, + instance_name ? _fbb.CreateString(instance_name) : 0, + registration_name ? _fbb.CreateString(registration_name) : 0); } struct BehaviorTree FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { @@ -326,19 +324,11 @@ inline flatbuffers::Offset CreateBehaviorTreeDirect( struct StatusChangeLog FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { enum { VT_BEHAVIOR_TREE = 4, - VT_INITIAL_STATUS = 6, - VT_INITIAL_TIME = 8, - VT_STATE_CHANGES = 10 + VT_STATE_CHANGES = 6 }; const BehaviorTree *behavior_tree() const { return GetPointer(VT_BEHAVIOR_TREE); } - const flatbuffers::Vector *initial_status() const { - return GetPointer *>(VT_INITIAL_STATUS); - } - const Timestamp *initial_time() const { - return GetStruct(VT_INITIAL_TIME); - } const flatbuffers::Vector *state_changes() const { return GetPointer *>(VT_STATE_CHANGES); } @@ -346,9 +336,6 @@ struct StatusChangeLog FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { return VerifyTableStart(verifier) && VerifyOffset(verifier, VT_BEHAVIOR_TREE) && verifier.VerifyTable(behavior_tree()) && - VerifyOffset(verifier, VT_INITIAL_STATUS) && - verifier.Verify(initial_status()) && - VerifyField(verifier, VT_INITIAL_TIME) && VerifyOffset(verifier, VT_STATE_CHANGES) && verifier.Verify(state_changes()) && verifier.EndTable(); @@ -361,12 +348,6 @@ struct StatusChangeLogBuilder { void add_behavior_tree(flatbuffers::Offset behavior_tree) { fbb_.AddOffset(StatusChangeLog::VT_BEHAVIOR_TREE, behavior_tree); } - void add_initial_status(flatbuffers::Offset> initial_status) { - fbb_.AddOffset(StatusChangeLog::VT_INITIAL_STATUS, initial_status); - } - void add_initial_time(const Timestamp *initial_time) { - fbb_.AddStruct(StatusChangeLog::VT_INITIAL_TIME, initial_time); - } void add_state_changes(flatbuffers::Offset> state_changes) { fbb_.AddOffset(StatusChangeLog::VT_STATE_CHANGES, state_changes); } @@ -385,13 +366,9 @@ struct StatusChangeLogBuilder { inline flatbuffers::Offset CreateStatusChangeLog( flatbuffers::FlatBufferBuilder &_fbb, flatbuffers::Offset behavior_tree = 0, - flatbuffers::Offset> initial_status = 0, - const Timestamp *initial_time = 0, flatbuffers::Offset> state_changes = 0) { StatusChangeLogBuilder builder_(_fbb); builder_.add_state_changes(state_changes); - builder_.add_initial_time(initial_time); - builder_.add_initial_status(initial_status); builder_.add_behavior_tree(behavior_tree); return builder_.Finish(); } @@ -399,44 +376,40 @@ inline flatbuffers::Offset CreateStatusChangeLog( inline flatbuffers::Offset CreateStatusChangeLogDirect( flatbuffers::FlatBufferBuilder &_fbb, flatbuffers::Offset behavior_tree = 0, - const std::vector *initial_status = nullptr, - const Timestamp *initial_time = 0, const std::vector *state_changes = nullptr) { return BT_Serialization::CreateStatusChangeLog( _fbb, behavior_tree, - initial_status ? _fbb.CreateVector(*initial_status) : 0, - initial_time, state_changes ? _fbb.CreateVectorOfStructs(*state_changes) : 0); } -inline const BT_Serialization::StatusChangeLog *GetStatusChangeLog(const void *buf) { - return flatbuffers::GetRoot(buf); +inline const BT_Serialization::BehaviorTree *GetBehaviorTree(const void *buf) { + return flatbuffers::GetRoot(buf); } -inline const BT_Serialization::StatusChangeLog *GetSizePrefixedStatusChangeLog(const void *buf) { - return flatbuffers::GetSizePrefixedRoot(buf); +inline const BT_Serialization::BehaviorTree *GetSizePrefixedBehaviorTree(const void *buf) { + return flatbuffers::GetSizePrefixedRoot(buf); } -inline bool VerifyStatusChangeLogBuffer( +inline bool VerifyBehaviorTreeBuffer( flatbuffers::Verifier &verifier) { - return verifier.VerifyBuffer(nullptr); + return verifier.VerifyBuffer(nullptr); } -inline bool VerifySizePrefixedStatusChangeLogBuffer( +inline bool VerifySizePrefixedBehaviorTreeBuffer( flatbuffers::Verifier &verifier) { - return verifier.VerifySizePrefixedBuffer(nullptr); + return verifier.VerifySizePrefixedBuffer(nullptr); } -inline void FinishStatusChangeLogBuffer( +inline void FinishBehaviorTreeBuffer( flatbuffers::FlatBufferBuilder &fbb, - flatbuffers::Offset root) { + flatbuffers::Offset root) { fbb.Finish(root); } -inline void FinishSizePrefixedStatusChangeLogBuffer( +inline void FinishSizePrefixedBehaviorTreeBuffer( flatbuffers::FlatBufferBuilder &fbb, - flatbuffers::Offset root) { + flatbuffers::Offset root) { fbb.FinishSizePrefixed(root); } diff --git a/include/behavior_tree_logger/abstract_logger.h b/include/behavior_tree_logger/abstract_logger.h index b35de7097..14d0d38c5 100644 --- a/include/behavior_tree_logger/abstract_logger.h +++ b/include/behavior_tree_logger/abstract_logger.h @@ -9,13 +9,17 @@ namespace BT{ class StatusChangeLogger { public: + StatusChangeLogger(TreeNode* root_node); virtual ~StatusChangeLogger() = default; - virtual void callback(const TreeNode& node, + virtual void callback(BT::TimePoint timestamp, + const TreeNode& node, NodeStatus prev_status, NodeStatus status) = 0; + virtual void flush() = 0; + void setEnabled(bool enabled) { _enabled = enabled; } bool enabled() const { return _enabled; } @@ -33,20 +37,21 @@ class StatusChangeLogger { //-------------------------------------------- -StatusChangeLogger::StatusChangeLogger(TreeNode *root_node): +inline StatusChangeLogger::StatusChangeLogger(TreeNode *root_node): _enabled(true), - _show_transition_to_idle(false) + _show_transition_to_idle(true) { recursiveVisitor(root_node, [this](TreeNode* node) { _subscribers.push_back( node->subscribeToStatusChange( - [this](const TreeNode& node, + [this](TimePoint timestamp, + const TreeNode& node, NodeStatus prev, NodeStatus status) { if(_enabled && ( status != NodeStatus::IDLE || _show_transition_to_idle)) { - this->callback(node,prev,status); + this->callback(timestamp, node,prev,status); } })); }); diff --git a/include/behavior_tree_logger/bt_cout_logger.h b/include/behavior_tree_logger/bt_cout_logger.h index dcaa1d081..968401da5 100644 --- a/include/behavior_tree_logger/bt_cout_logger.h +++ b/include/behavior_tree_logger/bt_cout_logger.h @@ -22,23 +22,33 @@ namespace BT{ class StdCoutLogger: public StatusChangeLogger { public: + StdCoutLogger(TreeNode* root_node): StatusChangeLogger(root_node) - {} + { + static bool first_instance = true; + if( first_instance ) + { + first_instance = false; + } + else{ + throw std::logic_error("Only one instance of StdCoutLogger shall be created"); + } + } virtual ~StdCoutLogger() = default; - virtual void callback(const TreeNode& node, + virtual void callback(TimePoint timestamp, + const TreeNode& node, NodeStatus prev_status, - NodeStatus status) + NodeStatus status) override { using namespace std::chrono; - auto now = high_resolution_clock::now(); - constexpr const char* whitespaces = " "; - constexpr const size_t ws_count = 20; + constexpr const char* whitespaces = " "; + constexpr const size_t ws_count = 25; - double since_epoch = duration( now.time_since_epoch() ).count(); + double since_epoch = duration( timestamp.time_since_epoch() ).count(); printf("[%.3f]: %s%s %s -> %s\n", since_epoch, node.name().c_str(), @@ -46,6 +56,8 @@ class StdCoutLogger: public StatusChangeLogger { toStr(prev_status, true), toStr(status, true) ); } + + virtual void flush() override { std::cout << std::flush; } }; diff --git a/include/behavior_tree_logger/bt_file_logger.h b/include/behavior_tree_logger/bt_file_logger.h new file mode 100644 index 000000000..87665063d --- /dev/null +++ b/include/behavior_tree_logger/bt_file_logger.h @@ -0,0 +1,40 @@ +#ifndef BT_FILE_LOGGER_H +#define BT_FILE_LOGGER_H + +#include +#include +#include +#include "abstract_logger.h" + +namespace BT{ + +class FileLogger: public StatusChangeLogger { + +public: + FileLogger(TreeNode* root_node, const char* filename, uint16_t buffer_size); + + virtual ~FileLogger(); + + virtual void callback(TimePoint timestamp, + const TreeNode& node, + NodeStatus prev_status, + NodeStatus status) override; + + virtual void flush() override; + +private: + + std::ofstream _file_os; + + std::chrono::high_resolution_clock::time_point _start_time; + + std::vector< std::array > _buffer; + + bool _buffer_max_size; +}; + + +} // end namespace + + +#endif // BT_FILE_LOGGER_H diff --git a/include/behavior_tree_logger/bt_flatbuffer_helper.h b/include/behavior_tree_logger/bt_flatbuffer_helper.h new file mode 100644 index 000000000..51f661610 --- /dev/null +++ b/include/behavior_tree_logger/bt_flatbuffer_helper.h @@ -0,0 +1,107 @@ +#ifndef BT_FLATBUFFER_HELPER_H +#define BT_FLATBUFFER_HELPER_H + +#include "abstract_logger.h" +#include "BT_logger_generated.h" + +namespace BT{ + + +inline BT_Serialization::Type convertToFlatbuffers(NodeType type) +{ + switch( type ){ + case BT::NodeType::ACTION: return BT_Serialization::Type::ACTION; + case BT::NodeType::DECORATOR: return BT_Serialization::Type::DECORATOR; + case BT::NodeType::CONTROL: return BT_Serialization::Type::CONTROL; + case BT::NodeType::CONDITION: return BT_Serialization::Type::CONDITION; + case BT::NodeType::SUBTREE: return BT_Serialization::Type::SUBTREE; + case BT::NodeType::UNDEFINED: return BT_Serialization::Type::UNDEFINED; + } + return BT_Serialization::Type::UNDEFINED; +} + +inline BT_Serialization::Status convertToFlatbuffers(NodeStatus type) +{ + switch( type ){ + case BT::NodeStatus::IDLE: return BT_Serialization::Status::IDLE; + case BT::NodeStatus::SUCCESS: return BT_Serialization::Status::SUCCESS; + case BT::NodeStatus::RUNNING: return BT_Serialization::Status::RUNNING; + case BT::NodeStatus::FAILURE: return BT_Serialization::Status::FAILURE; + } + return BT_Serialization::Status::IDLE; +} + +inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builder, + BT::TreeNode *root_node) +{ + + std::vector> fb_nodes; + + recursiveVisitor(root_node, [&](TreeNode* node) + { + std::vector children_uid; + if (auto control = dynamic_cast(node)) + { + children_uid.reserve( control->children().size() ); + for (const auto& child : control->children()) + { + children_uid.push_back( child->UID() ); + } + } + else if (auto decorator = dynamic_cast(node)) + { + const auto& child = decorator->child(); + children_uid.push_back( child->UID() ); + } + + fb_nodes.push_back( BT_Serialization::CreateTreeNode( + builder, + node->UID(), + builder.CreateVector( children_uid ), + convertToFlatbuffers(node->type() ), + convertToFlatbuffers(node->status()), + builder.CreateString(node->name().c_str()), + builder.CreateString(node->registrationName().c_str()) + ) + ); + }); + + auto behavior_tree = BT_Serialization::CreateBehaviorTree( + builder, + root_node->UID(), + builder.CreateVector(fb_nodes) + ); + + builder.Finish(behavior_tree); +} + +/** Serialize manually the informations about state transition + * No flatbuffer serialization here + */ +inline +std::array SerializeTransition(uint16_t UID, + TimePoint timestamp, + NodeStatus prev_status, + NodeStatus status) +{ + using namespace std::chrono; + std::array buffer; + auto usec_since_epoch = duration_cast( timestamp.time_since_epoch() ).count(); + uint32_t t_sec = usec_since_epoch / 1000000; + uint32_t t_usec = usec_since_epoch % 1000000; + + flatbuffers::WriteScalar( &buffer[0], t_sec ); + flatbuffers::WriteScalar( &buffer[4], t_usec ); + flatbuffers::WriteScalar( &buffer[8], UID ); + + flatbuffers::WriteScalar( &buffer[10], + static_cast(convertToFlatbuffers(prev_status)) ); + flatbuffers::WriteScalar( &buffer[11], + static_cast(convertToFlatbuffers(status)) ); + + return buffer; +} + +} // end namespace + +#endif // BT_FLATBUFFER_HELPER_H diff --git a/include/behavior_tree_logger/bt_minitrace_logger.h b/include/behavior_tree_logger/bt_minitrace_logger.h new file mode 100644 index 000000000..dd174ebdb --- /dev/null +++ b/include/behavior_tree_logger/bt_minitrace_logger.h @@ -0,0 +1,73 @@ +#ifndef BT_MINITRACE_LOGGER_H +#define BT_MINITRACE_LOGGER_H + +#include +#include "abstract_logger.h" +#include "minitrace/minitrace.h" + +namespace BT{ + + +class MinitraceLogger: public StatusChangeLogger { + +public: + MinitraceLogger(TreeNode* root_node, const char* filename_json): + StatusChangeLogger(root_node) + { + static bool first_instance = true; + if( first_instance ) + { + first_instance = false; + } + else{ + throw std::logic_error("Only one instance of MinitraceLogger shall be created"); + } + minitrace::mtr_register_sigint_handler(); + minitrace::mtr_init(filename_json); + this->enableTransitionToIdle(true); + } + + virtual ~MinitraceLogger() + { + minitrace::mtr_flush(); + minitrace::mtr_shutdown(); + } + + virtual void callback(TimePoint timestamp, const TreeNode& node, + NodeStatus prev_status, + NodeStatus status) override + { + using namespace minitrace; + + const bool statusCompleted = (status == NodeStatus::SUCCESS || + status == NodeStatus::FAILURE); + + const char* category = toStr(node.type()); + const char* name = node.name().c_str(); + + if( prev_status == NodeStatus::IDLE && statusCompleted) + { + MTR_INSTANT(category, name); + } + else if( status == NodeStatus::RUNNING ) + { + MTR_BEGIN(category, name); + } + else if( prev_status == NodeStatus::RUNNING && statusCompleted ) + { + MTR_END( category, name ); + } + } + + virtual void flush() override { + minitrace::mtr_flush(); + } +private: + TimePoint _prev_time; +}; + + +} // end namespace + + +#endif // BT_MINITRACE_LOGGER_H diff --git a/include/behavior_tree_logger/bt_zmq_publisher.h b/include/behavior_tree_logger/bt_zmq_publisher.h new file mode 100644 index 000000000..f721a6ac5 --- /dev/null +++ b/include/behavior_tree_logger/bt_zmq_publisher.h @@ -0,0 +1,46 @@ +#ifndef BT_ZMQ_PUBLISHER_H +#define BT_ZMQ_PUBLISHER_H + +#include +#include +#include "abstract_logger.h" +#include "BT_logger_generated.h" + +namespace BT{ + +class PublisherZMQ: public StatusChangeLogger +{ +public: + PublisherZMQ(TreeNode* root_node, int max_msg_per_second = 100); + + virtual ~PublisherZMQ(); + +private: + + virtual void callback(TimePoint timestamp, + const TreeNode& node, + NodeStatus prev_status, NodeStatus status) override; + + virtual void flush() override; + + TreeNode *_root_node; + std::vector _tree_buffer; + std::vector _status_buffer; + std::vector< std::array > _transition_buffer; + std::chrono::milliseconds _min_time_between_msgs; + std::chrono::high_resolution_clock::time_point _prev_time; + + zmq::context_t _zmq_context; + zmq::socket_t _zmq_publisher; + zmq::socket_t _zmq_server; + + std::atomic_bool _active_server; + std::thread _thread; + + void createStatusBuffer(); +}; + + +} + +#endif // BT_ZMQ_PUBLISHER_H diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index bee438df6..4ace64ae9 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -68,7 +68,9 @@ std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::st { throw BehaviorTreeException("ID '" + ID + "' not registered"); } - return it->second(name, params); + std::unique_ptr node = it->second(name, params); + node->setRegistrationName( ID ); + return node; } } // end namespace diff --git a/src/bt_file_logger.cpp b/src/bt_file_logger.cpp new file mode 100644 index 000000000..0e01e3857 --- /dev/null +++ b/src/bt_file_logger.cpp @@ -0,0 +1,73 @@ +#include "behavior_tree_logger/bt_file_logger.h" +#include "behavior_tree_logger/bt_flatbuffer_helper.h" + +namespace BT{ + +FileLogger::FileLogger(BT::TreeNode *root_node, const char *filename, uint16_t buffer_size): + StatusChangeLogger(root_node), + _buffer_max_size(buffer_size) +{ + if( _buffer_max_size != 0) + { + _buffer.reserve( _buffer_max_size ); + } + + enableTransitionToIdle( true ); + + flatbuffers::FlatBufferBuilder builder(1024); + CreateFlatbuffersBehaviorTree( builder, root_node); + + //------------------------------------- + + _file_os.open( filename, std::ofstream::binary | std::ofstream::out); + + // serialize the length of the buffer in the first 4 bytes + char size_buff[4]; + flatbuffers::WriteScalar(size_buff, static_cast( builder.GetSize()) ); + + _file_os.write( size_buff, 4 ); + _file_os.write( reinterpret_cast(builder.GetBufferPointer()), + builder.GetSize() ); + +} + +FileLogger::~FileLogger() +{ + this->flush(); + _file_os.close(); +} + +void FileLogger::callback(TimePoint timestamp, const TreeNode &node, NodeStatus prev_status, NodeStatus status) +{ + std::array buffer = SerializeTransition( + node.UID(), + timestamp, + prev_status, + status ); + + if( _buffer_max_size == 0 ) + { + _file_os.write( reinterpret_cast(buffer.data()), buffer.size() ); + } + else{ + _buffer.push_back( buffer ); + if( _buffer.size() >= _buffer_max_size) + { + this->flush(); + } + } +} + +void FileLogger::flush() +{ + for (const auto& array: _buffer ) + { + _file_os.write( reinterpret_cast(array.data()), array.size() ); + } + _file_os.flush(); + _buffer.clear(); +} + + + +} diff --git a/src/bt_zmq_publisher.cpp b/src/bt_zmq_publisher.cpp new file mode 100644 index 000000000..7901cd390 --- /dev/null +++ b/src/bt_zmq_publisher.cpp @@ -0,0 +1,127 @@ +#include "behavior_tree_logger/bt_zmq_publisher.h" +#include "behavior_tree_logger/bt_flatbuffer_helper.h" + +namespace BT { + +void PublisherZMQ::createStatusBuffer() +{ + _status_buffer.clear(); + recursiveVisitor(_root_node, [this](TreeNode* node) + { + size_t index = _status_buffer.size(); + _status_buffer.resize( index + 3 ); + flatbuffers::WriteScalar( &_status_buffer[index], node->UID() ); + flatbuffers::WriteScalar( &_status_buffer[index+2], + static_cast( convertToFlatbuffers(node->status())) ); + }); +} + +PublisherZMQ::PublisherZMQ(TreeNode *root_node, + int max_msg_per_second): + StatusChangeLogger(root_node), + _root_node(root_node), + _min_time_between_msgs( std::chrono::milliseconds(1000) / max_msg_per_second ), + _zmq_context(1), + _zmq_publisher( _zmq_context, ZMQ_PUB ), + _zmq_server( _zmq_context, ZMQ_REP ) +{ + static bool first_instance = true; + if( first_instance ) + { + first_instance = false; + } + else{ + throw std::logic_error("Only one instance of PublisherZMQ shall be created"); + } + + flatbuffers::FlatBufferBuilder builder(1024); + CreateFlatbuffersBehaviorTree( builder, root_node); + + _tree_buffer.resize(builder.GetSize()); + memcpy( _tree_buffer.data(), builder.GetBufferPointer(), builder.GetSize() ); + + _zmq_publisher.bind( "tcp://*:1666" ); + _zmq_server.bind( "tcp://*:1667" ); + + _active_server = true; + + _thread = std::thread([this]() + { + while(_active_server) + { + zmq::message_t req; + try{ + _zmq_server.recv( &req ); + zmq::message_t reply ( _tree_buffer.size() ); + memcpy( reply.data(), _tree_buffer.data(), _tree_buffer.size() ); + _zmq_server.send( reply ); + } + catch( zmq::error_t& err) + { + _active_server = false; + } + } + }); + + createStatusBuffer(); +} + +PublisherZMQ::~PublisherZMQ() +{ + _active_server = false; + if( _thread.joinable()) + { + _thread.join(); + } + flush(); +} + +void PublisherZMQ::callback(TimePoint timestamp, const TreeNode &node, NodeStatus prev_status, NodeStatus status) +{ + using namespace std::chrono; + + std::array transition = SerializeTransition(node.UID(), + timestamp, prev_status, status); + + _transition_buffer.push_back( transition ); + + if( (timestamp - _prev_time) >= _min_time_between_msgs ) + { + _prev_time = timestamp; + flush(); + }; +} + +void PublisherZMQ::flush() +{ + const size_t msg_size = _status_buffer.size() + 8 + + (_transition_buffer.size() * 12); + + zmq::message_t message ( msg_size ); + uint8_t* data_ptr = static_cast( message.data() ); + + // first 4 bytes are the side of the header + flatbuffers::WriteScalar( data_ptr, _status_buffer.size() ); + data_ptr += sizeof(uint32_t); + // copy the header part + memcpy( data_ptr, _status_buffer.data(), _status_buffer.size() ); + data_ptr += _status_buffer.size(); + + // first 4 bytes are the side of the transition buffer + flatbuffers::WriteScalar( data_ptr, _transition_buffer.size() ); + data_ptr += sizeof(uint32_t); + + for (auto& transition: _transition_buffer) + { + memcpy( data_ptr, transition.data(), transition.size() ); + data_ptr += transition.size(); + } + + _zmq_publisher.send(message); + _transition_buffer.clear(); + + // rebuild _status_buffer for the next time + createStatusBuffer(); +} + +} diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index fd59ecff8..6a596972a 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -19,6 +19,8 @@ BT::DecoratorNegationNode::DecoratorNegationNode(std::string name) : DecoratorNo BT::NodeStatus BT::DecoratorNegationNode::tick() { + setStatus( NodeStatus::RUNNING ); + const NodeStatus child_state = child_node_->executeTick(); switch (child_state) diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 957269aff..d4a0b7a80 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -15,7 +15,7 @@ static uint8_t getUID() { - static uint8_t uid = 0; + static uint8_t uid = 1; return uid++; } @@ -41,7 +41,8 @@ void BT::TreeNode::setStatus(NodeStatus new_status) if (prev_status != new_status) { state_condition_variable_.notify_all(); - state_change_signal_.notify(*this, prev_status, new_status); + state_change_signal_.notify( std::chrono::high_resolution_clock::now(), + *this, prev_status, new_status); } } @@ -84,3 +85,13 @@ uint16_t BT::TreeNode::UID() const { return _uid; } + +void BT::TreeNode::setRegistrationName(const std::string ®istration_name) +{ + _registration_name = registration_name; +} + +const std::string &BT::TreeNode::registrationName() const +{ + return _registration_name; +} diff --git a/tools/bt_log_cat.cpp b/tools/bt_log_cat.cpp new file mode 100644 index 000000000..9d860ecfe --- /dev/null +++ b/tools/bt_log_cat.cpp @@ -0,0 +1,99 @@ +#include +#include +#include +#include +#include "behavior_tree_logger/BT_logger_generated.h" + +int main(int argc, char* argv[]) +{ + if( argc != 2) + { + printf("Wrong number of arguments\nUsage: %s [filename]\n", argv[0]); + return 1; + } + + FILE* file = fopen(argv[1], "rb"); + + if( !file ) + { + printf("Failed to open file: [%s]\n", argv[1]); + return 1; + } + + fseek(file, 0L, SEEK_END); + const size_t length = ftell(file); + fseek(file, 0L, SEEK_SET); + std::vector buffer(length); + fread( buffer.data(), sizeof(char), length, file); + fclose(file); + + const int bt_header_size = flatbuffers::ReadScalar(&buffer[0]); + + auto behavior_tree = BT_Serialization::GetBehaviorTree( &buffer[4] ); + + std::unordered_map names_by_uid; + std::unordered_map node_by_uid; + + for( const BT_Serialization::TreeNode* node: *(behavior_tree->nodes()) ) + { + names_by_uid.insert( { node->uid(), std::string(node->instance_name()->c_str()) } ); + node_by_uid.insert( { node->uid(), node } ); + } + + printf("----------------------------\n"); + + std::function recursiveStep; + + recursiveStep = [&](uint16_t uid, int indent) + { + for(int i=0; i< indent; i++) + { + printf(" "); + names_by_uid[uid] = std::string(" ") + names_by_uid[uid]; + } + printf("%s\n", names_by_uid[uid].c_str() ); + std::cout << std::flush; + + const auto& node = node_by_uid[uid]; + + for (size_t i=0; i< node->children_uid()->size(); i++ ) + { + recursiveStep( node->children_uid()->Get(i), indent+1); + } + }; + + recursiveStep( behavior_tree->root_uid(), 0 ); + + printf("----------------------------\n"); + + constexpr const char* whitespaces = " "; + constexpr const size_t ws_count = 25; + + auto printStatus = [](BT_Serialization::Status status) + { + switch (status) + { + case BT_Serialization::Status::SUCCESS: return ( "\x1b[32m" "SUCCESS" "\x1b[0m"); // RED + case BT_Serialization::Status::FAILURE: return ( "\x1b[31m" "FAILURE" "\x1b[0m"); // GREEN + case BT_Serialization::Status::RUNNING: return ( "\x1b[33m" "RUNNING" "\x1b[0m"); // YELLOW + case BT_Serialization::Status::IDLE: return ( "\x1b[36m" "IDLE " "\x1b[0m"); // CYAN + } + return "Undefined"; + }; + + for( size_t index = bt_header_size + 4; index < length; index +=12 ) + { + const uint16_t uid = flatbuffers::ReadScalar(&buffer[index+8]); + const std::string& name = names_by_uid[uid]; + const uint32_t t_sec = flatbuffers::ReadScalar( &buffer[index] ); + const uint32_t t_usec = flatbuffers::ReadScalar( &buffer[index+4] ); + + printf("[%d.%06d]: %s%s %s -> %s\n", t_sec, t_usec, + name.c_str(), + &whitespaces[ std::min( ws_count, name.size())], + printStatus(flatbuffers::ReadScalar(&buffer[index+10] )), + printStatus(flatbuffers::ReadScalar(&buffer[index+11] )) ); + } + + return 0; +} diff --git a/tools/bt_recorder.cpp b/tools/bt_recorder.cpp new file mode 100644 index 000000000..81f2e6323 --- /dev/null +++ b/tools/bt_recorder.cpp @@ -0,0 +1,99 @@ +#include +#include +#include +#include +#include +#include +#include "behavior_tree_logger/BT_logger_generated.h" + +// http://zguide.zeromq.org/cpp:interrupt +static bool s_interrupted = false; + +static void s_signal_handler (int) +{ + s_interrupted = true; +} + +static void CatchSignals (void) +{ + struct sigaction action; + action.sa_handler = s_signal_handler; + action.sa_flags = 0; + sigemptyset (&action.sa_mask); + sigaction (SIGINT, &action, NULL); + sigaction (SIGTERM, &action, NULL); +} + +int main(int argc, char* argv[]) +{ + if( argc != 2) + { + printf("Wrong number of arguments\nUsage: %s [filename]\n", argv[0]); + return 1; + } + + // register CTRL+C signal handler + CatchSignals(); + + zmq::context_t context (1); + + // Socket to talk to server + std::cout << "Trying to connect to [tcp://localhost:1666]\n" << std::endl; + + zmq::socket_t subscriber (context, ZMQ_SUB); + subscriber.connect("tcp://localhost:1666"); + + // Subscribe to everything + subscriber.setsockopt(ZMQ_SUBSCRIBE, "", 0); + + printf("----------- Started -----------------\n"); + + bool first_message = true; + std::ofstream file_os; + + while( !s_interrupted ) + { + zmq::message_t update; + zmq::message_t msg; + try { + subscriber.recv (&update); + } + catch(zmq::error_t& e) + { + if( !s_interrupted ) + { + std::cout << "subscriber.recv() failed with exception: "<< + e.what() << std::endl; + return -1; + } + } + + if( !s_interrupted ) + { + char* data_ptr = static_cast( update.data() ); + const uint32_t header_size = flatbuffers::ReadScalar( data_ptr ); + + if( first_message ) + { + printf("First message received\n"); + first_message = false; + + file_os.open( argv[1], std::ofstream::binary | std::ofstream::out); + file_os.write( data_ptr, 4 + header_size ) ; + } + data_ptr += 4 + header_size; + + const uint32_t transition_count = flatbuffers::ReadScalar( data_ptr ); + data_ptr += sizeof( uint32_t ); + + file_os.write( data_ptr, 12*transition_count) ; + } + } + + subscriber.close(); + + printf("Results saved to file\n"); + file_os.close(); + + return 0; +} From 4f5bf839f17285abd4c8a2c26cac1323d463b636 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 1 Jun 2018 14:05:45 +0200 Subject: [PATCH 072/125] changed the wait logic in ZMQ publisher --- .../behavior_tree_logger/bt_zmq_publisher.h | 12 +++- src/bt_zmq_publisher.cpp | 71 +++++++++++-------- 2 files changed, 51 insertions(+), 32 deletions(-) diff --git a/include/behavior_tree_logger/bt_zmq_publisher.h b/include/behavior_tree_logger/bt_zmq_publisher.h index f721a6ac5..ffe981a07 100644 --- a/include/behavior_tree_logger/bt_zmq_publisher.h +++ b/include/behavior_tree_logger/bt_zmq_publisher.h @@ -2,6 +2,7 @@ #define BT_ZMQ_PUBLISHER_H #include +#include #include #include "abstract_logger.h" #include "BT_logger_generated.h" @@ -11,7 +12,7 @@ namespace BT{ class PublisherZMQ: public StatusChangeLogger { public: - PublisherZMQ(TreeNode* root_node, int max_msg_per_second = 100); + PublisherZMQ(TreeNode* root_node, int max_msg_per_second = 25); virtual ~PublisherZMQ(); @@ -27,8 +28,7 @@ class PublisherZMQ: public StatusChangeLogger std::vector _tree_buffer; std::vector _status_buffer; std::vector< std::array > _transition_buffer; - std::chrono::milliseconds _min_time_between_msgs; - std::chrono::high_resolution_clock::time_point _prev_time; + std::chrono::microseconds _min_time_between_msgs; zmq::context_t _zmq_context; zmq::socket_t _zmq_publisher; @@ -38,6 +38,12 @@ class PublisherZMQ: public StatusChangeLogger std::thread _thread; void createStatusBuffer(); + + TimePoint _deadline; + std::mutex _mutex; + std::atomic_bool _send_pending; + + std::future _send_future; }; diff --git a/src/bt_zmq_publisher.cpp b/src/bt_zmq_publisher.cpp index 7901cd390..782bca3c5 100644 --- a/src/bt_zmq_publisher.cpp +++ b/src/bt_zmq_publisher.cpp @@ -1,5 +1,6 @@ #include "behavior_tree_logger/bt_zmq_publisher.h" #include "behavior_tree_logger/bt_flatbuffer_helper.h" +#include namespace BT { @@ -20,10 +21,11 @@ PublisherZMQ::PublisherZMQ(TreeNode *root_node, int max_msg_per_second): StatusChangeLogger(root_node), _root_node(root_node), - _min_time_between_msgs( std::chrono::milliseconds(1000) / max_msg_per_second ), + _min_time_between_msgs( std::chrono::microseconds(1000*1000) / max_msg_per_second ), _zmq_context(1), _zmq_publisher( _zmq_context, ZMQ_PUB ), - _zmq_server( _zmq_context, ZMQ_REP ) + _zmq_server( _zmq_context, ZMQ_REP ), + _send_pending(false) { static bool first_instance = true; if( first_instance ) @@ -82,46 +84,57 @@ void PublisherZMQ::callback(TimePoint timestamp, const TreeNode &node, NodeStatu std::array transition = SerializeTransition(node.UID(), timestamp, prev_status, status); + { + std::unique_lock lock( _mutex ); + _transition_buffer.push_back( transition ); + } - _transition_buffer.push_back( transition ); - - if( (timestamp - _prev_time) >= _min_time_between_msgs ) + if( !_send_pending ) { - _prev_time = timestamp; - flush(); - }; + _send_pending = true; + _send_future = std::async(std::launch::async, [this]() + { + std::this_thread::sleep_for( _min_time_between_msgs ); + flush(); + } ); + } } void PublisherZMQ::flush() { - const size_t msg_size = _status_buffer.size() + 8 + - (_transition_buffer.size() * 12); + zmq::message_t message; + { + std::unique_lock lock( _mutex ); - zmq::message_t message ( msg_size ); - uint8_t* data_ptr = static_cast( message.data() ); + const size_t msg_size = _status_buffer.size() + 8 + + (_transition_buffer.size() * 12); - // first 4 bytes are the side of the header - flatbuffers::WriteScalar( data_ptr, _status_buffer.size() ); - data_ptr += sizeof(uint32_t); - // copy the header part - memcpy( data_ptr, _status_buffer.data(), _status_buffer.size() ); - data_ptr += _status_buffer.size(); + message.rebuild( msg_size ); + uint8_t* data_ptr = static_cast( message.data() ); - // first 4 bytes are the side of the transition buffer - flatbuffers::WriteScalar( data_ptr, _transition_buffer.size() ); - data_ptr += sizeof(uint32_t); + // first 4 bytes are the side of the header + flatbuffers::WriteScalar( data_ptr, _status_buffer.size() ); + data_ptr += sizeof(uint32_t); + // copy the header part + memcpy( data_ptr, _status_buffer.data(), _status_buffer.size() ); + data_ptr += _status_buffer.size(); - for (auto& transition: _transition_buffer) - { - memcpy( data_ptr, transition.data(), transition.size() ); - data_ptr += transition.size(); + // first 4 bytes are the side of the transition buffer + flatbuffers::WriteScalar( data_ptr, _transition_buffer.size() ); + data_ptr += sizeof(uint32_t); + + for (auto& transition: _transition_buffer) + { + memcpy( data_ptr, transition.data(), transition.size() ); + data_ptr += transition.size(); + } + _transition_buffer.clear(); + createStatusBuffer(); } _zmq_publisher.send(message); - _transition_buffer.clear(); - - // rebuild _status_buffer for the next time - createStatusBuffer(); + _send_pending = false; + // printf("%.3f zmq send\n", std::chrono::duration( std::chrono::high_resolution_clock::now().time_since_epoch() ).count()); } } From 7811dc4e2ce68c3ebc90d69295222feab34d512e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 13 Jun 2018 12:52:24 +0200 Subject: [PATCH 073/125] underscore as suffix --- include/behavior_tree_core/tree_node.h | 4 +- .../behavior_tree_logger/abstract_logger.h | 22 ++--- include/behavior_tree_logger/bt_cout_logger.h | 2 - include/behavior_tree_logger/bt_file_logger.h | 10 +-- .../bt_minitrace_logger.h | 4 +- .../behavior_tree_logger/bt_zmq_publisher.h | 28 +++--- src/bt_file_logger.cpp | 30 +++---- src/bt_zmq_publisher.cpp | 88 +++++++++---------- src/tree_node.cpp | 8 +- 9 files changed, 97 insertions(+), 99 deletions(-) diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 39f903af8..a925ef078 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -156,9 +156,9 @@ class TreeNode StatusChangeSignal state_change_signal_; - const uint16_t _uid; + const uint16_t uid_; - std::string _registration_name; + std::string registration_name_; }; diff --git a/include/behavior_tree_logger/abstract_logger.h b/include/behavior_tree_logger/abstract_logger.h index 14d0d38c5..131c28a8e 100644 --- a/include/behavior_tree_logger/abstract_logger.h +++ b/include/behavior_tree_logger/abstract_logger.h @@ -20,36 +20,36 @@ class StatusChangeLogger { virtual void flush() = 0; - void setEnabled(bool enabled) { _enabled = enabled; } + void setEnabled(bool enabled) { enabled_ = enabled; } - bool enabled() const { return _enabled; } + bool enabled() const { return enabled_; } // false by default. - bool showsTransitionToIdle() const { return _show_transition_to_idle; } + bool showsTransitionToIdle() const { return show_transition_to_idle_; } - void enableTransitionToIdle(bool enable ) { _show_transition_to_idle = enable; } + void enableTransitionToIdle(bool enable ) { show_transition_to_idle_ = enable; } private: - bool _enabled; - bool _show_transition_to_idle; - std::vector _subscribers; + bool enabled_; + bool show_transition_to_idle_; + std::vector subscribers_; }; //-------------------------------------------- inline StatusChangeLogger::StatusChangeLogger(TreeNode *root_node): - _enabled(true), - _show_transition_to_idle(true) + enabled_(true), + show_transition_to_idle_(true) { recursiveVisitor(root_node, [this](TreeNode* node) { - _subscribers.push_back( node->subscribeToStatusChange( + subscribers_.push_back( node->subscribeToStatusChange( [this](TimePoint timestamp, const TreeNode& node, NodeStatus prev, NodeStatus status) { - if(_enabled && ( status != NodeStatus::IDLE || _show_transition_to_idle)) + if(enabled_ && ( status != NodeStatus::IDLE || show_transition_to_idle_)) { this->callback(timestamp, node,prev,status); } diff --git a/include/behavior_tree_logger/bt_cout_logger.h b/include/behavior_tree_logger/bt_cout_logger.h index 968401da5..c29a5ab21 100644 --- a/include/behavior_tree_logger/bt_cout_logger.h +++ b/include/behavior_tree_logger/bt_cout_logger.h @@ -36,8 +36,6 @@ class StdCoutLogger: public StatusChangeLogger { } } - virtual ~StdCoutLogger() = default; - virtual void callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, diff --git a/include/behavior_tree_logger/bt_file_logger.h b/include/behavior_tree_logger/bt_file_logger.h index 87665063d..74b6c2bcf 100644 --- a/include/behavior_tree_logger/bt_file_logger.h +++ b/include/behavior_tree_logger/bt_file_logger.h @@ -13,7 +13,7 @@ class FileLogger: public StatusChangeLogger { public: FileLogger(TreeNode* root_node, const char* filename, uint16_t buffer_size); - virtual ~FileLogger(); + virtual ~FileLogger() override; virtual void callback(TimePoint timestamp, const TreeNode& node, @@ -24,13 +24,13 @@ class FileLogger: public StatusChangeLogger { private: - std::ofstream _file_os; + std::ofstream file_os_; - std::chrono::high_resolution_clock::time_point _start_time; + std::chrono::high_resolution_clock::time_point start_time; - std::vector< std::array > _buffer; + std::vector< std::array > buffer_; - bool _buffer_max_size; + bool buffer_max_size_; }; diff --git a/include/behavior_tree_logger/bt_minitrace_logger.h b/include/behavior_tree_logger/bt_minitrace_logger.h index dd174ebdb..3cc26f186 100644 --- a/include/behavior_tree_logger/bt_minitrace_logger.h +++ b/include/behavior_tree_logger/bt_minitrace_logger.h @@ -27,7 +27,7 @@ class MinitraceLogger: public StatusChangeLogger { this->enableTransitionToIdle(true); } - virtual ~MinitraceLogger() + virtual ~MinitraceLogger() override { minitrace::mtr_flush(); minitrace::mtr_shutdown(); @@ -63,7 +63,7 @@ class MinitraceLogger: public StatusChangeLogger { minitrace::mtr_flush(); } private: - TimePoint _prev_time; + TimePoint prev_time_; }; diff --git a/include/behavior_tree_logger/bt_zmq_publisher.h b/include/behavior_tree_logger/bt_zmq_publisher.h index ffe981a07..4bbc662ad 100644 --- a/include/behavior_tree_logger/bt_zmq_publisher.h +++ b/include/behavior_tree_logger/bt_zmq_publisher.h @@ -24,26 +24,26 @@ class PublisherZMQ: public StatusChangeLogger virtual void flush() override; - TreeNode *_root_node; - std::vector _tree_buffer; - std::vector _status_buffer; - std::vector< std::array > _transition_buffer; - std::chrono::microseconds _min_time_between_msgs; + TreeNode *root_node_; + std::vector tree_buffer_; + std::vector status_buffer_; + std::vector< std::array > transition_buffer_; + std::chrono::microseconds min_time_between_msgs_; - zmq::context_t _zmq_context; - zmq::socket_t _zmq_publisher; - zmq::socket_t _zmq_server; + zmq::context_t zmq_context_; + zmq::socket_t zmq_publisher_; + zmq::socket_t zmq_server_; - std::atomic_bool _active_server; - std::thread _thread; + std::atomic_bool active_server_; + std::thread thread_; void createStatusBuffer(); - TimePoint _deadline; - std::mutex _mutex; - std::atomic_bool _send_pending; + TimePoint deadline_; + std::mutex mutex_; + std::atomic_bool send_pending_; - std::future _send_future; + std::future send_future_; }; diff --git a/src/bt_file_logger.cpp b/src/bt_file_logger.cpp index 0e01e3857..ab30281ba 100644 --- a/src/bt_file_logger.cpp +++ b/src/bt_file_logger.cpp @@ -5,11 +5,11 @@ namespace BT{ FileLogger::FileLogger(BT::TreeNode *root_node, const char *filename, uint16_t buffer_size): StatusChangeLogger(root_node), - _buffer_max_size(buffer_size) + buffer_max_size_(buffer_size) { - if( _buffer_max_size != 0) + if( buffer_max_size_ != 0) { - _buffer.reserve( _buffer_max_size ); + buffer_.reserve( buffer_max_size_ ); } enableTransitionToIdle( true ); @@ -19,14 +19,14 @@ FileLogger::FileLogger(BT::TreeNode *root_node, const char *filename, uint16_t b //------------------------------------- - _file_os.open( filename, std::ofstream::binary | std::ofstream::out); + file_os_.open( filename, std::ofstream::binary | std::ofstream::out); // serialize the length of the buffer in the first 4 bytes char size_buff[4]; flatbuffers::WriteScalar(size_buff, static_cast( builder.GetSize()) ); - _file_os.write( size_buff, 4 ); - _file_os.write( reinterpret_cast(builder.GetBufferPointer()), + file_os_.write( size_buff, 4 ); + file_os_.write( reinterpret_cast(builder.GetBufferPointer()), builder.GetSize() ); } @@ -34,7 +34,7 @@ FileLogger::FileLogger(BT::TreeNode *root_node, const char *filename, uint16_t b FileLogger::~FileLogger() { this->flush(); - _file_os.close(); + file_os_.close(); } void FileLogger::callback(TimePoint timestamp, const TreeNode &node, NodeStatus prev_status, NodeStatus status) @@ -45,13 +45,13 @@ void FileLogger::callback(TimePoint timestamp, const TreeNode &node, NodeStatus prev_status, status ); - if( _buffer_max_size == 0 ) + if( buffer_max_size_ == 0 ) { - _file_os.write( reinterpret_cast(buffer.data()), buffer.size() ); + file_os_.write( reinterpret_cast(buffer.data()), buffer.size() ); } else{ - _buffer.push_back( buffer ); - if( _buffer.size() >= _buffer_max_size) + buffer_.push_back( buffer ); + if( buffer_.size() >= buffer_max_size_) { this->flush(); } @@ -60,12 +60,12 @@ void FileLogger::callback(TimePoint timestamp, const TreeNode &node, NodeStatus void FileLogger::flush() { - for (const auto& array: _buffer ) + for (const auto& array: buffer_ ) { - _file_os.write( reinterpret_cast(array.data()), array.size() ); + file_os_.write( reinterpret_cast(array.data()), array.size() ); } - _file_os.flush(); - _buffer.clear(); + file_os_.flush(); + buffer_.clear(); } diff --git a/src/bt_zmq_publisher.cpp b/src/bt_zmq_publisher.cpp index 782bca3c5..db5c6356c 100644 --- a/src/bt_zmq_publisher.cpp +++ b/src/bt_zmq_publisher.cpp @@ -6,13 +6,13 @@ namespace BT { void PublisherZMQ::createStatusBuffer() { - _status_buffer.clear(); - recursiveVisitor(_root_node, [this](TreeNode* node) + status_buffer_.clear(); + recursiveVisitor(root_node_, [this](TreeNode* node) { - size_t index = _status_buffer.size(); - _status_buffer.resize( index + 3 ); - flatbuffers::WriteScalar( &_status_buffer[index], node->UID() ); - flatbuffers::WriteScalar( &_status_buffer[index+2], + size_t index = status_buffer_.size(); + status_buffer_.resize( index + 3 ); + flatbuffers::WriteScalar( &status_buffer_[index], node->UID() ); + flatbuffers::WriteScalar( &status_buffer_[index+2], static_cast( convertToFlatbuffers(node->status())) ); }); } @@ -20,12 +20,12 @@ void PublisherZMQ::createStatusBuffer() PublisherZMQ::PublisherZMQ(TreeNode *root_node, int max_msg_per_second): StatusChangeLogger(root_node), - _root_node(root_node), - _min_time_between_msgs( std::chrono::microseconds(1000*1000) / max_msg_per_second ), - _zmq_context(1), - _zmq_publisher( _zmq_context, ZMQ_PUB ), - _zmq_server( _zmq_context, ZMQ_REP ), - _send_pending(false) + root_node_(root_node), + min_time_between_msgs_( std::chrono::microseconds(1000*1000) / max_msg_per_second ), + zmq_context_(1), + zmq_publisher_( zmq_context_, ZMQ_PUB ), + zmq_server_( zmq_context_, ZMQ_REP ), + send_pending_(false) { static bool first_instance = true; if( first_instance ) @@ -39,28 +39,28 @@ PublisherZMQ::PublisherZMQ(TreeNode *root_node, flatbuffers::FlatBufferBuilder builder(1024); CreateFlatbuffersBehaviorTree( builder, root_node); - _tree_buffer.resize(builder.GetSize()); - memcpy( _tree_buffer.data(), builder.GetBufferPointer(), builder.GetSize() ); + tree_buffer_.resize(builder.GetSize()); + memcpy( tree_buffer_.data(), builder.GetBufferPointer(), builder.GetSize() ); - _zmq_publisher.bind( "tcp://*:1666" ); - _zmq_server.bind( "tcp://*:1667" ); + zmq_publisher_.bind( "tcp://*:1666" ); + zmq_server_.bind( "tcp://*:1667" ); - _active_server = true; + active_server_ = true; - _thread = std::thread([this]() + thread_ = std::thread([this]() { - while(_active_server) + while(active_server_) { zmq::message_t req; try{ - _zmq_server.recv( &req ); - zmq::message_t reply ( _tree_buffer.size() ); - memcpy( reply.data(), _tree_buffer.data(), _tree_buffer.size() ); - _zmq_server.send( reply ); + zmq_server_.recv( &req ); + zmq::message_t reply ( tree_buffer_.size() ); + memcpy( reply.data(), tree_buffer_.data(), tree_buffer_.size() ); + zmq_server_.send( reply ); } catch( zmq::error_t& err) { - _active_server = false; + active_server_ = false; } } }); @@ -70,10 +70,10 @@ PublisherZMQ::PublisherZMQ(TreeNode *root_node, PublisherZMQ::~PublisherZMQ() { - _active_server = false; - if( _thread.joinable()) + active_server_ = false; + if( thread_.joinable()) { - _thread.join(); + thread_.join(); } flush(); } @@ -85,16 +85,16 @@ void PublisherZMQ::callback(TimePoint timestamp, const TreeNode &node, NodeStatu std::array transition = SerializeTransition(node.UID(), timestamp, prev_status, status); { - std::unique_lock lock( _mutex ); - _transition_buffer.push_back( transition ); + std::unique_lock lock( mutex_ ); + transition_buffer_.push_back( transition ); } - if( !_send_pending ) + if( !send_pending_ ) { - _send_pending = true; - _send_future = std::async(std::launch::async, [this]() + send_pending_ = true; + send_future_ = std::async(std::launch::async, [this]() { - std::this_thread::sleep_for( _min_time_between_msgs ); + std::this_thread::sleep_for( min_time_between_msgs_ ); flush(); } ); } @@ -104,36 +104,36 @@ void PublisherZMQ::flush() { zmq::message_t message; { - std::unique_lock lock( _mutex ); + std::unique_lock lock( mutex_ ); - const size_t msg_size = _status_buffer.size() + 8 + - (_transition_buffer.size() * 12); + const size_t msg_size = status_buffer_.size() + 8 + + (transition_buffer_.size() * 12); message.rebuild( msg_size ); uint8_t* data_ptr = static_cast( message.data() ); // first 4 bytes are the side of the header - flatbuffers::WriteScalar( data_ptr, _status_buffer.size() ); + flatbuffers::WriteScalar( data_ptr, status_buffer_.size() ); data_ptr += sizeof(uint32_t); // copy the header part - memcpy( data_ptr, _status_buffer.data(), _status_buffer.size() ); - data_ptr += _status_buffer.size(); + memcpy( data_ptr, status_buffer_.data(), status_buffer_.size() ); + data_ptr += status_buffer_.size(); // first 4 bytes are the side of the transition buffer - flatbuffers::WriteScalar( data_ptr, _transition_buffer.size() ); + flatbuffers::WriteScalar( data_ptr, transition_buffer_.size() ); data_ptr += sizeof(uint32_t); - for (auto& transition: _transition_buffer) + for (auto& transition: transition_buffer_) { memcpy( data_ptr, transition.data(), transition.size() ); data_ptr += transition.size(); } - _transition_buffer.clear(); + transition_buffer_.clear(); createStatusBuffer(); } - _zmq_publisher.send(message); - _send_pending = false; + zmq_publisher_.send(message); + send_pending_ = false; // printf("%.3f zmq send\n", std::chrono::duration( std::chrono::high_resolution_clock::now().time_since_epoch() ).count()); } diff --git a/src/tree_node.cpp b/src/tree_node.cpp index d4a0b7a80..83349c895 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -19,7 +19,7 @@ static uint8_t getUID() return uid++; } -BT::TreeNode::TreeNode(std::string name) : name_(name), status_(NodeStatus::IDLE), _uid( getUID() ) +BT::TreeNode::TreeNode(std::string name) : name_(name), status_(NodeStatus::IDLE), uid_( getUID() ) { } @@ -83,15 +83,15 @@ BT::TreeNode::StatusChangeSubscriber BT::TreeNode::subscribeToStatusChange(BT::T uint16_t BT::TreeNode::UID() const { - return _uid; + return uid_; } void BT::TreeNode::setRegistrationName(const std::string ®istration_name) { - _registration_name = registration_name; + registration_name_ = registration_name; } const std::string &BT::TreeNode::registrationName() const { - return _registration_name; + return registration_name_; } From 0f247b6da612b08d546baf68ef1d1bf582f1013d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 13 Jun 2018 13:29:58 +0200 Subject: [PATCH 074/125] added NodeParameters as a mandatory argument for TreeNode --- gtest/include/action_test_node.h | 2 +- gtest/include/condition_test_node.h | 2 +- gtest/src/action_test_node.cpp | 3 +- gtest/src/condition_test_node.cpp | 4 +- include/behavior_tree_core/action_node.h | 10 +- include/behavior_tree_core/behavior_tree.h | 23 ----- include/behavior_tree_core/condition_node.h | 4 +- include/behavior_tree_core/control_node.h | 2 +- .../decorator_negation_node.h | 2 +- include/behavior_tree_core/decorator_node.h | 2 +- .../decorator_repeat_node.h | 4 +- .../behavior_tree_core/decorator_retry_node.h | 4 +- .../decorator_subtree_node.h | 3 +- include/behavior_tree_core/fallback_node.h | 2 +- .../fallback_node_with_memory.h | 4 +- include/behavior_tree_core/leaf_node.h | 2 +- include/behavior_tree_core/parallel_node.h | 2 +- include/behavior_tree_core/sequence_node.h | 2 +- .../sequence_node_with_memory.h | 4 +- include/behavior_tree_core/tree_node.h | 42 +++++++- src/action_node.cpp | 10 +- src/behavior_tree.cpp | 50 ---------- src/condition_node.cpp | 3 +- src/control_node.cpp | 3 +- src/decorator_negation_node.cpp | 3 +- src/decorator_node.cpp | 3 +- src/decorator_repeat_node.cpp | 16 ++-- src/decorator_retry_node.cpp | 8 +- src/example.cpp | 8 +- src/fallback_node.cpp | 3 +- src/fallback_node_with_memory.cpp | 9 +- src/leaf_node.cpp | 3 +- src/parallel_node.cpp | 4 +- src/sequence_node.cpp | 3 +- src/sequence_node_with_memory.cpp | 10 +- src/tree_node.cpp | 96 ++++++++++++++++--- templates/action_node_template.cpp | 2 +- templates/condition_node_template.cpp | 2 +- 38 files changed, 207 insertions(+), 152 deletions(-) diff --git a/gtest/include/action_test_node.h b/gtest/include/action_test_node.h index cdefa664f..9dc9731c5 100644 --- a/gtest/include/action_test_node.h +++ b/gtest/include/action_test_node.h @@ -9,7 +9,7 @@ class ActionTestNode : public ActionNode { public: // Constructor - ActionTestNode(std::string name); + ActionTestNode(const std::string& name); ~ActionTestNode(); diff --git a/gtest/include/condition_test_node.h b/gtest/include/condition_test_node.h index 07161e991..386442ce4 100644 --- a/gtest/include/condition_test_node.h +++ b/gtest/include/condition_test_node.h @@ -9,7 +9,7 @@ class ConditionTestNode : public ConditionNode { public: // Constructor - ConditionTestNode(std::string name); + ConditionTestNode(const std::string& name); ~ConditionTestNode(); void set_boolean_value(bool boolean_value); diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index f65fe044f..a017dbcf0 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -14,7 +14,8 @@ #include "action_test_node.h" #include -BT::ActionTestNode::ActionTestNode(std::string name) : ActionNode(name) +BT::ActionTestNode::ActionTestNode(const std::string& name) : + ActionNode(name) { boolean_value_ = true; time_ = 3; diff --git a/gtest/src/condition_test_node.cpp b/gtest/src/condition_test_node.cpp index 8c343dab2..42706428e 100644 --- a/gtest/src/condition_test_node.cpp +++ b/gtest/src/condition_test_node.cpp @@ -13,7 +13,8 @@ #include "condition_test_node.h" #include -BT::ConditionTestNode::ConditionTestNode(std::string name) : ConditionNode::ConditionNode(name) +BT::ConditionTestNode::ConditionTestNode(const std::string& name) : + ConditionNode::ConditionNode(name) { boolean_value_ = true; } @@ -25,7 +26,6 @@ BT::ConditionTestNode::~ConditionTestNode() BT::NodeStatus BT::ConditionTestNode::tick() { // Condition checking and state update - if (boolean_value_) { setStatus(NodeStatus::SUCCESS); diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 9833527b8..438130887 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -23,8 +23,8 @@ class ActionNodeBase : public LeafNode { public: // Constructor - ActionNodeBase(std::string name); - ~ActionNodeBase() = default; + ActionNodeBase(const std::string& name, const NodeParameters ¶meters); + ~ActionNodeBase() override = default; virtual NodeType type() const override final { @@ -50,7 +50,7 @@ class SimpleActionNode : public ActionNodeBase typedef std::function TickFunctor; // Constructor: you must provide the funtion to call when tick() is invoked - SimpleActionNode(std::string name, TickFunctor tick_functor); + SimpleActionNode(const std::string& name, TickFunctor tick_functor); ~SimpleActionNode() = default; @@ -82,8 +82,8 @@ class ActionNode : public ActionNodeBase { public: // Constructor - ActionNode(std::string name); - virtual ~ActionNode(); + ActionNode(const std::string& name, const NodeParameters& parameters = NodeParameters() ); + virtual ~ActionNode() override; // The method that is going to be executed by the thread void waitForTick(); diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index f4e1e3c23..a7b8157b8 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -53,29 +53,6 @@ typedef std::vector> SerializedTreeStatus; void buildSerializedStatusSnapshot(const TreeNode *root_node, SerializedTreeStatus& serialized_buffer); -/** - * @brief toStr converts NodeStatus to string. Optionally colored. - */ -const char* toStr(const BT::NodeStatus& status, bool colored = false); - - -inline std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status) -{ - os << toStr(status); - return os; -} - -/** - * @brief toStr converts NodeType to string. - */ -const char* toStr(const BT::NodeType& type); - -inline std::ostream& operator<<(std::ostream& os, const BT::NodeType& type) -{ - os << toStr(type); - return os; -} - } diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index 2309dff43..82acc3e45 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -22,8 +22,8 @@ class ConditionNode : public LeafNode { public: // Constructor - ConditionNode(std::string name); - ~ConditionNode() = default; + ConditionNode(const std::string& name, const NodeParameters& parameters = NodeParameters() ); + ~ConditionNode() override = default; // The method used to interrupt the execution of the node virtual void halt() override; diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index 9aa138353..fc2d73c15 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -27,7 +27,7 @@ class ControlNode : public TreeNode public: // Constructor - ControlNode(std::string name); + ControlNode(const std::string& name, const NodeParameters& parameters); ~ControlNode() = default; // The method used to fill the child vector diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h index f2d6f028b..cefd1f81b 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -22,7 +22,7 @@ class DecoratorNegationNode : public DecoratorNode { public: // Constructor - DecoratorNegationNode(std::string name); + DecoratorNegationNode(const std::string& name, const NodeParameters& parameters); virtual ~DecoratorNegationNode() = default; diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index 59b9a4ff3..33bcffde1 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -12,7 +12,7 @@ class DecoratorNode : public TreeNode public: // Constructor - DecoratorNode(std::string name); + DecoratorNode(const std::string& name, const NodeParameters& parameters); ~DecoratorNode() = default; // The method used to fill the child vector diff --git a/include/behavior_tree_core/decorator_repeat_node.h b/include/behavior_tree_core/decorator_repeat_node.h index 0b25a644f..1c0395b07 100644 --- a/include/behavior_tree_core/decorator_repeat_node.h +++ b/include/behavior_tree_core/decorator_repeat_node.h @@ -22,9 +22,9 @@ class DecoratorRepeatNode : public DecoratorNode { public: // Constructor - DecoratorRepeatNode(std::string name, unsigned int NTries); + DecoratorRepeatNode(const std::string &name, unsigned int NTries); - DecoratorRepeatNode(std::string name, const NodeParameters& params); + DecoratorRepeatNode(const std::string& name, const NodeParameters& params); ~DecoratorRepeatNode() = default; diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h index 1db56a38d..dc07a177d 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -22,9 +22,9 @@ class DecoratorRetryNode : public DecoratorNode { public: // Constructor - DecoratorRetryNode(std::string name, unsigned int NTries); + DecoratorRetryNode(const std::string& name, unsigned int NTries); - DecoratorRetryNode(std::string name, const NodeParameters& params); + DecoratorRetryNode(const std::string& name, const NodeParameters& params); ~DecoratorRetryNode() = default; diff --git a/include/behavior_tree_core/decorator_subtree_node.h b/include/behavior_tree_core/decorator_subtree_node.h index be5f8d11c..c906838f9 100644 --- a/include/behavior_tree_core/decorator_subtree_node.h +++ b/include/behavior_tree_core/decorator_subtree_node.h @@ -9,7 +9,8 @@ class DecoratorSubtreeNode : public DecoratorNode { public: // Constructor - DecoratorSubtreeNode(std::string name) : DecoratorNode(name) + DecoratorSubtreeNode(const std::string& name, const NodeParameters& parameters) : + DecoratorNode(name, parameters) { } diff --git a/include/behavior_tree_core/fallback_node.h b/include/behavior_tree_core/fallback_node.h index aad97c505..e3b1f2fcd 100644 --- a/include/behavior_tree_core/fallback_node.h +++ b/include/behavior_tree_core/fallback_node.h @@ -22,7 +22,7 @@ class FallbackNode : public ControlNode { public: // Constructor - FallbackNode(std::string name); + FallbackNode(const std::string& name); ~FallbackNode() = default; private: diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index da166d1ff..9e808eb61 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -21,10 +21,10 @@ namespace BT class FallbackNodeWithMemory : public ControlNode { public: - FallbackNodeWithMemory(std::string name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); + FallbackNodeWithMemory(const std::string& name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); // Reset policy passed by parameter [reset_policy] - FallbackNodeWithMemory(std::string name, const NodeParameters& params); + FallbackNodeWithMemory(const std::string&, const NodeParameters& params); ~FallbackNodeWithMemory() = default; diff --git a/include/behavior_tree_core/leaf_node.h b/include/behavior_tree_core/leaf_node.h index 259155f23..ca8f9dfe6 100644 --- a/include/behavior_tree_core/leaf_node.h +++ b/include/behavior_tree_core/leaf_node.h @@ -22,7 +22,7 @@ class LeafNode : public TreeNode { protected: public: - LeafNode(std::string name); + LeafNode(const std::string& name, const NodeParameters ¶meters); ~LeafNode() = default; }; } diff --git a/include/behavior_tree_core/parallel_node.h b/include/behavior_tree_core/parallel_node.h index 8632c4ed1..617d9c3f8 100644 --- a/include/behavior_tree_core/parallel_node.h +++ b/include/behavior_tree_core/parallel_node.h @@ -22,7 +22,7 @@ class ParallelNode : public ControlNode { public: // Constructor - ParallelNode(std::string name, int threshold_M); + ParallelNode(const std::string &name, int threshold_M); ~ParallelNode() = default; virtual void halt() override; diff --git a/include/behavior_tree_core/sequence_node.h b/include/behavior_tree_core/sequence_node.h index d931d0baf..d29143e59 100644 --- a/include/behavior_tree_core/sequence_node.h +++ b/include/behavior_tree_core/sequence_node.h @@ -22,7 +22,7 @@ class SequenceNode : public ControlNode { public: // Constructor - SequenceNode(std::string name); + SequenceNode(const std::string& name); ~SequenceNode() = default; private: diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index b05fcf9ba..2c9e9183a 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -21,10 +21,10 @@ namespace BT class SequenceNodeWithMemory : public ControlNode { public: - SequenceNodeWithMemory(std::string name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); + SequenceNodeWithMemory(const std::string &name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); // Reset policy passed by parameter [reset_policy] - SequenceNodeWithMemory(std::string name, const NodeParameters& params); + SequenceNodeWithMemory(const std::string &name, const NodeParameters& params); ~SequenceNodeWithMemory() = default; diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index a925ef078..a531d21ad 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -109,7 +109,7 @@ class TreeNode public: // The constructor and the destructor - TreeNode(std::string name); + TreeNode(const std::string& name, const NodeParameters& parameters); virtual ~TreeNode() = default; // The method that is going to be executed when the node receive a tick @@ -160,12 +160,52 @@ class TreeNode std::string registration_name_; + const NodeParameters parameters_; + }; typedef std::shared_ptr TreeNodePtr; +//------------------------------------------------------------------ + // The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; + +/** + * @brief toStr converts NodeStatus to string. Optionally colored. + */ +const char* toStr(const BT::NodeStatus& status, bool colored = false); + + +inline std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status) +{ + os << toStr(status); + return os; +} + +/** + * @brief toStr converts NodeType to string. + */ +const char* toStr(const BT::NodeType& type); + +inline std::ostream& operator<<(std::ostream& os, const BT::NodeType& type) +{ + os << toStr(type); + return os; +} + +/** + * @brief toStr converts ResetPolicy to string. + */ +const char* toStr(const BT::ResetPolicy& policy); + +inline std::ostream& operator<<(std::ostream& os, const BT::ResetPolicy& type) +{ + os << toStr(type); + return os; +} + + } #endif diff --git a/src/action_node.cpp b/src/action_node.cpp index ae49cbfef..762713958 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -13,14 +13,15 @@ #include "behavior_tree_core/action_node.h" -BT::ActionNodeBase::ActionNodeBase(std::string name) : LeafNode::LeafNode(name) +BT::ActionNodeBase::ActionNodeBase(const std::string& name, const NodeParameters ¶meters) : + LeafNode::LeafNode(name,parameters) { } //------------------------------------------------------- -BT::SimpleActionNode::SimpleActionNode(std::string name, BT::SimpleActionNode::TickFunctor tick_functor) - : ActionNodeBase(name), tick_functor_(tick_functor) +BT::SimpleActionNode::SimpleActionNode(const std::string &name, BT::SimpleActionNode::TickFunctor tick_functor) + : ActionNodeBase(name, NodeParameters()), tick_functor_( std::move(tick_functor) ) { } @@ -44,7 +45,8 @@ BT::NodeStatus BT::SimpleActionNode::tick() //------------------------------------------------------- -BT::ActionNode::ActionNode(std::string name) : ActionNodeBase(name), loop_(true) +BT::ActionNode::ActionNode(const std::string& name, const NodeParameters& parameters) : + ActionNodeBase(name, parameters), loop_(true) { thread_ = std::thread(&ActionNode::waitForTick, this); } diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index 4c9b555e4..467e917c3 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -73,54 +73,4 @@ void buildSerializedStatusSnapshot(TreeNode *root_node, SerializedTreeStatus& se recursiveVisitor(root_node, visitor); } -const char *toStr(const NodeStatus &status, bool colored) -{ - if( ! colored ){ - switch (status) - { - case NodeStatus::SUCCESS: - return "SUCCESS"; - case NodeStatus::FAILURE: - return "FAILURE"; - case NodeStatus::RUNNING: - return "RUNNING"; - case NodeStatus::IDLE: - return "IDLE"; - } - } - else{ - switch (status) - { - case NodeStatus::SUCCESS: - return ( "\x1b[32m" "SUCCESS" "\x1b[0m"); // RED - case NodeStatus::FAILURE: - return ( "\x1b[31m" "FAILURE" "\x1b[0m"); // GREEN - case NodeStatus::RUNNING: - return ( "\x1b[33m" "RUNNING" "\x1b[0m"); // YELLOW - case NodeStatus::IDLE: - return ( "\x1b[36m" "IDLE" "\x1b[0m"); // CYAN - } - } - return "Undefined"; -} - -const char *toStr(const NodeType &type) -{ - switch (type) - { - case NodeType::ACTION: - return "Action"; - case NodeType::CONDITION: - return "Condition"; - case NodeType::DECORATOR: - return "Decorator"; - case NodeType::CONTROL: - return "Control"; - case NodeType::SUBTREE: - return "SubTree"; - default: - return "Undefined"; - } -} - } diff --git a/src/condition_node.cpp b/src/condition_node.cpp index d141b8f95..cb43ef781 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -13,7 +13,8 @@ #include "behavior_tree_core/condition_node.h" -BT::ConditionNode::ConditionNode(std::string name) : LeafNode::LeafNode(name) +BT::ConditionNode::ConditionNode(const std::string& name, const NodeParameters& parameters) + : LeafNode::LeafNode(name,parameters) { } diff --git a/src/control_node.cpp b/src/control_node.cpp index b4eb3012c..2cb88367c 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -13,7 +13,8 @@ #include "behavior_tree_core/control_node.h" -BT::ControlNode::ControlNode(std::string name) : TreeNode::TreeNode(name) +BT::ControlNode::ControlNode(const std::string& name, const NodeParameters& parameters) : + TreeNode::TreeNode(name,parameters) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index 6a596972a..ba513a56f 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -13,7 +13,8 @@ #include "behavior_tree_core/decorator_negation_node.h" -BT::DecoratorNegationNode::DecoratorNegationNode(std::string name) : DecoratorNode(name) +BT::DecoratorNegationNode::DecoratorNegationNode(const std::string& name, const NodeParameters& parameters) : + DecoratorNode(name,parameters) { } diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index dbd4dbc03..74574f81b 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -12,7 +12,8 @@ #include "behavior_tree_core/decorator_node.h" -BT::DecoratorNode::DecoratorNode(std::string name) : TreeNode::TreeNode(name), child_node_(nullptr) +BT::DecoratorNode::DecoratorNode(const std::string& name, const NodeParameters& parameters) : + TreeNode::TreeNode(name, parameters), child_node_(nullptr) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable diff --git a/src/decorator_repeat_node.cpp b/src/decorator_repeat_node.cpp index 1a1f10b1e..cf5618446 100644 --- a/src/decorator_repeat_node.cpp +++ b/src/decorator_repeat_node.cpp @@ -13,13 +13,15 @@ #include "behavior_tree_core/decorator_repeat_node.h" -BT::DecoratorRepeatNode::DecoratorRepeatNode(std::string name, unsigned int NTries) - : DecoratorNode(name), NTries_(NTries), TryIndx_(0) +namespace BT { + +DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, unsigned int NTries) + : DecoratorNode(name, {{"num_cycles", std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) { } -BT::DecoratorRepeatNode::DecoratorRepeatNode(std::string name, const BT::NodeParameters& params) - : DecoratorNode(name), NTries_(1), TryIndx_(0) +DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, const NodeParameters& params) + : DecoratorNode(name,params), NTries_(1), TryIndx_(0) { auto it = params.find("num_cycles"); if (it == params.end()) @@ -29,10 +31,10 @@ BT::DecoratorRepeatNode::DecoratorRepeatNode(std::string name, const BT::NodePar NTries_ = std::stoul(it->second); } -BT::NodeStatus BT::DecoratorRepeatNode::tick() +NodeStatus DecoratorRepeatNode::tick() { setStatus(NodeStatus::RUNNING); - BT::NodeStatus child_state = child_node_->executeTick(); + NodeStatus child_state = child_node_->executeTick(); switch (child_state) { @@ -69,3 +71,5 @@ BT::NodeStatus BT::DecoratorRepeatNode::tick() return status(); } + +} diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index 4ef4e361a..a28f8afc0 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -13,13 +13,13 @@ #include "behavior_tree_core/decorator_retry_node.h" -BT::DecoratorRetryNode::DecoratorRetryNode(std::string name, unsigned int NTries) - : DecoratorNode(name), NTries_(NTries), TryIndx_(0) +BT::DecoratorRetryNode::DecoratorRetryNode(const std::string& name, unsigned int NTries) + : DecoratorNode(name, {{"num_attempts", std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) { } -BT::DecoratorRetryNode::DecoratorRetryNode(std::string name, const BT::NodeParameters& params) - : DecoratorNode(name), NTries_(1), TryIndx_(0) +BT::DecoratorRetryNode::DecoratorRetryNode(const std::string& name, const BT::NodeParameters& params) + : DecoratorNode(name, params), NTries_(1), TryIndx_(0) { auto it = params.find("num_attempts"); if (it == params.end()) diff --git a/src/example.cpp b/src/example.cpp index f177d3384..e430603e8 100644 --- a/src/example.cpp +++ b/src/example.cpp @@ -4,12 +4,12 @@ class MyCondition : public BT::ConditionNode { public: - MyCondition(std::string name); + MyCondition(const std::string& name); ~MyCondition(); BT::ReturnStatus Tick(); }; -MyCondition::MyCondition(std::string name) : BT::ConditionNode::ConditionNode(name) +MyCondition::MyCondition(const std::string& name) : BT::ConditionNode::ConditionNode(name) { } @@ -23,13 +23,13 @@ BT::ReturnStatus MyCondition::Tick() class MyAction : public BT::ActionNode { public: - MyAction(std::string name); + MyAction(const std::string& name); ~MyAction(); BT::ReturnStatus Tick(); void Halt(); }; -MyAction::MyAction(std::string name) : ActionNode::ActionNode(name) +MyAction::MyAction(const std::string& name) : ActionNode::ActionNode(name) { } diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 774183bc7..060eba7dc 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -13,7 +13,8 @@ #include "behavior_tree_core/fallback_node.h" -BT::FallbackNode::FallbackNode(std::string name) : ControlNode::ControlNode(name) +BT::FallbackNode::FallbackNode(const std::string& name) : + ControlNode::ControlNode(name, NodeParameters()) { } diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index cd62895c8..1236b3018 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -13,13 +13,14 @@ #include "behavior_tree_core/fallback_node_with_memory.h" -BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, ResetPolicy reset_policy) - : ControlNode::ControlNode(name), current_child_idx_(0), reset_policy_(reset_policy) +BT::FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, ResetPolicy reset_policy) + : ControlNode::ControlNode(name, {{"reset_policy", toStr(reset_policy)}}), + current_child_idx_(0), reset_policy_(reset_policy) { } -BT::FallbackNodeWithMemory::FallbackNodeWithMemory(std::string name, const NodeParameters& params) - : ControlNode::ControlNode(name), current_child_idx_(0) +BT::FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, const NodeParameters& params) + : ControlNode::ControlNode(name,params), current_child_idx_(0) { auto it = params.find("reset_policy"); if( it == params.end()) diff --git a/src/leaf_node.cpp b/src/leaf_node.cpp index 478026f5e..919123b2b 100644 --- a/src/leaf_node.cpp +++ b/src/leaf_node.cpp @@ -13,6 +13,7 @@ #include "behavior_tree_core/leaf_node.h" -BT::LeafNode::LeafNode(std::string name) : TreeNode(name) +BT::LeafNode::LeafNode(const std::string& name, const NodeParameters& parameters) : + TreeNode(name,parameters) { } diff --git a/src/parallel_node.cpp b/src/parallel_node.cpp index b97734c47..541d6a728 100644 --- a/src/parallel_node.cpp +++ b/src/parallel_node.cpp @@ -13,8 +13,8 @@ #include "behavior_tree_core/parallel_node.h" -BT::ParallelNode::ParallelNode(std::string name, int threshold_M) - : ControlNode::ControlNode(name), threshold_M_(threshold_M) +BT::ParallelNode::ParallelNode(const std::string& name, int threshold_M) + : ControlNode::ControlNode(name, NodeParameters()), threshold_M_(threshold_M) { } diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 15768447a..08e16d959 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -13,7 +13,8 @@ #include "behavior_tree_core/sequence_node.h" -BT::SequenceNode::SequenceNode(std::string name) : ControlNode::ControlNode(name) +BT::SequenceNode::SequenceNode(const std::string& name) : + ControlNode::ControlNode(name, NodeParameters()) { } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index a389e9611..3151fa6bf 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -13,13 +13,15 @@ #include "behavior_tree_core/sequence_node_with_memory.h" -BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, ResetPolicy reset_policy) - : ControlNode::ControlNode(name), current_child_idx_(0), reset_policy_(reset_policy) +BT::SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string &name, ResetPolicy reset_policy) + : ControlNode::ControlNode(name, {{"reset_policy", toStr(reset_policy)}}), + current_child_idx_(0), + reset_policy_(reset_policy) { } -BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, const NodeParameters& params) - : ControlNode::ControlNode(name), current_child_idx_(0) +BT::SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, const NodeParameters& params) + : ControlNode::ControlNode(name, params), current_child_idx_(0) { auto it = params.find("reset_policy"); if( it == params.end()) diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 83349c895..4dba28727 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -13,24 +13,27 @@ #include "behavior_tree_core/tree_node.h" +namespace BT { + static uint8_t getUID() { static uint8_t uid = 1; return uid++; } -BT::TreeNode::TreeNode(std::string name) : name_(name), status_(NodeStatus::IDLE), uid_( getUID() ) +TreeNode::TreeNode(const std::string& name, const NodeParameters& parameters) : + name_(name), status_(NodeStatus::IDLE), uid_( getUID() ), parameters_(parameters) { } -BT::NodeStatus BT::TreeNode::executeTick() +NodeStatus TreeNode::executeTick() { const NodeStatus status = tick(); setStatus(status); return status; } -void BT::TreeNode::setStatus(NodeStatus new_status) +void TreeNode::setStatus(NodeStatus new_status) { NodeStatus prev_status; { @@ -46,18 +49,18 @@ void BT::TreeNode::setStatus(NodeStatus new_status) } } -BT::NodeStatus BT::TreeNode::status() const +NodeStatus TreeNode::status() const { std::lock_guard LockGuard(state_mutex_); return status_; } -void BT::TreeNode::setName(const std::string& new_name) +void TreeNode::setName(const std::string& new_name) { name_ = new_name; } -BT::NodeStatus BT::TreeNode::waitValidStatus() +NodeStatus TreeNode::waitValidStatus() { std::unique_lock lk(state_mutex_); @@ -66,32 +69,99 @@ BT::NodeStatus BT::TreeNode::waitValidStatus() return status_; } -const std::string& BT::TreeNode::name() const +const std::string& TreeNode::name() const { return name_; } -bool BT::TreeNode::isHalted() const +bool TreeNode::isHalted() const { return status() == NodeStatus::IDLE; } -BT::TreeNode::StatusChangeSubscriber BT::TreeNode::subscribeToStatusChange(BT::TreeNode::StatusChangeCallback callback) +TreeNode::StatusChangeSubscriber TreeNode::subscribeToStatusChange(TreeNode::StatusChangeCallback callback) { - return state_change_signal_.subscribe(callback); + return state_change_signal_.subscribe( std::move(callback) ); } -uint16_t BT::TreeNode::UID() const +uint16_t TreeNode::UID() const { return uid_; } -void BT::TreeNode::setRegistrationName(const std::string ®istration_name) +void TreeNode::setRegistrationName(const std::string ®istration_name) { registration_name_ = registration_name; } -const std::string &BT::TreeNode::registrationName() const +const std::string &TreeNode::registrationName() const { return registration_name_; } + +const char *toStr(const NodeStatus &status, bool colored) +{ + if( ! colored ){ + switch (status) + { + case NodeStatus::SUCCESS: + return "SUCCESS"; + case NodeStatus::FAILURE: + return "FAILURE"; + case NodeStatus::RUNNING: + return "RUNNING"; + case NodeStatus::IDLE: + return "IDLE"; + } + } + else{ + switch (status) + { + case NodeStatus::SUCCESS: + return ( "\x1b[32m" "SUCCESS" "\x1b[0m"); // RED + case NodeStatus::FAILURE: + return ( "\x1b[31m" "FAILURE" "\x1b[0m"); // GREEN + case NodeStatus::RUNNING: + return ( "\x1b[33m" "RUNNING" "\x1b[0m"); // YELLOW + case NodeStatus::IDLE: + return ( "\x1b[36m" "IDLE" "\x1b[0m"); // CYAN + } + } + return "Undefined"; +} + +const char *toStr(const NodeType &type) +{ + switch (type) + { + case NodeType::ACTION: + return "Action"; + case NodeType::CONDITION: + return "Condition"; + case NodeType::DECORATOR: + return "Decorator"; + case NodeType::CONTROL: + return "Control"; + case NodeType::SUBTREE: + return "SubTree"; + default: + return "Undefined"; + } +} + +const char *toStr(const ResetPolicy &policy) +{ + switch (policy) + { + case ResetPolicy::ON_FAILURE: + return "ON_FAILURE"; + case ResetPolicy::ON_SUCCESS: + return "ON_SUCCESS"; + case ResetPolicy::ON_SUCCESS_OR_FAILURE: + return "ON_SUCCESS_OR_FAILURE"; + default: + return "Undefined"; + } +} + +} diff --git a/templates/action_node_template.cpp b/templates/action_node_template.cpp index 83a426950..4c7f3d069 100644 --- a/templates/action_node_template.cpp +++ b/templates/action_node_template.cpp @@ -1,7 +1,7 @@ #include #include -BT::CLASSNAME::CONSTRUCTOR(std::string name) : ActionNode::ActionNode(name) +BT::CLASSNAME::CONSTRUCTOR(const std::string& name) : ActionNode::ActionNode(name) { thread_ = std::thread(&ActionTestNode::WaitForTick, this); } diff --git a/templates/condition_node_template.cpp b/templates/condition_node_template.cpp index 423b60154..eedc19959 100644 --- a/templates/condition_node_template.cpp +++ b/templates/condition_node_template.cpp @@ -1,6 +1,6 @@ #include -BT::CLASSNAME::CONSTRUCTOR(std::string name) : ConditionNode::ConditionNode(name) +BT::CLASSNAME::CONSTRUCTOR(const std::string& name) : ConditionNode::ConditionNode(name) { } From 564a3621c87f4bbab6f0abdd3769a19a8f19b92a Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 13 Jun 2018 14:41:35 +0200 Subject: [PATCH 075/125] Moved stuff to basic_types.h --- include/behavior_tree_core/basic_types.h | 114 +++++++++++++++++++ include/behavior_tree_core/tree_node.h | 109 +++--------------- src/basic_types.cpp | 136 +++++++++++++++++++++++ src/decorator_repeat_node.cpp | 14 +-- src/decorator_retry_node.cpp | 12 +- src/fallback_node_with_memory.cpp | 28 +---- src/sequence_node_with_memory.cpp | 25 +---- src/tree_node.cpp | 68 +----------- 8 files changed, 283 insertions(+), 223 deletions(-) create mode 100644 include/behavior_tree_core/basic_types.h create mode 100644 src/basic_types.cpp diff --git a/include/behavior_tree_core/basic_types.h b/include/behavior_tree_core/basic_types.h new file mode 100644 index 000000000..c947029d2 --- /dev/null +++ b/include/behavior_tree_core/basic_types.h @@ -0,0 +1,114 @@ +#ifndef BT_BASIC_TYPES_H +#define BT_BASIC_TYPES_H + +#include +#include + +namespace BT{ +// Enumerates the possible types of a node, for drawinf we +// have do discriminate whoich control node it is: +enum class NodeType +{ + UNDEFINED = 0, + ACTION, + CONDITION, + CONTROL, + DECORATOR, + SUBTREE +}; + +// Enumerates the states every node can be in after execution during a particular +// time step: +// - "Success" indicates that the node has completed running during this time step; +// - "Failure" indicates that the node has determined it will not be able to complete +// its task; +// - "Running" indicates that the node has successfully moved forward during this +// time step, but the task is not yet complete; +// - "Idle" indicates that the node hasn't run yet. +// - "Halted" indicates that the node has been halted by its father. +enum class NodeStatus +{ + IDLE = 0, + RUNNING, + SUCCESS, + FAILURE +}; + + +// Enumerates the options for when a parallel node is considered to have failed: +// - "FAIL_ON_ONE" indicates that the node will return failure as soon as one of +// its children fails; +// - "FAIL_ON_ALL" indicates that all of the node's children must fail before it +// returns failure. +enum FailurePolicy +{ + FAIL_ON_ONE, + FAIL_ON_ALL +}; +enum ResetPolicy +{ + ON_SUCCESS_OR_FAILURE, + ON_SUCCESS, + ON_FAILURE +}; + +// Enumerates the options for when a parallel node is considered to have succeeded: +// - "SUCCEED_ON_ONE" indicates that the node will return success as soon as one +// of its children succeeds; +// - "BT::SUCCEED_ON_ALL" indicates that all of the node's children must succeed before +// it returns success. +enum SuccessPolicy +{ + SUCCEED_ON_ONE, + SUCCEED_ON_ALL +}; + +template +T convertFromString(const char* str); + +template inline +T convertFromString(const std::string& str) +{ + return convertFromString( str.c_str() ); +} + +//------------------------------------------------------------------ + +/** + * @brief toStr converts NodeStatus to string. Optionally colored. + */ +const char* toStr(const BT::NodeStatus& status, bool colored = false); + + +inline std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status) +{ + os << toStr(status); + return os; +} + +/** + * @brief toStr converts NodeType to string. + */ +const char* toStr(const BT::NodeType& type); + +inline std::ostream& operator<<(std::ostream& os, const BT::NodeType& type) +{ + os << toStr(type); + return os; +} + +/** + * @brief toStr converts ResetPolicy to string. + */ +const char* toStr(const BT::ResetPolicy& policy); + +inline std::ostream& operator<<(std::ostream& os, const BT::ResetPolicy& type) +{ + os << toStr(type); + return os; +} + + +} + +#endif // BT_BASIC_TYPES_H diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index a531d21ad..8a63c4e38 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -22,69 +22,10 @@ #include "behavior_tree_core/tick_engine.h" #include "behavior_tree_core/exceptions.h" #include "behavior_tree_core/signal.h" +#include "behavior_tree_core/basic_types.h" namespace BT { -// Enumerates the possible types of a node, for drawinf we have do discriminate whoich control node it is: - -enum class NodeType -{ - UNDEFINED = 0, - ACTION, - CONDITION, - CONTROL, - DECORATOR, - SUBTREE -}; - -// Enumerates the states every node can be in after execution during a particular -// time step: -// - "Success" indicates that the node has completed running during this time step; -// - "Failure" indicates that the node has determined it will not be able to complete -// its task; -// - "Running" indicates that the node has successfully moved forward during this -// time step, but the task is not yet complete; -// - "Idle" indicates that the node hasn't run yet. -// - "Halted" indicates that the node has been halted by its father. -enum class NodeStatus -{ - IDLE = 0, - RUNNING, - SUCCESS, - FAILURE -}; - - -// Enumerates the options for when a parallel node is considered to have failed: -// - "FAIL_ON_ONE" indicates that the node will return failure as soon as one of -// its children fails; -// - "FAIL_ON_ALL" indicates that all of the node's children must fail before it -// returns failure. -enum FailurePolicy -{ - FAIL_ON_ONE, - FAIL_ON_ALL -}; -enum ResetPolicy -{ - ON_SUCCESS_OR_FAILURE, - ON_SUCCESS, - ON_FAILURE -}; - -// Enumerates the options for when a parallel node is considered to have succeeded: -// - "SUCCEED_ON_ONE" indicates that the node will return success as soon as one -// of its children succeeds; -// - "BT::SUCCEED_ON_ALL" indicates that all of the node's children must succeed before -// it returns success. -enum SuccessPolicy -{ - SUCCEED_ON_ONE, - SUCCEED_ON_ALL -}; - -// If "BT::FAIL_vON_ONE" and "BT::SUCCEED_ON_ONE" are both active and are both trigerred in the -// same time step, failure will take precedence. // We call Parameters the set of Key/Values that can be read from file and are // used to parametrize an object. It is up to the user's code to parse the string. @@ -92,6 +33,7 @@ typedef std::map NodeParameters; typedef std::chrono::high_resolution_clock::time_point TimePoint; + // Abstract base class for Behavior Tree Nodes class TreeNode { @@ -152,6 +94,17 @@ class TreeNode const std::string& registrationName() const; +protected: + template T getParam(const std::string& key) const + { + auto it = parameters_.find(key); + if( it == parameters_.end() ) + { + throw std::invalid_argument( std::string("Can't find the parameter with key: ") + key ); + } + return convertFromString( key.c_str() ); + } + private: StatusChangeSignal state_change_signal_; @@ -166,45 +119,9 @@ class TreeNode typedef std::shared_ptr TreeNodePtr; -//------------------------------------------------------------------ - // The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; -/** - * @brief toStr converts NodeStatus to string. Optionally colored. - */ -const char* toStr(const BT::NodeStatus& status, bool colored = false); - - -inline std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status) -{ - os << toStr(status); - return os; -} - -/** - * @brief toStr converts NodeType to string. - */ -const char* toStr(const BT::NodeType& type); - -inline std::ostream& operator<<(std::ostream& os, const BT::NodeType& type) -{ - os << toStr(type); - return os; -} - -/** - * @brief toStr converts ResetPolicy to string. - */ -const char* toStr(const BT::ResetPolicy& policy); - -inline std::ostream& operator<<(std::ostream& os, const BT::ResetPolicy& type) -{ - os << toStr(type); - return os; -} - } diff --git a/src/basic_types.cpp b/src/basic_types.cpp new file mode 100644 index 000000000..cb82379c2 --- /dev/null +++ b/src/basic_types.cpp @@ -0,0 +1,136 @@ +#include "behavior_tree_core/basic_types.h" +#include + +namespace BT{ + +const char *toStr(const NodeStatus &status, bool colored) +{ + if( ! colored ){ + switch (status) + { + case NodeStatus::SUCCESS: + return "SUCCESS"; + case NodeStatus::FAILURE: + return "FAILURE"; + case NodeStatus::RUNNING: + return "RUNNING"; + case NodeStatus::IDLE: + return "IDLE"; + } + } + else{ + switch (status) + { + case NodeStatus::SUCCESS: + return ( "\x1b[32m" "SUCCESS" "\x1b[0m"); // RED + case NodeStatus::FAILURE: + return ( "\x1b[31m" "FAILURE" "\x1b[0m"); // GREEN + case NodeStatus::RUNNING: + return ( "\x1b[33m" "RUNNING" "\x1b[0m"); // YELLOW + case NodeStatus::IDLE: + return ( "\x1b[36m" "IDLE" "\x1b[0m"); // CYAN + } + } + return "Undefined"; +} + +const char *toStr(const NodeType &type) +{ + switch (type) + { + case NodeType::ACTION: + return "Action"; + case NodeType::CONDITION: + return "Condition"; + case NodeType::DECORATOR: + return "Decorator"; + case NodeType::CONTROL: + return "Control"; + case NodeType::SUBTREE: + return "SubTree"; + default: + return "Undefined"; + } +} + +const char *toStr(const ResetPolicy &policy) +{ + switch (policy) + { + case ResetPolicy::ON_FAILURE: + return "ON_FAILURE"; + case ResetPolicy::ON_SUCCESS: + return "ON_SUCCESS"; + case ResetPolicy::ON_SUCCESS_OR_FAILURE: + return "ON_SUCCESS_OR_FAILURE"; + default: + return "Undefined"; + } +} + +template<> int convertFromString(const char* str) +{ + return std::stoi(str); +} + +template<> unsigned convertFromString(const char* str) +{ + return std::stoul(str); +} + +template<> double convertFromString(const char* str) +{ + return std::stod(str); +} + +template<> NodeStatus convertFromString(const char* str) +{ + for( auto status: { + NodeStatus::IDLE, + NodeStatus::RUNNING, + NodeStatus::SUCCESS, + NodeStatus::FAILURE} ) + { + if( std::strcmp( toStr(status), str) == 0 ) + { + return status; + } + } + throw std::invalid_argument( std::string("Cannot convert this to NodeStatus: ") + str ); +} + +template<> NodeType convertFromString(const char* str) +{ + for( auto status: { + NodeType::ACTION, + NodeType::CONDITION, + NodeType::CONTROL, + NodeType::DECORATOR, + NodeType::SUBTREE, + NodeType::UNDEFINED} ) + { + if( std::strcmp( toStr(status), str) == 0 ) + { + return status; + } + } + throw std::invalid_argument( std::string("Cannot convert this to NodeType: ") + str ); +} + +template<> ResetPolicy convertFromString(const char* str) +{ + for( auto status: { + ResetPolicy::ON_SUCCESS, + ResetPolicy::ON_SUCCESS_OR_FAILURE, + ResetPolicy::ON_FAILURE} ) + { + if( std::strcmp( toStr(status), str) == 0 ) + { + return status; + } + } + throw std::invalid_argument( std::string("Cannot convert this to ResetPolicy: ") + str ); +} + +} // end namespace + diff --git a/src/decorator_repeat_node.cpp b/src/decorator_repeat_node.cpp index cf5618446..c1bc91db1 100644 --- a/src/decorator_repeat_node.cpp +++ b/src/decorator_repeat_node.cpp @@ -16,19 +16,17 @@ namespace BT { DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, unsigned int NTries) - : DecoratorNode(name, {{"num_cycles", std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) + : DecoratorNode(name, {{"num_cycles", std::to_string(NTries)}}), + NTries_(NTries), TryIndx_(0) { } DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, const NodeParameters& params) - : DecoratorNode(name,params), NTries_(1), TryIndx_(0) + : DecoratorNode(name,params), + NTries_( getParam("num_cycles") ), + TryIndx_(0) { - auto it = params.find("num_cycles"); - if (it == params.end()) - { - throw std::runtime_error("[DecoratorRepeatNode] requires a parameter callen 'num_cycles'"); - } - NTries_ = std::stoul(it->second); + } NodeStatus DecoratorRepeatNode::tick() diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index a28f8afc0..b75ca049a 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -14,19 +14,15 @@ #include "behavior_tree_core/decorator_retry_node.h" BT::DecoratorRetryNode::DecoratorRetryNode(const std::string& name, unsigned int NTries) - : DecoratorNode(name, {{"num_attempts", std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) + : DecoratorNode(name, {{"num_attempts", std::to_string(NTries)}}), + NTries_(NTries), TryIndx_(0) { } BT::DecoratorRetryNode::DecoratorRetryNode(const std::string& name, const BT::NodeParameters& params) - : DecoratorNode(name, params), NTries_(1), TryIndx_(0) + : DecoratorNode(name, params), + NTries_( getParam("num_attempts") ), TryIndx_(0) { - auto it = params.find("num_attempts"); - if (it == params.end()) - { - throw std::runtime_error("[DecoratorRetryNode] requires a parameter callen 'num_attempts'"); - } - NTries_ = std::stoul(it->second); } BT::NodeStatus BT::DecoratorRetryNode::tick() diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 1236b3018..ca6271051 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -15,35 +15,17 @@ BT::FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, ResetPolicy reset_policy) : ControlNode::ControlNode(name, {{"reset_policy", toStr(reset_policy)}}), - current_child_idx_(0), reset_policy_(reset_policy) + current_child_idx_(0), + reset_policy_(reset_policy) { } BT::FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, const NodeParameters& params) - : ControlNode::ControlNode(name,params), current_child_idx_(0) + : ControlNode::ControlNode(name,params), + current_child_idx_(0), + reset_policy_( getParam("reset_policy") ) { - auto it = params.find("reset_policy"); - if( it == params.end()) - { - throw std::runtime_error("FallbackNodeWithMemory requires the parameter [reset_policy]"); - } - const std::string& policy = it->second; - if(policy == "ON_SUCCESS_OR_FAILURE") - { - reset_policy_ = ON_SUCCESS_OR_FAILURE; - } - else if(policy == "ON_SUCCESS") - { - reset_policy_ = ON_SUCCESS; - } - else if(policy == "ON_FAILURE") - { - reset_policy_ = ON_FAILURE; - } - else{ - throw std::runtime_error("FallbackNodeWithMemory has a [reset_policy] that doesn't match."); - } } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 3151fa6bf..d4adbd87a 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -21,30 +21,11 @@ BT::SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string &name, Rese } BT::SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, const NodeParameters& params) - : ControlNode::ControlNode(name, params), current_child_idx_(0) + : ControlNode::ControlNode(name,params), + current_child_idx_(0), + reset_policy_( getParam("reset_policy") ) { - auto it = params.find("reset_policy"); - if( it == params.end()) - { - throw std::runtime_error("SequenceNodeWithMemory requires the parameter [reset_policy]"); - } - const std::string& policy = it->second; - if(policy == "ON_SUCCESS_OR_FAILURE") - { - reset_policy_ = ON_SUCCESS_OR_FAILURE; - } - else if(policy == "ON_SUCCESS") - { - reset_policy_ = ON_SUCCESS; - } - else if(policy == "ON_FAILURE") - { - reset_policy_ = ON_FAILURE; - } - else{ - throw std::runtime_error("SequenceNodeWithMemory has a [reset_policy] that doesn't match."); - } } BT::NodeStatus BT::SequenceNodeWithMemory::tick() diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 4dba28727..a06248af1 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -12,6 +12,7 @@ */ #include "behavior_tree_core/tree_node.h" +#include namespace BT { @@ -99,69 +100,4 @@ const std::string &TreeNode::registrationName() const return registration_name_; } -const char *toStr(const NodeStatus &status, bool colored) -{ - if( ! colored ){ - switch (status) - { - case NodeStatus::SUCCESS: - return "SUCCESS"; - case NodeStatus::FAILURE: - return "FAILURE"; - case NodeStatus::RUNNING: - return "RUNNING"; - case NodeStatus::IDLE: - return "IDLE"; - } - } - else{ - switch (status) - { - case NodeStatus::SUCCESS: - return ( "\x1b[32m" "SUCCESS" "\x1b[0m"); // RED - case NodeStatus::FAILURE: - return ( "\x1b[31m" "FAILURE" "\x1b[0m"); // GREEN - case NodeStatus::RUNNING: - return ( "\x1b[33m" "RUNNING" "\x1b[0m"); // YELLOW - case NodeStatus::IDLE: - return ( "\x1b[36m" "IDLE" "\x1b[0m"); // CYAN - } - } - return "Undefined"; -} - -const char *toStr(const NodeType &type) -{ - switch (type) - { - case NodeType::ACTION: - return "Action"; - case NodeType::CONDITION: - return "Condition"; - case NodeType::DECORATOR: - return "Decorator"; - case NodeType::CONTROL: - return "Control"; - case NodeType::SUBTREE: - return "SubTree"; - default: - return "Undefined"; - } -} - -const char *toStr(const ResetPolicy &policy) -{ - switch (policy) - { - case ResetPolicy::ON_FAILURE: - return "ON_FAILURE"; - case ResetPolicy::ON_SUCCESS: - return "ON_SUCCESS"; - case ResetPolicy::ON_SUCCESS_OR_FAILURE: - return "ON_SUCCESS_OR_FAILURE"; - default: - return "Undefined"; - } -} - -} +} // end namespace From f14654a7f1630754b5e3d9e732f45545a1b9afba Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 13 Jun 2018 17:06:05 +0200 Subject: [PATCH 076/125] cleanups and refactoring --- CMakeLists.txt | 3 +- include/behavior_tree_core/bt_factory.h | 64 +++++++++++++------ include/behavior_tree_core/condition_node.h | 5 +- include/behavior_tree_core/control_node.h | 3 +- .../decorator_negation_node.h | 6 +- include/behavior_tree_core/decorator_node.h | 3 +- .../decorator_repeat_node.h | 9 ++- .../behavior_tree_core/decorator_retry_node.h | 8 ++- .../decorator_subtree_node.h | 11 ++-- include/behavior_tree_core/fallback_node.h | 5 +- .../fallback_node_with_memory.h | 16 ++++- include/behavior_tree_core/leaf_node.h | 3 +- include/behavior_tree_core/sequence_node.h | 4 +- .../sequence_node_with_memory.h | 9 ++- include/behavior_tree_core/tick_engine.h | 5 ++ src/action_node.cpp | 20 +++--- src/behavior_tree.cpp | 1 + src/bt_factory.cpp | 1 + src/control_node.cpp | 17 +++-- src/decorator_negation_node.cpp | 11 +++- src/decorator_node.cpp | 17 +++-- src/decorator_repeat_node.cpp | 6 +- src/decorator_retry_node.cpp | 18 ++++-- src/fallback_node.cpp | 9 ++- src/fallback_node_with_memory.cpp | 25 +++++--- src/sequence_node_with_memory.cpp | 25 +++++--- src/tick_engine.cpp | 5 ++ 27 files changed, 213 insertions(+), 96 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 42b349885..9f1010fea 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -7,7 +7,7 @@ set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake") ############################################################# # http://answers.ros.org/question/230877/optionally-build-a-package-with-catkin/ # -# This variable MUST NOT be set by the user manually, it will be detected +# This variable MUST NOT be set manually by the user, it will be detected # automatically if you compile using catkin if( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) set(catkin_FOUND 1) @@ -41,6 +41,7 @@ endif(catkin_FOUND) set(BT_Source src/action_node.cpp + src/basic_types.cpp src/decorator_node.cpp src/decorator_negation_node.cpp src/decorator_repeat_node.cpp diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 2310ade63..df15956e8 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -44,6 +44,11 @@ class BehaviorTreeFactory return builders_; } + const std::map& requiredNodeParameters() const + { + return required_parameters_; + } + template void registerNodeType(const std::string& ID) { @@ -55,16 +60,23 @@ class BehaviorTreeFactory constexpr bool default_constructable = std::is_constructible::value; constexpr bool param_constructable = std::is_constructible::value; + constexpr bool has_static_required_parameters = has_static_method_requiredNodeParameters::value; static_assert(default_constructable || param_constructable, - "[registerBuilder]: the registered class must have a Constructor with signature: " - " (const std::string&, const NodeParameters&) or (const std::string&)"); + "[registerBuilder]: the registered class must have a Constructor with signature:\n\n" + " (const std::string&, const NodeParameters&) or (const std::string&)"); + + static_assert( !(param_constructable && !has_static_required_parameters), + "[registerBuilder]: a node that accepts NodeParameters must also implement a static method:\n\n" + " const NodeParameters& requiredNodeParameters(); "); registerNodeTypeImpl(ID); + saveRequiredParameters(ID); } private: std::map builders_; + std::map required_parameters_; // template specialization + SFINAE + black magic @@ -75,25 +87,17 @@ class BehaviorTreeFactory template using has_params_constructor = typename std::is_constructible; - struct default_constructable{}; - struct param_constructable{}; - struct both_constructable{}; + template + struct has_static_method_requiredNodeParameters: std::false_type {}; template - using enable_if_default_constructable_only = - typename std::enable_if::value && !has_params_constructor::value, struct default_constructable>; + struct has_static_method_requiredNodeParameters::value>::type> + : std::true_type {}; template - using enable_if_param_constructable_only = - typename std::enable_if::value && has_params_constructor::value, struct param_constructable>; - - template - using enable_if_has_both_constructors = - typename std::enable_if::value && has_params_constructor::value, struct both_constructable>; - - - template ::type* = nullptr> - void registerNodeTypeImpl(const std::string& ID) + typename std::enable_if< has_default_constructor::value && !has_params_constructor::value>::type + registerNodeTypeImpl(const std::string& ID) { NodeBuilder builder = [](const std::string& name, const NodeParameters&) { @@ -102,8 +106,9 @@ class BehaviorTreeFactory registerBuilder(ID, builder); } - template ::type* = nullptr> - void registerNodeTypeImpl(const std::string& ID) + template + typename std::enable_if< !has_default_constructor::value && has_params_constructor::value>::type + registerNodeTypeImpl(const std::string& ID) { NodeBuilder builder = [](const std::string& name, const NodeParameters& params) { @@ -112,8 +117,9 @@ class BehaviorTreeFactory registerBuilder(ID, builder); } - template ::type* = nullptr> - void registerNodeTypeImpl(const std::string& ID) + template + typename std::enable_if< has_default_constructor::value && has_params_constructor::value>::type + registerNodeTypeImpl(const std::string& ID) { NodeBuilder builder = [](const std::string& name, const NodeParameters& params) { @@ -125,6 +131,22 @@ class BehaviorTreeFactory }; registerBuilder(ID, builder); } + + + template + typename std::enable_if< has_static_method_requiredNodeParameters::value>::type + saveRequiredParameters(const std::string& name) + { + required_parameters_.insert( { name, T::requiredNodeParameters()} ); + } + + template + typename std::enable_if< !has_static_method_requiredNodeParameters::value>::type + saveRequiredParameters(const std::string& ) + { + //do nothing. This implementation is intentionally empty + } + // clang-format on }; diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index 82acc3e45..cd3d9ff88 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -21,9 +21,10 @@ namespace BT class ConditionNode : public LeafNode { public: - // Constructor + ConditionNode(const std::string& name, const NodeParameters& parameters = NodeParameters() ); - ~ConditionNode() override = default; + + virtual ~ConditionNode() override = default; // The method used to interrupt the execution of the node virtual void halt() override; diff --git a/include/behavior_tree_core/control_node.h b/include/behavior_tree_core/control_node.h index fc2d73c15..460f7c713 100644 --- a/include/behavior_tree_core/control_node.h +++ b/include/behavior_tree_core/control_node.h @@ -28,7 +28,8 @@ class ControlNode : public TreeNode public: // Constructor ControlNode(const std::string& name, const NodeParameters& parameters); - ~ControlNode() = default; + + virtual ~ControlNode() override = default; // The method used to fill the child vector void addChild(TreeNode* child); diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h index cefd1f81b..9c4c5c96b 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -21,10 +21,10 @@ namespace BT class DecoratorNegationNode : public DecoratorNode { public: - // Constructor - DecoratorNegationNode(const std::string& name, const NodeParameters& parameters); + + DecoratorNegationNode(const std::string& name); - virtual ~DecoratorNegationNode() = default; + virtual ~DecoratorNegationNode() override = default; private: virtual BT::NodeStatus tick() override; diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index 33bcffde1..f541ff89c 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -13,7 +13,8 @@ class DecoratorNode : public TreeNode public: // Constructor DecoratorNode(const std::string& name, const NodeParameters& parameters); - ~DecoratorNode() = default; + + virtual ~DecoratorNode() override = default; // The method used to fill the child vector void setChild(TreeNode* child); diff --git a/include/behavior_tree_core/decorator_repeat_node.h b/include/behavior_tree_core/decorator_repeat_node.h index 1c0395b07..d5f643a94 100644 --- a/include/behavior_tree_core/decorator_repeat_node.h +++ b/include/behavior_tree_core/decorator_repeat_node.h @@ -26,12 +26,19 @@ class DecoratorRepeatNode : public DecoratorNode DecoratorRepeatNode(const std::string& name, const NodeParameters& params); - ~DecoratorRepeatNode() = default; + virtual ~DecoratorRepeatNode() override = default; + + static const NodeParameters& requiredNodeParameters() + { + static NodeParameters params = { {NUM_CYCLES, "1"} }; + return params; + } private: unsigned NTries_; unsigned TryIndx_; + static constexpr const char* NUM_CYCLES = "num_cycles"; virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h index dc07a177d..28e5a1e91 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -26,13 +26,19 @@ class DecoratorRetryNode : public DecoratorNode DecoratorRetryNode(const std::string& name, const NodeParameters& params); - ~DecoratorRetryNode() = default; + virtual ~DecoratorRetryNode() override = default; + static const NodeParameters& requiredNodeParameters() + { + static NodeParameters params = { {NUM_ATTEMPTS, "1"} }; + return params; + } private: unsigned int NTries_; unsigned int TryIndx_; + static constexpr const char* NUM_ATTEMPTS = "num_attempts"; virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/decorator_subtree_node.h b/include/behavior_tree_core/decorator_subtree_node.h index c906838f9..7a4dea7fe 100644 --- a/include/behavior_tree_core/decorator_subtree_node.h +++ b/include/behavior_tree_core/decorator_subtree_node.h @@ -8,16 +8,17 @@ namespace BT class DecoratorSubtreeNode : public DecoratorNode { public: - // Constructor - DecoratorSubtreeNode(const std::string& name, const NodeParameters& parameters) : - DecoratorNode(name, parameters) + + DecoratorSubtreeNode(const std::string& name) : + DecoratorNode(name, NodeParameters()) { } - virtual ~DecoratorSubtreeNode() = default; + virtual ~DecoratorSubtreeNode() override = default; private: - virtual BT::NodeStatus tick() + + virtual BT::NodeStatus tick() override { NodeStatus prev_status = status(); if ( prev_status== NodeStatus::IDLE) diff --git a/include/behavior_tree_core/fallback_node.h b/include/behavior_tree_core/fallback_node.h index e3b1f2fcd..c0590c8c1 100644 --- a/include/behavior_tree_core/fallback_node.h +++ b/include/behavior_tree_core/fallback_node.h @@ -21,9 +21,10 @@ namespace BT class FallbackNode : public ControlNode { public: - // Constructor + FallbackNode(const std::string& name); - ~FallbackNode() = default; + + virtual ~FallbackNode() override = default; private: virtual BT::NodeStatus tick() override; diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index 9e808eb61..e3f86e319 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -20,22 +20,32 @@ namespace BT { class FallbackNodeWithMemory : public ControlNode { - public: + +public: FallbackNodeWithMemory(const std::string& name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); // Reset policy passed by parameter [reset_policy] FallbackNodeWithMemory(const std::string&, const NodeParameters& params); - ~FallbackNodeWithMemory() = default; + virtual ~FallbackNodeWithMemory() override = default; virtual void halt() override; - private: + static const NodeParameters& requiredNodeParameters() + { + static NodeParameters params = { {RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)} }; + return params; + } + +private: unsigned int current_child_idx_; ResetPolicy reset_policy_; + constexpr static const char* RESET_POLICY = "reset_policy"; virtual BT::NodeStatus tick() override; }; + + } #endif // FALLBACK_NODE_WITH_MEMORY_H diff --git a/include/behavior_tree_core/leaf_node.h b/include/behavior_tree_core/leaf_node.h index ca8f9dfe6..a457ca3a0 100644 --- a/include/behavior_tree_core/leaf_node.h +++ b/include/behavior_tree_core/leaf_node.h @@ -23,7 +23,8 @@ class LeafNode : public TreeNode protected: public: LeafNode(const std::string& name, const NodeParameters ¶meters); - ~LeafNode() = default; + + virtual ~LeafNode() override = default; }; } diff --git a/include/behavior_tree_core/sequence_node.h b/include/behavior_tree_core/sequence_node.h index d29143e59..5342a9039 100644 --- a/include/behavior_tree_core/sequence_node.h +++ b/include/behavior_tree_core/sequence_node.h @@ -21,9 +21,9 @@ namespace BT class SequenceNode : public ControlNode { public: - // Constructor SequenceNode(const std::string& name); - ~SequenceNode() = default; + + virtual ~SequenceNode() override = default; private: virtual BT::NodeStatus tick() override; diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index 2c9e9183a..4c1a734b3 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -26,14 +26,21 @@ class SequenceNodeWithMemory : public ControlNode // Reset policy passed by parameter [reset_policy] SequenceNodeWithMemory(const std::string &name, const NodeParameters& params); - ~SequenceNodeWithMemory() = default; + virtual ~SequenceNodeWithMemory() override = default; virtual void halt() override; + static const NodeParameters& requiredNodeParameters() + { + static NodeParameters params = { {RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)} }; + return params; + } + private: unsigned int current_child_idx_; ResetPolicy reset_policy_; + static constexpr const char* RESET_POLICY = "reset_policy"; virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/tick_engine.h b/include/behavior_tree_core/tick_engine.h index 79a253be6..67888c366 100644 --- a/include/behavior_tree_core/tick_engine.h +++ b/include/behavior_tree_core/tick_engine.h @@ -19,6 +19,9 @@ #include #include +namespace BT +{ + class TickEngine { private: @@ -36,4 +39,6 @@ class TickEngine void notify(); }; +} + #endif diff --git a/src/action_node.cpp b/src/action_node.cpp index 762713958..731a377f4 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -13,19 +13,21 @@ #include "behavior_tree_core/action_node.h" -BT::ActionNodeBase::ActionNodeBase(const std::string& name, const NodeParameters ¶meters) : +namespace BT{ + +ActionNodeBase::ActionNodeBase(const std::string& name, const NodeParameters ¶meters) : LeafNode::LeafNode(name,parameters) { } //------------------------------------------------------- -BT::SimpleActionNode::SimpleActionNode(const std::string &name, BT::SimpleActionNode::TickFunctor tick_functor) +SimpleActionNode::SimpleActionNode(const std::string &name, SimpleActionNode::TickFunctor tick_functor) : ActionNodeBase(name, NodeParameters()), tick_functor_( std::move(tick_functor) ) { } -BT::NodeStatus BT::SimpleActionNode::tick() +NodeStatus SimpleActionNode::tick() { NodeStatus prev_status = status(); @@ -45,13 +47,13 @@ BT::NodeStatus BT::SimpleActionNode::tick() //------------------------------------------------------- -BT::ActionNode::ActionNode(const std::string& name, const NodeParameters& parameters) : +ActionNode::ActionNode(const std::string& name, const NodeParameters& parameters) : ActionNodeBase(name, parameters), loop_(true) { thread_ = std::thread(&ActionNode::waitForTick, this); } -BT::ActionNode::~ActionNode() +ActionNode::~ActionNode() { if (thread_.joinable()) { @@ -59,7 +61,7 @@ BT::ActionNode::~ActionNode() } } -void BT::ActionNode::waitForTick() +void ActionNode::waitForTick() { while (loop_.load()) { @@ -78,7 +80,7 @@ void BT::ActionNode::waitForTick() } } -BT::NodeStatus BT::ActionNode::executeTick() +NodeStatus ActionNode::executeTick() { //send signal to other thread. // The other thread is in charge for changing the status @@ -92,9 +94,11 @@ BT::NodeStatus BT::ActionNode::executeTick() return stat; } -void BT::ActionNode::stopAndJoinThread() +void ActionNode::stopAndJoinThread() { loop_.store(false); tick_engine_.notify(); thread_.join(); } + +} diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index 467e917c3..fcd00bccd 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -3,6 +3,7 @@ namespace BT { + void recursiveVisitor(TreeNode* node, std::function visitor) { if (!node) diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 4ace64ae9..87090611c 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -15,6 +15,7 @@ namespace BT { + BehaviorTreeFactory::BehaviorTreeFactory() { registerNodeType("Fallback"); diff --git a/src/control_node.cpp b/src/control_node.cpp index 2cb88367c..81955efa8 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -13,7 +13,10 @@ #include "behavior_tree_core/control_node.h" -BT::ControlNode::ControlNode(const std::string& name, const NodeParameters& parameters) : +namespace BT{ + + +ControlNode::ControlNode(const std::string& name, const NodeParameters& parameters) : TreeNode::TreeNode(name,parameters) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus @@ -21,7 +24,7 @@ BT::ControlNode::ControlNode(const std::string& name, const NodeParameters& para // ReturnStatus const NodeStatus child_status = NodeStatus::IDLE; // commented out as unused } -void BT::ControlNode::addChild(TreeNode* child) +void ControlNode::addChild(TreeNode* child) { // Checking if the child is not already present // for (auto node : children_nodes_) @@ -35,23 +38,23 @@ void BT::ControlNode::addChild(TreeNode* child) children_nodes_.push_back(child); } -unsigned int BT::ControlNode::childrenCount() const +unsigned int ControlNode::childrenCount() const { return children_nodes_.size(); } -void BT::ControlNode::halt() +void ControlNode::halt() { haltChildren(0); setStatus(NodeStatus::IDLE); } -const std::vector& BT::ControlNode::children() const +const std::vector& ControlNode::children() const { return children_nodes_; } -void BT::ControlNode::haltChildren(int i) +void ControlNode::haltChildren(int i) { for (unsigned int j = i; j < children_nodes_.size(); j++) { @@ -61,3 +64,5 @@ void BT::ControlNode::haltChildren(int i) } } } + +} diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index ba513a56f..de44de81f 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -13,12 +13,15 @@ #include "behavior_tree_core/decorator_negation_node.h" -BT::DecoratorNegationNode::DecoratorNegationNode(const std::string& name, const NodeParameters& parameters) : - DecoratorNode(name,parameters) +namespace BT +{ + +DecoratorNegationNode::DecoratorNegationNode(const std::string& name) : + DecoratorNode(name, NodeParameters() ) { } -BT::NodeStatus BT::DecoratorNegationNode::tick() +NodeStatus DecoratorNegationNode::tick() { setStatus( NodeStatus::RUNNING ); @@ -53,3 +56,5 @@ BT::NodeStatus BT::DecoratorNegationNode::tick() } return status(); } + +} diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 74574f81b..62c602771 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -12,7 +12,10 @@ #include "behavior_tree_core/decorator_node.h" -BT::DecoratorNode::DecoratorNode(const std::string& name, const NodeParameters& parameters) : +namespace BT +{ + +DecoratorNode::DecoratorNode(const std::string& name, const NodeParameters& parameters) : TreeNode::TreeNode(name, parameters), child_node_(nullptr) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus @@ -20,7 +23,7 @@ BT::DecoratorNode::DecoratorNode(const std::string& name, const NodeParameters& // ReturnStatus const NodeStatus child_status = NodeStatus::IDLE; // commented out as unused } -void BT::DecoratorNode::setChild(TreeNode* child) +void DecoratorNode::setChild(TreeNode* child) { if (child_node_) { @@ -30,26 +33,28 @@ void BT::DecoratorNode::setChild(TreeNode* child) child_node_ = child; } -void BT::DecoratorNode::halt() +void DecoratorNode::halt() { haltChild(); setStatus(NodeStatus::IDLE); } -const BT::TreeNode* BT::DecoratorNode::child() const +const TreeNode* DecoratorNode::child() const { return child_node_; } -BT::TreeNode* BT::DecoratorNode::child() +TreeNode* DecoratorNode::child() { return child_node_; } -void BT::DecoratorNode::haltChild() +void DecoratorNode::haltChild() { if (child_node_->status() == NodeStatus::RUNNING) { child_node_->halt(); } } + +} diff --git a/src/decorator_repeat_node.cpp b/src/decorator_repeat_node.cpp index c1bc91db1..805c19571 100644 --- a/src/decorator_repeat_node.cpp +++ b/src/decorator_repeat_node.cpp @@ -15,15 +15,17 @@ namespace BT { +constexpr const char* DecoratorRepeatNode::NUM_CYCLES; + DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, unsigned int NTries) - : DecoratorNode(name, {{"num_cycles", std::to_string(NTries)}}), + : DecoratorNode(name, {{NUM_CYCLES, std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) { } DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, const NodeParameters& params) : DecoratorNode(name,params), - NTries_( getParam("num_cycles") ), + NTries_( getParam(NUM_CYCLES) ), TryIndx_(0) { diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index b75ca049a..5580969e4 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -13,22 +13,26 @@ #include "behavior_tree_core/decorator_retry_node.h" -BT::DecoratorRetryNode::DecoratorRetryNode(const std::string& name, unsigned int NTries) - : DecoratorNode(name, {{"num_attempts", std::to_string(NTries)}}), +namespace BT{ + +constexpr const char* DecoratorRetryNode::NUM_ATTEMPTS; + +DecoratorRetryNode::DecoratorRetryNode(const std::string& name, unsigned int NTries) + : DecoratorNode(name, {{NUM_ATTEMPTS, std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) { } -BT::DecoratorRetryNode::DecoratorRetryNode(const std::string& name, const BT::NodeParameters& params) +DecoratorRetryNode::DecoratorRetryNode(const std::string& name, const NodeParameters& params) : DecoratorNode(name, params), - NTries_( getParam("num_attempts") ), TryIndx_(0) + NTries_( getParam(NUM_ATTEMPTS) ), TryIndx_(0) { } -BT::NodeStatus BT::DecoratorRetryNode::tick() +NodeStatus DecoratorRetryNode::tick() { setStatus(NodeStatus::RUNNING); - BT::NodeStatus child_state = child_node_->executeTick(); + NodeStatus child_state = child_node_->executeTick(); switch (child_state) { @@ -66,3 +70,5 @@ BT::NodeStatus BT::DecoratorRetryNode::tick() return status(); } + +} diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index 060eba7dc..be5d9d1d1 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -13,12 +13,15 @@ #include "behavior_tree_core/fallback_node.h" -BT::FallbackNode::FallbackNode(const std::string& name) : +namespace BT +{ + +FallbackNode::FallbackNode(const std::string& name) : ControlNode::ControlNode(name, NodeParameters()) { } -BT::NodeStatus BT::FallbackNode::tick() +NodeStatus FallbackNode::tick() { // gets the number of children. The number could change if, at runtime, one edits the tree. const unsigned N_of_children = children_nodes_.size(); @@ -64,3 +67,5 @@ BT::NodeStatus BT::FallbackNode::tick() } throw std::runtime_error("This is not supposed to happen"); } + +} diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index ca6271051..78b0b64a4 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -13,23 +13,28 @@ #include "behavior_tree_core/fallback_node_with_memory.h" -BT::FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, ResetPolicy reset_policy) - : ControlNode::ControlNode(name, {{"reset_policy", toStr(reset_policy)}}), +namespace BT +{ + +constexpr const char* FallbackNodeWithMemory::RESET_POLICY; + +FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, ResetPolicy reset_policy) + : ControlNode::ControlNode(name, {{RESET_POLICY, toStr(reset_policy)}}), current_child_idx_(0), reset_policy_(reset_policy) { } -BT::FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, const NodeParameters& params) +FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, const NodeParameters& params) : ControlNode::ControlNode(name,params), current_child_idx_(0), - reset_policy_( getParam("reset_policy") ) + reset_policy_( getParam(RESET_POLICY) ) { } -BT::NodeStatus BT::FallbackNodeWithMemory::tick() +NodeStatus FallbackNodeWithMemory::tick() { // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children = children_nodes_.size(); @@ -46,7 +51,7 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() if (child_status != NodeStatus::FAILURE) { // If the child status is not success, return the status - if (child_status == NodeStatus::SUCCESS && reset_policy_ != BT::ON_FAILURE) + if (child_status == NodeStatus::SUCCESS && reset_policy_ != ON_FAILURE) { for (unsigned t=0; t<=current_child_idx_; t++) { @@ -65,7 +70,7 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() else { // If it the last child. - if (child_status == NodeStatus::FAILURE && reset_policy_ != BT::ON_SUCCESS ) + if (child_status == NodeStatus::FAILURE && reset_policy_ != ON_SUCCESS ) { for (unsigned t=0; t<=current_child_idx_; t++) { @@ -80,8 +85,10 @@ BT::NodeStatus BT::FallbackNodeWithMemory::tick() throw std::runtime_error("This is not supposed to happen"); } -void BT::FallbackNodeWithMemory::halt() +void FallbackNodeWithMemory::halt() { current_child_idx_ = 0; - BT::ControlNode::halt(); + ControlNode::halt(); +} + } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index d4adbd87a..973a886b6 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -13,22 +13,27 @@ #include "behavior_tree_core/sequence_node_with_memory.h" -BT::SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string &name, ResetPolicy reset_policy) - : ControlNode::ControlNode(name, {{"reset_policy", toStr(reset_policy)}}), +namespace BT +{ + +constexpr const char* SequenceNodeWithMemory::RESET_POLICY; + +SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string &name, ResetPolicy reset_policy) + : ControlNode::ControlNode(name, {{RESET_POLICY, toStr(reset_policy)}}), current_child_idx_(0), reset_policy_(reset_policy) { } -BT::SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, const NodeParameters& params) +SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, const NodeParameters& params) : ControlNode::ControlNode(name,params), current_child_idx_(0), - reset_policy_( getParam("reset_policy") ) + reset_policy_( getParam(RESET_POLICY) ) { } -BT::NodeStatus BT::SequenceNodeWithMemory::tick() +NodeStatus SequenceNodeWithMemory::tick() { // Vector size initialization. N_of_children_ could change at runtime if you edit the tree const unsigned N_of_children = children_nodes_.size(); @@ -50,7 +55,7 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() if (child_status != NodeStatus::SUCCESS) { // If the child status is not success, return the status - if (child_status == NodeStatus::FAILURE && reset_policy_ != BT::ON_SUCCESS ) + if (child_status == NodeStatus::FAILURE && reset_policy_ != ON_SUCCESS ) { for (unsigned t=0; t<=current_child_idx_; t++) { @@ -69,7 +74,7 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() else { // if it the last child. - if (child_status == NodeStatus::SUCCESS || reset_policy_ != BT::ON_FAILURE) + if (child_status == NodeStatus::SUCCESS || reset_policy_ != ON_FAILURE) { // if it the last child and it has returned SUCCESS, reset the memory for (unsigned t=0; t<=current_child_idx_; t++) @@ -84,8 +89,10 @@ BT::NodeStatus BT::SequenceNodeWithMemory::tick() throw std::runtime_error("This is not supposed to happen"); } -void BT::SequenceNodeWithMemory::halt() +void SequenceNodeWithMemory::halt() { current_child_idx_ = 0; - BT::ControlNode::halt(); + ControlNode::halt(); +} + } diff --git a/src/tick_engine.cpp b/src/tick_engine.cpp index 3219322d7..d4314e904 100644 --- a/src/tick_engine.cpp +++ b/src/tick_engine.cpp @@ -15,6 +15,9 @@ // find how condition_variables work here http://es.cppreference.com/w/cpp/thread/condition_variable/wait +namespace BT +{ + TickEngine::TickEngine(bool start_ready) : ready_(start_ready) { } @@ -35,3 +38,5 @@ void TickEngine::notify() ready_ = true; condition_variable_.notify_all(); } + +} From 4f1e50a33307ac91828ec2960bc968fa2c4445b0 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 13 Jun 2018 17:08:26 +0200 Subject: [PATCH 077/125] clang format --- gtest/crossdoor_example.cpp | 9 +- gtest/gtest_factory.cpp | 5 +- gtest/gtest_tree.cpp | 180 ++--- gtest/include/crossdoor_dummy_nodes.h | 15 +- gtest/simple_example.cpp | 8 +- gtest/src/action_test_node.cpp | 7 +- gtest/src/condition_test_node.cpp | 3 +- include/behavior_tree_core/action_node.h | 5 +- include/behavior_tree_core/basic_types.h | 15 +- include/behavior_tree_core/behavior_tree.h | 10 +- include/behavior_tree_core/bt_factory.h | 8 +- include/behavior_tree_core/condition_node.h | 3 +- .../decorator_negation_node.h | 3 +- include/behavior_tree_core/decorator_node.h | 1 - .../decorator_repeat_node.h | 4 +- .../behavior_tree_core/decorator_retry_node.h | 2 +- .../decorator_subtree_node.h | 8 +- include/behavior_tree_core/fallback_node.h | 4 +- .../fallback_node_with_memory.h | 9 +- include/behavior_tree_core/leaf_node.h | 2 +- include/behavior_tree_core/parallel_node.h | 2 +- include/behavior_tree_core/sequence_node.h | 2 +- .../sequence_node_with_memory.h | 6 +- include/behavior_tree_core/signal.h | 26 +- include/behavior_tree_core/tick_engine.h | 2 - include/behavior_tree_core/tree_node.h | 52 +- .../BT_logger_generated.h | 689 +++++++++--------- .../behavior_tree_logger/abstract_logger.h | 68 +- include/behavior_tree_logger/bt_cout_logger.h | 48 +- include/behavior_tree_logger/bt_file_logger.h | 25 +- .../bt_flatbuffer_helper.h | 106 ++- .../bt_minitrace_logger.h | 46 +- .../behavior_tree_logger/bt_zmq_publisher.h | 28 +- src/action_node.cpp | 23 +- src/basic_types.cpp | 149 ++-- src/behavior_tree.cpp | 10 +- src/bt_factory.cpp | 3 +- src/bt_file_logger.cpp | 53 +- src/bt_zmq_publisher.cpp | 105 ++- src/condition_node.cpp | 2 +- src/control_node.cpp | 10 +- src/decorator_negation_node.cpp | 7 +- src/decorator_node.cpp | 6 +- src/decorator_repeat_node.cpp | 13 +- src/decorator_retry_node.cpp | 11 +- src/fallback_node.cpp | 9 +- src/fallback_node_with_memory.cpp | 24 +- src/leaf_node.cpp | 3 +- src/sequence_node.cpp | 11 +- src/sequence_node_with_memory.cpp | 23 +- src/tick_engine.cpp | 2 - src/tree_node.cpp | 24 +- src/xml_parsing.cpp | 6 +- tools/bt_log_cat.cpp | 72 +- tools/bt_recorder.cpp | 48 +- 55 files changed, 945 insertions(+), 1070 deletions(-) diff --git a/gtest/crossdoor_example.cpp b/gtest/crossdoor_example.cpp index 8b79519cf..5b2df0e26 100644 --- a/gtest/crossdoor_example.cpp +++ b/gtest/crossdoor_example.cpp @@ -5,7 +5,7 @@ #include "behavior_tree_logger/bt_file_logger.h" #ifdef ZMQ_FOUND - #include "behavior_tree_logger/bt_zmq_publisher.h" +#include "behavior_tree_logger/bt_zmq_publisher.h" #endif // clang-format off @@ -58,7 +58,7 @@ int main(int argc, char** argv) StdCoutLogger logger_cout(root_node.get()); MinitraceLogger logger_minitrace(root_node.get(), "bt_trace.json"); - FileLogger logger_file( root_node.get(), "bt_trace.fbl", 32 ); + FileLogger logger_file(root_node.get(), "bt_trace.fbl", 32); #ifdef ZMQ_FOUND PublisherZMQ publisher_zmq(root_node.get()); @@ -69,10 +69,11 @@ int main(int argc, char** argv) std::cout << "---------------" << std::endl; root_node->executeTick(); - std::this_thread::sleep_for( std::chrono::milliseconds(100) ); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); std::cout << "---------------" << std::endl; - while(1) root_node->executeTick(); + while (1) + root_node->executeTick(); std::cout << "---------------" << std::endl; return 0; } diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp index 171406ebb..e43c147f3 100644 --- a/gtest/gtest_factory.cpp +++ b/gtest/gtest_factory.cpp @@ -77,7 +77,6 @@ const std::string xml_text_subtree = R"( )"; // clang-format on - TEST(BehaviorTreeFactory, VerifyLargeTree) { BT::XMLParser parser; @@ -160,13 +159,13 @@ TEST(BehaviorTreeFactory, Subtree) ASSERT_EQ(root_node->name(), "root_selector"); auto root_selector = dynamic_cast(root_node.get()); - ASSERT_TRUE( root_selector != nullptr); + ASSERT_TRUE(root_selector != nullptr); ASSERT_EQ(root_selector->children().size(), 2); ASSERT_EQ(root_selector->child(0)->name(), "CrossDoorSubtree"); ASSERT_EQ(root_selector->child(1)->name(), "PassThroughWindow"); auto subtree = dynamic_cast(root_selector->child(0)); - ASSERT_TRUE( subtree != nullptr); + ASSERT_TRUE(subtree != nullptr); auto sequence = dynamic_cast(subtree->child()); ASSERT_TRUE(sequence != nullptr); diff --git a/gtest/gtest_tree.cpp b/gtest/gtest_tree.cpp index 54f77a440..825e167fa 100644 --- a/gtest/gtest_tree.cpp +++ b/gtest/gtest_tree.cpp @@ -23,10 +23,7 @@ struct SimpleSequenceTest : testing::Test BT::ActionTestNode action; BT::ConditionTestNode condition; - SimpleSequenceTest(): - root("root_sequence"), - action("action"), - condition("condition") + SimpleSequenceTest() : root("root_sequence"), action("action"), condition("condition") { root.addChild(&condition); root.addChild(&action); @@ -42,12 +39,12 @@ struct ComplexSequenceTest : testing::Test BT::SequenceNode seq_conditions; - ComplexSequenceTest(): - root("root_sequence"), - action_1("action_1"), - condition_1("condition_1"), - condition_2("condition_2"), - seq_conditions("sequence_conditions") + ComplexSequenceTest() + : root("root_sequence") + , action_1("action_1") + , condition_1("condition_1") + , condition_2("condition_2") + , seq_conditions("sequence_conditions") { root.addChild(&seq_conditions); { @@ -65,20 +62,14 @@ struct SequenceTripleActionTest : testing::Test BT::ActionTestNode action_2; BT::ActionTestNode action_3; - SequenceTripleActionTest(): - root("root_sequence"), - action_1("action_1"), - action_2("action_2"), - action_3("action_3") + SequenceTripleActionTest() : root("root_sequence"), action_1("action_1"), action_2("action_2"), action_3("action_3") { root.addChild(&action_1); root.addChild(&action_2); root.addChild(&action_3); - } }; - struct ComplexSequence2ActionsTest : testing::Test { BT::SequenceNode root; @@ -90,14 +81,14 @@ struct ComplexSequence2ActionsTest : testing::Test BT::ConditionTestNode condition_1; BT::ConditionTestNode condition_2; - ComplexSequence2ActionsTest(): - root("root_sequence"), - action_1("action_1"), - action_2("action_2"), - seq_1("sequence_1"), - seq_2("sequence_2"), - condition_1("condition_1"), - condition_2("condition_2") + ComplexSequence2ActionsTest() + : root("root_sequence") + , action_1("action_1") + , action_2("action_2") + , seq_1("sequence_1") + , seq_2("sequence_2") + , condition_1("condition_1") + , condition_2("condition_2") { root.addChild(&seq_1); { @@ -118,10 +109,7 @@ struct SimpleFallbackTest : testing::Test BT::ActionTestNode action; BT::ConditionTestNode condition; - SimpleFallbackTest(): - root("root_fallback"), - action("action"), - condition("condition") + SimpleFallbackTest() : root("root_fallback"), action("action"), condition("condition") { root.addChild(&condition); root.addChild(&action); @@ -137,12 +125,12 @@ struct ComplexFallbackTest : testing::Test BT::FallbackNode fal_conditions; - ComplexFallbackTest(): - root("root_fallback"), - action_1("action_1"), - condition_1("condition_1"), - condition_2("condition_2"), - fal_conditions("fallback_conditions") + ComplexFallbackTest() + : root("root_fallback") + , action_1("action_1") + , condition_1("condition_1") + , condition_2("condition_2") + , fal_conditions("fallback_conditions") { root.addChild(&fal_conditions); { @@ -162,14 +150,13 @@ struct BehaviorTreeTest : testing::Test BT::FallbackNode fal_conditions; - BehaviorTreeTest(): - root("root_sequence"), - action_1("action_1"), - condition_1("condition_1"), - condition_2("condition_2"), - fal_conditions("fallback_conditions") + BehaviorTreeTest() + : root("root_sequence") + , action_1("action_1") + , condition_1("condition_1") + , condition_2("condition_2") + , fal_conditions("fallback_conditions") { - root.addChild(&fal_conditions); { fal_conditions.addChild(&condition_1); @@ -185,10 +172,7 @@ struct SimpleSequenceWithMemoryTest : testing::Test BT::ActionTestNode action; BT::ConditionTestNode condition; - SimpleSequenceWithMemoryTest(): - root("root_sequence"), - action("action"), - condition("condition") + SimpleSequenceWithMemoryTest() : root("root_sequence"), action("action"), condition("condition") { root.addChild(&condition); root.addChild(&action); @@ -208,14 +192,14 @@ struct ComplexSequenceWithMemoryTest : testing::Test BT::SequenceNodeWithMemory seq_conditions; BT::SequenceNodeWithMemory seq_actions; - ComplexSequenceWithMemoryTest(): - root("root_sequence"), - action_1("action_1"), - action_2("action_2"), - condition_1("condition_1"), - condition_2("condition_2"), - seq_conditions("sequence_conditions"), - seq_actions("sequence_actions") + ComplexSequenceWithMemoryTest() + : root("root_sequence") + , action_1("action_1") + , action_2("action_2") + , condition_1("condition_1") + , condition_2("condition_2") + , seq_conditions("sequence_conditions") + , seq_actions("sequence_actions") { root.addChild(&seq_conditions); { @@ -236,10 +220,7 @@ struct SimpleFallbackWithMemoryTest : testing::Test BT::ActionTestNode action; BT::ConditionTestNode condition; - SimpleFallbackWithMemoryTest(): - root("root_sequence"), - action("action"), - condition("condition") + SimpleFallbackWithMemoryTest() : root("root_sequence"), action("action"), condition("condition") { root.addChild(&condition); root.addChild(&action); @@ -259,14 +240,14 @@ struct ComplexFallbackWithMemoryTest : testing::Test BT::FallbackNodeWithMemory fal_conditions; BT::FallbackNodeWithMemory fal_actions; - ComplexFallbackWithMemoryTest(): - root("root_fallback"), - action_1("action_1"), - action_2("action_2"), - condition_1("condition_1"), - condition_2("condition_2"), - fal_conditions("fallback_conditions"), - fal_actions("fallback_actions") + ComplexFallbackWithMemoryTest() + : root("root_fallback") + , action_1("action_1") + , action_2("action_2") + , condition_1("condition_1") + , condition_2("condition_2") + , fal_conditions("fallback_conditions") + , fal_actions("fallback_actions") { root.addChild(&fal_conditions); { @@ -290,12 +271,12 @@ struct SimpleParallelTest : testing::Test BT::ActionTestNode action_2; BT::ConditionTestNode condition_2; - SimpleParallelTest(): - root("root_parallel",4), - action_1("action_1"), - condition_1("condition_1"), - action_2("action_2"), - condition_2("condition_2") + SimpleParallelTest() + : root("root_parallel", 4) + , action_1("action_1") + , condition_1("condition_1") + , action_2("action_2") + , condition_2("condition_2") { root.addChild(&condition_1); root.addChild(&action_1); @@ -319,16 +300,16 @@ struct ComplexParallelTest : testing::Test BT::ActionTestNode action_3; BT::ConditionTestNode condition_3; - ComplexParallelTest(): - root("root",2), - parallel_1("par1",3), - parallel_2("par2",1), - action_1("action_1"), - condition_1("condition_1"), - action_2("action_2"), - condition_2("condition_2"), - action_3("action_3"), - condition_3("condition_3") + ComplexParallelTest() + : root("root", 2) + , parallel_1("par1", 3) + , parallel_2("par2", 1) + , action_1("action_1") + , condition_1("condition_1") + , action_2("action_2") + , condition_2("condition_2") + , action_3("action_3") + , condition_3("condition_3") { root.addChild(¶llel_1); { @@ -393,24 +374,21 @@ TEST_F(SequenceTripleActionTest, TripleAction) action_3.set_time(2); // the sequence is supposed to finish in (200 ms * 3) = 600 ms - bool done_1 = false, done_2 = false, done_3 = false; + bool done_1 = false, done_2 = false, done_3 = false; - auto sub1 = action_1.subscribeToStatusChange( - [&done_1](TimePoint, const TreeNode& , NodeStatus,NodeStatus status) - { - if( status == NodeStatus::SUCCESS) done_1 = true; + auto sub1 = action_1.subscribeToStatusChange([&done_1](TimePoint, const TreeNode&, NodeStatus, NodeStatus status) { + if (status == NodeStatus::SUCCESS) + done_1 = true; }); - auto sub2 = action_2.subscribeToStatusChange( - [&done_2](TimePoint, const TreeNode& , NodeStatus,NodeStatus status) - { - if( status == NodeStatus::SUCCESS) done_2 = true; + auto sub2 = action_2.subscribeToStatusChange([&done_2](TimePoint, const TreeNode&, NodeStatus, NodeStatus status) { + if (status == NodeStatus::SUCCESS) + done_2 = true; }); - auto sub3 = action_3.subscribeToStatusChange( - [&done_3](TimePoint, const TreeNode& , NodeStatus,NodeStatus status) - { - if( status == NodeStatus::SUCCESS) done_3 = true; + auto sub3 = action_3.subscribeToStatusChange([&done_3](TimePoint, const TreeNode&, NodeStatus, NodeStatus status) { + if (status == NodeStatus::SUCCESS) + done_3 = true; }); // first tick @@ -422,9 +400,9 @@ TEST_F(SequenceTripleActionTest, TripleAction) ASSERT_EQ(NodeStatus::IDLE, action_3.status()); // continue until succesfull - while ( state != NodeStatus::SUCCESS && system_clock::now() < timeout) + while (state != NodeStatus::SUCCESS && system_clock::now() < timeout) { - std::this_thread::sleep_for( milliseconds( 20) ); + std::this_thread::sleep_for(milliseconds(20)); state = root.executeTick(); } @@ -435,12 +413,11 @@ TEST_F(SequenceTripleActionTest, TripleAction) ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); ASSERT_EQ(NodeStatus::IDLE, action_3.status()); - ASSERT_TRUE(system_clock::now() < timeout); // no timeout should occur + ASSERT_TRUE(system_clock::now() < timeout); // no timeout should occur root.halt(); } - TEST_F(ComplexSequence2ActionsTest, ConditionsTrue) { BT::NodeStatus state = root.executeTick(); @@ -970,8 +947,9 @@ TEST_F(ComplexParallelTest, Condition3FalseAction1Done) ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); ASSERT_EQ(NodeStatus::IDLE, condition_3.status()); - ASSERT_EQ(NodeStatus::SUCCESS, action_1.status()); // success not read yet by the node parallel_1 - ASSERT_EQ(NodeStatus::RUNNING, parallel_1.status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded + ASSERT_EQ(NodeStatus::SUCCESS, action_1.status()); // success not read yet by the node parallel_1 + ASSERT_EQ(NodeStatus::RUNNING, + parallel_1.status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded state = root.executeTick(); diff --git a/gtest/include/crossdoor_dummy_nodes.h b/gtest/include/crossdoor_dummy_nodes.h index 159bf0078..5419a2b76 100644 --- a/gtest/include/crossdoor_dummy_nodes.h +++ b/gtest/include/crossdoor_dummy_nodes.h @@ -5,6 +5,7 @@ using namespace BT; class CrossDoor { int _multiplier; + public: CrossDoor(BT::BehaviorTreeFactory& factory, bool fast = true) { @@ -24,38 +25,38 @@ class CrossDoor BT::NodeStatus IsDoorOpen() { - std::this_thread::sleep_for( std::chrono::milliseconds(50) * _multiplier ); + std::this_thread::sleep_for(std::chrono::milliseconds(50) * _multiplier); return door_open_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } BT::NodeStatus IsDoorLocked() { - std::this_thread::sleep_for( std::chrono::milliseconds(50) * _multiplier ); + std::this_thread::sleep_for(std::chrono::milliseconds(50) * _multiplier); return door_locked_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } BT::NodeStatus UnlockDoor() { - std::this_thread::sleep_for( std::chrono::milliseconds(200) * _multiplier ); + std::this_thread::sleep_for(std::chrono::milliseconds(200) * _multiplier); door_locked_ = false; return NodeStatus::SUCCESS; } BT::NodeStatus PassThroughDoor() { - std::this_thread::sleep_for( std::chrono::milliseconds(100) * _multiplier ); + std::this_thread::sleep_for(std::chrono::milliseconds(100) * _multiplier); return door_open_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } BT::NodeStatus PassThroughWindow() { - std::this_thread::sleep_for( std::chrono::milliseconds(100) * _multiplier ); + std::this_thread::sleep_for(std::chrono::milliseconds(100) * _multiplier); return NodeStatus::SUCCESS; } BT::NodeStatus OpenDoor() { - std::this_thread::sleep_for( std::chrono::milliseconds(200) * _multiplier ); + std::this_thread::sleep_for(std::chrono::milliseconds(200) * _multiplier); if (door_locked_) return NodeStatus::FAILURE; door_open_ = true; @@ -64,7 +65,7 @@ class CrossDoor BT::NodeStatus CloseDoor() { - std::this_thread::sleep_for( std::chrono::milliseconds(150) * _multiplier ); + std::this_thread::sleep_for(std::chrono::milliseconds(150) * _multiplier); if (door_open_) { door_open_ = false; diff --git a/gtest/simple_example.cpp b/gtest/simple_example.cpp index c5bcbfb88..780dd39a2 100644 --- a/gtest/simple_example.cpp +++ b/gtest/simple_example.cpp @@ -67,7 +67,6 @@ const std::string xml_text_B = R"( )"; - // clang-format on int main(int argc, char** argv) @@ -86,17 +85,16 @@ int main(int argc, char** argv) BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); StdCoutLogger logger_cout(root_node.get()); - FileLogger file_file( root_node.get(), "simple_trace.fbl", 32 ); - + FileLogger file_file(root_node.get(), "simple_trace.fbl", 32); std::cout << "\n------- First executeTick() --------" << std::endl; root_node->executeTick(); std::cout << "\n------- sleep --------" << std::endl; - std::this_thread::sleep_for( std::chrono::milliseconds(50) ); + std::this_thread::sleep_for(std::chrono::milliseconds(50)); std::cout << "\n------- Second executeTick() --------" << std::endl; root_node->executeTick(); std::cout << "\n------- sleep --------" << std::endl; - std::this_thread::sleep_for( std::chrono::milliseconds(50) ); + std::this_thread::sleep_for(std::chrono::milliseconds(50)); std::cout << "\n------- Third executeTick() --------" << std::endl; root_node->executeTick(); std::cout << std::endl; diff --git a/gtest/src/action_test_node.cpp b/gtest/src/action_test_node.cpp index a017dbcf0..03a792b46 100644 --- a/gtest/src/action_test_node.cpp +++ b/gtest/src/action_test_node.cpp @@ -14,8 +14,7 @@ #include "action_test_node.h" #include -BT::ActionTestNode::ActionTestNode(const std::string& name) : - ActionNode(name) +BT::ActionTestNode::ActionTestNode(const std::string& name) : ActionNode(name) { boolean_value_ = true; time_ = 3; @@ -31,12 +30,12 @@ BT::NodeStatus BT::ActionTestNode::tick() { stop_loop_ = false; int i = 0; - while ( !stop_loop_ && i++ < time_) + while (!stop_loop_ && i++ < time_) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); } - if ( !stop_loop_ ) + if (!stop_loop_) { return boolean_value_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; } diff --git a/gtest/src/condition_test_node.cpp b/gtest/src/condition_test_node.cpp index 42706428e..130667c95 100644 --- a/gtest/src/condition_test_node.cpp +++ b/gtest/src/condition_test_node.cpp @@ -13,8 +13,7 @@ #include "condition_test_node.h" #include -BT::ConditionTestNode::ConditionTestNode(const std::string& name) : - ConditionNode::ConditionNode(name) +BT::ConditionTestNode::ConditionTestNode(const std::string& name) : ConditionNode::ConditionNode(name) { boolean_value_ = true; } diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 438130887..d9469117a 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -23,7 +23,7 @@ class ActionNodeBase : public LeafNode { public: // Constructor - ActionNodeBase(const std::string& name, const NodeParameters ¶meters); + ActionNodeBase(const std::string& name, const NodeParameters& parameters); ~ActionNodeBase() override = default; virtual NodeType type() const override final @@ -77,12 +77,11 @@ class SimpleActionNode : public ActionNodeBase * */ - class ActionNode : public ActionNodeBase { public: // Constructor - ActionNode(const std::string& name, const NodeParameters& parameters = NodeParameters() ); + ActionNode(const std::string& name, const NodeParameters& parameters = NodeParameters()); virtual ~ActionNode() override; // The method that is going to be executed by the thread diff --git a/include/behavior_tree_core/basic_types.h b/include/behavior_tree_core/basic_types.h index c947029d2..67e6925ea 100644 --- a/include/behavior_tree_core/basic_types.h +++ b/include/behavior_tree_core/basic_types.h @@ -4,7 +4,8 @@ #include #include -namespace BT{ +namespace BT +{ // Enumerates the possible types of a node, for drawinf we // have do discriminate whoich control node it is: enum class NodeType @@ -34,7 +35,6 @@ enum class NodeStatus FAILURE }; - // Enumerates the options for when a parallel node is considered to have failed: // - "FAIL_ON_ONE" indicates that the node will return failure as soon as one of // its children fails; @@ -66,10 +66,10 @@ enum SuccessPolicy template T convertFromString(const char* str); -template inline -T convertFromString(const std::string& str) +template +inline T convertFromString(const std::string& str) { - return convertFromString( str.c_str() ); + return convertFromString(str.c_str()); } //------------------------------------------------------------------ @@ -79,7 +79,6 @@ T convertFromString(const std::string& str) */ const char* toStr(const BT::NodeStatus& status, bool colored = false); - inline std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status) { os << toStr(status); @@ -107,8 +106,6 @@ inline std::ostream& operator<<(std::ostream& os, const BT::ResetPolicy& type) os << toStr(type); return os; } - - } -#endif // BT_BASIC_TYPES_H +#endif // BT_BASIC_TYPES_H diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index a7b8157b8..2258b4489 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -31,14 +31,13 @@ namespace BT { -void recursiveVisitor(TreeNode *node, std::function visitor); +void recursiveVisitor(TreeNode* node, std::function visitor); /** * Debug function to print on a stream */ void printTreeRecursively(const TreeNode* root_node); - /** * @brief buildSerializedStatusSnapshot can be used to create a serialize buffer that can be stored * (or sent to a client application) to know the status of all the nodes of a tree. @@ -48,12 +47,9 @@ void printTreeRecursively(const TreeNode* root_node); * @param serialized_buffer */ -typedef std::vector> SerializedTreeStatus; - -void buildSerializedStatusSnapshot(const TreeNode *root_node, SerializedTreeStatus& serialized_buffer); - - +typedef std::vector> SerializedTreeStatus; +void buildSerializedStatusSnapshot(const TreeNode* root_node, SerializedTreeStatus& serialized_buffer); } #endif // BEHAVIOR_TREE_H diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index df15956e8..276555469 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -53,7 +53,7 @@ class BehaviorTreeFactory void registerNodeType(const std::string& ID) { static_assert(std::is_base_of::value || std::is_base_of::value || - std::is_base_of::value || std::is_base_of::value, + std::is_base_of::value || std::is_base_of::value, "[registerBuilder]: accepts only classed derived from either ActionNode, DecoratorNode, " "ControlNode " "or ConditionNode"); @@ -66,9 +66,9 @@ class BehaviorTreeFactory "[registerBuilder]: the registered class must have a Constructor with signature:\n\n" " (const std::string&, const NodeParameters&) or (const std::string&)"); - static_assert( !(param_constructable && !has_static_required_parameters), - "[registerBuilder]: a node that accepts NodeParameters must also implement a static method:\n\n" - " const NodeParameters& requiredNodeParameters(); "); + static_assert(!(param_constructable && !has_static_required_parameters), + "[registerBuilder]: a node that accepts NodeParameters must also implement a static method:\n\n" + " const NodeParameters& requiredNodeParameters(); "); registerNodeTypeImpl(ID); saveRequiredParameters(ID); diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index cd3d9ff88..f8777d44d 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -21,8 +21,7 @@ namespace BT class ConditionNode : public LeafNode { public: - - ConditionNode(const std::string& name, const NodeParameters& parameters = NodeParameters() ); + ConditionNode(const std::string& name, const NodeParameters& parameters = NodeParameters()); virtual ~ConditionNode() override = default; diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorator_negation_node.h index 9c4c5c96b..0a3c5f03c 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorator_negation_node.h @@ -21,9 +21,8 @@ namespace BT class DecoratorNegationNode : public DecoratorNode { public: - DecoratorNegationNode(const std::string& name); - + virtual ~DecoratorNegationNode() override = default; private: diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index f541ff89c..0d2c4fad1 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -32,7 +32,6 @@ class DecoratorNode : public TreeNode return NodeType::DECORATOR; } }; - } #endif diff --git a/include/behavior_tree_core/decorator_repeat_node.h b/include/behavior_tree_core/decorator_repeat_node.h index d5f643a94..e5bf71760 100644 --- a/include/behavior_tree_core/decorator_repeat_node.h +++ b/include/behavior_tree_core/decorator_repeat_node.h @@ -22,7 +22,7 @@ class DecoratorRepeatNode : public DecoratorNode { public: // Constructor - DecoratorRepeatNode(const std::string &name, unsigned int NTries); + DecoratorRepeatNode(const std::string& name, unsigned int NTries); DecoratorRepeatNode(const std::string& name, const NodeParameters& params); @@ -30,7 +30,7 @@ class DecoratorRepeatNode : public DecoratorNode static const NodeParameters& requiredNodeParameters() { - static NodeParameters params = { {NUM_CYCLES, "1"} }; + static NodeParameters params = {{NUM_CYCLES, "1"}}; return params; } diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorator_retry_node.h index 28e5a1e91..f0ec0968c 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorator_retry_node.h @@ -30,7 +30,7 @@ class DecoratorRetryNode : public DecoratorNode static const NodeParameters& requiredNodeParameters() { - static NodeParameters params = { {NUM_ATTEMPTS, "1"} }; + static NodeParameters params = {{NUM_ATTEMPTS, "1"}}; return params; } diff --git a/include/behavior_tree_core/decorator_subtree_node.h b/include/behavior_tree_core/decorator_subtree_node.h index 7a4dea7fe..a0ce972fa 100644 --- a/include/behavior_tree_core/decorator_subtree_node.h +++ b/include/behavior_tree_core/decorator_subtree_node.h @@ -8,20 +8,17 @@ namespace BT class DecoratorSubtreeNode : public DecoratorNode { public: - - DecoratorSubtreeNode(const std::string& name) : - DecoratorNode(name, NodeParameters()) + DecoratorSubtreeNode(const std::string& name) : DecoratorNode(name, NodeParameters()) { } virtual ~DecoratorSubtreeNode() override = default; private: - virtual BT::NodeStatus tick() override { NodeStatus prev_status = status(); - if ( prev_status== NodeStatus::IDLE) + if (prev_status == NodeStatus::IDLE) { setStatus(NodeStatus::RUNNING); } @@ -30,7 +27,6 @@ class DecoratorSubtreeNode : public DecoratorNode return status; } }; - } #endif // DECORATOR_SUBTREE_NODE_H diff --git a/include/behavior_tree_core/fallback_node.h b/include/behavior_tree_core/fallback_node.h index c0590c8c1..044fabc2e 100644 --- a/include/behavior_tree_core/fallback_node.h +++ b/include/behavior_tree_core/fallback_node.h @@ -21,15 +21,13 @@ namespace BT class FallbackNode : public ControlNode { public: - FallbackNode(const std::string& name); virtual ~FallbackNode() override = default; -private: + private: virtual BT::NodeStatus tick() override; }; - } #endif diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/fallback_node_with_memory.h index e3f86e319..5376ab0b3 100644 --- a/include/behavior_tree_core/fallback_node_with_memory.h +++ b/include/behavior_tree_core/fallback_node_with_memory.h @@ -20,8 +20,7 @@ namespace BT { class FallbackNodeWithMemory : public ControlNode { - -public: + public: FallbackNodeWithMemory(const std::string& name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); // Reset policy passed by parameter [reset_policy] @@ -33,19 +32,17 @@ class FallbackNodeWithMemory : public ControlNode static const NodeParameters& requiredNodeParameters() { - static NodeParameters params = { {RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)} }; + static NodeParameters params = {{RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)}}; return params; } -private: + private: unsigned int current_child_idx_; ResetPolicy reset_policy_; constexpr static const char* RESET_POLICY = "reset_policy"; virtual BT::NodeStatus tick() override; }; - - } #endif // FALLBACK_NODE_WITH_MEMORY_H diff --git a/include/behavior_tree_core/leaf_node.h b/include/behavior_tree_core/leaf_node.h index a457ca3a0..476b45a62 100644 --- a/include/behavior_tree_core/leaf_node.h +++ b/include/behavior_tree_core/leaf_node.h @@ -22,7 +22,7 @@ class LeafNode : public TreeNode { protected: public: - LeafNode(const std::string& name, const NodeParameters ¶meters); + LeafNode(const std::string& name, const NodeParameters& parameters); virtual ~LeafNode() override = default; }; diff --git a/include/behavior_tree_core/parallel_node.h b/include/behavior_tree_core/parallel_node.h index 617d9c3f8..1c07a258e 100644 --- a/include/behavior_tree_core/parallel_node.h +++ b/include/behavior_tree_core/parallel_node.h @@ -22,7 +22,7 @@ class ParallelNode : public ControlNode { public: // Constructor - ParallelNode(const std::string &name, int threshold_M); + ParallelNode(const std::string& name, int threshold_M); ~ParallelNode() = default; virtual void halt() override; diff --git a/include/behavior_tree_core/sequence_node.h b/include/behavior_tree_core/sequence_node.h index 5342a9039..0c2f0566e 100644 --- a/include/behavior_tree_core/sequence_node.h +++ b/include/behavior_tree_core/sequence_node.h @@ -25,7 +25,7 @@ class SequenceNode : public ControlNode virtual ~SequenceNode() override = default; -private: + private: virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/sequence_node_with_memory.h index 4c1a734b3..d190fea4b 100644 --- a/include/behavior_tree_core/sequence_node_with_memory.h +++ b/include/behavior_tree_core/sequence_node_with_memory.h @@ -21,10 +21,10 @@ namespace BT class SequenceNodeWithMemory : public ControlNode { public: - SequenceNodeWithMemory(const std::string &name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); + SequenceNodeWithMemory(const std::string& name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); // Reset policy passed by parameter [reset_policy] - SequenceNodeWithMemory(const std::string &name, const NodeParameters& params); + SequenceNodeWithMemory(const std::string& name, const NodeParameters& params); virtual ~SequenceNodeWithMemory() override = default; @@ -32,7 +32,7 @@ class SequenceNodeWithMemory : public ControlNode static const NodeParameters& requiredNodeParameters() { - static NodeParameters params = { {RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)} }; + static NodeParameters params = {{RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)}}; return params; } diff --git a/include/behavior_tree_core/signal.h b/include/behavior_tree_core/signal.h index 6006dcb08..9bcb46719 100644 --- a/include/behavior_tree_core/signal.h +++ b/include/behavior_tree_core/signal.h @@ -5,30 +5,31 @@ #include #include -namespace BT{ - +namespace BT +{ /** * Super simple Signal/Slop implementation, AKA "Observable pattern". * The subscriber is active until it goes out of scope or Subscriber::reset() is called. */ template -class Signal{ -public: - +class Signal +{ + public: using CallableFunction = std::function; using Subscriber = std::shared_ptr; void notify(CallableArgs... args) { - for (size_t i=0; i< subscribers_.size(); ) + for (size_t i = 0; i < subscribers_.size();) { - if( auto sub = subscribers_[i].lock() ) + if (auto sub = subscribers_[i].lock()) { (*sub)(args...); i++; } - else{ - subscribers_.erase( subscribers_.begin()+i ); + else + { + subscribers_.erase(subscribers_.begin() + i); } } } @@ -40,12 +41,9 @@ class Signal{ return sub; } -private: - + private: std::vector> subscribers_; - }; - } -#endif // SIMPLE_SIGNAL_H +#endif // SIMPLE_SIGNAL_H diff --git a/include/behavior_tree_core/tick_engine.h b/include/behavior_tree_core/tick_engine.h index 67888c366..6dea77b81 100644 --- a/include/behavior_tree_core/tick_engine.h +++ b/include/behavior_tree_core/tick_engine.h @@ -21,7 +21,6 @@ namespace BT { - class TickEngine { private: @@ -38,7 +37,6 @@ class TickEngine void notify(); }; - } #endif diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 8a63c4e38..c339418d8 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -26,14 +26,12 @@ namespace BT { - // We call Parameters the set of Key/Values that can be read from file and are // used to parametrize an object. It is up to the user's code to parse the string. typedef std::map NodeParameters; typedef std::chrono::high_resolution_clock::time_point TimePoint; - // Abstract base class for Behavior Tree Nodes class TreeNode { @@ -45,7 +43,6 @@ class TreeNode mutable std::mutex state_mutex_; protected: - // Method to be implemented by the user virtual BT::NodeStatus tick() = 0; @@ -72,9 +69,9 @@ class TreeNode virtual NodeType type() const = 0; - using StatusChangeSignal = Signal; + using StatusChangeSignal = Signal; using StatusChangeSubscriber = StatusChangeSignal::Subscriber; - using StatusChangeCallback = StatusChangeSignal::CallableFunction; + using StatusChangeCallback = StatusChangeSignal::CallableFunction; /** * @brief subscribeToStatusChange is used to attach a callback to a status change. @@ -85,44 +82,41 @@ class TreeNode * * @return the subscriber. */ - StatusChangeSubscriber subscribeToStatusChange(StatusChangeCallback callback); - - // get an unique identifier of this instance of treeNode - uint16_t UID() const; - - void setRegistrationName(const std::string& registration_name); + StatusChangeSubscriber subscribeToStatusChange(StatusChangeCallback callback); - const std::string& registrationName() const; + // get an unique identifier of this instance of treeNode + uint16_t UID() const; -protected: - template T getParam(const std::string& key) const - { - auto it = parameters_.find(key); - if( it == parameters_.end() ) - { - throw std::invalid_argument( std::string("Can't find the parameter with key: ") + key ); - } - return convertFromString( key.c_str() ); - } + void setRegistrationName(const std::string& registration_name); -private: + const std::string& registrationName() const; - StatusChangeSignal state_change_signal_; + protected: + template + T getParam(const std::string& key) const + { + auto it = parameters_.find(key); + if (it == parameters_.end()) + { + throw std::invalid_argument(std::string("Can't find the parameter with key: ") + key); + } + return convertFromString(key.c_str()); + } - const uint16_t uid_; + private: + StatusChangeSignal state_change_signal_; - std::string registration_name_; + const uint16_t uid_; - const NodeParameters parameters_; + std::string registration_name_; + const NodeParameters parameters_; }; typedef std::shared_ptr TreeNodePtr; // The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; - - } #endif diff --git a/include/behavior_tree_logger/BT_logger_generated.h b/include/behavior_tree_logger/BT_logger_generated.h index 7c6630dab..5ff58c9aa 100644 --- a/include/behavior_tree_logger/BT_logger_generated.h +++ b/include/behavior_tree_logger/BT_logger_generated.h @@ -1,13 +1,12 @@ // automatically generated by the FlatBuffers compiler, do not modify - #ifndef FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ #define FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ #include "flatbuffers/flatbuffers.h" -namespace BT_Serialization { - +namespace BT_Serialization +{ struct Timestamp; struct TreeNode; @@ -18,401 +17,407 @@ struct StatusChange; struct StatusChangeLog; -enum class Status : int8_t { - IDLE = 0, - RUNNING = 1, - SUCCESS = 2, - FAILURE = 3, - MIN = IDLE, - MAX = FAILURE +enum class Status : int8_t +{ + IDLE = 0, + RUNNING = 1, + SUCCESS = 2, + FAILURE = 3, + MIN = IDLE, + MAX = FAILURE }; -inline const Status (&EnumValuesStatus())[4] { - static const Status values[] = { - Status::IDLE, - Status::RUNNING, - Status::SUCCESS, - Status::FAILURE - }; - return values; +inline const Status (&EnumValuesStatus())[4] +{ + static const Status values[] = {Status::IDLE, Status::RUNNING, Status::SUCCESS, Status::FAILURE}; + return values; } -inline const char * const *EnumNamesStatus() { - static const char * const names[] = { - "IDLE", - "RUNNING", - "SUCCESS", - "FAILURE", - nullptr - }; - return names; +inline const char* const* EnumNamesStatus() +{ + static const char* const names[] = {"IDLE", "RUNNING", "SUCCESS", "FAILURE", nullptr}; + return names; } -inline const char *EnumNameStatus(Status e) { - const size_t index = static_cast(e); - return EnumNamesStatus()[index]; +inline const char* EnumNameStatus(Status e) +{ + const size_t index = static_cast(e); + return EnumNamesStatus()[index]; } -enum class Type : int8_t { - UNDEFINED = 0, - ACTION = 1, - CONDITION = 2, - CONTROL = 3, - DECORATOR = 4, - SUBTREE = 5, - MIN = UNDEFINED, - MAX = SUBTREE +enum class Type : int8_t +{ + UNDEFINED = 0, + ACTION = 1, + CONDITION = 2, + CONTROL = 3, + DECORATOR = 4, + SUBTREE = 5, + MIN = UNDEFINED, + MAX = SUBTREE }; -inline const Type (&EnumValuesType())[6] { - static const Type values[] = { - Type::UNDEFINED, - Type::ACTION, - Type::CONDITION, - Type::CONTROL, - Type::DECORATOR, - Type::SUBTREE - }; - return values; +inline const Type (&EnumValuesType())[6] +{ + static const Type values[] = {Type::UNDEFINED, Type::ACTION, Type::CONDITION, + Type::CONTROL, Type::DECORATOR, Type::SUBTREE}; + return values; } -inline const char * const *EnumNamesType() { - static const char * const names[] = { - "UNDEFINED", - "ACTION", - "CONDITION", - "CONTROL", - "DECORATOR", - "SUBTREE", - nullptr - }; - return names; +inline const char* const* EnumNamesType() +{ + static const char* const names[] = {"UNDEFINED", "ACTION", "CONDITION", "CONTROL", "DECORATOR", "SUBTREE", nullptr}; + return names; } -inline const char *EnumNameType(Type e) { - const size_t index = static_cast(e); - return EnumNamesType()[index]; +inline const char* EnumNameType(Type e) +{ + const size_t index = static_cast(e); + return EnumNamesType()[index]; } -FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) Timestamp FLATBUFFERS_FINAL_CLASS { - private: - uint64_t usec_since_epoch_; - - public: - Timestamp() { - memset(this, 0, sizeof(Timestamp)); - } - Timestamp(uint64_t _usec_since_epoch) - : usec_since_epoch_(flatbuffers::EndianScalar(_usec_since_epoch)) { - } - uint64_t usec_since_epoch() const { - return flatbuffers::EndianScalar(usec_since_epoch_); - } +FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) Timestamp FLATBUFFERS_FINAL_CLASS +{ + private: + uint64_t usec_since_epoch_; + + public: + Timestamp() + { + memset(this, 0, sizeof(Timestamp)); + } + Timestamp(uint64_t _usec_since_epoch) : usec_since_epoch_(flatbuffers::EndianScalar(_usec_since_epoch)) + { + } + uint64_t usec_since_epoch() const + { + return flatbuffers::EndianScalar(usec_since_epoch_); + } }; FLATBUFFERS_STRUCT_END(Timestamp, 8); -FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) StatusChange FLATBUFFERS_FINAL_CLASS { - private: - uint16_t uid_; - int8_t prev_status_; - int8_t status_; - int32_t padding0__; - Timestamp timestamp_; - - public: - StatusChange() { - memset(this, 0, sizeof(StatusChange)); - } - StatusChange(uint16_t _uid, Status _prev_status, Status _status, const Timestamp &_timestamp) - : uid_(flatbuffers::EndianScalar(_uid)), - prev_status_(flatbuffers::EndianScalar(static_cast(_prev_status))), - status_(flatbuffers::EndianScalar(static_cast(_status))), - padding0__(0), - timestamp_(_timestamp) { - (void)padding0__; - } - uint16_t uid() const { - return flatbuffers::EndianScalar(uid_); - } - Status prev_status() const { - return static_cast(flatbuffers::EndianScalar(prev_status_)); - } - Status status() const { - return static_cast(flatbuffers::EndianScalar(status_)); - } - const Timestamp ×tamp() const { - return timestamp_; - } +FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) StatusChange FLATBUFFERS_FINAL_CLASS +{ + private: + uint16_t uid_; + int8_t prev_status_; + int8_t status_; + int32_t padding0__; + Timestamp timestamp_; + + public: + StatusChange() + { + memset(this, 0, sizeof(StatusChange)); + } + StatusChange(uint16_t _uid, Status _prev_status, Status _status, const Timestamp& _timestamp) + : uid_(flatbuffers::EndianScalar(_uid)) + , prev_status_(flatbuffers::EndianScalar(static_cast(_prev_status))) + , status_(flatbuffers::EndianScalar(static_cast(_status))) + , padding0__(0) + , timestamp_(_timestamp) + { + (void)padding0__; + } + uint16_t uid() const + { + return flatbuffers::EndianScalar(uid_); + } + Status prev_status() const + { + return static_cast(flatbuffers::EndianScalar(prev_status_)); + } + Status status() const + { + return static_cast(flatbuffers::EndianScalar(status_)); + } + const Timestamp& timestamp() const + { + return timestamp_; + } }; FLATBUFFERS_STRUCT_END(StatusChange, 16); -struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { - enum { - VT_UID = 4, - VT_CHILDREN_UID = 6, - VT_TYPE = 8, - VT_STATUS = 10, - VT_INSTANCE_NAME = 12, - VT_REGISTRATION_NAME = 14 - }; - uint16_t uid() const { - return GetField(VT_UID, 0); - } - const flatbuffers::Vector *children_uid() const { - return GetPointer *>(VT_CHILDREN_UID); - } - Type type() const { - return static_cast(GetField(VT_TYPE, 0)); - } - Status status() const { - return static_cast(GetField(VT_STATUS, 0)); - } - const flatbuffers::String *instance_name() const { - return GetPointer(VT_INSTANCE_NAME); - } - const flatbuffers::String *registration_name() const { - return GetPointer(VT_REGISTRATION_NAME); - } - bool Verify(flatbuffers::Verifier &verifier) const { - return VerifyTableStart(verifier) && - VerifyField(verifier, VT_UID) && - VerifyOffset(verifier, VT_CHILDREN_UID) && - verifier.Verify(children_uid()) && - VerifyField(verifier, VT_TYPE) && - VerifyField(verifier, VT_STATUS) && - VerifyOffsetRequired(verifier, VT_INSTANCE_NAME) && - verifier.Verify(instance_name()) && - VerifyOffsetRequired(verifier, VT_REGISTRATION_NAME) && - verifier.Verify(registration_name()) && - verifier.EndTable(); - } +struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table +{ + enum + { + VT_UID = 4, + VT_CHILDREN_UID = 6, + VT_TYPE = 8, + VT_STATUS = 10, + VT_INSTANCE_NAME = 12, + VT_REGISTRATION_NAME = 14 + }; + uint16_t uid() const + { + return GetField(VT_UID, 0); + } + const flatbuffers::Vector* children_uid() const + { + return GetPointer*>(VT_CHILDREN_UID); + } + Type type() const + { + return static_cast(GetField(VT_TYPE, 0)); + } + Status status() const + { + return static_cast(GetField(VT_STATUS, 0)); + } + const flatbuffers::String* instance_name() const + { + return GetPointer(VT_INSTANCE_NAME); + } + const flatbuffers::String* registration_name() const + { + return GetPointer(VT_REGISTRATION_NAME); + } + bool Verify(flatbuffers::Verifier& verifier) const + { + return VerifyTableStart(verifier) && VerifyField(verifier, VT_UID) && + VerifyOffset(verifier, VT_CHILDREN_UID) && verifier.Verify(children_uid()) && + VerifyField(verifier, VT_TYPE) && VerifyField(verifier, VT_STATUS) && + VerifyOffsetRequired(verifier, VT_INSTANCE_NAME) && verifier.Verify(instance_name()) && + VerifyOffsetRequired(verifier, VT_REGISTRATION_NAME) && verifier.Verify(registration_name()) && + verifier.EndTable(); + } }; -struct TreeNodeBuilder { - flatbuffers::FlatBufferBuilder &fbb_; - flatbuffers::uoffset_t start_; - void add_uid(uint16_t uid) { - fbb_.AddElement(TreeNode::VT_UID, uid, 0); - } - void add_children_uid(flatbuffers::Offset> children_uid) { - fbb_.AddOffset(TreeNode::VT_CHILDREN_UID, children_uid); - } - void add_type(Type type) { - fbb_.AddElement(TreeNode::VT_TYPE, static_cast(type), 0); - } - void add_status(Status status) { - fbb_.AddElement(TreeNode::VT_STATUS, static_cast(status), 0); - } - void add_instance_name(flatbuffers::Offset instance_name) { - fbb_.AddOffset(TreeNode::VT_INSTANCE_NAME, instance_name); - } - void add_registration_name(flatbuffers::Offset registration_name) { - fbb_.AddOffset(TreeNode::VT_REGISTRATION_NAME, registration_name); - } - explicit TreeNodeBuilder(flatbuffers::FlatBufferBuilder &_fbb) - : fbb_(_fbb) { - start_ = fbb_.StartTable(); - } - TreeNodeBuilder &operator=(const TreeNodeBuilder &); - flatbuffers::Offset Finish() { - const auto end = fbb_.EndTable(start_); - auto o = flatbuffers::Offset(end); - fbb_.Required(o, TreeNode::VT_INSTANCE_NAME); - fbb_.Required(o, TreeNode::VT_REGISTRATION_NAME); - return o; - } +struct TreeNodeBuilder +{ + flatbuffers::FlatBufferBuilder& fbb_; + flatbuffers::uoffset_t start_; + void add_uid(uint16_t uid) + { + fbb_.AddElement(TreeNode::VT_UID, uid, 0); + } + void add_children_uid(flatbuffers::Offset> children_uid) + { + fbb_.AddOffset(TreeNode::VT_CHILDREN_UID, children_uid); + } + void add_type(Type type) + { + fbb_.AddElement(TreeNode::VT_TYPE, static_cast(type), 0); + } + void add_status(Status status) + { + fbb_.AddElement(TreeNode::VT_STATUS, static_cast(status), 0); + } + void add_instance_name(flatbuffers::Offset instance_name) + { + fbb_.AddOffset(TreeNode::VT_INSTANCE_NAME, instance_name); + } + void add_registration_name(flatbuffers::Offset registration_name) + { + fbb_.AddOffset(TreeNode::VT_REGISTRATION_NAME, registration_name); + } + explicit TreeNodeBuilder(flatbuffers::FlatBufferBuilder& _fbb) : fbb_(_fbb) + { + start_ = fbb_.StartTable(); + } + TreeNodeBuilder& operator=(const TreeNodeBuilder&); + flatbuffers::Offset Finish() + { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + fbb_.Required(o, TreeNode::VT_INSTANCE_NAME); + fbb_.Required(o, TreeNode::VT_REGISTRATION_NAME); + return o; + } }; -inline flatbuffers::Offset CreateTreeNode( - flatbuffers::FlatBufferBuilder &_fbb, - uint16_t uid = 0, - flatbuffers::Offset> children_uid = 0, - Type type = Type::UNDEFINED, - Status status = Status::IDLE, - flatbuffers::Offset instance_name = 0, - flatbuffers::Offset registration_name = 0) { - TreeNodeBuilder builder_(_fbb); - builder_.add_registration_name(registration_name); - builder_.add_instance_name(instance_name); - builder_.add_children_uid(children_uid); - builder_.add_uid(uid); - builder_.add_status(status); - builder_.add_type(type); - return builder_.Finish(); +inline flatbuffers::Offset CreateTreeNode(flatbuffers::FlatBufferBuilder& _fbb, uint16_t uid = 0, + flatbuffers::Offset> children_uid = 0, + Type type = Type::UNDEFINED, Status status = Status::IDLE, + flatbuffers::Offset instance_name = 0, + flatbuffers::Offset registration_name = 0) +{ + TreeNodeBuilder builder_(_fbb); + builder_.add_registration_name(registration_name); + builder_.add_instance_name(instance_name); + builder_.add_children_uid(children_uid); + builder_.add_uid(uid); + builder_.add_status(status); + builder_.add_type(type); + return builder_.Finish(); } -inline flatbuffers::Offset CreateTreeNodeDirect( - flatbuffers::FlatBufferBuilder &_fbb, - uint16_t uid = 0, - const std::vector *children_uid = nullptr, - Type type = Type::UNDEFINED, - Status status = Status::IDLE, - const char *instance_name = nullptr, - const char *registration_name = nullptr) { - return BT_Serialization::CreateTreeNode( - _fbb, - uid, - children_uid ? _fbb.CreateVector(*children_uid) : 0, - type, - status, - instance_name ? _fbb.CreateString(instance_name) : 0, - registration_name ? _fbb.CreateString(registration_name) : 0); +inline flatbuffers::Offset CreateTreeNodeDirect(flatbuffers::FlatBufferBuilder& _fbb, uint16_t uid = 0, + const std::vector* children_uid = nullptr, + Type type = Type::UNDEFINED, Status status = Status::IDLE, + const char* instance_name = nullptr, + const char* registration_name = nullptr) +{ + return BT_Serialization::CreateTreeNode(_fbb, uid, children_uid ? _fbb.CreateVector(*children_uid) : 0, + type, status, instance_name ? _fbb.CreateString(instance_name) : 0, + registration_name ? _fbb.CreateString(registration_name) : 0); } -struct BehaviorTree FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { - enum { - VT_ROOT_UID = 4, - VT_NODES = 6 - }; - uint16_t root_uid() const { - return GetField(VT_ROOT_UID, 0); - } - const flatbuffers::Vector> *nodes() const { - return GetPointer> *>(VT_NODES); - } - bool Verify(flatbuffers::Verifier &verifier) const { - return VerifyTableStart(verifier) && - VerifyField(verifier, VT_ROOT_UID) && - VerifyOffset(verifier, VT_NODES) && - verifier.Verify(nodes()) && - verifier.VerifyVectorOfTables(nodes()) && - verifier.EndTable(); - } +struct BehaviorTree FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table +{ + enum + { + VT_ROOT_UID = 4, + VT_NODES = 6 + }; + uint16_t root_uid() const + { + return GetField(VT_ROOT_UID, 0); + } + const flatbuffers::Vector>* nodes() const + { + return GetPointer>*>(VT_NODES); + } + bool Verify(flatbuffers::Verifier& verifier) const + { + return VerifyTableStart(verifier) && VerifyField(verifier, VT_ROOT_UID) && + VerifyOffset(verifier, VT_NODES) && verifier.Verify(nodes()) && verifier.VerifyVectorOfTables(nodes()) && + verifier.EndTable(); + } }; -struct BehaviorTreeBuilder { - flatbuffers::FlatBufferBuilder &fbb_; - flatbuffers::uoffset_t start_; - void add_root_uid(uint16_t root_uid) { - fbb_.AddElement(BehaviorTree::VT_ROOT_UID, root_uid, 0); - } - void add_nodes(flatbuffers::Offset>> nodes) { - fbb_.AddOffset(BehaviorTree::VT_NODES, nodes); - } - explicit BehaviorTreeBuilder(flatbuffers::FlatBufferBuilder &_fbb) - : fbb_(_fbb) { - start_ = fbb_.StartTable(); - } - BehaviorTreeBuilder &operator=(const BehaviorTreeBuilder &); - flatbuffers::Offset Finish() { - const auto end = fbb_.EndTable(start_); - auto o = flatbuffers::Offset(end); - return o; - } +struct BehaviorTreeBuilder +{ + flatbuffers::FlatBufferBuilder& fbb_; + flatbuffers::uoffset_t start_; + void add_root_uid(uint16_t root_uid) + { + fbb_.AddElement(BehaviorTree::VT_ROOT_UID, root_uid, 0); + } + void add_nodes(flatbuffers::Offset>> nodes) + { + fbb_.AddOffset(BehaviorTree::VT_NODES, nodes); + } + explicit BehaviorTreeBuilder(flatbuffers::FlatBufferBuilder& _fbb) : fbb_(_fbb) + { + start_ = fbb_.StartTable(); + } + BehaviorTreeBuilder& operator=(const BehaviorTreeBuilder&); + flatbuffers::Offset Finish() + { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + return o; + } }; -inline flatbuffers::Offset CreateBehaviorTree( - flatbuffers::FlatBufferBuilder &_fbb, - uint16_t root_uid = 0, - flatbuffers::Offset>> nodes = 0) { - BehaviorTreeBuilder builder_(_fbb); - builder_.add_nodes(nodes); - builder_.add_root_uid(root_uid); - return builder_.Finish(); +inline flatbuffers::Offset +CreateBehaviorTree(flatbuffers::FlatBufferBuilder& _fbb, uint16_t root_uid = 0, + flatbuffers::Offset>> nodes = 0) +{ + BehaviorTreeBuilder builder_(_fbb); + builder_.add_nodes(nodes); + builder_.add_root_uid(root_uid); + return builder_.Finish(); } -inline flatbuffers::Offset CreateBehaviorTreeDirect( - flatbuffers::FlatBufferBuilder &_fbb, - uint16_t root_uid = 0, - const std::vector> *nodes = nullptr) { - return BT_Serialization::CreateBehaviorTree( - _fbb, - root_uid, - nodes ? _fbb.CreateVector>(*nodes) : 0); +inline flatbuffers::Offset +CreateBehaviorTreeDirect(flatbuffers::FlatBufferBuilder& _fbb, uint16_t root_uid = 0, + const std::vector>* nodes = nullptr) +{ + return BT_Serialization::CreateBehaviorTree(_fbb, root_uid, + nodes ? _fbb.CreateVector>(*nodes) : 0); } -struct StatusChangeLog FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { - enum { - VT_BEHAVIOR_TREE = 4, - VT_STATE_CHANGES = 6 - }; - const BehaviorTree *behavior_tree() const { - return GetPointer(VT_BEHAVIOR_TREE); - } - const flatbuffers::Vector *state_changes() const { - return GetPointer *>(VT_STATE_CHANGES); - } - bool Verify(flatbuffers::Verifier &verifier) const { - return VerifyTableStart(verifier) && - VerifyOffset(verifier, VT_BEHAVIOR_TREE) && - verifier.VerifyTable(behavior_tree()) && - VerifyOffset(verifier, VT_STATE_CHANGES) && - verifier.Verify(state_changes()) && - verifier.EndTable(); - } +struct StatusChangeLog FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table +{ + enum + { + VT_BEHAVIOR_TREE = 4, + VT_STATE_CHANGES = 6 + }; + const BehaviorTree* behavior_tree() const + { + return GetPointer(VT_BEHAVIOR_TREE); + } + const flatbuffers::Vector* state_changes() const + { + return GetPointer*>(VT_STATE_CHANGES); + } + bool Verify(flatbuffers::Verifier& verifier) const + { + return VerifyTableStart(verifier) && VerifyOffset(verifier, VT_BEHAVIOR_TREE) && + verifier.VerifyTable(behavior_tree()) && VerifyOffset(verifier, VT_STATE_CHANGES) && + verifier.Verify(state_changes()) && verifier.EndTable(); + } }; -struct StatusChangeLogBuilder { - flatbuffers::FlatBufferBuilder &fbb_; - flatbuffers::uoffset_t start_; - void add_behavior_tree(flatbuffers::Offset behavior_tree) { - fbb_.AddOffset(StatusChangeLog::VT_BEHAVIOR_TREE, behavior_tree); - } - void add_state_changes(flatbuffers::Offset> state_changes) { - fbb_.AddOffset(StatusChangeLog::VT_STATE_CHANGES, state_changes); - } - explicit StatusChangeLogBuilder(flatbuffers::FlatBufferBuilder &_fbb) - : fbb_(_fbb) { - start_ = fbb_.StartTable(); - } - StatusChangeLogBuilder &operator=(const StatusChangeLogBuilder &); - flatbuffers::Offset Finish() { - const auto end = fbb_.EndTable(start_); - auto o = flatbuffers::Offset(end); - return o; - } +struct StatusChangeLogBuilder +{ + flatbuffers::FlatBufferBuilder& fbb_; + flatbuffers::uoffset_t start_; + void add_behavior_tree(flatbuffers::Offset behavior_tree) + { + fbb_.AddOffset(StatusChangeLog::VT_BEHAVIOR_TREE, behavior_tree); + } + void add_state_changes(flatbuffers::Offset> state_changes) + { + fbb_.AddOffset(StatusChangeLog::VT_STATE_CHANGES, state_changes); + } + explicit StatusChangeLogBuilder(flatbuffers::FlatBufferBuilder& _fbb) : fbb_(_fbb) + { + start_ = fbb_.StartTable(); + } + StatusChangeLogBuilder& operator=(const StatusChangeLogBuilder&); + flatbuffers::Offset Finish() + { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + return o; + } }; -inline flatbuffers::Offset CreateStatusChangeLog( - flatbuffers::FlatBufferBuilder &_fbb, - flatbuffers::Offset behavior_tree = 0, - flatbuffers::Offset> state_changes = 0) { - StatusChangeLogBuilder builder_(_fbb); - builder_.add_state_changes(state_changes); - builder_.add_behavior_tree(behavior_tree); - return builder_.Finish(); +inline flatbuffers::Offset +CreateStatusChangeLog(flatbuffers::FlatBufferBuilder& _fbb, flatbuffers::Offset behavior_tree = 0, + flatbuffers::Offset> state_changes = 0) +{ + StatusChangeLogBuilder builder_(_fbb); + builder_.add_state_changes(state_changes); + builder_.add_behavior_tree(behavior_tree); + return builder_.Finish(); } -inline flatbuffers::Offset CreateStatusChangeLogDirect( - flatbuffers::FlatBufferBuilder &_fbb, - flatbuffers::Offset behavior_tree = 0, - const std::vector *state_changes = nullptr) { - return BT_Serialization::CreateStatusChangeLog( - _fbb, - behavior_tree, - state_changes ? _fbb.CreateVectorOfStructs(*state_changes) : 0); +inline flatbuffers::Offset +CreateStatusChangeLogDirect(flatbuffers::FlatBufferBuilder& _fbb, flatbuffers::Offset behavior_tree = 0, + const std::vector* state_changes = nullptr) +{ + return BT_Serialization::CreateStatusChangeLog( + _fbb, behavior_tree, state_changes ? _fbb.CreateVectorOfStructs(*state_changes) : 0); } -inline const BT_Serialization::BehaviorTree *GetBehaviorTree(const void *buf) { - return flatbuffers::GetRoot(buf); +inline const BT_Serialization::BehaviorTree* GetBehaviorTree(const void* buf) +{ + return flatbuffers::GetRoot(buf); } -inline const BT_Serialization::BehaviorTree *GetSizePrefixedBehaviorTree(const void *buf) { - return flatbuffers::GetSizePrefixedRoot(buf); +inline const BT_Serialization::BehaviorTree* GetSizePrefixedBehaviorTree(const void* buf) +{ + return flatbuffers::GetSizePrefixedRoot(buf); } -inline bool VerifyBehaviorTreeBuffer( - flatbuffers::Verifier &verifier) { - return verifier.VerifyBuffer(nullptr); +inline bool VerifyBehaviorTreeBuffer(flatbuffers::Verifier& verifier) +{ + return verifier.VerifyBuffer(nullptr); } -inline bool VerifySizePrefixedBehaviorTreeBuffer( - flatbuffers::Verifier &verifier) { - return verifier.VerifySizePrefixedBuffer(nullptr); +inline bool VerifySizePrefixedBehaviorTreeBuffer(flatbuffers::Verifier& verifier) +{ + return verifier.VerifySizePrefixedBuffer(nullptr); } -inline void FinishBehaviorTreeBuffer( - flatbuffers::FlatBufferBuilder &fbb, - flatbuffers::Offset root) { - fbb.Finish(root); +inline void FinishBehaviorTreeBuffer(flatbuffers::FlatBufferBuilder& fbb, + flatbuffers::Offset root) +{ + fbb.Finish(root); } -inline void FinishSizePrefixedBehaviorTreeBuffer( - flatbuffers::FlatBufferBuilder &fbb, - flatbuffers::Offset root) { - fbb.FinishSizePrefixed(root); +inline void FinishSizePrefixedBehaviorTreeBuffer(flatbuffers::FlatBufferBuilder& fbb, + flatbuffers::Offset root) +{ + fbb.FinishSizePrefixed(root); } -} // namespace BT_Serialization +} // namespace BT_Serialization -#endif // FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ +#endif // FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ diff --git a/include/behavior_tree_logger/abstract_logger.h b/include/behavior_tree_logger/abstract_logger.h index 131c28a8e..911bef0f5 100644 --- a/include/behavior_tree_logger/abstract_logger.h +++ b/include/behavior_tree_logger/abstract_logger.h @@ -3,33 +3,40 @@ #include "behavior_tree_core/behavior_tree.h" - -namespace BT{ - -class StatusChangeLogger { - -public: - +namespace BT +{ +class StatusChangeLogger +{ + public: StatusChangeLogger(TreeNode* root_node); virtual ~StatusChangeLogger() = default; - virtual void callback(BT::TimePoint timestamp, - const TreeNode& node, - NodeStatus prev_status, - NodeStatus status) = 0; + virtual void callback(BT::TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) = 0; virtual void flush() = 0; - void setEnabled(bool enabled) { enabled_ = enabled; } + void setEnabled(bool enabled) + { + enabled_ = enabled; + } - bool enabled() const { return enabled_; } + bool enabled() const + { + return enabled_; + } // false by default. - bool showsTransitionToIdle() const { return show_transition_to_idle_; } + bool showsTransitionToIdle() const + { + return show_transition_to_idle_; + } - void enableTransitionToIdle(bool enable ) { show_transition_to_idle_ = enable; } + void enableTransitionToIdle(bool enable) + { + show_transition_to_idle_ = enable; + } -private: + private: bool enabled_; bool show_transition_to_idle_; std::vector subscribers_; @@ -37,27 +44,18 @@ class StatusChangeLogger { //-------------------------------------------- -inline StatusChangeLogger::StatusChangeLogger(TreeNode *root_node): - enabled_(true), - show_transition_to_idle_(true) +inline StatusChangeLogger::StatusChangeLogger(TreeNode* root_node) : enabled_(true), show_transition_to_idle_(true) { - recursiveVisitor(root_node, [this](TreeNode* node) - { - subscribers_.push_back( node->subscribeToStatusChange( - [this](TimePoint timestamp, - const TreeNode& node, - NodeStatus prev, - NodeStatus status) - { - if(enabled_ && ( status != NodeStatus::IDLE || show_transition_to_idle_)) - { - this->callback(timestamp, node,prev,status); - } - })); + recursiveVisitor(root_node, [this](TreeNode* node) { + subscribers_.push_back(node->subscribeToStatusChange( + [this](TimePoint timestamp, const TreeNode& node, NodeStatus prev, NodeStatus status) { + if (enabled_ && (status != NodeStatus::IDLE || show_transition_to_idle_)) + { + this->callback(timestamp, node, prev, status); + } + })); }); } - - } -#endif // ABSTRACT_LOGGER_H +#endif // ABSTRACT_LOGGER_H diff --git a/include/behavior_tree_logger/bt_cout_logger.h b/include/behavior_tree_logger/bt_cout_logger.h index c29a5ab21..d61579e7a 100644 --- a/include/behavior_tree_logger/bt_cout_logger.h +++ b/include/behavior_tree_logger/bt_cout_logger.h @@ -4,11 +4,8 @@ #include #include "abstract_logger.h" - -namespace BT{ - - - +namespace BT +{ /** * @brief AddStdCoutLoggerToTree. Give the root node of a tree, * a simple callback is subscribed to any status change of each node. @@ -19,47 +16,40 @@ namespace BT{ * otherwise the logger is removed. */ -class StdCoutLogger: public StatusChangeLogger { - -public: - - StdCoutLogger(TreeNode* root_node): - StatusChangeLogger(root_node) +class StdCoutLogger : public StatusChangeLogger +{ + public: + StdCoutLogger(TreeNode* root_node) : StatusChangeLogger(root_node) { static bool first_instance = true; - if( first_instance ) + if (first_instance) { first_instance = false; } - else{ + else + { throw std::logic_error("Only one instance of StdCoutLogger shall be created"); } } - virtual void callback(TimePoint timestamp, - const TreeNode& node, - NodeStatus prev_status, - NodeStatus status) override + virtual void callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) override { using namespace std::chrono; constexpr const char* whitespaces = " "; constexpr const size_t ws_count = 25; - double since_epoch = duration( timestamp.time_since_epoch() ).count(); - printf("[%.3f]: %s%s %s -> %s\n", - since_epoch, - node.name().c_str(), - &whitespaces[ std::min( ws_count, node.name().size()) ], - toStr(prev_status, true), - toStr(status, true) ); + double since_epoch = duration(timestamp.time_since_epoch()).count(); + printf("[%.3f]: %s%s %s -> %s\n", since_epoch, node.name().c_str(), + &whitespaces[std::min(ws_count, node.name().size())], toStr(prev_status, true), toStr(status, true)); } - virtual void flush() override { std::cout << std::flush; } + virtual void flush() override + { + std::cout << std::flush; + } }; +} // end namespace -} // end namespace - - -#endif // BT_COUT_LOGGER_H +#endif // BT_COUT_LOGGER_H diff --git a/include/behavior_tree_logger/bt_file_logger.h b/include/behavior_tree_logger/bt_file_logger.h index 74b6c2bcf..21bd95ecc 100644 --- a/include/behavior_tree_logger/bt_file_logger.h +++ b/include/behavior_tree_logger/bt_file_logger.h @@ -6,35 +6,30 @@ #include #include "abstract_logger.h" -namespace BT{ - -class FileLogger: public StatusChangeLogger { - -public: +namespace BT +{ +class FileLogger : public StatusChangeLogger +{ + public: FileLogger(TreeNode* root_node, const char* filename, uint16_t buffer_size); virtual ~FileLogger() override; - virtual void callback(TimePoint timestamp, - const TreeNode& node, - NodeStatus prev_status, + virtual void callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) override; virtual void flush() override; -private: - + private: std::ofstream file_os_; std::chrono::high_resolution_clock::time_point start_time; - std::vector< std::array > buffer_; + std::vector > buffer_; bool buffer_max_size_; }; +} // end namespace -} // end namespace - - -#endif // BT_FILE_LOGGER_H +#endif // BT_FILE_LOGGER_H diff --git a/include/behavior_tree_logger/bt_flatbuffer_helper.h b/include/behavior_tree_logger/bt_flatbuffer_helper.h index 51f661610..7f4b28a97 100644 --- a/include/behavior_tree_logger/bt_flatbuffer_helper.h +++ b/include/behavior_tree_logger/bt_flatbuffer_helper.h @@ -4,73 +4,72 @@ #include "abstract_logger.h" #include "BT_logger_generated.h" -namespace BT{ - - +namespace BT +{ inline BT_Serialization::Type convertToFlatbuffers(NodeType type) { - switch( type ){ - case BT::NodeType::ACTION: return BT_Serialization::Type::ACTION; - case BT::NodeType::DECORATOR: return BT_Serialization::Type::DECORATOR; - case BT::NodeType::CONTROL: return BT_Serialization::Type::CONTROL; - case BT::NodeType::CONDITION: return BT_Serialization::Type::CONDITION; - case BT::NodeType::SUBTREE: return BT_Serialization::Type::SUBTREE; - case BT::NodeType::UNDEFINED: return BT_Serialization::Type::UNDEFINED; + switch (type) + { + case BT::NodeType::ACTION: + return BT_Serialization::Type::ACTION; + case BT::NodeType::DECORATOR: + return BT_Serialization::Type::DECORATOR; + case BT::NodeType::CONTROL: + return BT_Serialization::Type::CONTROL; + case BT::NodeType::CONDITION: + return BT_Serialization::Type::CONDITION; + case BT::NodeType::SUBTREE: + return BT_Serialization::Type::SUBTREE; + case BT::NodeType::UNDEFINED: + return BT_Serialization::Type::UNDEFINED; } return BT_Serialization::Type::UNDEFINED; } inline BT_Serialization::Status convertToFlatbuffers(NodeStatus type) { - switch( type ){ - case BT::NodeStatus::IDLE: return BT_Serialization::Status::IDLE; - case BT::NodeStatus::SUCCESS: return BT_Serialization::Status::SUCCESS; - case BT::NodeStatus::RUNNING: return BT_Serialization::Status::RUNNING; - case BT::NodeStatus::FAILURE: return BT_Serialization::Status::FAILURE; + switch (type) + { + case BT::NodeStatus::IDLE: + return BT_Serialization::Status::IDLE; + case BT::NodeStatus::SUCCESS: + return BT_Serialization::Status::SUCCESS; + case BT::NodeStatus::RUNNING: + return BT_Serialization::Status::RUNNING; + case BT::NodeStatus::FAILURE: + return BT_Serialization::Status::FAILURE; } return BT_Serialization::Status::IDLE; } -inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builder, - BT::TreeNode *root_node) +inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builder, BT::TreeNode* root_node) { + std::vector> fb_nodes; - std::vector> fb_nodes; - - recursiveVisitor(root_node, [&](TreeNode* node) - { + recursiveVisitor(root_node, [&](TreeNode* node) { std::vector children_uid; if (auto control = dynamic_cast(node)) { - children_uid.reserve( control->children().size() ); + children_uid.reserve(control->children().size()); for (const auto& child : control->children()) { - children_uid.push_back( child->UID() ); + children_uid.push_back(child->UID()); } } else if (auto decorator = dynamic_cast(node)) { const auto& child = decorator->child(); - children_uid.push_back( child->UID() ); + children_uid.push_back(child->UID()); } - fb_nodes.push_back( BT_Serialization::CreateTreeNode( - builder, - node->UID(), - builder.CreateVector( children_uid ), - convertToFlatbuffers(node->type() ), - convertToFlatbuffers(node->status()), - builder.CreateString(node->name().c_str()), - builder.CreateString(node->registrationName().c_str()) - ) - ); + fb_nodes.push_back(BT_Serialization::CreateTreeNode( + builder, node->UID(), builder.CreateVector(children_uid), convertToFlatbuffers(node->type()), + convertToFlatbuffers(node->status()), builder.CreateString(node->name().c_str()), + builder.CreateString(node->registrationName().c_str()))); }); - auto behavior_tree = BT_Serialization::CreateBehaviorTree( - builder, - root_node->UID(), - builder.CreateVector(fb_nodes) - ); + auto behavior_tree = + BT_Serialization::CreateBehaviorTree(builder, root_node->UID(), builder.CreateVector(fb_nodes)); builder.Finish(behavior_tree); } @@ -78,30 +77,25 @@ inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builde /** Serialize manually the informations about state transition * No flatbuffer serialization here */ -inline -std::array SerializeTransition(uint16_t UID, - TimePoint timestamp, - NodeStatus prev_status, - NodeStatus status) +inline std::array SerializeTransition(uint16_t UID, TimePoint timestamp, NodeStatus prev_status, + NodeStatus status) { using namespace std::chrono; - std::array buffer; - auto usec_since_epoch = duration_cast( timestamp.time_since_epoch() ).count(); - uint32_t t_sec = usec_since_epoch / 1000000; + std::array buffer; + auto usec_since_epoch = duration_cast(timestamp.time_since_epoch()).count(); + uint32_t t_sec = usec_since_epoch / 1000000; uint32_t t_usec = usec_since_epoch % 1000000; - flatbuffers::WriteScalar( &buffer[0], t_sec ); - flatbuffers::WriteScalar( &buffer[4], t_usec ); - flatbuffers::WriteScalar( &buffer[8], UID ); + flatbuffers::WriteScalar(&buffer[0], t_sec); + flatbuffers::WriteScalar(&buffer[4], t_usec); + flatbuffers::WriteScalar(&buffer[8], UID); - flatbuffers::WriteScalar( &buffer[10], - static_cast(convertToFlatbuffers(prev_status)) ); - flatbuffers::WriteScalar( &buffer[11], - static_cast(convertToFlatbuffers(status)) ); + flatbuffers::WriteScalar(&buffer[10], static_cast(convertToFlatbuffers(prev_status))); + flatbuffers::WriteScalar(&buffer[11], static_cast(convertToFlatbuffers(status))); return buffer; } -} // end namespace +} // end namespace -#endif // BT_FLATBUFFER_HELPER_H +#endif // BT_FLATBUFFER_HELPER_H diff --git a/include/behavior_tree_logger/bt_minitrace_logger.h b/include/behavior_tree_logger/bt_minitrace_logger.h index 3cc26f186..c89974b54 100644 --- a/include/behavior_tree_logger/bt_minitrace_logger.h +++ b/include/behavior_tree_logger/bt_minitrace_logger.h @@ -5,21 +5,20 @@ #include "abstract_logger.h" #include "minitrace/minitrace.h" -namespace BT{ - - -class MinitraceLogger: public StatusChangeLogger { - -public: - MinitraceLogger(TreeNode* root_node, const char* filename_json): - StatusChangeLogger(root_node) +namespace BT +{ +class MinitraceLogger : public StatusChangeLogger +{ + public: + MinitraceLogger(TreeNode* root_node, const char* filename_json) : StatusChangeLogger(root_node) { static bool first_instance = true; - if( first_instance ) + if (first_instance) { first_instance = false; } - else{ + else + { throw std::logic_error("Only one instance of MinitraceLogger shall be created"); } minitrace::mtr_register_sigint_handler(); @@ -33,41 +32,38 @@ class MinitraceLogger: public StatusChangeLogger { minitrace::mtr_shutdown(); } - virtual void callback(TimePoint timestamp, const TreeNode& node, - NodeStatus prev_status, - NodeStatus status) override + virtual void callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) override { using namespace minitrace; - const bool statusCompleted = (status == NodeStatus::SUCCESS || - status == NodeStatus::FAILURE); + const bool statusCompleted = (status == NodeStatus::SUCCESS || status == NodeStatus::FAILURE); const char* category = toStr(node.type()); const char* name = node.name().c_str(); - if( prev_status == NodeStatus::IDLE && statusCompleted) + if (prev_status == NodeStatus::IDLE && statusCompleted) { MTR_INSTANT(category, name); } - else if( status == NodeStatus::RUNNING ) + else if (status == NodeStatus::RUNNING) { MTR_BEGIN(category, name); } - else if( prev_status == NodeStatus::RUNNING && statusCompleted ) + else if (prev_status == NodeStatus::RUNNING && statusCompleted) { - MTR_END( category, name ); + MTR_END(category, name); } } - virtual void flush() override { + virtual void flush() override + { minitrace::mtr_flush(); } -private: + + private: TimePoint prev_time_; }; +} // end namespace -} // end namespace - - -#endif // BT_MINITRACE_LOGGER_H +#endif // BT_MINITRACE_LOGGER_H diff --git a/include/behavior_tree_logger/bt_zmq_publisher.h b/include/behavior_tree_logger/bt_zmq_publisher.h index 4bbc662ad..7f3db0393 100644 --- a/include/behavior_tree_logger/bt_zmq_publisher.h +++ b/include/behavior_tree_logger/bt_zmq_publisher.h @@ -7,32 +7,30 @@ #include "abstract_logger.h" #include "BT_logger_generated.h" -namespace BT{ - -class PublisherZMQ: public StatusChangeLogger +namespace BT +{ +class PublisherZMQ : public StatusChangeLogger { -public: + public: PublisherZMQ(TreeNode* root_node, int max_msg_per_second = 25); virtual ~PublisherZMQ(); -private: - - virtual void callback(TimePoint timestamp, - const TreeNode& node, - NodeStatus prev_status, NodeStatus status) override; + private: + virtual void callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, + NodeStatus status) override; virtual void flush() override; - TreeNode *root_node_; + TreeNode* root_node_; std::vector tree_buffer_; std::vector status_buffer_; - std::vector< std::array > transition_buffer_; + std::vector > transition_buffer_; std::chrono::microseconds min_time_between_msgs_; zmq::context_t zmq_context_; - zmq::socket_t zmq_publisher_; - zmq::socket_t zmq_server_; + zmq::socket_t zmq_publisher_; + zmq::socket_t zmq_server_; std::atomic_bool active_server_; std::thread thread_; @@ -45,8 +43,6 @@ class PublisherZMQ: public StatusChangeLogger std::future send_future_; }; - - } -#endif // BT_ZMQ_PUBLISHER_H +#endif // BT_ZMQ_PUBLISHER_H diff --git a/src/action_node.cpp b/src/action_node.cpp index 731a377f4..4185a64de 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -13,17 +13,17 @@ #include "behavior_tree_core/action_node.h" -namespace BT{ - -ActionNodeBase::ActionNodeBase(const std::string& name, const NodeParameters ¶meters) : - LeafNode::LeafNode(name,parameters) +namespace BT +{ +ActionNodeBase::ActionNodeBase(const std::string& name, const NodeParameters& parameters) + : LeafNode::LeafNode(name, parameters) { } //------------------------------------------------------- -SimpleActionNode::SimpleActionNode(const std::string &name, SimpleActionNode::TickFunctor tick_functor) - : ActionNodeBase(name, NodeParameters()), tick_functor_( std::move(tick_functor) ) +SimpleActionNode::SimpleActionNode(const std::string& name, SimpleActionNode::TickFunctor tick_functor) + : ActionNodeBase(name, NodeParameters()), tick_functor_(std::move(tick_functor)) { } @@ -31,7 +31,7 @@ NodeStatus SimpleActionNode::tick() { NodeStatus prev_status = status(); - if ( prev_status == NodeStatus::IDLE) + if (prev_status == NodeStatus::IDLE) { setStatus(NodeStatus::RUNNING); prev_status = NodeStatus::RUNNING; @@ -47,8 +47,8 @@ NodeStatus SimpleActionNode::tick() //------------------------------------------------------- -ActionNode::ActionNode(const std::string& name, const NodeParameters& parameters) : - ActionNodeBase(name, parameters), loop_(true) +ActionNode::ActionNode(const std::string& name, const NodeParameters& parameters) + : ActionNodeBase(name, parameters), loop_(true) { thread_ = std::thread(&ActionNode::waitForTick, this); } @@ -70,12 +70,12 @@ void ActionNode::waitForTick() // check this again because the tick_engine_ could be // notified from the method stopAndJoinThread if (loop_.load()) - { + { if (status() == NodeStatus::IDLE) { setStatus(NodeStatus::RUNNING); } - setStatus( tick() ); + setStatus(tick()); } } } @@ -100,5 +100,4 @@ void ActionNode::stopAndJoinThread() tick_engine_.notify(); thread_.join(); } - } diff --git a/src/basic_types.cpp b/src/basic_types.cpp index cb82379c2..caacf0949 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -1,136 +1,139 @@ #include "behavior_tree_core/basic_types.h" #include -namespace BT{ - -const char *toStr(const NodeStatus &status, bool colored) +namespace BT +{ +const char* toStr(const NodeStatus& status, bool colored) { - if( ! colored ){ + if (!colored) + { switch (status) { - case NodeStatus::SUCCESS: - return "SUCCESS"; - case NodeStatus::FAILURE: - return "FAILURE"; - case NodeStatus::RUNNING: - return "RUNNING"; - case NodeStatus::IDLE: - return "IDLE"; + case NodeStatus::SUCCESS: + return "SUCCESS"; + case NodeStatus::FAILURE: + return "FAILURE"; + case NodeStatus::RUNNING: + return "RUNNING"; + case NodeStatus::IDLE: + return "IDLE"; } } - else{ + else + { switch (status) { - case NodeStatus::SUCCESS: - return ( "\x1b[32m" "SUCCESS" "\x1b[0m"); // RED - case NodeStatus::FAILURE: - return ( "\x1b[31m" "FAILURE" "\x1b[0m"); // GREEN - case NodeStatus::RUNNING: - return ( "\x1b[33m" "RUNNING" "\x1b[0m"); // YELLOW - case NodeStatus::IDLE: - return ( "\x1b[36m" "IDLE" "\x1b[0m"); // CYAN + case NodeStatus::SUCCESS: + return ("\x1b[32m" + "SUCCESS" + "\x1b[0m"); // RED + case NodeStatus::FAILURE: + return ("\x1b[31m" + "FAILURE" + "\x1b[0m"); // GREEN + case NodeStatus::RUNNING: + return ("\x1b[33m" + "RUNNING" + "\x1b[0m"); // YELLOW + case NodeStatus::IDLE: + return ("\x1b[36m" + "IDLE" + "\x1b[0m"); // CYAN } } return "Undefined"; } -const char *toStr(const NodeType &type) +const char* toStr(const NodeType& type) { switch (type) { - case NodeType::ACTION: - return "Action"; - case NodeType::CONDITION: - return "Condition"; - case NodeType::DECORATOR: - return "Decorator"; - case NodeType::CONTROL: - return "Control"; - case NodeType::SUBTREE: - return "SubTree"; - default: - return "Undefined"; + case NodeType::ACTION: + return "Action"; + case NodeType::CONDITION: + return "Condition"; + case NodeType::DECORATOR: + return "Decorator"; + case NodeType::CONTROL: + return "Control"; + case NodeType::SUBTREE: + return "SubTree"; + default: + return "Undefined"; } } -const char *toStr(const ResetPolicy &policy) +const char* toStr(const ResetPolicy& policy) { switch (policy) { - case ResetPolicy::ON_FAILURE: - return "ON_FAILURE"; - case ResetPolicy::ON_SUCCESS: - return "ON_SUCCESS"; - case ResetPolicy::ON_SUCCESS_OR_FAILURE: - return "ON_SUCCESS_OR_FAILURE"; - default: - return "Undefined"; + case ResetPolicy::ON_FAILURE: + return "ON_FAILURE"; + case ResetPolicy::ON_SUCCESS: + return "ON_SUCCESS"; + case ResetPolicy::ON_SUCCESS_OR_FAILURE: + return "ON_SUCCESS_OR_FAILURE"; + default: + return "Undefined"; } } -template<> int convertFromString(const char* str) +template <> +int convertFromString(const char* str) { return std::stoi(str); } -template<> unsigned convertFromString(const char* str) +template <> +unsigned convertFromString(const char* str) { return std::stoul(str); } -template<> double convertFromString(const char* str) +template <> +double convertFromString(const char* str) { return std::stod(str); } -template<> NodeStatus convertFromString(const char* str) +template <> +NodeStatus convertFromString(const char* str) { - for( auto status: { - NodeStatus::IDLE, - NodeStatus::RUNNING, - NodeStatus::SUCCESS, - NodeStatus::FAILURE} ) + for (auto status : {NodeStatus::IDLE, NodeStatus::RUNNING, NodeStatus::SUCCESS, NodeStatus::FAILURE}) { - if( std::strcmp( toStr(status), str) == 0 ) + if (std::strcmp(toStr(status), str) == 0) { return status; } } - throw std::invalid_argument( std::string("Cannot convert this to NodeStatus: ") + str ); + throw std::invalid_argument(std::string("Cannot convert this to NodeStatus: ") + str); } -template<> NodeType convertFromString(const char* str) +template <> +NodeType convertFromString(const char* str) { - for( auto status: { - NodeType::ACTION, - NodeType::CONDITION, - NodeType::CONTROL, - NodeType::DECORATOR, - NodeType::SUBTREE, - NodeType::UNDEFINED} ) + for (auto status : {NodeType::ACTION, NodeType::CONDITION, NodeType::CONTROL, NodeType::DECORATOR, + NodeType::SUBTREE, NodeType::UNDEFINED}) { - if( std::strcmp( toStr(status), str) == 0 ) + if (std::strcmp(toStr(status), str) == 0) { return status; } } - throw std::invalid_argument( std::string("Cannot convert this to NodeType: ") + str ); + throw std::invalid_argument(std::string("Cannot convert this to NodeType: ") + str); } -template<> ResetPolicy convertFromString(const char* str) +template <> +ResetPolicy convertFromString(const char* str) { - for( auto status: { - ResetPolicy::ON_SUCCESS, - ResetPolicy::ON_SUCCESS_OR_FAILURE, - ResetPolicy::ON_FAILURE} ) + for (auto status : {ResetPolicy::ON_SUCCESS, ResetPolicy::ON_SUCCESS_OR_FAILURE, ResetPolicy::ON_FAILURE}) { - if( std::strcmp( toStr(status), str) == 0 ) + if (std::strcmp(toStr(status), str) == 0) { return status; } } - throw std::invalid_argument( std::string("Cannot convert this to ResetPolicy: ") + str ); + throw std::invalid_argument(std::string("Cannot convert this to ResetPolicy: ") + str); } -} // end namespace - +} // end namespace diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index fcd00bccd..802212a09 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -3,7 +3,6 @@ namespace BT { - void recursiveVisitor(TreeNode* node, std::function visitor) { if (!node) @@ -61,17 +60,14 @@ void printTreeRecursively(const TreeNode* root_node) std::cout << "----------------" << std::endl; } -void buildSerializedStatusSnapshot(TreeNode *root_node, SerializedTreeStatus& serialized_buffer) +void buildSerializedStatusSnapshot(TreeNode* root_node, SerializedTreeStatus& serialized_buffer) { serialized_buffer.clear(); - auto visitor = [ &serialized_buffer ](const TreeNode *node) - { - serialized_buffer.push_back( std::make_pair( node->UID(), - static_cast( node->status()) ) ); + auto visitor = [&serialized_buffer](const TreeNode* node) { + serialized_buffer.push_back(std::make_pair(node->UID(), static_cast(node->status()))); }; recursiveVisitor(root_node, visitor); } - } diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 87090611c..04987cf7f 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -15,7 +15,6 @@ namespace BT { - BehaviorTreeFactory::BehaviorTreeFactory() { registerNodeType("Fallback"); @@ -70,7 +69,7 @@ std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::st throw BehaviorTreeException("ID '" + ID + "' not registered"); } std::unique_ptr node = it->second(name, params); - node->setRegistrationName( ID ); + node->setRegistrationName(ID); return node; } diff --git a/src/bt_file_logger.cpp b/src/bt_file_logger.cpp index ab30281ba..7ed75eeb7 100644 --- a/src/bt_file_logger.cpp +++ b/src/bt_file_logger.cpp @@ -1,34 +1,31 @@ #include "behavior_tree_logger/bt_file_logger.h" #include "behavior_tree_logger/bt_flatbuffer_helper.h" -namespace BT{ - -FileLogger::FileLogger(BT::TreeNode *root_node, const char *filename, uint16_t buffer_size): - StatusChangeLogger(root_node), - buffer_max_size_(buffer_size) +namespace BT +{ +FileLogger::FileLogger(BT::TreeNode* root_node, const char* filename, uint16_t buffer_size) + : StatusChangeLogger(root_node), buffer_max_size_(buffer_size) { - if( buffer_max_size_ != 0) + if (buffer_max_size_ != 0) { - buffer_.reserve( buffer_max_size_ ); + buffer_.reserve(buffer_max_size_); } - enableTransitionToIdle( true ); + enableTransitionToIdle(true); flatbuffers::FlatBufferBuilder builder(1024); - CreateFlatbuffersBehaviorTree( builder, root_node); + CreateFlatbuffersBehaviorTree(builder, root_node); //------------------------------------- - file_os_.open( filename, std::ofstream::binary | std::ofstream::out); + file_os_.open(filename, std::ofstream::binary | std::ofstream::out); // serialize the length of the buffer in the first 4 bytes char size_buff[4]; - flatbuffers::WriteScalar(size_buff, static_cast( builder.GetSize()) ); - - file_os_.write( size_buff, 4 ); - file_os_.write( reinterpret_cast(builder.GetBufferPointer()), - builder.GetSize() ); + flatbuffers::WriteScalar(size_buff, static_cast(builder.GetSize())); + file_os_.write(size_buff, 4); + file_os_.write(reinterpret_cast(builder.GetBufferPointer()), builder.GetSize()); } FileLogger::~FileLogger() @@ -37,21 +34,18 @@ FileLogger::~FileLogger() file_os_.close(); } -void FileLogger::callback(TimePoint timestamp, const TreeNode &node, NodeStatus prev_status, NodeStatus status) +void FileLogger::callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) { - std::array buffer = SerializeTransition( - node.UID(), - timestamp, - prev_status, - status ); + std::array buffer = SerializeTransition(node.UID(), timestamp, prev_status, status); - if( buffer_max_size_ == 0 ) + if (buffer_max_size_ == 0) { - file_os_.write( reinterpret_cast(buffer.data()), buffer.size() ); + file_os_.write(reinterpret_cast(buffer.data()), buffer.size()); } - else{ - buffer_.push_back( buffer ); - if( buffer_.size() >= buffer_max_size_) + else + { + buffer_.push_back(buffer); + if (buffer_.size() >= buffer_max_size_) { this->flush(); } @@ -60,14 +54,11 @@ void FileLogger::callback(TimePoint timestamp, const TreeNode &node, NodeStatus void FileLogger::flush() { - for (const auto& array: buffer_ ) + for (const auto& array : buffer_) { - file_os_.write( reinterpret_cast(array.data()), array.size() ); + file_os_.write(reinterpret_cast(array.data()), array.size()); } file_os_.flush(); buffer_.clear(); } - - - } diff --git a/src/bt_zmq_publisher.cpp b/src/bt_zmq_publisher.cpp index db5c6356c..0e48d8ad2 100644 --- a/src/bt_zmq_publisher.cpp +++ b/src/bt_zmq_publisher.cpp @@ -2,63 +2,62 @@ #include "behavior_tree_logger/bt_flatbuffer_helper.h" #include -namespace BT { - +namespace BT +{ void PublisherZMQ::createStatusBuffer() { status_buffer_.clear(); - recursiveVisitor(root_node_, [this](TreeNode* node) - { + recursiveVisitor(root_node_, [this](TreeNode* node) { size_t index = status_buffer_.size(); - status_buffer_.resize( index + 3 ); - flatbuffers::WriteScalar( &status_buffer_[index], node->UID() ); - flatbuffers::WriteScalar( &status_buffer_[index+2], - static_cast( convertToFlatbuffers(node->status())) ); + status_buffer_.resize(index + 3); + flatbuffers::WriteScalar(&status_buffer_[index], node->UID()); + flatbuffers::WriteScalar(&status_buffer_[index + 2], + static_cast(convertToFlatbuffers(node->status()))); }); } -PublisherZMQ::PublisherZMQ(TreeNode *root_node, - int max_msg_per_second): - StatusChangeLogger(root_node), - root_node_(root_node), - min_time_between_msgs_( std::chrono::microseconds(1000*1000) / max_msg_per_second ), - zmq_context_(1), - zmq_publisher_( zmq_context_, ZMQ_PUB ), - zmq_server_( zmq_context_, ZMQ_REP ), - send_pending_(false) +PublisherZMQ::PublisherZMQ(TreeNode* root_node, int max_msg_per_second) + : StatusChangeLogger(root_node) + , root_node_(root_node) + , min_time_between_msgs_(std::chrono::microseconds(1000 * 1000) / max_msg_per_second) + , zmq_context_(1) + , zmq_publisher_(zmq_context_, ZMQ_PUB) + , zmq_server_(zmq_context_, ZMQ_REP) + , send_pending_(false) { static bool first_instance = true; - if( first_instance ) + if (first_instance) { first_instance = false; } - else{ + else + { throw std::logic_error("Only one instance of PublisherZMQ shall be created"); } flatbuffers::FlatBufferBuilder builder(1024); - CreateFlatbuffersBehaviorTree( builder, root_node); + CreateFlatbuffersBehaviorTree(builder, root_node); tree_buffer_.resize(builder.GetSize()); - memcpy( tree_buffer_.data(), builder.GetBufferPointer(), builder.GetSize() ); + memcpy(tree_buffer_.data(), builder.GetBufferPointer(), builder.GetSize()); - zmq_publisher_.bind( "tcp://*:1666" ); - zmq_server_.bind( "tcp://*:1667" ); + zmq_publisher_.bind("tcp://*:1666"); + zmq_server_.bind("tcp://*:1667"); active_server_ = true; - thread_ = std::thread([this]() - { - while(active_server_) + thread_ = std::thread([this]() { + while (active_server_) { zmq::message_t req; - try{ - zmq_server_.recv( &req ); - zmq::message_t reply ( tree_buffer_.size() ); - memcpy( reply.data(), tree_buffer_.data(), tree_buffer_.size() ); - zmq_server_.send( reply ); + try + { + zmq_server_.recv(&req); + zmq::message_t reply(tree_buffer_.size()); + memcpy(reply.data(), tree_buffer_.data(), tree_buffer_.size()); + zmq_server_.send(reply); } - catch( zmq::error_t& err) + catch (zmq::error_t& err) { active_server_ = false; } @@ -71,32 +70,30 @@ PublisherZMQ::PublisherZMQ(TreeNode *root_node, PublisherZMQ::~PublisherZMQ() { active_server_ = false; - if( thread_.joinable()) + if (thread_.joinable()) { thread_.join(); } flush(); } -void PublisherZMQ::callback(TimePoint timestamp, const TreeNode &node, NodeStatus prev_status, NodeStatus status) +void PublisherZMQ::callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) { using namespace std::chrono; - std::array transition = SerializeTransition(node.UID(), - timestamp, prev_status, status); + std::array transition = SerializeTransition(node.UID(), timestamp, prev_status, status); { - std::unique_lock lock( mutex_ ); - transition_buffer_.push_back( transition ); + std::unique_lock lock(mutex_); + transition_buffer_.push_back(transition); } - if( !send_pending_ ) + if (!send_pending_) { send_pending_ = true; - send_future_ = std::async(std::launch::async, [this]() - { - std::this_thread::sleep_for( min_time_between_msgs_ ); + send_future_ = std::async(std::launch::async, [this]() { + std::this_thread::sleep_for(min_time_between_msgs_); flush(); - } ); + }); } } @@ -104,28 +101,27 @@ void PublisherZMQ::flush() { zmq::message_t message; { - std::unique_lock lock( mutex_ ); + std::unique_lock lock(mutex_); - const size_t msg_size = status_buffer_.size() + 8 + - (transition_buffer_.size() * 12); + const size_t msg_size = status_buffer_.size() + 8 + (transition_buffer_.size() * 12); - message.rebuild( msg_size ); - uint8_t* data_ptr = static_cast( message.data() ); + message.rebuild(msg_size); + uint8_t* data_ptr = static_cast(message.data()); // first 4 bytes are the side of the header - flatbuffers::WriteScalar( data_ptr, status_buffer_.size() ); + flatbuffers::WriteScalar(data_ptr, status_buffer_.size()); data_ptr += sizeof(uint32_t); // copy the header part - memcpy( data_ptr, status_buffer_.data(), status_buffer_.size() ); + memcpy(data_ptr, status_buffer_.data(), status_buffer_.size()); data_ptr += status_buffer_.size(); // first 4 bytes are the side of the transition buffer - flatbuffers::WriteScalar( data_ptr, transition_buffer_.size() ); + flatbuffers::WriteScalar(data_ptr, transition_buffer_.size()); data_ptr += sizeof(uint32_t); - for (auto& transition: transition_buffer_) + for (auto& transition : transition_buffer_) { - memcpy( data_ptr, transition.data(), transition.size() ); + memcpy(data_ptr, transition.data(), transition.size()); data_ptr += transition.size(); } transition_buffer_.clear(); @@ -134,7 +130,6 @@ void PublisherZMQ::flush() zmq_publisher_.send(message); send_pending_ = false; - // printf("%.3f zmq send\n", std::chrono::duration( std::chrono::high_resolution_clock::now().time_since_epoch() ).count()); + // printf("%.3f zmq send\n", std::chrono::duration( std::chrono::high_resolution_clock::now().time_since_epoch() ).count()); } - } diff --git a/src/condition_node.cpp b/src/condition_node.cpp index cb43ef781..926be7038 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -14,7 +14,7 @@ #include "behavior_tree_core/condition_node.h" BT::ConditionNode::ConditionNode(const std::string& name, const NodeParameters& parameters) - : LeafNode::LeafNode(name,parameters) + : LeafNode::LeafNode(name, parameters) { } diff --git a/src/control_node.cpp b/src/control_node.cpp index 81955efa8..26de334fe 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -13,11 +13,10 @@ #include "behavior_tree_core/control_node.h" -namespace BT{ - - -ControlNode::ControlNode(const std::string& name, const NodeParameters& parameters) : - TreeNode::TreeNode(name,parameters) +namespace BT +{ +ControlNode::ControlNode(const std::string& name, const NodeParameters& parameters) + : TreeNode::TreeNode(name, parameters) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable @@ -64,5 +63,4 @@ void ControlNode::haltChildren(int i) } } } - } diff --git a/src/decorator_negation_node.cpp b/src/decorator_negation_node.cpp index de44de81f..039719f19 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorator_negation_node.cpp @@ -15,15 +15,13 @@ namespace BT { - -DecoratorNegationNode::DecoratorNegationNode(const std::string& name) : - DecoratorNode(name, NodeParameters() ) +DecoratorNegationNode::DecoratorNegationNode(const std::string& name) : DecoratorNode(name, NodeParameters()) { } NodeStatus DecoratorNegationNode::tick() { - setStatus( NodeStatus::RUNNING ); + setStatus(NodeStatus::RUNNING); const NodeStatus child_state = child_node_->executeTick(); @@ -56,5 +54,4 @@ NodeStatus DecoratorNegationNode::tick() } return status(); } - } diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 62c602771..1eb9bd56b 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -14,9 +14,8 @@ namespace BT { - -DecoratorNode::DecoratorNode(const std::string& name, const NodeParameters& parameters) : - TreeNode::TreeNode(name, parameters), child_node_(nullptr) +DecoratorNode::DecoratorNode(const std::string& name, const NodeParameters& parameters) + : TreeNode::TreeNode(name, parameters), child_node_(nullptr) { // TODO(...) In case it is desired to set to idle remove the ReturnStatus // type in order to set the member variable @@ -56,5 +55,4 @@ void DecoratorNode::haltChild() child_node_->halt(); } } - } diff --git a/src/decorator_repeat_node.cpp b/src/decorator_repeat_node.cpp index 805c19571..40139e9b5 100644 --- a/src/decorator_repeat_node.cpp +++ b/src/decorator_repeat_node.cpp @@ -13,22 +13,18 @@ #include "behavior_tree_core/decorator_repeat_node.h" -namespace BT { - +namespace BT +{ constexpr const char* DecoratorRepeatNode::NUM_CYCLES; DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, unsigned int NTries) - : DecoratorNode(name, {{NUM_CYCLES, std::to_string(NTries)}}), - NTries_(NTries), TryIndx_(0) + : DecoratorNode(name, {{NUM_CYCLES, std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) { } DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, const NodeParameters& params) - : DecoratorNode(name,params), - NTries_( getParam(NUM_CYCLES) ), - TryIndx_(0) + : DecoratorNode(name, params), NTries_(getParam(NUM_CYCLES)), TryIndx_(0) { - } NodeStatus DecoratorRepeatNode::tick() @@ -71,5 +67,4 @@ NodeStatus DecoratorRepeatNode::tick() return status(); } - } diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index 5580969e4..00f123850 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -13,19 +13,17 @@ #include "behavior_tree_core/decorator_retry_node.h" -namespace BT{ - +namespace BT +{ constexpr const char* DecoratorRetryNode::NUM_ATTEMPTS; DecoratorRetryNode::DecoratorRetryNode(const std::string& name, unsigned int NTries) - : DecoratorNode(name, {{NUM_ATTEMPTS, std::to_string(NTries)}}), - NTries_(NTries), TryIndx_(0) + : DecoratorNode(name, {{NUM_ATTEMPTS, std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) { } DecoratorRetryNode::DecoratorRetryNode(const std::string& name, const NodeParameters& params) - : DecoratorNode(name, params), - NTries_( getParam(NUM_ATTEMPTS) ), TryIndx_(0) + : DecoratorNode(name, params), NTries_(getParam(NUM_ATTEMPTS)), TryIndx_(0) { } @@ -70,5 +68,4 @@ NodeStatus DecoratorRetryNode::tick() return status(); } - } diff --git a/src/fallback_node.cpp b/src/fallback_node.cpp index be5d9d1d1..2658e8415 100644 --- a/src/fallback_node.cpp +++ b/src/fallback_node.cpp @@ -15,9 +15,7 @@ namespace BT { - -FallbackNode::FallbackNode(const std::string& name) : - ControlNode::ControlNode(name, NodeParameters()) +FallbackNode::FallbackNode(const std::string& name) : ControlNode::ControlNode(name, NodeParameters()) { } @@ -41,7 +39,7 @@ NodeStatus FallbackNode::tick() { if (child_status == NodeStatus::SUCCESS) { - for (unsigned t=0; t<=i; t++) + for (unsigned t = 0; t <= i; t++) { children_nodes_[t]->setStatus(NodeStatus::IDLE); } @@ -57,7 +55,7 @@ NodeStatus FallbackNode::tick() { // If the child status is failure, and it is the last child to be ticked, // then the sequence has failed. - for (unsigned t=0; t<=i; t++) + for (unsigned t = 0; t <= i; t++) { children_nodes_[t]->setStatus(NodeStatus::IDLE); } @@ -67,5 +65,4 @@ NodeStatus FallbackNode::tick() } throw std::runtime_error("This is not supposed to happen"); } - } diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 78b0b64a4..81b49bc46 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -15,25 +15,20 @@ namespace BT { - constexpr const char* FallbackNodeWithMemory::RESET_POLICY; -FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, ResetPolicy reset_policy) - : ControlNode::ControlNode(name, {{RESET_POLICY, toStr(reset_policy)}}), - current_child_idx_(0), - reset_policy_(reset_policy) +FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string& name, ResetPolicy reset_policy) + : ControlNode::ControlNode(name, {{RESET_POLICY, toStr(reset_policy)}}) + , current_child_idx_(0) + , reset_policy_(reset_policy) { } -FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string &name, const NodeParameters& params) - : ControlNode::ControlNode(name,params), - current_child_idx_(0), - reset_policy_( getParam(RESET_POLICY) ) +FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string& name, const NodeParameters& params) + : ControlNode::ControlNode(name, params), current_child_idx_(0), reset_policy_(getParam(RESET_POLICY)) { - } - NodeStatus FallbackNodeWithMemory::tick() { // Vector size initialization. N_of_children_ could change at runtime if you edit the tree @@ -53,7 +48,7 @@ NodeStatus FallbackNodeWithMemory::tick() // If the child status is not success, return the status if (child_status == NodeStatus::SUCCESS && reset_policy_ != ON_FAILURE) { - for (unsigned t=0; t<=current_child_idx_; t++) + for (unsigned t = 0; t <= current_child_idx_; t++) { children_nodes_[t]->setStatus(NodeStatus::IDLE); } @@ -70,9 +65,9 @@ NodeStatus FallbackNodeWithMemory::tick() else { // If it the last child. - if (child_status == NodeStatus::FAILURE && reset_policy_ != ON_SUCCESS ) + if (child_status == NodeStatus::FAILURE && reset_policy_ != ON_SUCCESS) { - for (unsigned t=0; t<=current_child_idx_; t++) + for (unsigned t = 0; t <= current_child_idx_; t++) { children_nodes_[t]->setStatus(NodeStatus::IDLE); } @@ -90,5 +85,4 @@ void FallbackNodeWithMemory::halt() current_child_idx_ = 0; ControlNode::halt(); } - } diff --git a/src/leaf_node.cpp b/src/leaf_node.cpp index 919123b2b..3cae81132 100644 --- a/src/leaf_node.cpp +++ b/src/leaf_node.cpp @@ -13,7 +13,6 @@ #include "behavior_tree_core/leaf_node.h" -BT::LeafNode::LeafNode(const std::string& name, const NodeParameters& parameters) : - TreeNode(name,parameters) +BT::LeafNode::LeafNode(const std::string& name, const NodeParameters& parameters) : TreeNode(name, parameters) { } diff --git a/src/sequence_node.cpp b/src/sequence_node.cpp index 08e16d959..4750e9d97 100644 --- a/src/sequence_node.cpp +++ b/src/sequence_node.cpp @@ -13,8 +13,7 @@ #include "behavior_tree_core/sequence_node.h" -BT::SequenceNode::SequenceNode(const std::string& name) : - ControlNode::ControlNode(name, NodeParameters()) +BT::SequenceNode::SequenceNode(const std::string& name) : ControlNode::ControlNode(name, NodeParameters()) { } @@ -39,9 +38,9 @@ BT::NodeStatus BT::SequenceNode::tick() // If the child status is not success, halt the next children and return the status to your parent. if (child_status == NodeStatus::FAILURE) { - for(unsigned t=0; t<=i; t++) + for (unsigned t = 0; t <= i; t++) { - children_nodes_[t]->setStatus( NodeStatus::IDLE ); + children_nodes_[t]->setStatus(NodeStatus::IDLE); } } @@ -54,9 +53,9 @@ BT::NodeStatus BT::SequenceNode::tick() { // If the child status is success, and it is the last child to be ticked, // then the sequence has succeeded. - for(auto &ch: children_nodes_) + for (auto& ch : children_nodes_) { - ch->setStatus( NodeStatus::IDLE ); + ch->setStatus(NodeStatus::IDLE); } return NodeStatus::SUCCESS; } diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index 973a886b6..e7afff70e 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -15,22 +15,18 @@ namespace BT { - constexpr const char* SequenceNodeWithMemory::RESET_POLICY; -SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string &name, ResetPolicy reset_policy) - : ControlNode::ControlNode(name, {{RESET_POLICY, toStr(reset_policy)}}), - current_child_idx_(0), - reset_policy_(reset_policy) +SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, ResetPolicy reset_policy) + : ControlNode::ControlNode(name, {{RESET_POLICY, toStr(reset_policy)}}) + , current_child_idx_(0) + , reset_policy_(reset_policy) { } SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, const NodeParameters& params) - : ControlNode::ControlNode(name,params), - current_child_idx_(0), - reset_policy_( getParam(RESET_POLICY) ) + : ControlNode::ControlNode(name, params), current_child_idx_(0), reset_policy_(getParam(RESET_POLICY)) { - } NodeStatus SequenceNodeWithMemory::tick() @@ -55,9 +51,9 @@ NodeStatus SequenceNodeWithMemory::tick() if (child_status != NodeStatus::SUCCESS) { // If the child status is not success, return the status - if (child_status == NodeStatus::FAILURE && reset_policy_ != ON_SUCCESS ) - { - for (unsigned t=0; t<=current_child_idx_; t++) + if (child_status == NodeStatus::FAILURE && reset_policy_ != ON_SUCCESS) + { + for (unsigned t = 0; t <= current_child_idx_; t++) { children_nodes_[t]->setStatus(NodeStatus::IDLE); } @@ -77,7 +73,7 @@ NodeStatus SequenceNodeWithMemory::tick() if (child_status == NodeStatus::SUCCESS || reset_policy_ != ON_FAILURE) { // if it the last child and it has returned SUCCESS, reset the memory - for (unsigned t=0; t<=current_child_idx_; t++) + for (unsigned t = 0; t <= current_child_idx_; t++) { children_nodes_[t]->setStatus(NodeStatus::IDLE); } @@ -94,5 +90,4 @@ void SequenceNodeWithMemory::halt() current_child_idx_ = 0; ControlNode::halt(); } - } diff --git a/src/tick_engine.cpp b/src/tick_engine.cpp index d4314e904..311ce46e4 100644 --- a/src/tick_engine.cpp +++ b/src/tick_engine.cpp @@ -17,7 +17,6 @@ namespace BT { - TickEngine::TickEngine(bool start_ready) : ready_(start_ready) { } @@ -38,5 +37,4 @@ void TickEngine::notify() ready_ = true; condition_variable_.notify_all(); } - } diff --git a/src/tree_node.cpp b/src/tree_node.cpp index a06248af1..59253dafc 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -14,16 +14,16 @@ #include "behavior_tree_core/tree_node.h" #include -namespace BT { - +namespace BT +{ static uint8_t getUID() { static uint8_t uid = 1; return uid++; } -TreeNode::TreeNode(const std::string& name, const NodeParameters& parameters) : - name_(name), status_(NodeStatus::IDLE), uid_( getUID() ), parameters_(parameters) +TreeNode::TreeNode(const std::string& name, const NodeParameters& parameters) + : name_(name), status_(NodeStatus::IDLE), uid_(getUID()), parameters_(parameters) { } @@ -45,8 +45,7 @@ void TreeNode::setStatus(NodeStatus new_status) if (prev_status != new_status) { state_condition_variable_.notify_all(); - state_change_signal_.notify( std::chrono::high_resolution_clock::now(), - *this, prev_status, new_status); + state_change_signal_.notify(std::chrono::high_resolution_clock::now(), *this, prev_status, new_status); } } @@ -65,8 +64,9 @@ NodeStatus TreeNode::waitValidStatus() { std::unique_lock lk(state_mutex_); - state_condition_variable_.wait( - lk, [&]() { return (status_ == NodeStatus::RUNNING || status_ == NodeStatus::SUCCESS || status_ == NodeStatus::FAILURE); }); + state_condition_variable_.wait(lk, [&]() { + return (status_ == NodeStatus::RUNNING || status_ == NodeStatus::SUCCESS || status_ == NodeStatus::FAILURE); + }); return status_; } @@ -82,7 +82,7 @@ bool TreeNode::isHalted() const TreeNode::StatusChangeSubscriber TreeNode::subscribeToStatusChange(TreeNode::StatusChangeCallback callback) { - return state_change_signal_.subscribe( std::move(callback) ); + return state_change_signal_.subscribe(std::move(callback)); } uint16_t TreeNode::UID() const @@ -90,14 +90,14 @@ uint16_t TreeNode::UID() const return uid_; } -void TreeNode::setRegistrationName(const std::string ®istration_name) +void TreeNode::setRegistrationName(const std::string& registration_name) { registration_name_ = registration_name; } -const std::string &TreeNode::registrationName() const +const std::string& TreeNode::registrationName() const { return registration_name_; } -} // end namespace +} // end namespace diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 041bcd1ab..212bfe038 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -83,10 +83,8 @@ bool XMLParser::verifyXML(std::vector& error_messages) const for (auto node = xml_root->FirstChildElement(); node != nullptr; node = node->NextSiblingElement()) { const char* name = node->Name(); - if (strEqual(name, "Action") || - strEqual(name, "Decorator") || - strEqual(name, "SubTree") || - strEqual(name, "Condition")) + if (strEqual(name, "Action") || strEqual(name, "Decorator") || strEqual(name, "SubTree") || + strEqual(name, "Condition")) { const char* ID = node->Attribute("ID"); if (!ID) diff --git a/tools/bt_log_cat.cpp b/tools/bt_log_cat.cpp index 9d860ecfe..4e5a52493 100644 --- a/tools/bt_log_cat.cpp +++ b/tools/bt_log_cat.cpp @@ -6,7 +6,7 @@ int main(int argc, char* argv[]) { - if( argc != 2) + if (argc != 2) { printf("Wrong number of arguments\nUsage: %s [filename]\n", argv[0]); return 1; @@ -14,7 +14,7 @@ int main(int argc, char* argv[]) FILE* file = fopen(argv[1], "rb"); - if( !file ) + if (!file) { printf("Failed to open file: [%s]\n", argv[1]); return 1; @@ -24,75 +24,83 @@ int main(int argc, char* argv[]) const size_t length = ftell(file); fseek(file, 0L, SEEK_SET); std::vector buffer(length); - fread( buffer.data(), sizeof(char), length, file); + fread(buffer.data(), sizeof(char), length, file); fclose(file); const int bt_header_size = flatbuffers::ReadScalar(&buffer[0]); - auto behavior_tree = BT_Serialization::GetBehaviorTree( &buffer[4] ); + auto behavior_tree = BT_Serialization::GetBehaviorTree(&buffer[4]); std::unordered_map names_by_uid; - std::unordered_map node_by_uid; + std::unordered_map node_by_uid; - for( const BT_Serialization::TreeNode* node: *(behavior_tree->nodes()) ) + for (const BT_Serialization::TreeNode* node : *(behavior_tree->nodes())) { - names_by_uid.insert( { node->uid(), std::string(node->instance_name()->c_str()) } ); - node_by_uid.insert( { node->uid(), node } ); + names_by_uid.insert({node->uid(), std::string(node->instance_name()->c_str())}); + node_by_uid.insert({node->uid(), node}); } printf("----------------------------\n"); - std::function recursiveStep; + std::function recursiveStep; - recursiveStep = [&](uint16_t uid, int indent) - { - for(int i=0; i< indent; i++) + recursiveStep = [&](uint16_t uid, int indent) { + for (int i = 0; i < indent; i++) { printf(" "); names_by_uid[uid] = std::string(" ") + names_by_uid[uid]; } - printf("%s\n", names_by_uid[uid].c_str() ); + printf("%s\n", names_by_uid[uid].c_str()); std::cout << std::flush; const auto& node = node_by_uid[uid]; - for (size_t i=0; i< node->children_uid()->size(); i++ ) + for (size_t i = 0; i < node->children_uid()->size(); i++) { - recursiveStep( node->children_uid()->Get(i), indent+1); + recursiveStep(node->children_uid()->Get(i), indent + 1); } }; - recursiveStep( behavior_tree->root_uid(), 0 ); + recursiveStep(behavior_tree->root_uid(), 0); printf("----------------------------\n"); constexpr const char* whitespaces = " "; constexpr const size_t ws_count = 25; - auto printStatus = [](BT_Serialization::Status status) - { + auto printStatus = [](BT_Serialization::Status status) { switch (status) { - case BT_Serialization::Status::SUCCESS: return ( "\x1b[32m" "SUCCESS" "\x1b[0m"); // RED - case BT_Serialization::Status::FAILURE: return ( "\x1b[31m" "FAILURE" "\x1b[0m"); // GREEN - case BT_Serialization::Status::RUNNING: return ( "\x1b[33m" "RUNNING" "\x1b[0m"); // YELLOW - case BT_Serialization::Status::IDLE: return ( "\x1b[36m" "IDLE " "\x1b[0m"); // CYAN + case BT_Serialization::Status::SUCCESS: + return ("\x1b[32m" + "SUCCESS" + "\x1b[0m"); // RED + case BT_Serialization::Status::FAILURE: + return ("\x1b[31m" + "FAILURE" + "\x1b[0m"); // GREEN + case BT_Serialization::Status::RUNNING: + return ("\x1b[33m" + "RUNNING" + "\x1b[0m"); // YELLOW + case BT_Serialization::Status::IDLE: + return ("\x1b[36m" + "IDLE " + "\x1b[0m"); // CYAN } return "Undefined"; }; - for( size_t index = bt_header_size + 4; index < length; index +=12 ) + for (size_t index = bt_header_size + 4; index < length; index += 12) { - const uint16_t uid = flatbuffers::ReadScalar(&buffer[index+8]); + const uint16_t uid = flatbuffers::ReadScalar(&buffer[index + 8]); const std::string& name = names_by_uid[uid]; - const uint32_t t_sec = flatbuffers::ReadScalar( &buffer[index] ); - const uint32_t t_usec = flatbuffers::ReadScalar( &buffer[index+4] ); - - printf("[%d.%06d]: %s%s %s -> %s\n", t_sec, t_usec, - name.c_str(), - &whitespaces[ std::min( ws_count, name.size())], - printStatus(flatbuffers::ReadScalar(&buffer[index+10] )), - printStatus(flatbuffers::ReadScalar(&buffer[index+11] )) ); + const uint32_t t_sec = flatbuffers::ReadScalar(&buffer[index]); + const uint32_t t_usec = flatbuffers::ReadScalar(&buffer[index + 4]); + + printf("[%d.%06d]: %s%s %s -> %s\n", t_sec, t_usec, name.c_str(), &whitespaces[std::min(ws_count, name.size())], + printStatus(flatbuffers::ReadScalar(&buffer[index + 10])), + printStatus(flatbuffers::ReadScalar(&buffer[index + 11]))); } return 0; diff --git a/tools/bt_recorder.cpp b/tools/bt_recorder.cpp index 81f2e6323..dc8712609 100644 --- a/tools/bt_recorder.cpp +++ b/tools/bt_recorder.cpp @@ -9,24 +9,24 @@ // http://zguide.zeromq.org/cpp:interrupt static bool s_interrupted = false; -static void s_signal_handler (int) +static void s_signal_handler(int) { s_interrupted = true; } -static void CatchSignals (void) +static void CatchSignals(void) { struct sigaction action; action.sa_handler = s_signal_handler; action.sa_flags = 0; - sigemptyset (&action.sa_mask); - sigaction (SIGINT, &action, NULL); - sigaction (SIGTERM, &action, NULL); + sigemptyset(&action.sa_mask); + sigaction(SIGINT, &action, NULL); + sigaction(SIGTERM, &action, NULL); } int main(int argc, char* argv[]) { - if( argc != 2) + if (argc != 2) { printf("Wrong number of arguments\nUsage: %s [filename]\n", argv[0]); return 1; @@ -35,12 +35,12 @@ int main(int argc, char* argv[]) // register CTRL+C signal handler CatchSignals(); - zmq::context_t context (1); + zmq::context_t context(1); // Socket to talk to server std::cout << "Trying to connect to [tcp://localhost:1666]\n" << std::endl; - zmq::socket_t subscriber (context, ZMQ_SUB); + zmq::socket_t subscriber(context, ZMQ_SUB); subscriber.connect("tcp://localhost:1666"); // Subscribe to everything @@ -51,42 +51,42 @@ int main(int argc, char* argv[]) bool first_message = true; std::ofstream file_os; - while( !s_interrupted ) + while (!s_interrupted) { zmq::message_t update; zmq::message_t msg; - try { - subscriber.recv (&update); + try + { + subscriber.recv(&update); } - catch(zmq::error_t& e) + catch (zmq::error_t& e) { - if( !s_interrupted ) + if (!s_interrupted) { - std::cout << "subscriber.recv() failed with exception: "<< - e.what() << std::endl; + std::cout << "subscriber.recv() failed with exception: " << e.what() << std::endl; return -1; } } - if( !s_interrupted ) + if (!s_interrupted) { - char* data_ptr = static_cast( update.data() ); - const uint32_t header_size = flatbuffers::ReadScalar( data_ptr ); + char* data_ptr = static_cast(update.data()); + const uint32_t header_size = flatbuffers::ReadScalar(data_ptr); - if( first_message ) + if (first_message) { printf("First message received\n"); first_message = false; - file_os.open( argv[1], std::ofstream::binary | std::ofstream::out); - file_os.write( data_ptr, 4 + header_size ) ; + file_os.open(argv[1], std::ofstream::binary | std::ofstream::out); + file_os.write(data_ptr, 4 + header_size); } data_ptr += 4 + header_size; - const uint32_t transition_count = flatbuffers::ReadScalar( data_ptr ); - data_ptr += sizeof( uint32_t ); + const uint32_t transition_count = flatbuffers::ReadScalar(data_ptr); + data_ptr += sizeof(uint32_t); - file_os.write( data_ptr, 12*transition_count) ; + file_os.write(data_ptr, 12 * transition_count); } } From 1716ea3f8b0e4b0f0166adcda05ac524a9ed27be Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 Jun 2018 13:56:37 +0200 Subject: [PATCH 078/125] make exceptions consistent with the standard library --- include/behavior_tree_core/exceptions.h | 19 ++++++++++++------- src/exceptions.cpp | 5 +++-- 2 files changed, 15 insertions(+), 9 deletions(-) diff --git a/include/behavior_tree_core/exceptions.h b/include/behavior_tree_core/exceptions.h index 509b77ff2..373981471 100644 --- a/include/behavior_tree_core/exceptions.h +++ b/include/behavior_tree_core/exceptions.h @@ -11,22 +11,27 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#ifndef EXCEPTIONS_H -#define EXCEPTIONS_H +#ifndef BT_EXCEPTIONS_H +#define BT_EXCEPTIONS_H #include #include namespace BT { -/// Exception class + class BehaviorTreeException : public std::exception { - private: - const char* Message; - public: - BehaviorTreeException(const std::string Message); + BehaviorTreeException(const std::string& Message); + + const char* what() const noexcept + { + return message_.c_str(); + } + +private: + std::string message_; }; } diff --git a/src/exceptions.cpp b/src/exceptions.cpp index 917e902f8..e8f9f70e2 100644 --- a/src/exceptions.cpp +++ b/src/exceptions.cpp @@ -13,7 +13,8 @@ #include "behavior_tree_core/exceptions.h" -BT::BehaviorTreeException::BehaviorTreeException(const std::string Message) +BT::BehaviorTreeException::BehaviorTreeException(const std::string &message): + message_( std::string("BehaviorTreeException: ") + message ) { - this->Message = std::string("BehaviorTreeException: " + Message).c_str(); + } From 33ce53a64df4c023b3325d328b8f7833eb9c1e1b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 Jun 2018 13:58:01 +0200 Subject: [PATCH 079/125] more simple nodes --- include/behavior_tree_core/action_node.h | 2 +- include/behavior_tree_core/condition_node.h | 23 +++++++++++++++++++++ include/behavior_tree_core/decorator_node.h | 17 +++++++++++++++ src/condition_node.cpp | 23 ++++++++++++++++++--- src/decorator_node.cpp | 13 ++++++++++++ 5 files changed, 74 insertions(+), 4 deletions(-) diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index d9469117a..ca0342851 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -52,7 +52,7 @@ class SimpleActionNode : public ActionNodeBase // Constructor: you must provide the funtion to call when tick() is invoked SimpleActionNode(const std::string& name, TickFunctor tick_functor); - ~SimpleActionNode() = default; + ~SimpleActionNode() override = default; virtual void halt() override { diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index f8777d44d..4f932a169 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -33,6 +33,29 @@ class ConditionNode : public LeafNode return NodeType::CONDITION; } }; + +class SimpleConditionNode : public ConditionNode +{ + public: + typedef std::function TickFunctor; + + // Constructor: you must provide the funtion to call when tick() is invoked + SimpleConditionNode(const std::string& name, TickFunctor tick_functor); + + ~SimpleConditionNode() override = default; + + virtual void halt() override + { + // not supported + } + + protected: + virtual NodeStatus tick() override; + + TickFunctor tick_functor_; +}; + + } #endif diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index 0d2c4fad1..bb8bad426 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -32,6 +32,23 @@ class DecoratorNode : public TreeNode return NodeType::DECORATOR; } }; + +class SimpleDecoratorNode : public DecoratorNode +{ + public: + typedef std::function TickFunctor; + + // Constructor: you must provide the funtion to call when tick() is invoked + SimpleDecoratorNode(const std::string& name, TickFunctor tick_functor); + + ~SimpleDecoratorNode() override = default; + + protected: + virtual NodeStatus tick() override; + + TickFunctor tick_functor_; +}; + } #endif diff --git a/src/condition_node.cpp b/src/condition_node.cpp index 926be7038..4fbf0a7c2 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -13,11 +13,28 @@ #include "behavior_tree_core/condition_node.h" -BT::ConditionNode::ConditionNode(const std::string& name, const NodeParameters& parameters) - : LeafNode::LeafNode(name, parameters) +namespace BT +{ + +ConditionNode::ConditionNode(const std::string& name, const NodeParameters& parameters) + : LeafNode::LeafNode(name, parameters) +{ +} + +void ConditionNode::halt() { } -void BT::ConditionNode::halt() +SimpleConditionNode::SimpleConditionNode(const std::string &name, + TickFunctor tick_functor) : + ConditionNode(name, NodeParameters()), + tick_functor_(std::move(tick_functor)) { } + +NodeStatus SimpleConditionNode::tick() +{ + return tick_functor_(); +} + +} diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 1eb9bd56b..e2f24a079 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -55,4 +55,17 @@ void DecoratorNode::haltChild() child_node_->halt(); } } + +SimpleDecoratorNode::SimpleDecoratorNode(const std::string &name, + TickFunctor tick_functor) + : DecoratorNode(name, NodeParameters()), + tick_functor_(std::move(tick_functor)) +{ +} + +NodeStatus SimpleDecoratorNode::tick() +{ + return tick_functor_( child()->executeTick() ); +} + } From 20a2a34a13160cc6fdb75f35d96f8d66b42775dc Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 Jun 2018 13:59:18 +0200 Subject: [PATCH 080/125] multiple changes and improvements --- gtest/crossdoor_example.cpp | 18 +- gtest/gtest_factory.cpp | 22 +- gtest/include/crossdoor_dummy_nodes.h | 4 +- gtest/simple_example.cpp | 9 +- include/behavior_tree_core/behavior_tree.h | 27 ++- include/behavior_tree_core/bt_factory.h | 37 +++- include/behavior_tree_core/tree_node.h | 4 +- include/behavior_tree_core/xml_parsing.h | 101 +++------ .../behavior_tree_logger/abstract_logger.h | 2 +- .../bt_flatbuffer_helper.h | 2 +- src/behavior_tree.cpp | 31 ++- src/bt_factory.cpp | 29 ++- src/bt_zmq_publisher.cpp | 17 +- src/tree_node.cpp | 5 + src/xml_parsing.cpp | 208 +++++++++++++++++- 15 files changed, 383 insertions(+), 133 deletions(-) diff --git a/gtest/crossdoor_example.cpp b/gtest/crossdoor_example.cpp index 5b2df0e26..38fb6f65e 100644 --- a/gtest/crossdoor_example.cpp +++ b/gtest/crossdoor_example.cpp @@ -23,10 +23,12 @@ const std::string xml_text = R"( - - - - + + + + + + @@ -50,11 +52,11 @@ int main(int argc, char** argv) // register all the actions into the factory CrossDoor cross_door(factory, false); - XMLParser parser; + XMLParser parser(factory); parser.loadFromText(xml_text); std::vector nodes; - BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); + BT::TreeNodePtr root_node = parser.instantiateTree(nodes); StdCoutLogger logger_cout(root_node.get()); MinitraceLogger logger_minitrace(root_node.get(), "bt_trace.json"); @@ -66,6 +68,10 @@ int main(int argc, char** argv) cross_door.CloseDoor(); + std::cout << "\n-------\n"; + XMLWriter writer(factory); + std::cout << writer.writeXML( root_node.get(), false) << std::endl; + std::cout << "---------------" << std::endl; root_node->executeTick(); diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp index e43c147f3..5eed08b3b 100644 --- a/gtest/gtest_factory.cpp +++ b/gtest/gtest_factory.cpp @@ -79,8 +79,12 @@ const std::string xml_text_subtree = R"( TEST(BehaviorTreeFactory, VerifyLargeTree) { - BT::XMLParser parser; + BT::BehaviorTreeFactory factory; + CrossDoor cross_door(factory); + + BT::XMLParser parser(factory); parser.loadFromText(xml_text); + std::vector errors; bool res = parser.verifyXML(errors); @@ -93,11 +97,8 @@ TEST(BehaviorTreeFactory, VerifyLargeTree) ASSERT_EQ(errors.size(), 0); std::vector nodes; - BT::BehaviorTreeFactory factory; - - CrossDoor cross_door(factory); - BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); + BT::TreeNodePtr root_node = parser.instantiateTree(nodes); BT::printTreeRecursively(root_node.get()); @@ -135,8 +136,12 @@ TEST(BehaviorTreeFactory, VerifyLargeTree) TEST(BehaviorTreeFactory, Subtree) { - BT::XMLParser parser; + BT::BehaviorTreeFactory factory; + CrossDoor cross_door(factory); + + BT::XMLParser parser(factory); parser.loadFromText(xml_text_subtree); + std::vector errors; bool res = parser.verifyXML(errors); @@ -149,11 +154,8 @@ TEST(BehaviorTreeFactory, Subtree) ASSERT_EQ(errors.size(), 0); std::vector nodes; - BT::BehaviorTreeFactory factory; - - CrossDoor cross_door(factory); - BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); + BT::TreeNodePtr root_node = parser.instantiateTree( nodes); BT::printTreeRecursively(root_node.get()); ASSERT_EQ(root_node->name(), "root_selector"); diff --git a/gtest/include/crossdoor_dummy_nodes.h b/gtest/include/crossdoor_dummy_nodes.h index 5419a2b76..e4a79523c 100644 --- a/gtest/include/crossdoor_dummy_nodes.h +++ b/gtest/include/crossdoor_dummy_nodes.h @@ -12,12 +12,12 @@ class CrossDoor door_open_ = true; door_locked_ = false; - factory.registerSimpleAction("IsDoorOpen", [this]() { return IsDoorOpen(); }); + factory.registerSimpleCondition("IsDoorOpen", [this]() { return IsDoorOpen(); }); factory.registerSimpleAction("PassThroughDoor", [this]() { return PassThroughDoor(); }); factory.registerSimpleAction("PassThroughWindow", [this]() { return PassThroughWindow(); }); factory.registerSimpleAction("OpenDoor", [this]() { return OpenDoor(); }); factory.registerSimpleAction("CloseDoor", [this]() { return CloseDoor(); }); - factory.registerSimpleAction("IsDoorLocked", [this]() { return IsDoorLocked(); }); + factory.registerSimpleCondition("IsDoorLocked", [this]() { return IsDoorLocked(); }); factory.registerSimpleAction("UnlockDoor", [this]() { return UnlockDoor(); }); _multiplier = fast ? 1 : 10; diff --git a/gtest/simple_example.cpp b/gtest/simple_example.cpp index 780dd39a2..9edb5035b 100644 --- a/gtest/simple_example.cpp +++ b/gtest/simple_example.cpp @@ -78,11 +78,11 @@ int main(int argc, char** argv) factory.registerNodeType("BatteryOK"); factory.registerNodeType("Move"); - XMLParser parser; + XMLParser parser(factory); parser.loadFromText(xml_text_A); std::vector nodes; - BT::TreeNodePtr root_node = parser.instantiateTree(factory, nodes); + BT::TreeNodePtr root_node = parser.instantiateTree(nodes); StdCoutLogger logger_cout(root_node.get()); FileLogger file_file(root_node.get(), "simple_trace.fbl", 32); @@ -98,5 +98,10 @@ int main(int argc, char** argv) std::cout << "\n------- Third executeTick() --------" << std::endl; root_node->executeTick(); std::cout << std::endl; + + std::cout << "\n-------\n"; + XMLWriter writer(factory); + std::cout << writer.writeXML( root_node.get() ) << std::endl; + return 0; } diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index 2258b4489..36e30eaf6 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -31,7 +31,10 @@ namespace BT { -void recursiveVisitor(TreeNode* node, std::function visitor); + +void applyRecursiveVisitor(const TreeNode* node, const std::function& visitor); + +void applyRecursiveVisitor(TreeNode* node, const std::function &visitor); /** * Debug function to print on a stream @@ -49,7 +52,29 @@ void printTreeRecursively(const TreeNode* root_node); typedef std::vector> SerializedTreeStatus; +/** + * @brief buildSerializedStatusSnapshot create a snapshot of the tree and the status of each node. + * The serialization protocol is implemented with Flatbuffers. + * + * @param root_node + * @param serialized_buffer is the output. + */ void buildSerializedStatusSnapshot(const TreeNode* root_node, SerializedTreeStatus& serialized_buffer); + +/// Simple way to extract the type of a TreeNode at COMPILE TIME. +/// Useful to avoid the cost of without dynamic_cast or the virtual method TreeNode::type(). +template< typename T> inline NodeType getType() +{ + // clang-format off + if( std::is_base_of::value ) return NodeType::ACTION; + if( std::is_base_of::value ) return NodeType::CONDITION; + if( std::is_base_of::value ) return NodeType::SUBTREE; + if( std::is_base_of::value ) return NodeType::DECORATOR; + if( std::is_base_of::value ) return NodeType::CONTROL; + return NodeType::UNDEFINED; + // clang-format on +} + } #endif // BEHAVIOR_TREE_H diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 276555469..55d722365 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -18,12 +18,20 @@ #include #include #include +#include +#include #include "behavior_tree_core/behavior_tree.h" namespace BT { -typedef std::set RequiredParameters; + +struct TreeNodeModel +{ + NodeType type; + std::string registration_ID; + NodeParameters required_parameters; +}; class BehaviorTreeFactory { @@ -34,7 +42,9 @@ class BehaviorTreeFactory void registerBuilder(const std::string& ID, NodeBuilder builder); - void registerSimpleAction(const std::string& ID, std::function tick_functor); + void registerSimpleAction(const std::string& ID, const std::function &tick_functor); + + void registerSimpleCondition(const std::string& ID, const std::function &tick_functor); std::unique_ptr instantiateTreeNode(const std::string& ID, const std::string& name, const NodeParameters& params) const; @@ -44,9 +54,9 @@ class BehaviorTreeFactory return builders_; } - const std::map& requiredNodeParameters() const + const std::vector& models() const { - return required_parameters_; + return treenode_models_; } template @@ -63,7 +73,7 @@ class BehaviorTreeFactory constexpr bool has_static_required_parameters = has_static_method_requiredNodeParameters::value; static_assert(default_constructable || param_constructable, - "[registerBuilder]: the registered class must have a Constructor with signature:\n\n" + "[registerBuilder]: the registered class must have at least one of these two constructors:\n\n" " (const std::string&, const NodeParameters&) or (const std::string&)"); static_assert(!(param_constructable && !has_static_required_parameters), @@ -71,12 +81,12 @@ class BehaviorTreeFactory " const NodeParameters& requiredNodeParameters(); "); registerNodeTypeImpl(ID); - saveRequiredParameters(ID); + storeNodeModel(ID); } private: std::map builders_; - std::map required_parameters_; + std::vector treenode_models_; // template specialization + SFINAE + black magic @@ -125,6 +135,7 @@ class BehaviorTreeFactory { if( params.empty() ) { + // call this one that MIGHT use default initialization return std::unique_ptr(new T(name)); } return std::unique_ptr(new T(name, params)); @@ -135,18 +146,22 @@ class BehaviorTreeFactory template typename std::enable_if< has_static_method_requiredNodeParameters::value>::type - saveRequiredParameters(const std::string& name) + storeNodeModel(const std::string& ID) { - required_parameters_.insert( { name, T::requiredNodeParameters()} ); + treenode_models_.push_back( { getType(), ID, T::requiredNodeParameters()} ); + sortTreeNodeModel(); } template typename std::enable_if< !has_static_method_requiredNodeParameters::value>::type - saveRequiredParameters(const std::string& ) + storeNodeModel(const std::string& ID) { - //do nothing. This implementation is intentionally empty + treenode_models_.push_back( { getType(), ID, NodeParameters()} ); + sortTreeNodeModel(); } + void sortTreeNodeModel(); + // clang-format on }; diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index c339418d8..ca12e21f4 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -91,6 +91,8 @@ class TreeNode const std::string& registrationName() const; + const NodeParameters& initializationParameters() const; + protected: template T getParam(const std::string& key) const @@ -100,7 +102,7 @@ class TreeNode { throw std::invalid_argument(std::string("Can't find the parameter with key: ") + key); } - return convertFromString(key.c_str()); + return convertFromString(it->second.c_str()); } private: diff --git a/include/behavior_tree_core/xml_parsing.h b/include/behavior_tree_core/xml_parsing.h index a9ba06e78..5d0a26314 100644 --- a/include/behavior_tree_core/xml_parsing.h +++ b/include/behavior_tree_core/xml_parsing.h @@ -9,7 +9,7 @@ namespace BT class XMLParser { public: - XMLParser() = default; + XMLParser(const BehaviorTreeFactory& factory): factory_(factory) {} void loadFromFile(const std::string& filename) noexcept(false); @@ -17,88 +17,39 @@ class XMLParser bool verifyXML(std::vector& error_messages) const noexcept(false); - template using NodeBuilder = - std::function; + std::function; - // general and reusable method to visit each node of a tree - template - NodePtr treeParsing(const tinyxml2::XMLElement* root_element, const NodeBuilder& node_builder, - std::vector& nodes, NodePtr root_parent); - - TreeNodePtr instantiateTree(const BehaviorTreeFactory& factory, std::vector& nodes); + TreeNodePtr instantiateTree(std::vector& nodes); private: + + //method to visit each node of a tree + TreeNodePtr treeParsing(const tinyxml2::XMLElement* root_element, + const NodeBuilder& node_builder, + std::vector& nodes, + const TreeNodePtr &root_parent); + tinyxml2::XMLDocument doc_; -}; -//--------------------------------------------- + const BehaviorTreeFactory& factory_; +}; -template -inline NodePtr XMLParser::treeParsing(const tinyxml2::XMLElement* root_element, - const NodeBuilder& node_builder, std::vector& nodes, - NodePtr root_parent) +class XMLWriter { - using namespace tinyxml2; - - std::function RecursiveVisitor; - - RecursiveVisitor = [&](NodePtr parent, const tinyxml2::XMLElement* element) -> NodePtr { - const std::string element_name = element->Name(); - std::string node_ID; - std::string node_alias; - NodeParameters node_params; - - // Actions and Decorators have their own ID - if (element_name == "Action" || element_name == "Decorator" || element_name == "Condition") - { - node_ID = element->Attribute("ID"); - } - else - { - node_ID = element_name; - } - - const char* attr_alias = element->Attribute("name"); - if (attr_alias) - { - node_alias = attr_alias; - } - else - { - node_alias = node_ID; - } - - if (element_name == "SubTree") - { - node_alias = element->Attribute("ID"); - } - - for (const XMLAttribute* att = element->FirstAttribute(); att; att = att->Next()) - { - const std::string attribute_name = att->Name(); - if (attribute_name != "ID" && attribute_name != "name") - { - node_params[attribute_name] = att->Value(); - } - } - - NodePtr node = node_builder(node_ID, node_alias, node_params, parent); - nodes.push_back(node); - - for (auto child_element = element->FirstChildElement(); child_element; - child_element = child_element->NextSiblingElement()) - { - RecursiveVisitor(node, child_element); - } - - return node; - }; - - // start recursion - NodePtr root = RecursiveVisitor(root_parent, root_element); - return root; -} +public: + XMLWriter( const BehaviorTreeFactory& factory): + factory_(factory) + {} + + std::string writeXML(const TreeNode* root_node, bool compact_representation = false) const; + +private: + const BehaviorTreeFactory& factory_; + +}; + + } #endif // XML_PARSING_BT_H diff --git a/include/behavior_tree_logger/abstract_logger.h b/include/behavior_tree_logger/abstract_logger.h index 911bef0f5..b58e20a95 100644 --- a/include/behavior_tree_logger/abstract_logger.h +++ b/include/behavior_tree_logger/abstract_logger.h @@ -46,7 +46,7 @@ class StatusChangeLogger inline StatusChangeLogger::StatusChangeLogger(TreeNode* root_node) : enabled_(true), show_transition_to_idle_(true) { - recursiveVisitor(root_node, [this](TreeNode* node) { + applyRecursiveVisitor(root_node, [this](TreeNode* node) { subscribers_.push_back(node->subscribeToStatusChange( [this](TimePoint timestamp, const TreeNode& node, NodeStatus prev, NodeStatus status) { if (enabled_ && (status != NodeStatus::IDLE || show_transition_to_idle_)) diff --git a/include/behavior_tree_logger/bt_flatbuffer_helper.h b/include/behavior_tree_logger/bt_flatbuffer_helper.h index 7f4b28a97..7a6458a58 100644 --- a/include/behavior_tree_logger/bt_flatbuffer_helper.h +++ b/include/behavior_tree_logger/bt_flatbuffer_helper.h @@ -46,7 +46,7 @@ inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builde { std::vector> fb_nodes; - recursiveVisitor(root_node, [&](TreeNode* node) { + applyRecursiveVisitor(root_node, [&](TreeNode* node) { std::vector children_uid; if (auto control = dynamic_cast(node)) { diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index 802212a09..4dfb37a88 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -3,7 +3,30 @@ namespace BT { -void recursiveVisitor(TreeNode* node, std::function visitor) + +void applyRecursiveVisitor(const TreeNode* node, const std::function& visitor) +{ + if (!node) + { + throw std::runtime_error("One of the children of a DecoratorNode or ControlNode is nulltr"); + } + + visitor(node); + + if (auto control = dynamic_cast(node)) + { + for (const auto& child : control->children()) + { + applyRecursiveVisitor( static_cast(child), visitor); + } + } + else if (auto decorator = dynamic_cast(node)) + { + applyRecursiveVisitor(decorator->child(), visitor); + } +} + +void applyRecursiveVisitor(TreeNode* node, const std::function& visitor) { if (!node) { @@ -16,12 +39,12 @@ void recursiveVisitor(TreeNode* node, std::function visitor) { for (const auto& child : control->children()) { - recursiveVisitor(child, visitor); + applyRecursiveVisitor(child, visitor); } } else if (auto decorator = dynamic_cast(node)) { - recursiveVisitor(decorator->child(), visitor); + applyRecursiveVisitor(decorator->child(), visitor); } } @@ -68,6 +91,6 @@ void buildSerializedStatusSnapshot(TreeNode* root_node, SerializedTreeStatus& se serialized_buffer.push_back(std::make_pair(node->UID(), static_cast(node->status()))); }; - recursiveVisitor(root_node, visitor); + applyRecursiveVisitor(root_node, visitor); } } diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 04987cf7f..92a558157 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -24,7 +24,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("Negation"); registerNodeType("RetryUntilSuccesful"); - registerNodeType("Repeat"); + registerNodeType("Repeat"); registerNodeType("SubTree"); } @@ -51,13 +51,24 @@ void BehaviorTreeFactory::registerBuilder(const std::string& ID, NodeBuilder bui builders_.insert(std::make_pair(ID, builder)); } -void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, std::function tick_functor) +void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, const std::function &tick_functor) +{ + NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeParameters&) { + return std::unique_ptr(new SimpleConditionNode(name, tick_functor)); + }; + + registerBuilder(ID, builder); + storeNodeModel(ID); +} + +void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, const std::function& tick_functor) { NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeParameters&) { return std::unique_ptr(new SimpleActionNode(name, tick_functor)); }; registerBuilder(ID, builder); + storeNodeModel(ID); } std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::string& ID, const std::string& name, @@ -73,4 +84,18 @@ std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::st return node; } +void BehaviorTreeFactory::sortTreeNodeModel() +{ + std::sort( treenode_models_.begin(), treenode_models_.end(), + [](const TreeNodeModel& a, const TreeNodeModel& b) + { + int comp = std::strcmp( toStr( a.type ), toStr( b.type )); + if( comp == 0) + { + return a.registration_ID < b.registration_ID; + } + return comp < 0; + }); +} + } // end namespace diff --git a/src/bt_zmq_publisher.cpp b/src/bt_zmq_publisher.cpp index 0e48d8ad2..ad031e72d 100644 --- a/src/bt_zmq_publisher.cpp +++ b/src/bt_zmq_publisher.cpp @@ -7,7 +7,7 @@ namespace BT void PublisherZMQ::createStatusBuffer() { status_buffer_.clear(); - recursiveVisitor(root_node_, [this](TreeNode* node) { + applyRecursiveVisitor(root_node_, [this](TreeNode* node) { size_t index = status_buffer_.size(); status_buffer_.resize(index + 3); flatbuffers::WriteScalar(&status_buffer_[index], node->UID()); @@ -44,6 +44,9 @@ PublisherZMQ::PublisherZMQ(TreeNode* root_node, int max_msg_per_second) zmq_publisher_.bind("tcp://*:1666"); zmq_server_.bind("tcp://*:1667"); + int timeout_ms = 100; + zmq_server_.setsockopt(ZMQ_RCVTIMEO, &timeout_ms, sizeof(int)); + active_server_ = true; thread_ = std::thread([this]() { @@ -52,13 +55,17 @@ PublisherZMQ::PublisherZMQ(TreeNode* root_node, int max_msg_per_second) zmq::message_t req; try { - zmq_server_.recv(&req); - zmq::message_t reply(tree_buffer_.size()); - memcpy(reply.data(), tree_buffer_.data(), tree_buffer_.size()); - zmq_server_.send(reply); + bool received = zmq_server_.recv(&req); + if( received ) + { + zmq::message_t reply(tree_buffer_.size()); + memcpy(reply.data(), tree_buffer_.data(), tree_buffer_.size()); + zmq_server_.send(reply); + } } catch (zmq::error_t& err) { + std::cout << "[PublisherZMQ] just died. Exeption " << err.what() << std::endl; active_server_ = false; } } diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 59253dafc..8e4d1dd26 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -100,4 +100,9 @@ const std::string& TreeNode::registrationName() const return registration_name_; } +const NodeParameters &TreeNode::initializationParameters() const +{ + return parameters_; +} + } // end namespace diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 212bfe038..3a7c879f2 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -43,9 +43,9 @@ bool XMLParser::verifyXML(std::vector& error_messages) const //-------- Helper functions (lambdas) ----------------- auto strEqual = [](const char* str1, const char* str2) -> bool { return strcmp(str1, str2) == 0; }; - auto AppendError = [&](int line_num, const char* text) { + auto AppendError = [&](int line_num, const std::string& text) { char buffer[256]; - sprintf(buffer, "Error at line %d: -> %s", line_num, text); + sprintf(buffer, "Error at line %d: -> %s", line_num, text.c_str() ); error_messages.emplace_back(buffer); is_valid = false; }; @@ -84,7 +84,7 @@ bool XMLParser::verifyXML(std::vector& error_messages) const { const char* name = node->Name(); if (strEqual(name, "Action") || strEqual(name, "Decorator") || strEqual(name, "SubTree") || - strEqual(name, "Condition")) + strEqual(name, "Condition")) { const char* ID = node->Attribute("ID"); if (!ID) @@ -166,9 +166,21 @@ bool XMLParser::verifyXML(std::vector& error_messages) const AppendError(node->GetLineNum(), "The node must have the attribute [ID]"); } } - else - { - AppendError(node->GetLineNum(), "Node not recognized"); + else{ + // Last resort: MAYBE used ID as element name? + bool found = false; + for( const auto& model: factory_.models()) + { + if(model.registration_ID == name) + { + found = true; + break; + } + } + if( !found ) + { + AppendError(node->GetLineNum(), std::string("Node not recognized: ") + name); + } } //recursion for (auto child = node->FirstChildElement(); child != nullptr; child = child->NextSiblingElement()) @@ -192,8 +204,10 @@ bool XMLParser::verifyXML(std::vector& error_messages) const return is_valid; } -TreeNodePtr XMLParser::instantiateTree(const BehaviorTreeFactory& factory, std::vector& nodes) +TreeNodePtr XMLParser::instantiateTree(std::vector& nodes) { + nodes.clear(); + std::vector error_messages; this->verifyXML(error_messages); @@ -219,9 +233,10 @@ TreeNodePtr XMLParser::instantiateTree(const BehaviorTreeFactory& factory, std:: } //-------------------------------------- - NodeBuilder node_builder = [&](const std::string& ID, const std::string& name, - const NodeParameters& params, TreeNodePtr parent) -> TreeNodePtr { - TreeNodePtr child_node = factory.instantiateTreeNode(ID, name, params); + NodeBuilder node_builder = [&](const std::string& ID, const std::string& name, + const NodeParameters& params, TreeNodePtr parent) -> TreeNodePtr + { + TreeNodePtr child_node = factory_.instantiateTreeNode(ID, name, params); nodes.push_back(child_node); if (parent) { @@ -241,13 +256,182 @@ TreeNodePtr XMLParser::instantiateTree(const BehaviorTreeFactory& factory, std:: if (subtree_node) { auto subtree_elem = bt_roots[name]->FirstChildElement(); - treeParsing(subtree_elem, node_builder, nodes, child_node); + treeParsing(subtree_elem, node_builder, nodes, child_node); } return child_node; }; //-------------------------------------- auto root_element = bt_roots[main_tree_ID]->FirstChildElement(); - return treeParsing(root_element, node_builder, nodes, TreeNodePtr()); + return treeParsing(root_element, node_builder, nodes, TreeNodePtr()); +} + +TreeNodePtr BT::XMLParser::treeParsing(const XMLElement *root_element, + const NodeBuilder &node_builder, + std::vector &nodes, + const TreeNodePtr& root_parent) +{ + using namespace tinyxml2; + + std::function recursiveStep; + + recursiveStep = [&](const TreeNodePtr& parent, const tinyxml2::XMLElement* element) -> TreeNodePtr { + const std::string element_name = element->Name(); + std::string node_ID; + std::string node_alias; + NodeParameters node_params; + + // Actions and Decorators have their own ID + if (element_name == "Action" || element_name == "Decorator" || element_name == "Condition") + { + node_ID = element->Attribute("ID"); + } + else + { + node_ID = element_name; + } + + const char* attr_alias = element->Attribute("name"); + if (attr_alias) + { + node_alias = attr_alias; + } + else + { + node_alias = node_ID; + } + + if (element_name == "SubTree") + { + node_alias = element->Attribute("ID"); + } + + for (const XMLAttribute* att = element->FirstAttribute(); att; att = att->Next()) + { + const std::string attribute_name = att->Name(); + if (attribute_name != "ID" && attribute_name != "name") + { + node_params[attribute_name] = att->Value(); + } + } + + TreeNodePtr node = node_builder(node_ID, node_alias, node_params, parent); + nodes.push_back(node); + + for (auto child_element = element->FirstChildElement(); child_element; + child_element = child_element->NextSiblingElement()) + { + recursiveStep(node, child_element); + } + + return node; + }; + + // start recursion + TreeNodePtr root = recursiveStep(root_parent, root_element); + return root; +} + +std::string XMLWriter::writeXML(const TreeNode *root_node, bool compact_representation) const +{ + using namespace tinyxml2; + + XMLDocument doc; + + XMLElement* rootXML = doc.NewElement( "root"); + doc.InsertFirstChild(rootXML); + + if( root_node ) + { + XMLElement* bt_root = doc.NewElement("BehaviorTree"); + rootXML->InsertEndChild(bt_root); + + std::function recursiveVisitor; + + recursiveVisitor = [&recursiveVisitor, &doc, compact_representation, this] + (const TreeNode* node, XMLElement* parent) -> void + { + std::string node_type = toStr(node->type()); + std::string node_ID = node->registrationName(); + std::string node_name = node->name(); + + + if( node->type() == NodeType::CONTROL) + { + node_type = node_ID; + } + else if(compact_representation) + { + for(const auto& model: factory_.models() ) + { + if( model.registration_ID == node_ID) + { + node_type = node_ID; + break; + } + } + } + + XMLElement* element = doc.NewElement( node_type.c_str() ); + if( node_type != node_ID && !node_ID.empty()) + { + element->SetAttribute("ID", node_ID.c_str()); + } + if( node_type != node_name && !node_name.empty() && node_name != node_ID) + { + element->SetAttribute("name", node_name.c_str()); + } + + for(const auto& param: node->initializationParameters()) + { + element->SetAttribute( param.first.c_str(), param.second.c_str() ); + } + + parent->InsertEndChild(element); + + if (auto control = dynamic_cast(node)) + { + for (const auto& child : control->children()) + { + recursiveVisitor( static_cast(child), element); + } + } + else if (auto decorator = dynamic_cast(node)) + { + recursiveVisitor(decorator->child(), element); + } + }; + + recursiveVisitor(root_node, bt_root); + } + //-------------------------- + + XMLElement* model_root = doc.NewElement("TreeNodesModel"); + rootXML->InsertEndChild(model_root); + + for( auto& model: factory_.models()) + { + if( model.type == NodeType::CONTROL) + { + continue; + } + XMLElement* element = doc.NewElement( toStr(model.type) ); + element->SetAttribute( "ID", model.registration_ID.c_str() ); + + for( auto& param: model.required_parameters) + { + XMLElement* param_el = doc.NewElement( "Parameter" ); + param_el->SetAttribute("label", param.first.c_str() ); + param_el->SetAttribute("default", param.second.c_str() ); + element->InsertEndChild(param_el); + } + + model_root->InsertEndChild(element); + } + + tinyxml2::XMLPrinter printer; + doc.Print( &printer ); + return std::string( printer.CStr(), printer.CStrSize()-1 ); } + } From 8d8d2158dffe009c0a2c030a778fbcd442244bdd Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 Jun 2018 15:55:25 +0200 Subject: [PATCH 081/125] comments and cleanups --- include/behavior_tree_core/action_node.h | 9 ++-- include/behavior_tree_core/behavior_tree.h | 13 ++--- include/behavior_tree_core/bt_factory.h | 3 ++ include/behavior_tree_core/condition_node.h | 12 +++++ include/behavior_tree_core/decorator_node.h | 11 ++++ include/behavior_tree_core/tree_node.h | 58 ++++++++++++++------- src/bt_factory.cpp | 2 +- src/tree_node.cpp | 5 -- 8 files changed, 72 insertions(+), 41 deletions(-) diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index ca0342851..42c2d7efc 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -33,16 +33,15 @@ class ActionNodeBase : public LeafNode }; /** - * @brief The SimpleActionNode provides a easy to use ActionNode. + * @brief The SimpleActionNode provides an easy to use ActionNode. * The user should simply provide a callback with this signature * - * BT::NodeStatus funtionName(void) + * BT::NodeStatus functionName(void) * * This avoids the hassle of inheriting from a ActionNode. * - * Using lambdas or std::bind it is easy to pass a pointer to a method too. - * For the time being, this class of Actions can not carry use the BT::NodeParameters - * This may change in the future. + * Using lambdas or std::bind it is easy to pass a pointer to a method. + * SimpleActionNode does not support halting, NodeParameters, nor Blackboards. */ class SimpleActionNode : public ActionNodeBase { diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index 36e30eaf6..39358d6ad 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -41,20 +41,13 @@ void applyRecursiveVisitor(TreeNode* node, const std::function */ void printTreeRecursively(const TreeNode* root_node); -/** - * @brief buildSerializedStatusSnapshot can be used to create a serialize buffer that can be stored - * (or sent to a client application) to know the status of all the nodes of a tree. - * It is not "human readable". - * - * @param root_node - * @param serialized_buffer - */ typedef std::vector> SerializedTreeStatus; /** - * @brief buildSerializedStatusSnapshot create a snapshot of the tree and the status of each node. - * The serialization protocol is implemented with Flatbuffers. + * @brief buildSerializedStatusSnapshot can be used to create a serialize buffer that can be stored + * (or sent to a client application) to know the status of all the nodes of a tree. + * It is not "human readable". * * @param root_node * @param serialized_buffer is the output. diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 55d722365..e5842fe6b 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -26,6 +26,9 @@ namespace BT { +// The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) +typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; + struct TreeNodeModel { NodeType type; diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index 4f932a169..04262b6ed 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -34,6 +34,18 @@ class ConditionNode : public LeafNode } }; + +/** + * @brief The SimpleConditionNode provides an easy to use ConditionNode. + * The user should simply provide a callback with this signature + * + * BT::NodeStatus functionName(void) + * + * This avoids the hassle of inheriting from a ActionNode. + * + * Using lambdas or std::bind it is easy to pass a pointer to a method. + * SimpleConditionNode does not support halting, NodeParameters, nor Blackboards. + */ class SimpleConditionNode : public ConditionNode { public: diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index bb8bad426..db7f1fd03 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -33,6 +33,17 @@ class DecoratorNode : public TreeNode } }; +/** + * @brief The SimpleDecoratorNode provides an easy to use DecoratorNode. + * The user should simply provide a callback with this signature + * + * BT::NodeStatus functionName(BT::NodeStatus child_status) + * + * This avoids the hassle of inheriting from a DecoratorNode. + * + * Using lambdas or std::bind it is easy to pass a pointer to a method. + * SimpleDecoratorNode does not support halting, NodeParameters, nor Blackboards. + */ class SimpleDecoratorNode : public DecoratorNode { public: diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index ca12e21f4..4edb12374 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -35,36 +35,37 @@ typedef std::chrono::high_resolution_clock::time_point TimePoint; // Abstract base class for Behavior Tree Nodes class TreeNode { - private: - // Node name - std::string name_; - NodeStatus status_; - std::condition_variable state_condition_variable_; - mutable std::mutex state_mutex_; - - protected: - // Method to be implemented by the user - virtual BT::NodeStatus tick() = 0; - public: - // The constructor and the destructor + + /** + * @brief TreeNode main constructor. + * + * @param name name of the instance, not the type of sensor. + * @param parameters this might be empty. use getParam(key) to parse the value. + * + * Note: a node that accepts a not empty set of NodeParameters must also implement the method: + * + * static const NodeParameters& requiredNodeParameters(); + */ TreeNode(const std::string& name, const NodeParameters& parameters); virtual ~TreeNode() = default; - // The method that is going to be executed when the node receive a tick + /// The method that will be executed to invoke tick(); and setStatus(); virtual BT::NodeStatus executeTick(); - // The method used to interrupt the execution of the node + /// The method used to interrupt the execution of a RUNNING node virtual void halt() = 0; bool isHalted() const; NodeStatus status() const; + void setStatus(NodeStatus new_status); const std::string& name() const; - void setName(const std::string& new_name); + /// Blocking funtion that will sleep until the setStatus() is called with + /// either RUNNING, FAILURE or SUCCESS. BT::NodeStatus waitValidStatus(); virtual NodeType type() const = 0; @@ -76,7 +77,7 @@ class TreeNode /** * @brief subscribeToStatusChange is used to attach a callback to a status change. * AS soon as StatusChangeSubscriber goes out of scope (it is a shared_ptr) the callback - * is unsubscribed + * is unsubscribed automatically. * * @param callback. Must have signature void funcname(NodeStatus prev_status, NodeStatus new_status) * @@ -87,13 +88,18 @@ class TreeNode // get an unique identifier of this instance of treeNode uint16_t UID() const; - void setRegistrationName(const std::string& registration_name); - + /// registrationName is the ID used by BehaviorTreeFactory to create an instance. const std::string& registrationName() const; + /// Parameters passed at construction time. Can never change after the + /// creation of the TreeNode instance. const NodeParameters& initializationParameters() const; protected: + + /// Method to be implemented by the user + virtual BT::NodeStatus tick() = 0; + template T getParam(const std::string& key) const { @@ -105,7 +111,20 @@ class TreeNode return convertFromString(it->second.c_str()); } + /// registrationName() is set by the BehaviorTreeFactory + void setRegistrationName(const std::string& registration_name); + + friend class BehaviorTreeFactory; + private: + const std::string name_; + + NodeStatus status_; + + std::condition_variable state_condition_variable_; + + mutable std::mutex state_mutex_; + StatusChangeSignal state_change_signal_; const uint16_t uid_; @@ -117,8 +136,7 @@ class TreeNode typedef std::shared_ptr TreeNodePtr; -// The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) -typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; + } #endif diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 92a558157..908246a13 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -77,7 +77,7 @@ std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::st auto it = builders_.find(ID); if (it == builders_.end()) { - throw BehaviorTreeException("ID '" + ID + "' not registered"); + throw std::invalid_argument("ID '" + ID + "' not registered"); } std::unique_ptr node = it->second(name, params); node->setRegistrationName(ID); diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 8e4d1dd26..9bd529270 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -55,11 +55,6 @@ NodeStatus TreeNode::status() const return status_; } -void TreeNode::setName(const std::string& new_name) -{ - name_ = new_name; -} - NodeStatus TreeNode::waitValidStatus() { std::unique_lock lk(state_mutex_); From a510b386ece2c2656437a89a44ad9b2061788535 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 18 Jun 2018 14:42:35 +0200 Subject: [PATCH 082/125] fix compilation error --- include/behavior_tree_core/basic_types.h | 1 + 1 file changed, 1 insertion(+) diff --git a/include/behavior_tree_core/basic_types.h b/include/behavior_tree_core/basic_types.h index 67e6925ea..0891c2028 100644 --- a/include/behavior_tree_core/basic_types.h +++ b/include/behavior_tree_core/basic_types.h @@ -3,6 +3,7 @@ #include #include +#include namespace BT { From a57c7ad043a601ed85e41dd49e46d64d5ba50e3d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 26 Jun 2018 16:00:50 +0200 Subject: [PATCH 083/125] better template specialization --- include/behavior_tree_core/basic_types.h | 8 +----- include/behavior_tree_core/tree_node.h | 3 +- src/basic_types.cpp | 35 ++++++++++++++++-------- 3 files changed, 27 insertions(+), 19 deletions(-) diff --git a/include/behavior_tree_core/basic_types.h b/include/behavior_tree_core/basic_types.h index 0891c2028..5d75829b0 100644 --- a/include/behavior_tree_core/basic_types.h +++ b/include/behavior_tree_core/basic_types.h @@ -64,14 +64,8 @@ enum SuccessPolicy SUCCEED_ON_ALL }; -template -T convertFromString(const char* str); -template -inline T convertFromString(const std::string& str) -{ - return convertFromString(str.c_str()); -} +template T convertFromString(const std::string& str); //------------------------------------------------------------------ diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 4edb12374..fc72234dc 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -108,9 +108,10 @@ class TreeNode { throw std::invalid_argument(std::string("Can't find the parameter with key: ") + key); } - return convertFromString(it->second.c_str()); + return convertFromString(it->second); } + /// registrationName() is set by the BehaviorTreeFactory void setRegistrationName(const std::string& registration_name); diff --git a/src/basic_types.cpp b/src/basic_types.cpp index caacf0949..c1975f1f2 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -79,29 +79,42 @@ const char* toStr(const ResetPolicy& policy) } template <> -int convertFromString(const char* str) +std::string convertFromString(const std::string& str) { - return std::stoi(str); + return str; } template <> -unsigned convertFromString(const char* str) +const char* convertFromString(const std::string& str) { - return std::stoul(str); + return str.c_str(); +} + + +template <> +int convertFromString(const std::string& str) +{ + return std::stoi(str.c_str()); +} + +template <> +unsigned convertFromString(const std::string& str) +{ + return std::stoul(str.c_str()); } template <> -double convertFromString(const char* str) +double convertFromString(const std::string& str) { return std::stod(str); } template <> -NodeStatus convertFromString(const char* str) +NodeStatus convertFromString(const std::string& str) { for (auto status : {NodeStatus::IDLE, NodeStatus::RUNNING, NodeStatus::SUCCESS, NodeStatus::FAILURE}) { - if (std::strcmp(toStr(status), str) == 0) + if (std::strcmp(toStr(status), str.c_str()) == 0) { return status; } @@ -110,12 +123,12 @@ NodeStatus convertFromString(const char* str) } template <> -NodeType convertFromString(const char* str) +NodeType convertFromString(const std::string& str) { for (auto status : {NodeType::ACTION, NodeType::CONDITION, NodeType::CONTROL, NodeType::DECORATOR, NodeType::SUBTREE, NodeType::UNDEFINED}) { - if (std::strcmp(toStr(status), str) == 0) + if (std::strcmp(toStr(status), str.c_str()) == 0) { return status; } @@ -124,11 +137,11 @@ NodeType convertFromString(const char* str) } template <> -ResetPolicy convertFromString(const char* str) +ResetPolicy convertFromString(const std::string& str) { for (auto status : {ResetPolicy::ON_SUCCESS, ResetPolicy::ON_SUCCESS_OR_FAILURE, ResetPolicy::ON_FAILURE}) { - if (std::strcmp(toStr(status), str) == 0) + if (std::strcmp(toStr(status), str.c_str()) == 0) { return status; } From 339df6de08599fd821f857882cb95dacc10b1b07 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 26 Jun 2018 16:01:14 +0200 Subject: [PATCH 084/125] more checks in the XML parsing --- src/xml_parsing.cpp | 51 +++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 49 insertions(+), 2 deletions(-) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 3a7c879f2..51bfe7eae 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -189,9 +189,17 @@ bool XMLParser::verifyXML(std::vector& error_messages) const } }; + std::vector tree_names; + int tree_count = 0; + for (auto bt_root = xml_root->FirstChildElement("BehaviorTree"); bt_root != nullptr; bt_root = bt_root->NextSiblingElement("BehaviorTree")) { + tree_count++; + if( bt_root->Attribute("ID")) + { + tree_names.push_back(bt_root->Attribute("ID")); + } if (ChildrenCount(bt_root) != 1) { AppendError(bt_root->GetLineNum(), "The node must have exactly 1 child"); @@ -201,6 +209,25 @@ bool XMLParser::verifyXML(std::vector& error_messages) const recursiveStep(bt_root->FirstChildElement()); } } + + if( xml_root->Attribute("main_tree_to_execute") ) + { + std::string main_tree = xml_root->Attribute("main_tree_to_execute"); + if( std::find( tree_names.begin(), tree_names.end(), main_tree) == tree_names.end()) + { + error_messages.emplace_back("The tree esecified in [main_tree_to_execute] " + "can't be found"); + is_valid = false; + } + } + else{ + if( tree_count != 1) + { + error_messages.emplace_back("If you don't specify the attribute [main_tree_to_execute], " + "Your file must contain a single BehaviorTree"); + is_valid = false; + } + } return is_valid; } @@ -222,14 +249,34 @@ TreeNodePtr XMLParser::instantiateTree(std::vector& nodes) //-------------------------------------- XMLElement* xml_root = doc_.RootElement(); - const std::string main_tree_ID = xml_root->Attribute("main_tree_to_execute"); + + std::string main_tree_ID; + if( xml_root->Attribute("main_tree_to_execute") ) + { + main_tree_ID = xml_root->Attribute("main_tree_to_execute"); + } std::map bt_roots; + int tree_count = 0; + for (auto node = xml_root->FirstChildElement("BehaviorTree"); node != nullptr; node = node->NextSiblingElement("BehaviorTree")) { - bt_roots[node->Attribute("ID")] = node; + std::string tree_name = main_tree_ID; + if( tree_count++ > 0 ) + { + tree_name += std::string("_") + std::to_string(tree_count); + } + if( node->Attribute("ID")) + { + tree_name = node->Attribute("ID"); + } + bt_roots[tree_name] = node; + if( main_tree_ID.empty() ) + { + main_tree_ID = tree_name; + } } //-------------------------------------- From e13d2acebf8cf210f2a7e42a5fe8599929a01e77 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 20 Aug 2018 15:11:01 +0200 Subject: [PATCH 085/125] adding blackboard --- 3rdparty/non_std/optional.hpp | 1212 ++++++++++++++++++++++++ include/Blackboard/blackboard.h | 59 ++ include/Blackboard/blackboard_local.h | 34 + include/SafeAny/any.hpp | 461 +++++++++ include/SafeAny/safe_any.hpp | 500 ++++++++++ include/behavior_tree_core/tree_node.h | 28 +- src/decorator_repeat_node.cpp | 6 +- src/decorator_retry_node.cpp | 6 +- src/fallback_node_with_memory.cpp | 6 +- src/sequence_node_with_memory.cpp | 6 +- src/tree_node.cpp | 10 + 11 files changed, 2320 insertions(+), 8 deletions(-) create mode 100644 3rdparty/non_std/optional.hpp create mode 100644 include/Blackboard/blackboard.h create mode 100644 include/Blackboard/blackboard_local.h create mode 100644 include/SafeAny/any.hpp create mode 100644 include/SafeAny/safe_any.hpp diff --git a/3rdparty/non_std/optional.hpp b/3rdparty/non_std/optional.hpp new file mode 100644 index 000000000..34b0e8d2b --- /dev/null +++ b/3rdparty/non_std/optional.hpp @@ -0,0 +1,1212 @@ +// +// Copyright (c) 2014-2018 Martin Moene +// +// https://github.com/martinmoene/optional-lite +// +// Distributed under the Boost Software License, Version 1.0. +// (See accompanying file LICENSE.txt or copy at http://www.boost.org/LICENSE_1_0.txt) + +#pragma once + +#ifndef NONSTD_OPTIONAL_LITE_HPP +#define NONSTD_OPTIONAL_LITE_HPP + +#define optional_lite_VERSION "3.1.0" + +// C++ language version detection (C++20 is speculative): +// Note: VC14.0/1900 (VS2015) lacks too much from C++14. + +#ifndef optional_CPLUSPLUS +# ifdef _MSVC_LANG +# define optional_CPLUSPLUS (_MSC_VER == 1900 ? 201103L : _MSVC_LANG ) +# else +# define optional_CPLUSPLUS __cplusplus +# endif +#endif + +#define optional_CPP98_OR_GREATER ( optional_CPLUSPLUS >= 199711L ) +#define optional_CPP11_OR_GREATER ( optional_CPLUSPLUS >= 201103L ) +#define optional_CPP14_OR_GREATER ( optional_CPLUSPLUS >= 201402L ) +#define optional_CPP17_OR_GREATER ( optional_CPLUSPLUS >= 201703L ) +#define optional_CPP20_OR_GREATER ( optional_CPLUSPLUS >= 202000L ) + +// C++ language version (represent 98 as 3): + +#define optional_CPLUSPLUS_V ( optional_CPLUSPLUS / 100 - (optional_CPLUSPLUS > 200000 ? 2000 : 1994) ) + +// use C++17 std::optional if available: + +#if defined( __has_include ) +# define optional_HAS_INCLUDE( arg ) __has_include( arg ) +#else +# define optional_HAS_INCLUDE( arg ) 0 +#endif + +#define optional_HAVE_STD_OPTIONAL ( optional_CPP17_OR_GREATER && optional_HAS_INCLUDE( ) ) + +#if optional_HAVE_STD_OPTIONAL + +#include + +namespace nonstd { + + using std::optional; + using std::bad_optional_access; + using std::hash; + + using std::nullopt; + using std::nullopt_t; + using std::in_place; + using std::in_place_type; + using std::in_place_index; + using std::in_place_t; + using std::in_place_type_t; + using std::in_place_index_t; + + using std::operator==; + using std::operator!=; + using std::operator<; + using std::operator<=; + using std::operator>; + using std::operator>=; + using std::make_optional; + using std::swap; +} + +#else // C++17 std::optional + +#include +#include +#include + +// optional-lite alignment configuration: + +#ifndef optional_CONFIG_MAX_ALIGN_HACK +# define optional_CONFIG_MAX_ALIGN_HACK 0 +#endif + +#ifndef optional_CONFIG_ALIGN_AS +// no default, used in #if defined() +#endif + +#ifndef optional_CONFIG_ALIGN_AS_FALLBACK +# define optional_CONFIG_ALIGN_AS_FALLBACK double +#endif + +// Compiler warning suppression: + +#ifdef __clang__ +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wundef" +#elif defined __GNUC__ +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wundef" +#endif + +// half-open range [lo..hi): +#define optional_BETWEEN( v, lo, hi ) ( lo <= v && v < hi ) + +#if defined(_MSC_VER) && !defined(__clang__) +# define optional_COMPILER_MSVC_VERSION (_MSC_VER / 10 - 10 * ( 5 + (_MSC_VER < 1900)) ) +#else +# define optional_COMPILER_MSVC_VERSION 0 +#endif + +#define optional_COMPILER_VERSION( major, minor, patch ) ( 10 * (10 * major + minor ) + patch ) + +#if defined __GNUC__ +# define optional_COMPILER_GNUC_VERSION optional_COMPILER_VERSION(__GNUC__, __GNUC_MINOR__, __GNUC_PATCHLEVEL__) +#else +# define optional_COMPILER_GNUC_VERSION 0 +#endif + +#if defined __clang__ +# define optional_COMPILER_CLANG_VERSION optional_COMPILER_VERSION(__clang_major__, __clang_minor__, __clang_patchlevel__) +#else +# define optional_COMPILER_CLANG_VERSION 0 +#endif + +#if optional_BETWEEN(optional_COMPILER_MSVC_VERSION, 70, 140 ) +# pragma warning( push ) +# pragma warning( disable: 4345 ) // initialization behavior changed +#endif + +#if optional_BETWEEN(optional_COMPILER_MSVC_VERSION, 70, 150 ) +# pragma warning( push ) +# pragma warning( disable: 4814 ) // in C++14 'constexpr' will not imply 'const' +#endif + +// Presence of language and library features: + +#define optional_HAVE(FEATURE) ( optional_HAVE_##FEATURE ) + +// Presence of C++11 language features: + +#if optional_CPP11_OR_GREATER || optional_COMPILER_MSVC_VERSION >= 100 +# define optional_HAVE_AUTO 1 +# define optional_HAVE_NULLPTR 1 +# define optional_HAVE_STATIC_ASSERT 1 +#endif + +#if optional_CPP11_OR_GREATER || optional_COMPILER_MSVC_VERSION >= 120 +# define optional_HAVE_DEFAULT_FUNCTION_TEMPLATE_ARG 1 +# define optional_HAVE_INITIALIZER_LIST 1 +#endif + +#if optional_CPP11_OR_GREATER || optional_COMPILER_MSVC_VERSION >= 140 +# define optional_HAVE_ALIAS_TEMPLATE 1 +# define optional_HAVE_CONSTEXPR_11 1 +# define optional_HAVE_ENUM_CLASS 1 +# define optional_HAVE_EXPLICIT_CONVERSION 1 +# define optional_HAVE_IS_DEFAULT 1 +# define optional_HAVE_IS_DELETE 1 +# define optional_HAVE_NOEXCEPT 1 +# define optional_HAVE_REF_QUALIFIER 1 +#endif + +// Presence of C++14 language features: + +#if optional_CPP14_OR_GREATER +# define optional_HAVE_CONSTEXPR_14 1 +#endif + +// Presence of C++17 language features: + +#if optional_CPP17_OR_GREATER +# define optional_HAVE_ENUM_CLASS_CONSTRUCTION_FROM_UNDERLYING_TYPE 1 +#endif + +// Presence of C++ library features: + +#if optional_COMPILER_GNUC_VERSION +# define optional_HAVE_TR1_TYPE_TRAITS 1 +# define optional_HAVE_TR1_ADD_POINTER 1 +#endif + +#if optional_CPP11_OR_GREATER || optional_COMPILER_MSVC_VERSION >= 90 +# define optional_HAVE_TYPE_TRAITS 1 +# define optional_HAVE_STD_ADD_POINTER 1 +#endif + +#if optional_CPP11_OR_GREATER || optional_COMPILER_MSVC_VERSION >= 110 +# define optional_HAVE_ARRAY 1 +#endif + +#if optional_CPP11_OR_GREATER || optional_COMPILER_MSVC_VERSION >= 120 +# define optional_HAVE_CONDITIONAL 1 +#endif + +#if optional_CPP11_OR_GREATER || optional_COMPILER_MSVC_VERSION >= 140 || (optional_COMPILER_MSVC_VERSION >= 90 && _HAS_CPP0X) +# define optional_HAVE_CONTAINER_DATA_METHOD 1 +#endif + +#if optional_CPP11_OR_GREATER || optional_COMPILER_MSVC_VERSION >= 120 +# define optional_HAVE_REMOVE_CV 1 +#endif + +#if optional_CPP11_OR_GREATER || optional_COMPILER_MSVC_VERSION >= 140 +# define optional_HAVE_SIZED_TYPES 1 +#endif + +// For the rest, consider VC14 as C++11 for optional-lite: + +#if optional_COMPILER_MSVC_VERSION >= 140 +# undef optional_CPP11_OR_GREATER +# define optional_CPP11_OR_GREATER 1 +#endif + +// C++ feature usage: + +#if optional_HAVE( CONSTEXPR_11 ) +# define optional_constexpr constexpr +#else +# define optional_constexpr /*constexpr*/ +#endif + +#if optional_HAVE( CONSTEXPR_14 ) +# define optional_constexpr14 constexpr +#else +# define optional_constexpr14 /*constexpr*/ +#endif + +#if optional_HAVE( NOEXCEPT ) +# define optional_noexcept noexcept +#else +# define optional_noexcept /*noexcept*/ +#endif + +#if optional_HAVE( NULLPTR ) +# define optional_nullptr nullptr +#else +# define optional_nullptr NULL +#endif + +#if optional_HAVE( REF_QUALIFIER ) +# define optional_ref_qual & +# define optional_refref_qual && +#else +# define optional_ref_qual /*&*/ +# define optional_refref_qual /*&&*/ +#endif + +// additional includes: + +#if optional_CPP11_OR_GREATER +# include +#endif + +#if optional_HAVE( INITIALIZER_LIST ) +# include +#endif + +#if optional_HAVE( TYPE_TRAITS ) +# include +#elif optional_HAVE( TR1_TYPE_TRAITS ) +# include +#endif + +// type traits needed: + +namespace nonstd { namespace optional_lite { namespace detail { + +#if optional_HAVE( CONDITIONAL ) + using std::conditional; +#else + template< bool B, typename T, typename F > struct conditional { typedef T type; }; + template< typename T, typename F > struct conditional { typedef F type; }; +#endif // optional_HAVE_CONDITIONAL + +}}} + +// +// in_place: code duplicated in any-lite, optional-lite, variant-lite: +// + +#ifndef nonstd_lite_HAVE_IN_PLACE_TYPES + +namespace nonstd { + +namespace detail { + +template< class T > +struct in_place_type_tag {}; + +template< std::size_t I > +struct in_place_index_tag {}; + +} // namespace detail + +struct in_place_t {}; + +template< class T > +inline in_place_t in_place( detail::in_place_type_tag = detail::in_place_type_tag() ) +{ + return in_place_t(); +} + +template< std::size_t I > +inline in_place_t in_place( detail::in_place_index_tag = detail::in_place_index_tag() ) +{ + return in_place_t(); +} + +template< class T > +inline in_place_t in_place_type( detail::in_place_type_tag = detail::in_place_type_tag() ) +{ + return in_place_t(); +} + +template< std::size_t I > +inline in_place_t in_place_index( detail::in_place_index_tag = detail::in_place_index_tag() ) +{ + return in_place_t(); +} + +// mimic templated typedef: + +#define nonstd_lite_in_place_type_t( T) nonstd::in_place_t(&)( nonstd::detail::in_place_type_tag ) +#define nonstd_lite_in_place_index_t(T) nonstd::in_place_t(&)( nonstd::detail::in_place_index_tag ) + +#define nonstd_lite_HAVE_IN_PLACE_TYPES 1 + +} // namespace nonstd + +#endif // nonstd_lite_HAVE_IN_PLACE_TYPES + +// +// optional: +// + +namespace nonstd { namespace optional_lite { + +/// class optional + +template< typename T > +class optional; + +namespace detail { + +// C++11 emulation: + +struct nulltype{}; + +template< typename Head, typename Tail > +struct typelist +{ + typedef Head head; + typedef Tail tail; +}; + +#if optional_CONFIG_MAX_ALIGN_HACK + +// Max align, use most restricted type for alignment: + +#define optional_UNIQUE( name ) optional_UNIQUE2( name, __LINE__ ) +#define optional_UNIQUE2( name, line ) optional_UNIQUE3( name, line ) +#define optional_UNIQUE3( name, line ) name ## line + +#define optional_ALIGN_TYPE( type ) \ + type optional_UNIQUE( _t ); struct_t< type > optional_UNIQUE( _st ) + +template< typename T > +struct struct_t { T _; }; + +union max_align_t +{ + optional_ALIGN_TYPE( char ); + optional_ALIGN_TYPE( short int ); + optional_ALIGN_TYPE( int ); + optional_ALIGN_TYPE( long int ); + optional_ALIGN_TYPE( float ); + optional_ALIGN_TYPE( double ); + optional_ALIGN_TYPE( long double ); + optional_ALIGN_TYPE( char * ); + optional_ALIGN_TYPE( short int * ); + optional_ALIGN_TYPE( int * ); + optional_ALIGN_TYPE( long int * ); + optional_ALIGN_TYPE( float * ); + optional_ALIGN_TYPE( double * ); + optional_ALIGN_TYPE( long double * ); + optional_ALIGN_TYPE( void * ); + +#ifdef HAVE_LONG_LONG + optional_ALIGN_TYPE( long long ); +#endif + + struct Unknown; + + Unknown ( * optional_UNIQUE(_) )( Unknown ); + Unknown * Unknown::* optional_UNIQUE(_); + Unknown ( Unknown::* optional_UNIQUE(_) )( Unknown ); + + struct_t< Unknown ( * )( Unknown) > optional_UNIQUE(_); + struct_t< Unknown * Unknown::* > optional_UNIQUE(_); + struct_t< Unknown ( Unknown::* )(Unknown) > optional_UNIQUE(_); +}; + +#undef optional_UNIQUE +#undef optional_UNIQUE2 +#undef optional_UNIQUE3 + +#undef optional_ALIGN_TYPE + +#elif defined( optional_CONFIG_ALIGN_AS ) // optional_CONFIG_MAX_ALIGN_HACK + +// Use user-specified type for alignment: + +#define optional_ALIGN_AS( unused ) \ + optional_CONFIG_ALIGN_AS + +#else // optional_CONFIG_MAX_ALIGN_HACK + +// Determine POD type to use for alignment: + +#define optional_ALIGN_AS( to_align ) \ + typename type_of_size< alignment_types, alignment_of< to_align >::value >::type + +template +struct alignment_of; + +template +struct alignment_of_hack +{ + char c; + T t; + alignment_of_hack(); +}; + +template +struct alignment_logic +{ + enum { value = A < S ? A : S }; +}; + +template< typename T > +struct alignment_of +{ + enum { value = alignment_logic< + sizeof( alignment_of_hack ) - sizeof(T), sizeof(T) >::value, }; +}; + +template< typename List, size_t N > +struct type_of_size +{ + typedef typename conditional< + N == sizeof( typename List::head ), + typename List::head, + typename type_of_size::type >::type type; +}; + +template< size_t N > +struct type_of_size< nulltype, N > +{ + typedef optional_CONFIG_ALIGN_AS_FALLBACK type; +}; + +template< typename T> +struct struct_t { T _; }; + +#define optional_ALIGN_TYPE( type ) \ + typelist< type , typelist< struct_t< type > + +struct Unknown; + +typedef + optional_ALIGN_TYPE( char ), + optional_ALIGN_TYPE( short ), + optional_ALIGN_TYPE( int ), + optional_ALIGN_TYPE( long ), + optional_ALIGN_TYPE( float ), + optional_ALIGN_TYPE( double ), + optional_ALIGN_TYPE( long double ), + + optional_ALIGN_TYPE( char *), + optional_ALIGN_TYPE( short * ), + optional_ALIGN_TYPE( int * ), + optional_ALIGN_TYPE( long * ), + optional_ALIGN_TYPE( float * ), + optional_ALIGN_TYPE( double * ), + optional_ALIGN_TYPE( long double * ), + + optional_ALIGN_TYPE( Unknown ( * )( Unknown ) ), + optional_ALIGN_TYPE( Unknown * Unknown::* ), + optional_ALIGN_TYPE( Unknown ( Unknown::* )( Unknown ) ), + + nulltype + > > > > > > > > > > > > > > + > > > > > > > > > > > > > > + > > > > > > + alignment_types; + +#undef optional_ALIGN_TYPE + +#endif // optional_CONFIG_MAX_ALIGN_HACK + +/// C++03 constructed union to hold value. + +template< typename T > +union storage_t +{ +private: + friend class optional; + + typedef T value_type; + + storage_t() {} + + storage_t( value_type const & v ) + { + construct_value( v ); + } + + void construct_value( value_type const & v ) + { + ::new( value_ptr() ) value_type( v ); + } + +#if optional_CPP11_OR_GREATER + + storage_t( value_type && v ) + { + construct_value( std::move( v ) ); + } + + void construct_value( value_type && v ) + { + ::new( value_ptr() ) value_type( std::move( v ) ); + } + + template< class... Args > + void emplace( Args&&... args ) + { + ::new( value_ptr() ) value_type( std::forward(args)... ); + } + + template< class U, class... Args > + void emplace( std::initializer_list il, Args&&... args ) + { + ::new( value_ptr() ) value_type( il, std::forward(args)... ); + } + +#endif + + void destruct_value() + { + value_ptr()->~T(); + } + + value_type const * value_ptr() const + { + return as(); + } + + value_type * value_ptr() + { + return as(); + } + + value_type const & value() const optional_ref_qual + { + return * value_ptr(); + } + + value_type & value() optional_ref_qual + { + return * value_ptr(); + } + +#if optional_CPP11_OR_GREATER + + value_type const && value() const optional_refref_qual + { + return std::move( value() ); + } + + value_type && value() optional_refref_qual + { + return std::move( value() ); + } + +#endif + +#if optional_CPP11_OR_GREATER + + using aligned_storage_t = typename std::aligned_storage< sizeof(value_type), alignof(value_type) >::type; + aligned_storage_t data; + +#elif optional_CONFIG_MAX_ALIGN_HACK + + typedef struct { unsigned char data[ sizeof(value_type) ]; } aligned_storage_t; + + max_align_t hack; + aligned_storage_t data; + +#else + typedef optional_ALIGN_AS(value_type) align_as_type; + + typedef struct { align_as_type data[ 1 + ( sizeof(value_type) - 1 ) / sizeof(align_as_type) ]; } aligned_storage_t; + aligned_storage_t data; + +# undef optional_ALIGN_AS + +#endif // optional_CONFIG_MAX_ALIGN_HACK + + void * ptr() optional_noexcept + { + return &data; + } + + void const * ptr() const optional_noexcept + { + return &data; + } + + template + U * as() + { + return reinterpret_cast( ptr() ); + } + + template + U const * as() const + { + return reinterpret_cast( ptr() ); + } +}; + +} // namespace detail + +/// disengaged state tag + +struct nullopt_t +{ + struct init{}; + optional_constexpr nullopt_t( init ) {} +}; + +#if optional_HAVE( CONSTEXPR_11 ) +constexpr nullopt_t nullopt{ nullopt_t::init{} }; +#else +// extra parenthesis to prevent the most vexing parse: +const nullopt_t nullopt(( nullopt_t::init() )); +#endif + +/// optional access error + +class bad_optional_access : public std::logic_error +{ +public: + explicit bad_optional_access() + : logic_error( "bad optional access" ) {} +}; + +/// optional + +template< typename T> +class optional +{ +private: + typedef void (optional::*safe_bool)() const; + +public: + typedef T value_type; + + optional_constexpr optional() optional_noexcept + : has_value_( false ) + , contained() + {} + + optional_constexpr optional( nullopt_t ) optional_noexcept + : has_value_( false ) + , contained() + {} + + optional( optional const & rhs ) + : has_value_( rhs.has_value() ) + { + if ( rhs.has_value() ) + contained.construct_value( rhs.contained.value() ); + } + +#if optional_CPP11_OR_GREATER + optional_constexpr14 optional( optional && rhs ) noexcept( std::is_nothrow_move_constructible::value ) + : has_value_( rhs.has_value() ) + { + if ( rhs.has_value() ) + contained.construct_value( std::move( rhs.contained.value() ) ); + } +#endif + + optional_constexpr optional( value_type const & value ) + : has_value_( true ) + , contained( value ) + {} + +#if optional_CPP11_OR_GREATER + + optional_constexpr optional( value_type && value ) + : has_value_( true ) + , contained( std::move( value ) ) + {} + + template< class... Args > + optional_constexpr explicit optional( nonstd_lite_in_place_type_t(T), Args&&... args ) + : has_value_( true ) + , contained( T( std::forward(args)...) ) + {} + + template< class U, class... Args > + optional_constexpr explicit optional( nonstd_lite_in_place_type_t(T), std::initializer_list il, Args&&... args ) + : has_value_( true ) + , contained( T( il, std::forward(args)...) ) + {} + +#endif // optional_CPP11_OR_GREATER + + ~optional() + { + if ( has_value() ) + contained.destruct_value(); + } + + // assignment + + optional & operator=( nullopt_t ) optional_noexcept + { + reset(); + return *this; + } + + optional & operator=( optional const & rhs ) +#if optional_CPP11_OR_GREATER + noexcept( std::is_nothrow_move_assignable::value && std::is_nothrow_move_constructible::value ) +#endif + { + if ( has_value() == true && rhs.has_value() == false ) reset(); + else if ( has_value() == false && rhs.has_value() == true ) initialize( *rhs ); + else if ( has_value() == true && rhs.has_value() == true ) contained.value() = *rhs; + return *this; + } + +#if optional_CPP11_OR_GREATER + + optional & operator=( optional && rhs ) noexcept + { + if ( has_value() == true && rhs.has_value() == false ) reset(); + else if ( has_value() == false && rhs.has_value() == true ) initialize( std::move( *rhs ) ); + else if ( has_value() == true && rhs.has_value() == true ) contained.value() = std::move( *rhs ); + return *this; + } + + template< class U, + typename = typename std::enable_if< std::is_same< typename std::decay::type, T>::value >::type > + optional & operator=( U && v ) + { + if ( has_value() ) contained.value() = std::forward( v ); + else initialize( T( std::forward( v ) ) ); + return *this; + } + + template< class... Args > + void emplace( Args&&... args ) + { + *this = nullopt; + contained.emplace( std::forward(args)... ); + has_value_ = true; + } + + + template< class U, class... Args > + void emplace( std::initializer_list il, Args&&... args ) + { + *this = nullopt; + contained.emplace( il, std::forward(args)... ); + has_value_ = true; + } + +#endif // optional_CPP11_OR_GREATER + + // swap + + void swap( optional & rhs ) +#if optional_CPP11_OR_GREATER + noexcept( std::is_nothrow_move_constructible::value && noexcept( std::swap( std::declval(), std::declval() ) ) ) +#endif + { + using std::swap; + if ( has_value() == true && rhs.has_value() == true ) { swap( **this, *rhs ); } + else if ( has_value() == false && rhs.has_value() == true ) { initialize( *rhs ); rhs.reset(); } + else if ( has_value() == true && rhs.has_value() == false ) { rhs.initialize( **this ); reset(); } + } + + // observers + + optional_constexpr value_type const * operator ->() const + { + return assert( has_value() ), + contained.value_ptr(); + } + + optional_constexpr14 value_type * operator ->() + { + return assert( has_value() ), + contained.value_ptr(); + } + + optional_constexpr value_type const & operator *() const optional_ref_qual + { + return assert( has_value() ), + contained.value(); + } + + optional_constexpr14 value_type & operator *() optional_ref_qual + { + return assert( has_value() ), + contained.value(); + } + +#if optional_CPP11_OR_GREATER + + optional_constexpr value_type const && operator *() const optional_refref_qual + { + return std::move( **this ); + } + + optional_constexpr14 value_type && operator *() optional_refref_qual + { + return std::move( **this ); + } + +#endif + +#if optional_CPP11_OR_GREATER + optional_constexpr explicit operator bool() const optional_noexcept + { + return has_value(); + } +#else + optional_constexpr operator safe_bool() const optional_noexcept + { + return has_value() ? &optional::this_type_does_not_support_comparisons : 0; + } +#endif + + optional_constexpr bool has_value() const optional_noexcept + { + return has_value_; + } + + optional_constexpr14 value_type const & value() const optional_ref_qual + { + if ( ! has_value() ) + throw bad_optional_access(); + + return contained.value(); + } + + optional_constexpr14 value_type & value() optional_ref_qual + { + if ( ! has_value() ) + throw bad_optional_access(); + + return contained.value(); + } + +#if optional_HAVE( REF_QUALIFIER ) + + optional_constexpr14 value_type const && value() const optional_refref_qual + { + return std::move( value() ); + } + + optional_constexpr14 value_type && value() optional_refref_qual + { + return std::move( value() ); + } + +#endif + +#if optional_CPP11_OR_GREATER + + template< class U > + optional_constexpr value_type value_or( U && v ) const optional_ref_qual + { + return has_value() ? contained.value() : static_cast(std::forward( v ) ); + } + + template< class U > + optional_constexpr value_type value_or( U && v ) const optional_refref_qual + { + return has_value() ? std::move( contained.value() ) : static_cast(std::forward( v ) ); + } + +#else + + template< class U > + optional_constexpr value_type value_or( U const & v ) const + { + return has_value() ? contained.value() : static_cast( v ); + } + +#endif // optional_CPP11_OR_GREATER + + // modifiers + + void reset() optional_noexcept + { + if ( has_value() ) + contained.destruct_value(); + + has_value_ = false; + } + +private: + void this_type_does_not_support_comparisons() const {} + + template< typename V > + void initialize( V const & value ) + { + assert( ! has_value() ); + contained.construct_value( value ); + has_value_ = true; + } + +#if optional_CPP11_OR_GREATER + template< typename V > + void initialize( V && value ) + { + assert( ! has_value() ); + contained.construct_value( std::move( value ) ); + has_value_ = true; + } + +#endif + +private: + bool has_value_; + detail::storage_t< value_type > contained; + +}; + +// Relational operators + +template< typename T, typename U > +inline optional_constexpr bool operator==( optional const & x, optional const & y ) +{ + return bool(x) != bool(y) ? false : !bool( x ) ? true : *x == *y; +} + +template< typename T, typename U > +inline optional_constexpr bool operator!=( optional const & x, optional const & y ) +{ + return !(x == y); +} + +template< typename T, typename U > +inline optional_constexpr bool operator<( optional const & x, optional const & y ) +{ + return (!y) ? false : (!x) ? true : *x < *y; +} + +template< typename T, typename U > +inline optional_constexpr bool operator>( optional const & x, optional const & y ) +{ + return (y < x); +} + +template< typename T, typename U > +inline optional_constexpr bool operator<=( optional const & x, optional const & y ) +{ + return !(y < x); +} + +template< typename T, typename U > +inline optional_constexpr bool operator>=( optional const & x, optional const & y ) +{ + return !(x < y); +} + +// Comparison with nullopt + +template< typename T > +inline optional_constexpr bool operator==( optional const & x, nullopt_t ) optional_noexcept +{ + return (!x); +} + +template< typename T > +inline optional_constexpr bool operator==( nullopt_t, optional const & x ) optional_noexcept +{ + return (!x); +} + +template< typename T > +inline optional_constexpr bool operator!=( optional const & x, nullopt_t ) optional_noexcept +{ + return bool(x); +} + +template< typename T > +inline optional_constexpr bool operator!=( nullopt_t, optional const & x ) optional_noexcept +{ + return bool(x); +} + +template< typename T > +inline optional_constexpr bool operator<( optional const &, nullopt_t ) optional_noexcept +{ + return false; +} + +template< typename T > +inline optional_constexpr bool operator<( nullopt_t, optional const & x ) optional_noexcept +{ + return bool(x); +} + +template< typename T > +inline optional_constexpr bool operator<=( optional const & x, nullopt_t ) optional_noexcept +{ + return (!x); +} + +template< typename T > +inline optional_constexpr bool operator<=( nullopt_t, optional const & ) optional_noexcept +{ + return true; +} + +template< typename T > +inline optional_constexpr bool operator>( optional const & x, nullopt_t ) optional_noexcept +{ + return bool(x); +} + +template< typename T > +inline optional_constexpr bool operator>( nullopt_t, optional const & ) optional_noexcept +{ + return false; +} + +template< typename T > +inline optional_constexpr bool operator>=( optional const &, nullopt_t ) optional_noexcept +{ + return true; +} + +template< typename T > +inline optional_constexpr bool operator>=( nullopt_t, optional const & x ) optional_noexcept +{ + return (!x); +} + +// Comparison with T + +template< typename T, typename U > +inline optional_constexpr bool operator==( optional const & x, U const & v ) +{ + return bool(x) ? *x == v : false; +} + +template< typename T, typename U > +inline optional_constexpr bool operator==( U const & v, optional const & x ) +{ + return bool(x) ? v == *x : false; +} + +template< typename T, typename U > +inline optional_constexpr bool operator!=( optional const & x, U const & v ) +{ + return bool(x) ? *x != v : true; +} + +template< typename T, typename U > +inline optional_constexpr bool operator!=( U const & v, optional const & x ) +{ + return bool(x) ? v != *x : true; +} + +template< typename T, typename U > +inline optional_constexpr bool operator<( optional const & x, U const & v ) +{ + return bool(x) ? *x < v : true; +} + +template< typename T, typename U > +inline optional_constexpr bool operator<( U const & v, optional const & x ) +{ + return bool(x) ? v < *x : false; +} + +template< typename T, typename U > +inline optional_constexpr bool operator<=( optional const & x, U const & v ) +{ + return bool(x) ? *x <= v : true; +} + +template< typename T, typename U > +inline optional_constexpr bool operator<=( U const & v, optional const & x ) +{ + return bool(x) ? v <= *x : false; +} + +template< typename T, typename U > +inline optional_constexpr bool operator>( optional const & x, U const & v ) +{ + return bool(x) ? *x > v : false; +} + +template< typename T, typename U > +inline optional_constexpr bool operator>( U const & v, optional const & x ) +{ + return bool(x) ? v > *x : true; +} + +template< typename T, typename U > +inline optional_constexpr bool operator>=( optional const & x, U const & v ) +{ + return bool(x) ? *x >= v : false; +} + +template< typename T, typename U > +inline optional_constexpr bool operator>=( U const & v, optional const & x ) +{ + return bool(x) ? v >= *x : true; +} + +// Specialized algorithms + +template< typename T > +void swap( optional & x, optional & y ) +#if optional_CPP11_OR_GREATER + noexcept( noexcept( x.swap(y) ) ) +#endif +{ + x.swap( y ); +} + +#if optional_CPP11_OR_GREATER + +template< class T > +optional_constexpr optional< typename std::decay::type > make_optional( T && v ) +{ + return optional< typename std::decay::type >( std::forward( v ) ); +} + +template< class T, class...Args > +optional_constexpr optional make_optional( Args&&... args ) +{ + return optional( in_place, std::forward(args)...); +} + +template< class T, class U, class... Args > +optional_constexpr optional make_optional( std::initializer_list il, Args&&... args ) +{ + return optional( in_place, il, std::forward(args)...); +} + +#else + +template< typename T > +optional make_optional( T const & v ) +{ + return optional( v ); +} + +#endif // optional_CPP11_OR_GREATER + +} // namespace optional + +using namespace optional_lite; + +} // namespace nonstd + +#if optional_CPP11_OR_GREATER + +// specialize the std::hash algorithm: + +namespace std { + +template< class T > +struct hash< nonstd::optional > +{ +public: + std::size_t operator()( nonstd::optional const & v ) const optional_noexcept + { + return bool( v ) ? hash()( *v ) : 0; + } +}; + +} //namespace std + +#endif // optional_CPP11_OR_GREATER + +#ifdef __clang__ +# pragma clang diagnostic pop +#elif defined __GNUC__ +# pragma GCC diagnostic pop +#endif + +#endif // have C++17 std::optional + +#endif // NONSTD_OPTIONAL_LITE_HPP diff --git a/include/Blackboard/blackboard.h b/include/Blackboard/blackboard.h new file mode 100644 index 000000000..1497e64bf --- /dev/null +++ b/include/Blackboard/blackboard.h @@ -0,0 +1,59 @@ +#ifndef BLACKBOARD_H +#define BLACKBOARD_H + +#include +#include +#include +#include +#include + +#include + +namespace BT{ + +class BlackboardImpl +{ +public: + + virtual ~BlackboardImpl() = default; + + virtual const SafeAny::Any* get(const std::string& key) const = 0; + virtual void set(const std::string& key, const SafeAny::Any& value) = 0; +}; + + +// Blackboard is the front-end to be used by the developer. +// Even if the abstract class BlackboardImpl can be used directly, +// the templatized methods set() and get() are more user-friendly +class Blackboard +{ +public: + + Blackboard( std::unique_ptr implementation): + impl_( std::move(implementation ) ) + { } + + virtual ~Blackboard() = default; + + template bool get(const std::string& key, T& value) const + { + const SafeAny::Any* val = impl_->get(key); + if( !val ){ return false; } + + value = val->convert(); + return true; + } + + template void set(const std::string& key, const T& value) { + impl_->set(key, SafeAny::Any(value)); + } + +private: + + std::unique_ptr impl_; +}; + +} + + +#endif // BLACKBOARD_H diff --git a/include/Blackboard/blackboard_local.h b/include/Blackboard/blackboard_local.h new file mode 100644 index 000000000..c783b1370 --- /dev/null +++ b/include/Blackboard/blackboard_local.h @@ -0,0 +1,34 @@ +#ifndef BLACKBOARD_LOCAL_H +#define BLACKBOARD_LOCAL_H + +#include "blackboard.h" + +namespace BT{ + +class BlackboardLocal: public BlackboardImpl +{ +public: + + BlackboardLocal() {} + + virtual const SafeAny::Any* get(const std::string& key) const override + { + auto it = storage_.find(key); + if( it == storage_.end() ){ return nullptr; } + return &(it->second); + } + + virtual void set(const std::string& key, const SafeAny::Any& value) override + { + storage_[key] = value; + } + + +private: + std::unordered_map storage_; + +}; + +} + +#endif // BLACKBOARD_LOCAL_H diff --git a/include/SafeAny/any.hpp b/include/SafeAny/any.hpp new file mode 100644 index 000000000..6f87b9c31 --- /dev/null +++ b/include/SafeAny/any.hpp @@ -0,0 +1,461 @@ +// +// Implementation of N4562 std::experimental::any (merged into C++17) for C++11 compilers. +// +// See also: +// + http://en.cppreference.com/w/cpp/any +// + http://en.cppreference.com/w/cpp/experimental/any +// + http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2015/n4562.html#any +// + https://cplusplus.github.io/LWG/lwg-active.html#2509 +// +// +// Copyright (c) 2016 Denilson das Merc�s Amorim +// +// Distributed under the Boost Software License, Version 1.0. (See accompanying +// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) +// +#ifndef LINB_ANY_HPP +#define LINB_ANY_HPP +#pragma once +#include +#include +#include + +namespace linb +{ + +class bad_any_cast : public std::bad_cast +{ +public: + const char* what() const noexcept override + { + return "bad any cast"; + } +}; + +class any final +{ +public: + /// Constructs an object of type any with an empty state. + any() : + vtable(nullptr) + { + } + + /// Constructs an object of type any with an equivalent state as other. + any(const any& rhs) : + vtable(rhs.vtable) + { + if(!rhs.empty()) + { + rhs.vtable->copy(rhs.storage, this->storage); + } + } + + /// Constructs an object of type any with a state equivalent to the original state of other. + /// rhs is left in a valid but otherwise unspecified state. + any(any&& rhs) noexcept : + vtable(rhs.vtable) + { + if(!rhs.empty()) + { + rhs.vtable->move(rhs.storage, this->storage); + rhs.vtable = nullptr; + } + } + + /// Same effect as this->clear(). + ~any() + { + this->clear(); + } + + /// Constructs an object of type any that contains an object of type T direct-initialized with std::forward(value). + /// + /// T shall satisfy the CopyConstructible requirements, otherwise the program is ill-formed. + /// This is because an `any` may be copy constructed into another `any` at any time, so a copy should always be allowed. + template::type, any>::value>::type> + any(ValueType&& value) + { + static_assert(std::is_copy_constructible::type>::value, + "T shall satisfy the CopyConstructible requirements."); + this->construct(std::forward(value)); + } + + /// Has the same effect as any(rhs).swap(*this). No effects if an exception is thrown. + any& operator=(const any& rhs) + { + any(rhs).swap(*this); + return *this; + } + + /// Has the same effect as any(std::move(rhs)).swap(*this). + /// + /// The state of *this is equivalent to the original state of rhs and rhs is left in a valid + /// but otherwise unspecified state. + any& operator=(any&& rhs) noexcept + { + any(std::move(rhs)).swap(*this); + return *this; + } + + /// Has the same effect as any(std::forward(value)).swap(*this). No effect if a exception is thrown. + /// + /// T shall satisfy the CopyConstructible requirements, otherwise the program is ill-formed. + /// This is because an `any` may be copy constructed into another `any` at any time, so a copy should always be allowed. + template::type, any>::value>::type> + any& operator=(ValueType&& value) + { + static_assert(std::is_copy_constructible::type>::value, + "T shall satisfy the CopyConstructible requirements."); + any(std::forward(value)).swap(*this); + return *this; + } + + /// If not empty, destroys the contained object. + void clear() noexcept + { + if(!empty()) + { + this->vtable->destroy(storage); + this->vtable = nullptr; + } + } + + /// Returns true if *this has no contained object, otherwise false. + bool empty() const noexcept + { + return this->vtable == nullptr; + } + + /// If *this has a contained object of type T, typeid(T); otherwise typeid(void). + const std::type_info& type() const noexcept + { + return empty()? typeid(void) : this->vtable->type(); + } + + /// Exchange the states of *this and rhs. + void swap(any& rhs) noexcept + { + if(this->vtable != rhs.vtable) + { + any tmp(std::move(rhs)); + + // move from *this to rhs. + rhs.vtable = this->vtable; + if(this->vtable != nullptr) + { + this->vtable->move(this->storage, rhs.storage); + //this->vtable = nullptr; -- uneeded, see below + } + + // move from tmp (previously rhs) to *this. + this->vtable = tmp.vtable; + if(tmp.vtable != nullptr) + { + tmp.vtable->move(tmp.storage, this->storage); + tmp.vtable = nullptr; + } + } + else // same types + { + if(this->vtable != nullptr) + this->vtable->swap(this->storage, rhs.storage); + } + } + +private: // Storage and Virtual Method Table + + union storage_union + { + using stack_storage_t = typename std::aligned_storage<2 * sizeof(void*), std::alignment_of::value>::type; + + void* dynamic; + stack_storage_t stack; // 2 words for e.g. shared_ptr + }; + + /// Base VTable specification. + struct vtable_type + { + // Note: The caller is responssible for doing .vtable = nullptr after destructful operations + // such as destroy() and/or move(). + + /// The type of the object this vtable is for. + const std::type_info& (*type)() noexcept; + + /// Destroys the object in the union. + /// The state of the union after this call is unspecified, caller must ensure not to use src anymore. + void(*destroy)(storage_union&) noexcept; + + /// Copies the **inner** content of the src union into the yet unitialized dest union. + /// As such, both inner objects will have the same state, but on separate memory locations. + void(*copy)(const storage_union& src, storage_union& dest); + + /// Moves the storage from src to the yet unitialized dest union. + /// The state of src after this call is unspecified, caller must ensure not to use src anymore. + void(*move)(storage_union& src, storage_union& dest) noexcept; + + /// Exchanges the storage between lhs and rhs. + void(*swap)(storage_union& lhs, storage_union& rhs) noexcept; + }; + + /// VTable for dynamically allocated storage. + template + struct vtable_dynamic + { + static const std::type_info& type() noexcept + { + return typeid(T); + } + + static void destroy(storage_union& storage) noexcept + { + //assert(reinterpret_cast(storage.dynamic)); + delete reinterpret_cast(storage.dynamic); + } + + static void copy(const storage_union& src, storage_union& dest) + { + dest.dynamic = new T(*reinterpret_cast(src.dynamic)); + } + + static void move(storage_union& src, storage_union& dest) noexcept + { + dest.dynamic = src.dynamic; + src.dynamic = nullptr; + } + + static void swap(storage_union& lhs, storage_union& rhs) noexcept + { + // just exchage the storage pointers. + std::swap(lhs.dynamic, rhs.dynamic); + } + }; + + /// VTable for stack allocated storage. + template + struct vtable_stack + { + static const std::type_info& type() noexcept + { + return typeid(T); + } + + static void destroy(storage_union& storage) noexcept + { + reinterpret_cast(&storage.stack)->~T(); + } + + static void copy(const storage_union& src, storage_union& dest) + { + new (&dest.stack) T(reinterpret_cast(src.stack)); + } + + static void move(storage_union& src, storage_union& dest) noexcept + { + // one of the conditions for using vtable_stack is a nothrow move constructor, + // so this move constructor will never throw a exception. + new (&dest.stack) T(std::move(reinterpret_cast(src.stack))); + destroy(src); + } + + static void swap(storage_union& lhs, storage_union& rhs) noexcept + { + storage_union tmp_storage; + move(rhs, tmp_storage); + move(lhs, rhs); + move(tmp_storage, lhs); + } + }; + + /// Whether the type T must be dynamically allocated or can be stored on the stack. + template + struct requires_allocation : + std::integral_constant::value // N4562 �6.3/3 [any.class] + && sizeof(T) <= sizeof(storage_union::stack) + && std::alignment_of::value <= std::alignment_of::value)> + {}; + + /// Returns the pointer to the vtable of the type T. + template + static vtable_type* vtable_for_type() + { + using VTableType = typename std::conditional::value, vtable_dynamic, vtable_stack>::type; + static vtable_type table = { + VTableType::type, VTableType::destroy, + VTableType::copy, VTableType::move, + VTableType::swap, + }; + return &table; + } + +protected: + template + friend const T* any_cast(const any* operand) noexcept; + template + friend T* any_cast(any* operand) noexcept; + + /// Same effect as is_same(this->type(), t); + bool is_typed(const std::type_info& t) const + { + return is_same(this->type(), t); + } + + /// Checks if two type infos are the same. + /// + /// If ANY_IMPL_FAST_TYPE_INFO_COMPARE is defined, checks only the address of the + /// type infos, otherwise does an actual comparision. Checking addresses is + /// only a valid approach when there's no interaction with outside sources + /// (other shared libraries and such). + static bool is_same(const std::type_info& a, const std::type_info& b) + { +#ifdef ANY_IMPL_FAST_TYPE_INFO_COMPARE + return &a == &b; +#else + return a == b; +#endif + } + + /// Casts (with no type_info checks) the storage pointer as const T*. + template + const T* cast() const noexcept + { + return requires_allocation::type>::value? + reinterpret_cast(storage.dynamic) : + reinterpret_cast(&storage.stack); + } + + /// Casts (with no type_info checks) the storage pointer as T*. + template + T* cast() noexcept + { + return requires_allocation::type>::value? + reinterpret_cast(storage.dynamic) : + reinterpret_cast(&storage.stack); + } + +private: + storage_union storage; // on offset(0) so no padding for align + vtable_type* vtable; + + template + typename std::enable_if::value>::type + do_construct(ValueType&& value) + { + storage.dynamic = new T(std::forward(value)); + } + + template + typename std::enable_if::value>::type + do_construct(ValueType&& value) + { + new (&storage.stack) T(std::forward(value)); + } + + /// Chooses between stack and dynamic allocation for the type decay_t, + /// assigns the correct vtable, and constructs the object on our storage. + template + void construct(ValueType&& value) + { + using T = typename std::decay::type; + + this->vtable = vtable_for_type(); + + do_construct(std::forward(value)); + } +}; + + + +namespace detail +{ + template + inline ValueType any_cast_move_if_true(typename std::remove_reference::type* p, std::true_type) + { + return std::move(*p); + } + + template + inline ValueType any_cast_move_if_true(typename std::remove_reference::type* p, std::false_type) + { + return *p; + } +} + +/// Performs *any_cast>>(&operand), or throws bad_any_cast on failure. +template +inline ValueType any_cast(const any& operand) +{ + auto p = any_cast::type>::type>(&operand); + if(p == nullptr) throw bad_any_cast(); + return *p; +} + +/// Performs *any_cast>(&operand), or throws bad_any_cast on failure. +template +inline ValueType any_cast(any& operand) +{ + auto p = any_cast::type>(&operand); + if(p == nullptr) throw bad_any_cast(); + return *p; +} + +/// +/// If ANY_IMPL_ANYCAST_MOVEABLE is not defined, does as N4562 specifies: +/// Performs *any_cast>(&operand), or throws bad_any_cast on failure. +/// +/// If ANY_IMPL_ANYCAST_MOVEABLE is defined, does as LWG Defect 2509 specifies: +/// If ValueType is MoveConstructible and isn't a lvalue reference, performs +/// std::move(*any_cast>(&operand)), otherwise +/// *any_cast>(&operand). Throws bad_any_cast on failure. +/// +template +inline ValueType any_cast(any&& operand) +{ +#ifdef ANY_IMPL_ANY_CAST_MOVEABLE + // https://cplusplus.github.io/LWG/lwg-active.html#2509 + using can_move = std::integral_constant::value + && !std::is_lvalue_reference::value>; +#else + using can_move = std::false_type; +#endif + + auto p = any_cast::type>(&operand); + if(p == nullptr) throw bad_any_cast(); + return detail::any_cast_move_if_true(p, can_move()); +} + +/// If operand != nullptr && operand->type() == typeid(ValueType), a pointer to the object +/// contained by operand, otherwise nullptr. +template +inline const T* any_cast(const any* operand) noexcept +{ + if(operand == nullptr || !operand->is_typed(typeid(T))) + return nullptr; + else + return operand->cast(); +} + +/// If operand != nullptr && operand->type() == typeid(ValueType), a pointer to the object +/// contained by operand, otherwise nullptr. +template +inline T* any_cast(any* operand) noexcept +{ + if(operand == nullptr || !operand->is_typed(typeid(T))) + return nullptr; + else + return operand->cast(); +} + +} + +namespace std +{ + inline void swap(linb::any& lhs, linb::any& rhs) noexcept + { + lhs.swap(rhs); + } +} + +#endif diff --git a/include/SafeAny/safe_any.hpp b/include/SafeAny/safe_any.hpp new file mode 100644 index 000000000..8d55eace7 --- /dev/null +++ b/include/SafeAny/safe_any.hpp @@ -0,0 +1,500 @@ +#ifndef SAFE_ANY_VARNUMBER_H +#define SAFE_ANY_VARNUMBER_H + +#include +#include +#include +#include +#include +#include +#include "any.hpp" + +namespace SafeAny{ + +// Version of string that uses only two words. Good for small object optimization in linb::any +class SimpleString +{ +public: + SimpleString(const std::string& str): SimpleString(str.data(), str.size()) + { } + SimpleString(const char* data): SimpleString( data, strlen(data) ) + { } + + SimpleString(const char* data, std::size_t size): _size(size) + { + _data = new char[_size+1]; + strncpy(_data, data, _size); + _data[_size] = '\0'; + } + + SimpleString(const SimpleString& other): SimpleString(other.data(), other.size()) + { } + + + ~SimpleString() { + if(_data){ + delete[] _data; + } + } + + std::string toStdString() const + { + return std::string(_data, _size); + } + + const char* data() const { return _data;} + + std::size_t size() const { return _size;} + +private: + char* _data; + std::size_t _size; +}; + + + +class Any +{ + +public: + + Any() {} + + ~Any() = default; + + template Any(const T& value) : _any(value) + { } + + template T convert( ) const; + + template T extract( ) const + { + return linb::any_cast(_any); + } + + const std::type_info& type() const { return _any.type(); } + +private: + + linb::any _any; +}; + +//---------------------------------------------- +//specialization for std::string +template <> inline Any::Any(const std::string& str) +{ + _any = linb::any(SimpleString(str)); +} + +template <> inline std::string Any::extract() const +{ + return linb::any_cast(_any).toStdString(); +} + +namespace details{ + + +template +using EnableIf = typename std::enable_if< BoolCondition::value, void>::type; + +template +struct is_integer : std::integral_constant::value + && !std::is_same::value + && !std::is_same::value> +{}; + +template +struct is_same_real : std::integral_constant::value + && std::is_floating_point::value > +{}; + + +template +struct is_safe_integer_conversion + : std::integral_constant::value + && is_integer::value + && sizeof(From) < sizeof(To) +&& std::is_signed::value == std::is_signed::value> +{}; + +template +struct is_convertible_type + : std::integral_constant::value + || std::is_floating_point::value + || std::is_same::value + || std::is_same::value + || std::is_same::value + || std::is_same::value> +{}; + +template +struct float_conversion + : std::integral_constant::value + && std::is_floating_point::value && !std::is_same::value > +{}; + +template +struct unsigned_to_smaller_conversion + : std::integral_constant::value + && is_integer::value + && (sizeof(From) > sizeof(To)) +&& !std::is_signed::value +&& !std::is_signed::value > +{}; + +template +struct signed_to_smaller_conversion + : std::integral_constant::value + && is_integer::value + && (sizeof(From) > sizeof(To)) +&& std::is_signed::value +&& std::is_signed::value > +{}; + +//--------------------------- +template +struct signed_to_smaller_unsigned_conversion + : std::integral_constant::value + && is_integer::value + && sizeof(From) >= sizeof(To) +&& std::is_signed::value +&& !std::is_signed::value > +{}; + +template +struct signed_to_larger_unsigned_conversion + : std::integral_constant::value + && is_integer::value + && sizeof(From) < sizeof(To) +&& std::is_signed::value +&& !std::is_signed::value > +{}; + +template +struct unsigned_to_smaller_signed_conversion + : std::integral_constant::value + && is_integer::value + && (sizeof(From) >= sizeof(To)) +&& !std::is_signed::value +&& std::is_signed::value > +{}; + +template +struct unsigned_to_larger_signed_conversion + : std::integral_constant::value + && is_integer::value + && sizeof(From) < sizeof(To) +&& !std::is_signed::value +&& std::is_signed::value > +{}; + +template +struct floating_to_signed_conversion + : std::integral_constant::value + && is_integer::value + && std::is_signed::value > +{}; + +template +struct floating_to_unsigned_conversion + : std::integral_constant::value + && is_integer::value + && !std::is_signed::value > +{}; + +template +struct integer_to_floating_conversion + : std::integral_constant::value + && std::is_floating_point::value > +{}; + +template +inline void checkUpperLimit(const From& from) +{ + if ((sizeof(To) < sizeof(From)) && + (from > static_cast(std::numeric_limits::max()))) { + throw std::runtime_error("Value too large."); + } + else if (static_cast(from) > std::numeric_limits::max()) { + throw std::runtime_error("Value too large."); + } +} + +template +inline void checkUpperLimitFloat(const From& from) +{ + if (from > std::numeric_limits::max()){ + throw std::runtime_error("Value too large."); + } +} + +template +inline void checkLowerLimitFloat(const From& from) +{ + if (from < -std::numeric_limits::max()){ + throw std::runtime_error("Value too small."); + } +} + +template +inline void checkLowerLimit(const From& from) +{ + if (from < std::numeric_limits::min()){ + throw std::runtime_error("Value too small."); + } +} + +template +inline void checkTruncation(const From& from) +{ + if( from != static_cast(static_cast( from))){ + throw std::runtime_error("Floating point truncated"); + } +} + + +//----------------------- Implementation ---------------------------------------------- + +template inline +typename std::enable_if< !is_convertible_type::value, void>::type +convert_impl( const SRC& , DST& ) +{ + throw std::runtime_error("Not convertible"); +} + + +template inline +EnableIf< std::is_same> +convert_impl( const SRC& from, DST& target ) +{ + target = from; +} + +template inline +EnableIf< is_safe_integer_conversion> +convert_impl( const SRC& from, DST& target ) +{ + target = static_cast( from); +} + +template inline +EnableIf< float_conversion> +convert_impl( const SRC& from, DST& target ) +{ + checkTruncation(from); + target = static_cast( from ); +} + + +template inline +EnableIf< unsigned_to_smaller_conversion> +convert_impl( const SRC& from, DST& target ) +{ + checkUpperLimit(from); + target = static_cast( from); +} + +template inline +EnableIf< signed_to_smaller_conversion> +convert_impl( const SRC& from, DST& target ) +{ + checkLowerLimit(from); + checkUpperLimit(from); + target = static_cast( from); +} + + +template inline +EnableIf< signed_to_smaller_unsigned_conversion> +convert_impl( const SRC& from, DST& target ) +{ + if (from < 0 ) + throw std::runtime_error("Value is negative and can't be converted to signed"); + + checkUpperLimit(from); + target = static_cast( from ); +} + + +template inline +EnableIf< signed_to_larger_unsigned_conversion> +convert_impl( const SRC& from, DST& target ) +{ + //std::cout << "signed_to_larger_unsigned_conversion" << std::endl; + + if ( from < 0 ) + throw std::runtime_error("Value is negative and can't be converted to signed"); + + target = static_cast( from); +} + +template inline +EnableIf< unsigned_to_larger_signed_conversion> +convert_impl( const SRC& from, DST& target ) +{ + //std::cout << "unsigned_to_larger_signed_conversion" << std::endl; + target = static_cast( from); +} + +template inline +EnableIf< unsigned_to_smaller_signed_conversion> +convert_impl( const SRC& from, DST& target ) +{ + checkUpperLimit(from); + target = static_cast( from); +} + +template inline +EnableIf< floating_to_signed_conversion> +convert_impl( const SRC& from, DST& target ) +{ + checkLowerLimitFloat(from); + checkLowerLimitFloat(from); + + if( from != static_cast(static_cast( from))) + throw std::runtime_error("Floating point truncated"); + + target = static_cast( from); +} + +template inline +EnableIf< floating_to_unsigned_conversion> +convert_impl( const SRC& from, DST& target ) +{ + if ( from < 0 ) + throw std::runtime_error("Value is negative and can't be converted to signed"); + + checkLowerLimitFloat(from); + + if( from != static_cast(static_cast( from))) + throw std::runtime_error("Floating point truncated"); + + target = static_cast( from); +} + +template inline +EnableIf< integer_to_floating_conversion> +convert_impl( const SRC& from, DST& target ) +{ + checkTruncation(from); + target = static_cast( from); +} + +} //end namespace details + + +template inline +DST Any::convert() const +{ + using details::convert_impl; + DST out; + + const auto& type = _any.type(); + + if( ! details::is_convertible_type::value ) + { + return linb::any_cast(_any); + } + + if( type == typeid(bool)) { + return DST( extract() ); + } + else if( type == typeid(char)) { + convert_impl( int8_t(extract()), out ); + } + else if( type == typeid(int8_t)) { + convert_impl(extract(), out ); + } + else if( type == typeid(int16_t)) { + convert_impl(extract(), out ); + } + else if( type == typeid(int32_t)) { + convert_impl(extract(), out ); + } + else if( type == typeid(int64_t)) { + convert_impl(extract(), out ); + } + else if( type == typeid(uint8_t)) { + convert_impl(extract(), out ); + } + else if( type == typeid(uint16_t)) { + convert_impl(extract(), out ); + } + else if( type == typeid(uint32_t)) { + convert_impl(extract(), out ); + } + else if( type == typeid(uint64_t)) { + convert_impl(extract(), out ); + } + else if( type == typeid(float)) { + convert_impl(extract(), out ); + } + else if( type == typeid(double)) { + convert_impl(extract(), out ); + } + else if( type == typeid(SimpleString) ) + { + throw std::runtime_error("String can not be converted to another type implicitly"); + } + else{ + return linb::any_cast(_any); + } + + return out; +} + +template<> inline std::string Any::convert() const +{ + const auto& type = _any.type(); + + if( type == typeid(SimpleString) ) + { + return extract().toStdString(); + } + else if( type == typeid(bool)) { + return std::to_string( extract() ); + } + else if( type == typeid(char)) { + return std::to_string( extract() ); + } + else if( type == typeid(int8_t)) { + return std::to_string( extract() ); + } + else if( type == typeid(int16_t)) { + return std::to_string( extract() ); + } + else if( type == typeid(int32_t)) { + return std::to_string( extract() ); + } + else if( type == typeid(int64_t)) { + return std::to_string( extract() ); + } + else if( type == typeid(uint8_t)) { + return std::to_string( extract() ); + } + else if( type == typeid(uint16_t)) { + return std::to_string( extract() ); + } + else if( type == typeid(uint32_t)) { + return std::to_string( extract() ); + } + else if( type == typeid(uint64_t)) { + return std::to_string( extract() ); + } + else if( type == typeid(float)) { + return std::to_string( extract() ); + } + else if( type == typeid(double)) { + return std::to_string( extract() ); + } + + throw std::runtime_error("Conversion to std::string failed"); +} + + +} // end namespace VarNumber + + +#endif // VARNUMBER_H diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 4edb12374..a9031d2ef 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -19,16 +19,18 @@ #include #include +#include "non_std/optional.hpp" #include "behavior_tree_core/tick_engine.h" #include "behavior_tree_core/exceptions.h" #include "behavior_tree_core/signal.h" #include "behavior_tree_core/basic_types.h" +#include "Blackboard/blackboard.h" namespace BT { // We call Parameters the set of Key/Values that can be read from file and are // used to parametrize an object. It is up to the user's code to parse the string. -typedef std::map NodeParameters; +typedef std::unordered_map NodeParameters; typedef std::chrono::high_resolution_clock::time_point TimePoint; @@ -62,6 +64,10 @@ class TreeNode void setStatus(NodeStatus new_status); + void setBlackboard(std::shared_ptr bb); + + const std::shared_ptr& blackboard() const; + const std::string& name() const; /// Blocking funtion that will sleep until the setStatus() is called with @@ -101,14 +107,26 @@ class TreeNode virtual BT::NodeStatus tick() = 0; template - T getParam(const std::string& key) const + nonstd::optional getParam(const std::string& key) const { auto it = parameters_.find(key); if (it == parameters_.end()) { - throw std::invalid_argument(std::string("Can't find the parameter with key: ") + key); + return nonstd::nullopt; + } + const std::string& str = it->second; + + // check if it follows this ${pattern}, if it does, search inside the blackboard + if( bb_ && str.size()>=4 && str[0] == '$' && str[1] == '{' && str.back() == '}') + { + const std::string stripped_key( &str[2], str.size()-3); + T value; + bool found = bb_->get(stripped_key, value); + return found ? nonstd::optional(value) : nonstd::nullopt; + } + else{ + return convertFromString(str.c_str()); } - return convertFromString(it->second.c_str()); } /// registrationName() is set by the BehaviorTreeFactory @@ -132,6 +150,8 @@ class TreeNode std::string registration_name_; const NodeParameters parameters_; + + std::shared_ptr bb_; }; typedef std::shared_ptr TreeNodePtr; diff --git a/src/decorator_repeat_node.cpp b/src/decorator_repeat_node.cpp index 40139e9b5..fa32583df 100644 --- a/src/decorator_repeat_node.cpp +++ b/src/decorator_repeat_node.cpp @@ -23,8 +23,12 @@ DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, unsigned int N } DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, const NodeParameters& params) - : DecoratorNode(name, params), NTries_(getParam(NUM_CYCLES)), TryIndx_(0) + : DecoratorNode(name, params), NTries_(1), TryIndx_(0) { + auto param = getParam(NUM_CYCLES); + if(param){ + NTries_ = param.value(); + } } NodeStatus DecoratorRepeatNode::tick() diff --git a/src/decorator_retry_node.cpp b/src/decorator_retry_node.cpp index 00f123850..1913fadcc 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorator_retry_node.cpp @@ -23,8 +23,12 @@ DecoratorRetryNode::DecoratorRetryNode(const std::string& name, unsigned int NTr } DecoratorRetryNode::DecoratorRetryNode(const std::string& name, const NodeParameters& params) - : DecoratorNode(name, params), NTries_(getParam(NUM_ATTEMPTS)), TryIndx_(0) + : DecoratorNode(name, params), NTries_(1), TryIndx_(0) { + auto param = getParam(NUM_ATTEMPTS); + if(param){ + NTries_ = param.value(); + } } NodeStatus DecoratorRetryNode::tick() diff --git a/src/fallback_node_with_memory.cpp b/src/fallback_node_with_memory.cpp index 81b49bc46..917f69837 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/fallback_node_with_memory.cpp @@ -25,8 +25,12 @@ FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string& name, ResetPol } FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string& name, const NodeParameters& params) - : ControlNode::ControlNode(name, params), current_child_idx_(0), reset_policy_(getParam(RESET_POLICY)) + : ControlNode::ControlNode(name, params), current_child_idx_(0), reset_policy_(ON_SUCCESS_OR_FAILURE) { + auto param = getParam(RESET_POLICY); + if(param){ + reset_policy_ = param.value(); + } } NodeStatus FallbackNodeWithMemory::tick() diff --git a/src/sequence_node_with_memory.cpp b/src/sequence_node_with_memory.cpp index e7afff70e..09504ed65 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/sequence_node_with_memory.cpp @@ -25,8 +25,12 @@ SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, ResetPol } SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, const NodeParameters& params) - : ControlNode::ControlNode(name, params), current_child_idx_(0), reset_policy_(getParam(RESET_POLICY)) + : ControlNode::ControlNode(name, params), current_child_idx_(0), reset_policy_(ON_SUCCESS_OR_FAILURE) { + auto param = getParam(RESET_POLICY); + if(param){ + reset_policy_ = param.value(); + } } NodeStatus SequenceNodeWithMemory::tick() diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 9bd529270..721552e94 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -49,6 +49,16 @@ void TreeNode::setStatus(NodeStatus new_status) } } +void TreeNode::setBlackboard(std::shared_ptr bb) +{ + bb_ = bb; +} + +const std::shared_ptr& TreeNode::blackboard() const +{ + return bb_; +} + NodeStatus TreeNode::status() const { std::lock_guard LockGuard(state_mutex_); From 8bc80bb7388a91c80edea37de58310d79ea08b6e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 21 Aug 2018 15:13:28 +0200 Subject: [PATCH 086/125] BB updated and example added --- 3rdparty/non_std/optional.hpp | 14 +- CMakeLists.txt | 6 +- {gtest => examples}/simple_example.cpp | 8 +- examples/tutorial_blackboard.cpp | 160 +++++++ include/Blackboard/blackboard.h | 28 +- include/SafeAny/convert_impl.hpp | 306 +++++++++++++ include/SafeAny/safe_any.hpp | 549 +++++------------------ include/SafeAny/simple_string.hpp | 51 +++ include/behavior_tree_core/action_node.h | 5 + include/behavior_tree_core/basic_types.h | 17 + include/behavior_tree_core/bt_factory.h | 25 +- include/behavior_tree_core/tree_node.h | 25 +- 12 files changed, 723 insertions(+), 471 deletions(-) rename {gtest => examples}/simple_example.cpp (93%) create mode 100644 examples/tutorial_blackboard.cpp create mode 100644 include/SafeAny/convert_impl.hpp create mode 100644 include/SafeAny/simple_string.hpp diff --git a/3rdparty/non_std/optional.hpp b/3rdparty/non_std/optional.hpp index 34b0e8d2b..e8e45518b 100644 --- a/3rdparty/non_std/optional.hpp +++ b/3rdparty/non_std/optional.hpp @@ -267,7 +267,7 @@ namespace nonstd { // type traits needed: -namespace nonstd { namespace optional_lite { namespace detail { +namespace BT { namespace optional_lite { namespace detail { #if optional_HAVE( CONDITIONAL ) using std::conditional; @@ -284,7 +284,7 @@ namespace nonstd { namespace optional_lite { namespace detail { #ifndef nonstd_lite_HAVE_IN_PLACE_TYPES -namespace nonstd { +namespace BT { namespace detail { @@ -324,8 +324,8 @@ inline in_place_t in_place_index( detail::in_place_index_tag = detail::in_pla // mimic templated typedef: -#define nonstd_lite_in_place_type_t( T) nonstd::in_place_t(&)( nonstd::detail::in_place_type_tag ) -#define nonstd_lite_in_place_index_t(T) nonstd::in_place_t(&)( nonstd::detail::in_place_index_tag ) +#define nonstd_lite_in_place_type_t( T) BT::in_place_t(&)( BT::detail::in_place_type_tag ) +#define nonstd_lite_in_place_index_t(T) BT::in_place_t(&)( BT::detail::in_place_index_tag ) #define nonstd_lite_HAVE_IN_PLACE_TYPES 1 @@ -337,7 +337,7 @@ inline in_place_t in_place_index( detail::in_place_index_tag = detail::in_pla // optional: // -namespace nonstd { namespace optional_lite { +namespace BT { namespace optional_lite { /// class optional @@ -1188,10 +1188,10 @@ using namespace optional_lite; namespace std { template< class T > -struct hash< nonstd::optional > +struct hash< BT::optional > { public: - std::size_t operator()( nonstd::optional const & v ) const optional_noexcept + std::size_t operator()( BT::optional const & v ) const optional_noexcept { return bool( v ) ? hash()( *v ) : 0; } diff --git a/CMakeLists.txt b/CMakeLists.txt index 9f1010fea..27e05a410 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -133,10 +133,14 @@ if( ZMQ_FOUND ) target_link_libraries(bt_recorder ${BEHAVIOR_TRE_LIBRARIES} ) endif() -add_executable(simple_example gtest/simple_example.cpp ) +add_executable(simple_example examples/simple_example.cpp ) target_link_libraries(simple_example ${BEHAVIOR_TRE_LIBRARIES} ) +add_executable(tutorial_blackboard examples/tutorial_blackboard.cpp ) +target_link_libraries(tutorial_blackboard ${BEHAVIOR_TRE_LIBRARIES} ) + + ###################################################### # INSTALLATION OF LIBRARY AND EXECUTABLE ###################################################### diff --git a/gtest/simple_example.cpp b/examples/simple_example.cpp similarity index 93% rename from gtest/simple_example.cpp rename to examples/simple_example.cpp index 9edb5035b..21347b6c9 100644 --- a/gtest/simple_example.cpp +++ b/examples/simple_example.cpp @@ -78,14 +78,14 @@ int main(int argc, char** argv) factory.registerNodeType("BatteryOK"); factory.registerNodeType("Move"); - XMLParser parser(factory); + BT::XMLParser parser(factory); parser.loadFromText(xml_text_A); std::vector nodes; BT::TreeNodePtr root_node = parser.instantiateTree(nodes); - StdCoutLogger logger_cout(root_node.get()); - FileLogger file_file(root_node.get(), "simple_trace.fbl", 32); + BT::StdCoutLogger logger_cout(root_node.get()); + BT::FileLogger file_file(root_node.get(), "simple_trace.fbl", 32); std::cout << "\n------- First executeTick() --------" << std::endl; root_node->executeTick(); @@ -100,7 +100,7 @@ int main(int argc, char** argv) std::cout << std::endl; std::cout << "\n-------\n"; - XMLWriter writer(factory); + BT::XMLWriter writer(factory); std::cout << writer.writeXML( root_node.get() ) << std::endl; return 0; diff --git a/examples/tutorial_blackboard.cpp b/examples/tutorial_blackboard.cpp new file mode 100644 index 000000000..e849d90aa --- /dev/null +++ b/examples/tutorial_blackboard.cpp @@ -0,0 +1,160 @@ +#include "behavior_tree_core/xml_parsing.h" +#include "behavior_tree_logger/bt_cout_logger.h" +#include "Blackboard/blackboard_local.h" + +using namespace BT; + +struct Pose2D +{ + double x,y,theta; +}; + +// This action will read the desired robot position +// and store it on the BlackBoard (key: "GoalPose") +class PullGoalPose: public ActionNodeBase +{ +public: + PullGoalPose(const std::string& name): ActionNodeBase(name, NodeParameters() ) {} + + NodeStatus tick() override + { + //In this example we hardcode a fixed value. + //In a real application we would read it from an external + // source (GUI, fleet manager, etc.) + Pose2D goal = { 1, 2, M_PI}; + + // store it in the blackboard + blackboard()->set("GoalPose", goal); + + return NodeStatus::SUCCESS; + } +}; + + +// First approach: read ALWAYS from the same +// blackboard key: [GoalPose] +class MoveAction_A: public ActionNodeBase +{ +public: + MoveAction_A(const std::string& name): + ActionNodeBase(name, NodeParameters() ) {} + + NodeStatus tick() override + { + Pose2D goal; + + if( blackboard()->get("GoalPose", goal) ) // return true if succesful + { + printf("[MoveBase] [Taget: x=%.ff y=%.1f theta=%.2f\n", + goal.x, goal.y, goal.theta); + return NodeStatus::SUCCESS; + } + else{ + printf("The blackboard does not contain the key [GoalPose]\n"); + return NodeStatus::FAILURE; + } + } +}; + +// Second approach: read the goal from the NodeParameter "goal". +// This value can be static or point to the key of a blackboard. +class MoveAction_B: public ActionNodeBase +{ +public: + MoveAction_B(const std::string& name, + const NodeParameters& params): + ActionNodeBase(name, params) {} + + NodeStatus tick() override + { + Pose2D goal; + + if( getParam("goal", goal) ) + { + printf("[MoveBase] [Taget: x=%.ff y=%.1f theta=%.2f\n", + goal.x, goal.y, goal.theta); + return NodeStatus::SUCCESS; + } + else{ + printf("The NodeParameter does not contain the key [goal] " + " or the blackboard does not contain the provided key\n"); + return NodeStatus::FAILURE; + } + } + static const NodeParameters& requiredNodeParameters() + { + static NodeParameters params = {{"goal","0;0;0"}}; + return params; + } +}; + +namespace BT{ + +template <> +Pose2D convertFromString(const std::string& str) +{ + auto parts = splitString(str, ';'); + if( parts.size() != 3) + { + throw std::runtime_error("invalid input)"); + } + else{ + Pose2D output; + output.x = convertFromString( parts[0] ); + output.y = convertFromString( parts[1] ); + output.theta = convertFromString( parts[2] ); + return output; + } +} + +} + + +const std::string xml_text = R"( + + + + + + + + + + + + + + + )"; + + +// clang-format on + +int main(int argc, char** argv) +{ + using namespace BT; + + BehaviorTreeFactory factory; + factory.registerNodeType("PullGoalPose"); + factory.registerNodeType("MoveAction_A"); + factory.registerNodeType("MoveAction_B"); + + XMLParser parser(factory); + parser.loadFromText(xml_text); + + std::vector nodes; + TreeNodePtr root_node = parser.instantiateTree(nodes); + + // create a Blackboard and assign it to your tree + auto bb = Blackboard::create(); + for(auto& node: nodes) + { + node->setBlackboard(bb); + } + + // StdCoutLogger logger_cout(root_node.get()); + + root_node->executeTick(); + + return 0; +} diff --git a/include/Blackboard/blackboard.h b/include/Blackboard/blackboard.h index 1497e64bf..014b132e4 100644 --- a/include/Blackboard/blackboard.h +++ b/include/Blackboard/blackboard.h @@ -8,6 +8,7 @@ #include #include +#include namespace BT{ @@ -27,25 +28,42 @@ class BlackboardImpl // the templatized methods set() and get() are more user-friendly class Blackboard { -public: - Blackboard( std::unique_ptr implementation): - impl_( std::move(implementation ) ) + +public: + // This is intentionally private. Use Blackboard::create instead + Blackboard(std::unique_ptr base ): impl_( std::move(base) ) { } + Blackboard() = delete; + + template + static std::shared_ptr create(Args... args ) + { + std::unique_ptr base( new ImplClass(args...) ); + return std::make_shared(std::move(base)); + } + virtual ~Blackboard() = default; template bool get(const std::string& key, T& value) const { + if( !impl_ ) + { + return false; + } const SafeAny::Any* val = impl_->get(key); if( !val ){ return false; } - value = val->convert(); + value = val->cast(); return true; } template void set(const std::string& key, const T& value) { - impl_->set(key, SafeAny::Any(value)); + if( impl_) + { + impl_->set(key, SafeAny::Any(value)); + } } private: diff --git a/include/SafeAny/convert_impl.hpp b/include/SafeAny/convert_impl.hpp new file mode 100644 index 000000000..a8707076c --- /dev/null +++ b/include/SafeAny/convert_impl.hpp @@ -0,0 +1,306 @@ +#ifndef CONVERT_IMPL_HPP +#define CONVERT_IMPL_HPP + +#include +#include +#include "simple_string.hpp" + +namespace SafeAny{ + +namespace details{ + +template +using EnableIf = typename std::enable_if< BoolCondition::value, void>::type; + +template +struct is_integer : std::integral_constant::value + && !std::is_same::value + && !std::is_same::value> +{}; + +template +struct is_same_real : std::integral_constant::value + && std::is_floating_point::value > +{}; + + +template +struct is_safe_integer_conversion + : std::integral_constant::value + && is_integer::value + && sizeof(From) < sizeof(To) +&& std::is_signed::value == std::is_signed::value> +{}; + +template +struct is_convertible_type + : std::integral_constant::value + || std::is_floating_point::value + || std::is_same::value + || std::is_same::value + || std::is_same::value + || std::is_same::value + || std::is_enum::value> +{}; + +template +struct float_conversion + : std::integral_constant::value + && std::is_floating_point::value && !std::is_same::value > +{}; + +template +struct unsigned_to_smaller_conversion + : std::integral_constant::value + && is_integer::value + && (sizeof(From) > sizeof(To)) +&& !std::is_signed::value +&& !std::is_signed::value > +{}; + +template +struct signed_to_smaller_conversion + : std::integral_constant::value + && is_integer::value + && (sizeof(From) > sizeof(To)) +&& std::is_signed::value +&& std::is_signed::value > +{}; + +//--------------------------- +template +struct signed_to_smaller_unsigned_conversion + : std::integral_constant::value + && is_integer::value + && sizeof(From) >= sizeof(To) +&& std::is_signed::value +&& !std::is_signed::value > +{}; + +template +struct signed_to_larger_unsigned_conversion + : std::integral_constant::value + && is_integer::value + && sizeof(From) < sizeof(To) +&& std::is_signed::value +&& !std::is_signed::value > +{}; + +template +struct unsigned_to_smaller_signed_conversion + : std::integral_constant::value + && is_integer::value + && (sizeof(From) >= sizeof(To)) +&& !std::is_signed::value +&& std::is_signed::value > +{}; + +template +struct unsigned_to_larger_signed_conversion + : std::integral_constant::value + && is_integer::value + && sizeof(From) < sizeof(To) +&& !std::is_signed::value +&& std::is_signed::value > +{}; + +template +struct floating_to_signed_conversion + : std::integral_constant::value + && is_integer::value + && std::is_signed::value > +{}; + +template +struct floating_to_unsigned_conversion + : std::integral_constant::value + && is_integer::value + && !std::is_signed::value > +{}; + +template +struct integer_to_floating_conversion + : std::integral_constant::value + && std::is_floating_point::value > +{}; + +template +inline void checkUpperLimit(const From& from) +{ + if ((sizeof(To) < sizeof(From)) && + (from > static_cast(std::numeric_limits::max()))) { + throw std::runtime_error("Value too large."); + } + else if (static_cast(from) > std::numeric_limits::max()) { + throw std::runtime_error("Value too large."); + } +} + +template +inline void checkUpperLimitFloat(const From& from) +{ + if (from > std::numeric_limits::max()){ + throw std::runtime_error("Value too large."); + } +} + +template +inline void checkLowerLimitFloat(const From& from) +{ + if (from < -std::numeric_limits::max()){ + throw std::runtime_error("Value too small."); + } +} + +template +inline void checkLowerLimit(const From& from) +{ + if (from < std::numeric_limits::min()){ + throw std::runtime_error("Value too small."); + } +} + +template +inline void checkTruncation(const From& from) +{ + if( from != static_cast(static_cast( from))){ + throw std::runtime_error("Floating point truncated"); + } +} + + +//----------------------- Implementation ---------------------------------------------- + +template inline +typename std::enable_if< !is_convertible_type::value, void>::type +convertNumber( const SRC& , DST& ) +{ + throw std::runtime_error("Not convertible"); +} + + +template inline +EnableIf< std::is_same> +convertNumber( const SRC& from, DST& target ) +{ + target = from; +} + +template inline +EnableIf< is_safe_integer_conversion> +convertNumber( const SRC& from, DST& target ) +{ + target = static_cast( from); +} + +template inline +EnableIf< float_conversion> +convertNumber( const SRC& from, DST& target ) +{ + checkTruncation(from); + target = static_cast( from ); +} + + +template inline +EnableIf< unsigned_to_smaller_conversion> +convertNumber( const SRC& from, DST& target ) +{ + checkUpperLimit(from); + target = static_cast( from); +} + +template inline +EnableIf< signed_to_smaller_conversion> +convertNumber( const SRC& from, DST& target ) +{ + checkLowerLimit(from); + checkUpperLimit(from); + target = static_cast( from); +} + + +template inline +EnableIf< signed_to_smaller_unsigned_conversion> +convertNumber( const SRC& from, DST& target ) +{ + if (from < 0 ){ + throw std::runtime_error("Value is negative and can't be converted to signed"); + } + + checkUpperLimit(from); + target = static_cast( from ); +} + + +template inline +EnableIf< signed_to_larger_unsigned_conversion> +convertNumber( const SRC& from, DST& target ) +{ + if ( from < 0 ){ + throw std::runtime_error("Value is negative and can't be converted to signed"); + } + + target = static_cast( from); +} + +template inline +EnableIf< unsigned_to_larger_signed_conversion> +convertNumber( const SRC& from, DST& target ) +{ + target = static_cast( from); +} + +template inline +EnableIf< unsigned_to_smaller_signed_conversion> +convertNumber( const SRC& from, DST& target ) +{ + checkUpperLimit(from); + target = static_cast( from); +} + +template inline +EnableIf< floating_to_signed_conversion> +convertNumber( const SRC& from, DST& target ) +{ + checkLowerLimitFloat(from); + checkLowerLimitFloat(from); + + if( from != static_cast(static_cast( from))){ + throw std::runtime_error("Floating point truncated"); + } + + target = static_cast( from); +} + +template inline +EnableIf< floating_to_unsigned_conversion> +convertNumber( const SRC& from, DST& target ) +{ + if ( from < 0 ){ + throw std::runtime_error("Value is negative and can't be converted to signed"); + } + + checkLowerLimitFloat(from); + + if( from != static_cast(static_cast( from))){ + throw std::runtime_error("Floating point truncated"); + } + + target = static_cast( from); +} + +template inline +EnableIf< integer_to_floating_conversion> +convertNumber( const SRC& from, DST& target ) +{ + checkTruncation(from); + target = static_cast( from); +} + +} //end namespace details +} //end namespace details + +#endif // CONVERT_IMPL_HPP diff --git a/include/SafeAny/safe_any.hpp b/include/SafeAny/safe_any.hpp index 8d55eace7..b05c7a8e8 100644 --- a/include/SafeAny/safe_any.hpp +++ b/include/SafeAny/safe_any.hpp @@ -7,491 +7,168 @@ #include #include #include +#include #include "any.hpp" +#include "convert_impl.hpp" namespace SafeAny{ -// Version of string that uses only two words. Good for small object optimization in linb::any -class SimpleString + +// Rational: since type erased numbers will always use at least 8 bytes +// it is faster to cast everything to either double, uint64_t or int64_t. +class Any { -public: - SimpleString(const std::string& str): SimpleString(str.data(), str.size()) - { } - SimpleString(const char* data): SimpleString( data, strlen(data) ) - { } + template + using EnableIntegral = typename std::enable_if::value || + std::is_enum::value>::type*; - SimpleString(const char* data, std::size_t size): _size(size) - { - _data = new char[_size+1]; - strncpy(_data, data, _size); - _data[_size] = '\0'; - } + template + using EnableNonIntegral = typename std::enable_if< !std::is_integral::value && + !std::is_enum::value>::type*; - SimpleString(const SimpleString& other): SimpleString(other.data(), other.size()) - { } + template + using EnableString = typename std::enable_if< std::is_same::value>::type*; + template + using EnableArithmetic = typename std::enable_if< std::is_arithmetic::value > ::type*; - ~SimpleString() { - if(_data){ - delete[] _data; - } - } + template + using EnableEnum = typename std::enable_if< std::is_enum::value > ::type*; - std::string toStdString() const - { - return std::string(_data, _size); - } - - const char* data() const { return _data;} - - std::size_t size() const { return _size;} + template + using EnableUnknownType = typename std::enable_if< !std::is_arithmetic::value && + !std::is_enum::value && + !std::is_same::value > ::type*; +public: -private: - char* _data; - std::size_t _size; -}; + Any() {} + ~Any() = default; + Any(const double& value) : _any(value) { } -class Any -{ + Any(const uint64_t& value) : _any(value) { } -public: + Any(const float& value) : _any( double(value) ) { } - Any() {} + Any(const std::string& str) : _any(SimpleString(str)) { } - ~Any() = default; + // all the other integrals are casted to int64_t + template + explicit Any(const T& value, EnableIntegral = 0): + _any( int64_t(value) ) { } - template Any(const T& value) : _any(value) - { } + // default for other custom types + template + explicit Any(const T& value, EnableNonIntegral = 0): + _any( value ) { } - template T convert( ) const; - template T extract( ) const + // this is different from any_cast, because if allows safe + // conversions between arithmetic values. + template T cast() const { - return linb::any_cast(_any); + if( _any.type() == typeid (T) ) + { + return linb::any_cast(_any); + } + else{ + return convert(); + } } - const std::type_info& type() const { return _any.type(); } - private: linb::any _any; -}; - -//---------------------------------------------- -//specialization for std::string -template <> inline Any::Any(const std::string& str) -{ - _any = linb::any(SimpleString(str)); -} - -template <> inline std::string Any::extract() const -{ - return linb::any_cast(_any).toStdString(); -} - -namespace details{ - - -template -using EnableIf = typename std::enable_if< BoolCondition::value, void>::type; - -template -struct is_integer : std::integral_constant::value - && !std::is_same::value - && !std::is_same::value> -{}; - -template -struct is_same_real : std::integral_constant::value - && std::is_floating_point::value > -{}; - - -template -struct is_safe_integer_conversion - : std::integral_constant::value - && is_integer::value - && sizeof(From) < sizeof(To) -&& std::is_signed::value == std::is_signed::value> -{}; - -template -struct is_convertible_type - : std::integral_constant::value - || std::is_floating_point::value - || std::is_same::value - || std::is_same::value - || std::is_same::value - || std::is_same::value> -{}; - -template -struct float_conversion - : std::integral_constant::value - && std::is_floating_point::value && !std::is_same::value > -{}; - -template -struct unsigned_to_smaller_conversion - : std::integral_constant::value - && is_integer::value - && (sizeof(From) > sizeof(To)) -&& !std::is_signed::value -&& !std::is_signed::value > -{}; - -template -struct signed_to_smaller_conversion - : std::integral_constant::value - && is_integer::value - && (sizeof(From) > sizeof(To)) -&& std::is_signed::value -&& std::is_signed::value > -{}; - -//--------------------------- -template -struct signed_to_smaller_unsigned_conversion - : std::integral_constant::value - && is_integer::value - && sizeof(From) >= sizeof(To) -&& std::is_signed::value -&& !std::is_signed::value > -{}; - -template -struct signed_to_larger_unsigned_conversion - : std::integral_constant::value - && is_integer::value - && sizeof(From) < sizeof(To) -&& std::is_signed::value -&& !std::is_signed::value > -{}; - -template -struct unsigned_to_smaller_signed_conversion - : std::integral_constant::value - && is_integer::value - && (sizeof(From) >= sizeof(To)) -&& !std::is_signed::value -&& std::is_signed::value > -{}; - -template -struct unsigned_to_larger_signed_conversion - : std::integral_constant::value - && is_integer::value - && sizeof(From) < sizeof(To) -&& !std::is_signed::value -&& std::is_signed::value > -{}; - -template -struct floating_to_signed_conversion - : std::integral_constant::value - && is_integer::value - && std::is_signed::value > -{}; - -template -struct floating_to_unsigned_conversion - : std::integral_constant::value - && is_integer::value - && !std::is_signed::value > -{}; - -template -struct integer_to_floating_conversion - : std::integral_constant::value - && std::is_floating_point::value > -{}; - -template -inline void checkUpperLimit(const From& from) -{ - if ((sizeof(To) < sizeof(From)) && - (from > static_cast(std::numeric_limits::max()))) { - throw std::runtime_error("Value too large."); - } - else if (static_cast(from) > std::numeric_limits::max()) { - throw std::runtime_error("Value too large."); - } -} -template -inline void checkUpperLimitFloat(const From& from) -{ - if (from > std::numeric_limits::max()){ - throw std::runtime_error("Value too large."); - } -} + //---------------------------- -template -inline void checkLowerLimitFloat(const From& from) -{ - if (from < -std::numeric_limits::max()){ - throw std::runtime_error("Value too small."); - } -} + template + DST convert( EnableString = 0 ) const + { + const auto& type = _any.type(); -template -inline void checkLowerLimit(const From& from) -{ - if (from < std::numeric_limits::min()){ - throw std::runtime_error("Value too small."); - } -} + if( type == typeid(SimpleString) ) + { + return linb::any_cast(_any).toStdString(); + } + else if( type == typeid(int64_t)) { + return std::to_string( linb::any_cast(_any) ); + } + else if( type == typeid(uint64_t)) { + return std::to_string( linb::any_cast(_any) ); + } + else if( type == typeid(double)) { + return std::to_string( linb::any_cast(_any) ); + } -template -inline void checkTruncation(const From& from) -{ - if( from != static_cast(static_cast( from))){ - throw std::runtime_error("Floating point truncated"); + throw errorMsg(); } -} - - -//----------------------- Implementation ---------------------------------------------- - -template inline -typename std::enable_if< !is_convertible_type::value, void>::type -convert_impl( const SRC& , DST& ) -{ - throw std::runtime_error("Not convertible"); -} - - -template inline -EnableIf< std::is_same> -convert_impl( const SRC& from, DST& target ) -{ - target = from; -} - -template inline -EnableIf< is_safe_integer_conversion> -convert_impl( const SRC& from, DST& target ) -{ - target = static_cast( from); -} - -template inline -EnableIf< float_conversion> -convert_impl( const SRC& from, DST& target ) -{ - checkTruncation(from); - target = static_cast( from ); -} - - -template inline -EnableIf< unsigned_to_smaller_conversion> -convert_impl( const SRC& from, DST& target ) -{ - checkUpperLimit(from); - target = static_cast( from); -} - -template inline -EnableIf< signed_to_smaller_conversion> -convert_impl( const SRC& from, DST& target ) -{ - checkLowerLimit(from); - checkUpperLimit(from); - target = static_cast( from); -} -template inline -EnableIf< signed_to_smaller_unsigned_conversion> -convert_impl( const SRC& from, DST& target ) -{ - if (from < 0 ) - throw std::runtime_error("Value is negative and can't be converted to signed"); - - checkUpperLimit(from); - target = static_cast( from ); -} - - -template inline -EnableIf< signed_to_larger_unsigned_conversion> -convert_impl( const SRC& from, DST& target ) -{ - //std::cout << "signed_to_larger_unsigned_conversion" << std::endl; - - if ( from < 0 ) - throw std::runtime_error("Value is negative and can't be converted to signed"); - - target = static_cast( from); -} - -template inline -EnableIf< unsigned_to_larger_signed_conversion> -convert_impl( const SRC& from, DST& target ) -{ - //std::cout << "unsigned_to_larger_signed_conversion" << std::endl; - target = static_cast( from); -} - -template inline -EnableIf< unsigned_to_smaller_signed_conversion> -convert_impl( const SRC& from, DST& target ) -{ - checkUpperLimit(from); - target = static_cast( from); -} - -template inline -EnableIf< floating_to_signed_conversion> -convert_impl( const SRC& from, DST& target ) -{ - checkLowerLimitFloat(from); - checkLowerLimitFloat(from); - - if( from != static_cast(static_cast( from))) - throw std::runtime_error("Floating point truncated"); - - target = static_cast( from); -} - -template inline -EnableIf< floating_to_unsigned_conversion> -convert_impl( const SRC& from, DST& target ) -{ - if ( from < 0 ) - throw std::runtime_error("Value is negative and can't be converted to signed"); - - checkLowerLimitFloat(from); - - if( from != static_cast(static_cast( from))) - throw std::runtime_error("Floating point truncated"); + template + DST convert( EnableArithmetic = 0 ) const + { + using details::convertNumber; + DST out; - target = static_cast( from); -} + const auto& type = _any.type(); -template inline -EnableIf< integer_to_floating_conversion> -convert_impl( const SRC& from, DST& target ) -{ - checkTruncation(from); - target = static_cast( from); -} + if( type == typeid(int64_t)) { + convertNumber(linb::any_cast(_any), out ); + } + else if( type == typeid(uint64_t)) { + convertNumber(linb::any_cast(_any), out ); + } + else if( type == typeid(double)) { + convertNumber(linb::any_cast(_any), out ); + } + else{ + throw errorMsg(); + } + return out; + } -} //end namespace details + template + DST convert( EnableEnum = 0 ) const + { + using details::convertNumber; + const auto& type = _any.type(); -template inline -DST Any::convert() const -{ - using details::convert_impl; - DST out; + if( type == typeid(int64_t)) + { + uint64_t out = linb::any_cast(_any); + return static_cast(out); + } + else if( type == typeid(uint64_t)) + { + uint64_t out = linb::any_cast(_any); + return static_cast(out); + } - const auto& type = _any.type(); + throw errorMsg(); + } - if( ! details::is_convertible_type::value ) + template + DST convert( EnableUnknownType = 0 ) const { - return linb::any_cast(_any); + throw errorMsg(); } - if( type == typeid(bool)) { - return DST( extract() ); - } - else if( type == typeid(char)) { - convert_impl( int8_t(extract()), out ); - } - else if( type == typeid(int8_t)) { - convert_impl(extract(), out ); - } - else if( type == typeid(int16_t)) { - convert_impl(extract(), out ); - } - else if( type == typeid(int32_t)) { - convert_impl(extract(), out ); - } - else if( type == typeid(int64_t)) { - convert_impl(extract(), out ); - } - else if( type == typeid(uint8_t)) { - convert_impl(extract(), out ); - } - else if( type == typeid(uint16_t)) { - convert_impl(extract(), out ); - } - else if( type == typeid(uint32_t)) { - convert_impl(extract(), out ); - } - else if( type == typeid(uint64_t)) { - convert_impl(extract(), out ); - } - else if( type == typeid(float)) { - convert_impl(extract(), out ); - } - else if( type == typeid(double)) { - convert_impl(extract(), out ); - } - else if( type == typeid(SimpleString) ) + template + std::runtime_error errorMsg() const { - throw std::runtime_error("String can not be converted to another type implicitly"); - } - else{ - return linb::any_cast(_any); + char buffer[1024]; + sprintf(buffer, "[Any::convert]: no known safe conversion between %s and %s", + _any.type().name(), typeid (T).name() ); + return std::runtime_error(buffer); } - return out; -} +}; -template<> inline std::string Any::convert() const -{ - const auto& type = _any.type(); - if( type == typeid(SimpleString) ) - { - return extract().toStdString(); - } - else if( type == typeid(bool)) { - return std::to_string( extract() ); - } - else if( type == typeid(char)) { - return std::to_string( extract() ); - } - else if( type == typeid(int8_t)) { - return std::to_string( extract() ); - } - else if( type == typeid(int16_t)) { - return std::to_string( extract() ); - } - else if( type == typeid(int32_t)) { - return std::to_string( extract() ); - } - else if( type == typeid(int64_t)) { - return std::to_string( extract() ); - } - else if( type == typeid(uint8_t)) { - return std::to_string( extract() ); - } - else if( type == typeid(uint16_t)) { - return std::to_string( extract() ); - } - else if( type == typeid(uint32_t)) { - return std::to_string( extract() ); - } - else if( type == typeid(uint64_t)) { - return std::to_string( extract() ); - } - else if( type == typeid(float)) { - return std::to_string( extract() ); - } - else if( type == typeid(double)) { - return std::to_string( extract() ); - } - throw std::runtime_error("Conversion to std::string failed"); -} } // end namespace VarNumber diff --git a/include/SafeAny/simple_string.hpp b/include/SafeAny/simple_string.hpp new file mode 100644 index 000000000..8d1e375c8 --- /dev/null +++ b/include/SafeAny/simple_string.hpp @@ -0,0 +1,51 @@ +#ifndef SIMPLE_STRING_HPP +#define SIMPLE_STRING_HPP + +#include +#include + +namespace SafeAny{ + +// Version of string that uses only two words. Good for small object optimization in linb::any +class SimpleString +{ +public: + SimpleString(const std::string& str): SimpleString(str.data(), str.size()) + { } + SimpleString(const char* data): SimpleString( data, strlen(data) ) + { } + + SimpleString(const char* data, std::size_t size): _size(size) + { + _data = new char[_size+1]; + strncpy(_data, data, _size); + _data[_size] = '\0'; + } + + SimpleString(const SimpleString& other): SimpleString(other.data(), other.size()) + { } + + + ~SimpleString() { + if(_data){ + delete[] _data; + } + } + + std::string toStdString() const + { + return std::string(_data, _size); + } + + const char* data() const { return _data;} + + std::size_t size() const { return _size;} + +private: + char* _data; + std::size_t _size; +}; + +} + +#endif // SIMPLE_STRING_HPP diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 42c2d7efc..6a408f7c4 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -30,6 +30,11 @@ class ActionNodeBase : public LeafNode { return NodeType::ACTION; } + + virtual void halt() override + { + setStatus(NodeStatus::IDLE); + } }; /** diff --git a/include/behavior_tree_core/basic_types.h b/include/behavior_tree_core/basic_types.h index 5d75829b0..663541aff 100644 --- a/include/behavior_tree_core/basic_types.h +++ b/include/behavior_tree_core/basic_types.h @@ -4,6 +4,8 @@ #include #include #include +#include +#include namespace BT { @@ -101,6 +103,21 @@ inline std::ostream& operator<<(std::ostream& os, const BT::ResetPolicy& type) os << toStr(type); return os; } + +// small utility, unless you want to use +inline std::vector splitString(const std::string& strToSplit, char delimeter) +{ + std::stringstream ss(strToSplit); + std::string item; + std::vector splitted_strings; + while (std::getline(ss, item, delimeter)) + { + splitted_strings.push_back(item); + } + return splitted_strings; +} + + } #endif // BT_BASIC_TYPES_H diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index e5842fe6b..f4607c9a6 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -65,23 +65,24 @@ class BehaviorTreeFactory template void registerNodeType(const std::string& ID) { - static_assert(std::is_base_of::value || std::is_base_of::value || - std::is_base_of::value || std::is_base_of::value, - "[registerBuilder]: accepts only classed derived from either ActionNode, DecoratorNode, " - "ControlNode " - "or ConditionNode"); - - constexpr bool default_constructable = std::is_constructible::value; - constexpr bool param_constructable = std::is_constructible::value; + static_assert(std::is_base_of::value || + std::is_base_of::value || + std::is_base_of::value || + std::is_base_of::value, + "[registerBuilder]: accepts only classed derived from either ActionNodeBase, " + "DecoratorNode, ControlNode or ConditionNode"); + + constexpr bool default_constructable = std::is_constructible::value; + constexpr bool param_constructable = std::is_constructible::value; constexpr bool has_static_required_parameters = has_static_method_requiredNodeParameters::value; static_assert(default_constructable || param_constructable, - "[registerBuilder]: the registered class must have at least one of these two constructors:\n\n" - " (const std::string&, const NodeParameters&) or (const std::string&)"); + "[registerBuilder]: the registered class must have at least one of these two constructors: " + " (const std::string&, const NodeParameters&) or (const std::string&)\n"); static_assert(!(param_constructable && !has_static_required_parameters), - "[registerBuilder]: a node that accepts NodeParameters must also implement a static method:\n\n" - " const NodeParameters& requiredNodeParameters(); "); + "[registerBuilder]: a node that accepts NodeParameters must also implement a static method: " + " const NodeParameters& requiredNodeParameters();\n"); registerNodeTypeImpl(ID); storeNodeModel(ID); diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index a9031d2ef..fc4758655 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -107,12 +107,25 @@ class TreeNode virtual BT::NodeStatus tick() = 0; template - nonstd::optional getParam(const std::string& key) const + BT::optional getParam(const std::string& key) const + { + T out; + if( getParam(key, out)) + { + return std::move(out); + } + else{ + return BT::nullopt; + } + } + + template + bool getParam(const std::string& key, T& destination) const { auto it = parameters_.find(key); if (it == parameters_.end()) { - return nonstd::nullopt; + return false; } const std::string& str = it->second; @@ -120,12 +133,12 @@ class TreeNode if( bb_ && str.size()>=4 && str[0] == '$' && str[1] == '{' && str.back() == '}') { const std::string stripped_key( &str[2], str.size()-3); - T value; - bool found = bb_->get(stripped_key, value); - return found ? nonstd::optional(value) : nonstd::nullopt; + bool found = bb_->get(stripped_key, destination); + return found; } else{ - return convertFromString(str.c_str()); + destination = convertFromString(str.c_str()); + return true; } } From d37b1860c3e848329d5873f7bef824394f13a445 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 21 Aug 2018 15:22:34 +0200 Subject: [PATCH 087/125] cleanup --- examples/tutorial_blackboard.cpp | 13 ++++++------- include/behavior_tree_core/action_node.h | 2 +- include/behavior_tree_core/bt_factory.h | 4 ++++ 3 files changed, 11 insertions(+), 8 deletions(-) diff --git a/examples/tutorial_blackboard.cpp b/examples/tutorial_blackboard.cpp index e849d90aa..b19a817af 100644 --- a/examples/tutorial_blackboard.cpp +++ b/examples/tutorial_blackboard.cpp @@ -14,7 +14,7 @@ struct Pose2D class PullGoalPose: public ActionNodeBase { public: - PullGoalPose(const std::string& name): ActionNodeBase(name, NodeParameters() ) {} + PullGoalPose(const std::string& name): ActionNodeBase(name) {} NodeStatus tick() override { @@ -36,8 +36,7 @@ class PullGoalPose: public ActionNodeBase class MoveAction_A: public ActionNodeBase { public: - MoveAction_A(const std::string& name): - ActionNodeBase(name, NodeParameters() ) {} + MoveAction_A(const std::string& name): ActionNodeBase(name) {} NodeStatus tick() override { @@ -61,8 +60,7 @@ class MoveAction_A: public ActionNodeBase class MoveAction_B: public ActionNodeBase { public: - MoveAction_B(const std::string& name, - const NodeParameters& params): + MoveAction_B(const std::string& name, const NodeParameters& params): ActionNodeBase(name, params) {} NodeStatus tick() override @@ -90,6 +88,9 @@ class MoveAction_B: public ActionNodeBase namespace BT{ +// this template specialization is needed if you want +// to automatically convert a NodeParameter into a Pose2D + template <> Pose2D convertFromString(const std::string& str) { @@ -152,8 +153,6 @@ int main(int argc, char** argv) node->setBlackboard(bb); } - // StdCoutLogger logger_cout(root_node.get()); - root_node->executeTick(); return 0; diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 6a408f7c4..27368312f 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -23,7 +23,7 @@ class ActionNodeBase : public LeafNode { public: // Constructor - ActionNodeBase(const std::string& name, const NodeParameters& parameters); + ActionNodeBase(const std::string& name, const NodeParameters& parameters = NodeParameters()); ~ActionNodeBase() override = default; virtual NodeType type() const override final diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index f4607c9a6..7df03bb84 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -84,6 +84,10 @@ class BehaviorTreeFactory "[registerBuilder]: a node that accepts NodeParameters must also implement a static method: " " const NodeParameters& requiredNodeParameters();\n"); + static_assert( !( has_static_required_parameters && !param_constructable), + "[registerBuilder]: since you have a static method requiredNodeParameters(), " + "you will also need a constructor sign signature (const std::string&, const NodeParameters&)\n)" ); + registerNodeTypeImpl(ID); storeNodeModel(ID); } From 04da1a56589530eb9dd65778da56529ad6f133f0 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 21 Aug 2018 15:58:27 +0200 Subject: [PATCH 088/125] typo fixed --- include/behavior_tree_core/condition_node.h | 2 +- include/behavior_tree_core/decorator_node.h | 2 +- include/behavior_tree_core/tree_node.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index 04262b6ed..efc089477 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -51,7 +51,7 @@ class SimpleConditionNode : public ConditionNode public: typedef std::function TickFunctor; - // Constructor: you must provide the funtion to call when tick() is invoked + // Constructor: you must provide the function to call when tick() is invoked SimpleConditionNode(const std::string& name, TickFunctor tick_functor); ~SimpleConditionNode() override = default; diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index db7f1fd03..288a787f5 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -49,7 +49,7 @@ class SimpleDecoratorNode : public DecoratorNode public: typedef std::function TickFunctor; - // Constructor: you must provide the funtion to call when tick() is invoked + // Constructor: you must provide the function to call when tick() is invoked SimpleDecoratorNode(const std::string& name, TickFunctor tick_functor); ~SimpleDecoratorNode() override = default; diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index fc4758655..dfd75da8b 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -70,7 +70,7 @@ class TreeNode const std::string& name() const; - /// Blocking funtion that will sleep until the setStatus() is called with + /// Blocking function that will sleep until the setStatus() is called with /// either RUNNING, FAILURE or SUCCESS. BT::NodeStatus waitValidStatus(); From f911e487cba380bc3f90a2736ba068af382b6064 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 22 Aug 2018 09:54:58 +0200 Subject: [PATCH 089/125] Blackboard related updates --- examples/tutorial_blackboard.cpp | 39 ++++++++++----------- include/Blackboard/blackboard.h | 21 ++++++----- include/behavior_tree_core/action_node.h | 7 ++-- include/behavior_tree_core/bt_factory.h | 2 ++ include/behavior_tree_core/condition_node.h | 2 +- include/behavior_tree_core/tree_node.h | 6 ++-- src/action_node.cpp | 2 +- src/bt_factory.cpp | 14 +++++++- src/condition_node.cpp | 2 +- src/tree_node.cpp | 4 +-- 10 files changed, 59 insertions(+), 40 deletions(-) diff --git a/examples/tutorial_blackboard.cpp b/examples/tutorial_blackboard.cpp index b19a817af..a53caa281 100644 --- a/examples/tutorial_blackboard.cpp +++ b/examples/tutorial_blackboard.cpp @@ -11,25 +11,17 @@ struct Pose2D // This action will read the desired robot position // and store it on the BlackBoard (key: "GoalPose") -class PullGoalPose: public ActionNodeBase +NodeStatus PullGoalPose(const std::shared_ptr& blackboard) { -public: - PullGoalPose(const std::string& name): ActionNodeBase(name) {} - - NodeStatus tick() override - { - //In this example we hardcode a fixed value. - //In a real application we would read it from an external - // source (GUI, fleet manager, etc.) - Pose2D goal = { 1, 2, M_PI}; + //In this example we store a fixed value. In a real application + // we would read it from an external source (GUI, fleet manager, etc.) + Pose2D goal = { 1, 2, M_PI}; - // store it in the blackboard - blackboard()->set("GoalPose", goal); - - return NodeStatus::SUCCESS; - } -}; + // store it in the blackboard + blackboard->set("GoalPose", goal); + return NodeStatus::SUCCESS; +} // First approach: read ALWAYS from the same // blackboard key: [GoalPose] @@ -41,7 +33,6 @@ class MoveAction_A: public ActionNodeBase NodeStatus tick() override { Pose2D goal; - if( blackboard()->get("GoalPose", goal) ) // return true if succesful { printf("[MoveBase] [Taget: x=%.ff y=%.1f theta=%.2f\n", @@ -57,6 +48,7 @@ class MoveAction_A: public ActionNodeBase // Second approach: read the goal from the NodeParameter "goal". // This value can be static or point to the key of a blackboard. +// A pointer to a Blackboard entry is written as ${key} class MoveAction_B: public ActionNodeBase { public: @@ -66,7 +58,6 @@ class MoveAction_B: public ActionNodeBase NodeStatus tick() override { Pose2D goal; - if( getParam("goal", goal) ) { printf("[MoveBase] [Taget: x=%.ff y=%.1f theta=%.2f\n", @@ -111,6 +102,15 @@ Pose2D convertFromString(const std::string& str) } +/** Example: simple sequence of 4 actions + + 1) Store a value of Pose2D in the key "GoalPose" of the blackboard. + 2) Call MoveAction_A. It will read "GoalPose" from the blackboard. + 3) Call MoveAction_B that reads the NodeParameter "goal". It's value "2;4;0" is converted + to Pose2D using the function [ Pose2D convertFromString(const std::string& str) ]. + 4) Call MoveAction_B. It will read "GoalPose" from the blackboard . + +*/ const std::string xml_text = R"( @@ -120,7 +120,6 @@ const std::string xml_text = R"( - @@ -136,7 +135,7 @@ int main(int argc, char** argv) using namespace BT; BehaviorTreeFactory factory; - factory.registerNodeType("PullGoalPose"); + factory.registerSimpleAction("PullGoalPose", PullGoalPose); factory.registerNodeType("MoveAction_A"); factory.registerNodeType("MoveAction_B"); diff --git a/include/Blackboard/blackboard.h b/include/Blackboard/blackboard.h index 014b132e4..3afa3a0a4 100644 --- a/include/Blackboard/blackboard.h +++ b/include/Blackboard/blackboard.h @@ -12,6 +12,9 @@ namespace BT{ +// This is the "backend" of the blackboard. +// To create a new blackboard, user must inherit from BlackboardImpl +// and override set and get. class BlackboardImpl { public: @@ -22,26 +25,27 @@ class BlackboardImpl virtual void set(const std::string& key, const SafeAny::Any& value) = 0; }; - -// Blackboard is the front-end to be used by the developer. +// This is the "frontend" to be used by the developer. +// // Even if the abstract class BlackboardImpl can be used directly, // the templatized methods set() and get() are more user-friendly class Blackboard { - - -public: // This is intentionally private. Use Blackboard::create instead Blackboard(std::unique_ptr base ): impl_( std::move(base) ) { } +public: + + typedef std::shared_ptr Ptr; + Blackboard() = delete; template - static std::shared_ptr create(Args... args ) + static Blackboard::Ptr create(Args... args ) { std::unique_ptr base( new ImplClass(args...) ); - return std::make_shared(std::move(base)); + return std::shared_ptr( new Blackboard(std::move(base)) ); } virtual ~Blackboard() = default; @@ -59,7 +63,8 @@ class Blackboard return true; } - template void set(const std::string& key, const T& value) { + template void set(const std::string& key, const T& value) + { if( impl_) { impl_->set(key, SafeAny::Any(value)); diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index 27368312f..d7937603b 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -46,14 +46,15 @@ class ActionNodeBase : public LeafNode * This avoids the hassle of inheriting from a ActionNode. * * Using lambdas or std::bind it is easy to pass a pointer to a method. - * SimpleActionNode does not support halting, NodeParameters, nor Blackboards. + * SimpleActionNode is executed synchronously and does not support halting. + * NodeParameters aren't supported. */ class SimpleActionNode : public ActionNodeBase { public: - typedef std::function TickFunctor; + typedef std::function TickFunctor; - // Constructor: you must provide the funtion to call when tick() is invoked + // Constructor: you must provide the function to call when tick() is invoked SimpleActionNode(const std::string& name, TickFunctor tick_functor); ~SimpleActionNode() override = default; diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 7df03bb84..273be6c6f 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -46,8 +46,10 @@ class BehaviorTreeFactory void registerBuilder(const std::string& ID, NodeBuilder builder); void registerSimpleAction(const std::string& ID, const std::function &tick_functor); + void registerSimpleAction(const std::string& ID, const SimpleActionNode::TickFunctor &tick_functor); void registerSimpleCondition(const std::string& ID, const std::function &tick_functor); + void registerSimpleCondition(const std::string& ID, const SimpleConditionNode::TickFunctor &tick_functor); std::unique_ptr instantiateTreeNode(const std::string& ID, const std::string& name, const NodeParameters& params) const; diff --git a/include/behavior_tree_core/condition_node.h b/include/behavior_tree_core/condition_node.h index efc089477..6c2b02144 100644 --- a/include/behavior_tree_core/condition_node.h +++ b/include/behavior_tree_core/condition_node.h @@ -49,7 +49,7 @@ class ConditionNode : public LeafNode class SimpleConditionNode : public ConditionNode { public: - typedef std::function TickFunctor; + typedef std::function TickFunctor; // Constructor: you must provide the function to call when tick() is invoked SimpleConditionNode(const std::string& name, TickFunctor tick_functor); diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index dfd75da8b..77c7274be 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -64,9 +64,9 @@ class TreeNode void setStatus(NodeStatus new_status); - void setBlackboard(std::shared_ptr bb); + void setBlackboard(const Blackboard::Ptr& bb); - const std::shared_ptr& blackboard() const; + const Blackboard::Ptr &blackboard() const; const std::string& name() const; @@ -164,7 +164,7 @@ class TreeNode const NodeParameters parameters_; - std::shared_ptr bb_; + Blackboard::Ptr bb_; }; typedef std::shared_ptr TreeNodePtr; diff --git a/src/action_node.cpp b/src/action_node.cpp index 4185a64de..584d6d1eb 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -37,7 +37,7 @@ NodeStatus SimpleActionNode::tick() prev_status = NodeStatus::RUNNING; } - NodeStatus status = tick_functor_(); + NodeStatus status = tick_functor_( blackboard() ); if (status != prev_status) { setStatus(status); diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 908246a13..a911ff343 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -52,6 +52,18 @@ void BehaviorTreeFactory::registerBuilder(const std::string& ID, NodeBuilder bui } void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, const std::function &tick_functor) +{ + auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; + registerSimpleCondition(ID, wrapper); +} + +void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, const std::function &tick_functor) +{ + auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; + registerSimpleAction(ID, wrapper); +} + +void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, const SimpleConditionNode::TickFunctor &tick_functor) { NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeParameters&) { return std::unique_ptr(new SimpleConditionNode(name, tick_functor)); @@ -61,7 +73,7 @@ void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, const s storeNodeModel(ID); } -void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, const std::function& tick_functor) +void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, const SimpleActionNode::TickFunctor& tick_functor) { NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeParameters&) { return std::unique_ptr(new SimpleActionNode(name, tick_functor)); diff --git a/src/condition_node.cpp b/src/condition_node.cpp index 4fbf0a7c2..839f74606 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -34,7 +34,7 @@ SimpleConditionNode::SimpleConditionNode(const std::string &name, NodeStatus SimpleConditionNode::tick() { - return tick_functor_(); + return tick_functor_(blackboard()); } } diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 721552e94..467cb9627 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -49,12 +49,12 @@ void TreeNode::setStatus(NodeStatus new_status) } } -void TreeNode::setBlackboard(std::shared_ptr bb) +void TreeNode::setBlackboard(const Blackboard::Ptr &bb) { bb_ = bb; } -const std::shared_ptr& TreeNode::blackboard() const +const Blackboard::Ptr& TreeNode::blackboard() const { return bb_; } From f269673929c47897981dc89df50b00f84a38335f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 22 Aug 2018 10:40:30 +0200 Subject: [PATCH 090/125] added registerSimpleDecorator --- include/behavior_tree_core/bt_factory.h | 3 +++ include/behavior_tree_core/decorator_node.h | 2 +- src/bt_factory.cpp | 30 ++++++++++++++++++--- src/decorator_node.cpp | 2 +- 4 files changed, 31 insertions(+), 6 deletions(-) diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 273be6c6f..2ce9d7e81 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -51,6 +51,9 @@ class BehaviorTreeFactory void registerSimpleCondition(const std::string& ID, const std::function &tick_functor); void registerSimpleCondition(const std::string& ID, const SimpleConditionNode::TickFunctor &tick_functor); + void registerSimpleDecorator(const std::string& ID, const std::function &tick_functor); + void registerSimpleDecorator(const std::string& ID, const SimpleDecoratorNode::TickFunctor &tick_functor); + std::unique_ptr instantiateTreeNode(const std::string& ID, const std::string& name, const NodeParameters& params) const; diff --git a/include/behavior_tree_core/decorator_node.h b/include/behavior_tree_core/decorator_node.h index 288a787f5..f55f69027 100644 --- a/include/behavior_tree_core/decorator_node.h +++ b/include/behavior_tree_core/decorator_node.h @@ -47,7 +47,7 @@ class DecoratorNode : public TreeNode class SimpleDecoratorNode : public DecoratorNode { public: - typedef std::function TickFunctor; + typedef std::function TickFunctor; // Constructor: you must provide the function to call when tick() is invoked SimpleDecoratorNode(const std::string& name, TickFunctor tick_functor); diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index a911ff343..0c67a28e3 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -51,19 +51,29 @@ void BehaviorTreeFactory::registerBuilder(const std::string& ID, NodeBuilder bui builders_.insert(std::make_pair(ID, builder)); } -void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, const std::function &tick_functor) +void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, + const std::function &tick_functor) { auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; registerSimpleCondition(ID, wrapper); } -void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, const std::function &tick_functor) +void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, + const std::function &tick_functor) { auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; registerSimpleAction(ID, wrapper); } -void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, const SimpleConditionNode::TickFunctor &tick_functor) +void BehaviorTreeFactory::registerSimpleDecorator(const std::string& ID, + const std::function &tick_functor) +{ + auto wrapper = [tick_functor](NodeStatus status, const Blackboard::Ptr&){ return tick_functor(status); }; + registerSimpleDecorator(ID, wrapper); +} + +void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, + const SimpleConditionNode::TickFunctor &tick_functor) { NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeParameters&) { return std::unique_ptr(new SimpleConditionNode(name, tick_functor)); @@ -73,7 +83,8 @@ void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, const S storeNodeModel(ID); } -void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, const SimpleActionNode::TickFunctor& tick_functor) +void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, + const SimpleActionNode::TickFunctor& tick_functor) { NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeParameters&) { return std::unique_ptr(new SimpleActionNode(name, tick_functor)); @@ -83,6 +94,17 @@ void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, const Simp storeNodeModel(ID); } +void BehaviorTreeFactory::registerSimpleDecorator(const std::string &ID, + const SimpleDecoratorNode::TickFunctor &tick_functor) +{ + NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeParameters&) { + return std::unique_ptr(new SimpleDecoratorNode(name, tick_functor)); + }; + + registerBuilder(ID, builder); + storeNodeModel(ID); +} + std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::string& ID, const std::string& name, const NodeParameters& params) const { diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index e2f24a079..c3dca50a7 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -65,7 +65,7 @@ SimpleDecoratorNode::SimpleDecoratorNode(const std::string &name, NodeStatus SimpleDecoratorNode::tick() { - return tick_functor_( child()->executeTick() ); + return tick_functor_( child()->executeTick(), blackboard() ); } } From c6068bd60eca8067ede98b98d6193cdfe353e629 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 22 Aug 2018 12:11:51 +0200 Subject: [PATCH 091/125] more comments and less boilerplate --- examples/simple_example.cpp | 7 +-- examples/tutorial_blackboard.cpp | 62 +++++++++---------- include/Blackboard/blackboard.h | 7 +++ include/behavior_tree_core/behavior_tree.h | 8 ++- include/behavior_tree_core/bt_factory.h | 47 +++++++++----- include/behavior_tree_core/xml_parsing.h | 28 ++++++++- .../behavior_tree_logger/abstract_logger.h | 3 +- src/behavior_tree.cpp | 9 +++ src/bt_factory.cpp | 10 +++ src/xml_parsing.cpp | 28 +++++++++ 10 files changed, 152 insertions(+), 57 deletions(-) diff --git a/examples/simple_example.cpp b/examples/simple_example.cpp index 21347b6c9..43a3de815 100644 --- a/examples/simple_example.cpp +++ b/examples/simple_example.cpp @@ -78,11 +78,8 @@ int main(int argc, char** argv) factory.registerNodeType("BatteryOK"); factory.registerNodeType("Move"); - BT::XMLParser parser(factory); - parser.loadFromText(xml_text_A); - - std::vector nodes; - BT::TreeNodePtr root_node = parser.instantiateTree(nodes); + auto res = buildTreeFromText(factory, xml_text_A); + const TreeNodePtr& root_node = res.first; BT::StdCoutLogger logger_cout(root_node.get()); BT::FileLogger file_file(root_node.get(), "simple_trace.fbl", 32); diff --git a/examples/tutorial_blackboard.cpp b/examples/tutorial_blackboard.cpp index a53caa281..4ab932780 100644 --- a/examples/tutorial_blackboard.cpp +++ b/examples/tutorial_blackboard.cpp @@ -9,6 +9,30 @@ struct Pose2D double x,y,theta; }; +namespace BT{ + +// this template specialization is needed ONLY if you want +// to AUTOMATICALLY convert a NodeParameter into a Pose2D +template <> Pose2D convertFromString(const std::string& str) +{ + auto parts = BT::splitString(str, ';'); + if( parts.size() != 3) + { + throw std::runtime_error("invalid input)"); + } + else{ + Pose2D output; + output.x = convertFromString( parts[0] ); + output.y = convertFromString( parts[1] ); + output.theta = convertFromString( parts[2] ); + return output; + } +} + +} + +//----------------------------------------- + // This action will read the desired robot position // and store it on the BlackBoard (key: "GoalPose") NodeStatus PullGoalPose(const std::shared_ptr& blackboard) @@ -77,29 +101,7 @@ class MoveAction_B: public ActionNodeBase } }; -namespace BT{ -// this template specialization is needed if you want -// to automatically convert a NodeParameter into a Pose2D - -template <> -Pose2D convertFromString(const std::string& str) -{ - auto parts = splitString(str, ';'); - if( parts.size() != 3) - { - throw std::runtime_error("invalid input)"); - } - else{ - Pose2D output; - output.x = convertFromString( parts[0] ); - output.y = convertFromString( parts[1] ); - output.theta = convertFromString( parts[2] ); - return output; - } -} - -} /** Example: simple sequence of 4 actions @@ -130,7 +132,7 @@ const std::string xml_text = R"( // clang-format on -int main(int argc, char** argv) +int main() { using namespace BT; @@ -139,18 +141,12 @@ int main(int argc, char** argv) factory.registerNodeType("MoveAction_A"); factory.registerNodeType("MoveAction_B"); - XMLParser parser(factory); - parser.loadFromText(xml_text); + // create a Blackboard from BlackboardLocal (simple local storage) + auto blackboard = Blackboard::create(); - std::vector nodes; - TreeNodePtr root_node = parser.instantiateTree(nodes); + auto res = buildTreeFromText(factory, xml_text, blackboard); - // create a Blackboard and assign it to your tree - auto bb = Blackboard::create(); - for(auto& node: nodes) - { - node->setBlackboard(bb); - } + const TreeNodePtr& root_node = res.first; root_node->executeTick(); diff --git a/include/Blackboard/blackboard.h b/include/Blackboard/blackboard.h index 3afa3a0a4..e50d5de10 100644 --- a/include/Blackboard/blackboard.h +++ b/include/Blackboard/blackboard.h @@ -41,6 +41,9 @@ class Blackboard Blackboard() = delete; + /** Use this static method to create an instance of the BlackBoard + * to share among all your NodeTrees. + */ template static Blackboard::Ptr create(Args... args ) { @@ -50,6 +53,9 @@ class Blackboard virtual ~Blackboard() = default; + /** Return true if the entry with the given key was found. + * Note that this method may throw an exception if the cast to T failed. + */ template bool get(const std::string& key, T& value) const { if( !impl_ ) @@ -63,6 +69,7 @@ class Blackboard return true; } + /// Update the entry with the given key template void set(const std::string& key, const T& value) { if( impl_) diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index 39358d6ad..942ef0abe 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -32,15 +32,19 @@ namespace BT { -void applyRecursiveVisitor(const TreeNode* node, const std::function& visitor); +void applyRecursiveVisitor(const TreeNode* node, + const std::function& visitor); -void applyRecursiveVisitor(TreeNode* node, const std::function &visitor); +void applyRecursiveVisitor(TreeNode* node, + const std::function &visitor); /** * Debug function to print on a stream */ void printTreeRecursively(const TreeNode* root_node); +void assignBlackboardToEntireTree(TreeNode* root_node, + const Blackboard::Ptr& bb); typedef std::vector> SerializedTreeStatus; diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 2ce9d7e81..2a5416198 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -29,6 +29,7 @@ namespace BT // The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) typedef std::function(const std::string&, const NodeParameters&)> NodeBuilder; +/// This information is used mostly by the XMLParser. struct TreeNodeModel { NodeType type; @@ -43,6 +44,9 @@ class BehaviorTreeFactory bool unregisterBuilder(const std::string& ID); + /** More generic way to register your own builder. + * Most of the time you should use registerSimple???? or registerNodeType<> instead. + */ void registerBuilder(const std::string& ID, NodeBuilder builder); void registerSimpleAction(const std::string& ID, const std::function &tick_functor); @@ -54,19 +58,25 @@ class BehaviorTreeFactory void registerSimpleDecorator(const std::string& ID, const std::function &tick_functor); void registerSimpleDecorator(const std::string& ID, const SimpleDecoratorNode::TickFunctor &tick_functor); - std::unique_ptr instantiateTreeNode(const std::string& ID, const std::string& name, + /** + * @brief instantiateTreeNode creates a TreeNode + * + * @param ID unique ID used to register the node type + * @param name name of this particular instance + * @param params parameters (usually read from the XML definition) + * @return new node. + */ + std::unique_ptr instantiateTreeNode(const std::string& ID, + const std::string& name, const NodeParameters& params) const; - const std::map& builders() const - { - return builders_; - } - - const std::vector& models() const - { - return treenode_models_; - } - + /** registerNodeType is the method to use to register your custom TreeNode. + * + * It accepts only classed derived from either ActionNodeBase, DecoratorNode, + * ControlNode or ConditionNode. + * + * REMINDER: If you want your derived class to + */ template void registerNodeType(const std::string& ID) { @@ -77,26 +87,35 @@ class BehaviorTreeFactory "[registerBuilder]: accepts only classed derived from either ActionNodeBase, " "DecoratorNode, ControlNode or ConditionNode"); + static_assert( !std::is_abstract::value, "[registerBuilder]: Some methods are pure virtual. " + "Did you override the methods tick() and halt()?" ); + constexpr bool default_constructable = std::is_constructible::value; constexpr bool param_constructable = std::is_constructible::value; constexpr bool has_static_required_parameters = has_static_method_requiredNodeParameters::value; static_assert(default_constructable || param_constructable, "[registerBuilder]: the registered class must have at least one of these two constructors: " - " (const std::string&, const NodeParameters&) or (const std::string&)\n"); + " (const std::string&, const NodeParameters&) or (const std::string&)."); static_assert(!(param_constructable && !has_static_required_parameters), - "[registerBuilder]: a node that accepts NodeParameters must also implement a static method: " + "[registerBuilder]: you MUST implement the static method: " " const NodeParameters& requiredNodeParameters();\n"); static_assert( !( has_static_required_parameters && !param_constructable), "[registerBuilder]: since you have a static method requiredNodeParameters(), " - "you will also need a constructor sign signature (const std::string&, const NodeParameters&)\n)" ); + "you MUST add a constructor sign signature (const std::string&, const NodeParameters&)\n" ); registerNodeTypeImpl(ID); storeNodeModel(ID); } + // All the builders. Made available mostly for debug purposes. + const std::map& builders() const; + + // Exposes all the TreeNodeModel. + const std::vector& models() const; + private: std::map builders_; std::vector treenode_models_; diff --git a/include/behavior_tree_core/xml_parsing.h b/include/behavior_tree_core/xml_parsing.h index 5d0a26314..665651488 100644 --- a/include/behavior_tree_core/xml_parsing.h +++ b/include/behavior_tree_core/xml_parsing.h @@ -11,9 +11,9 @@ class XMLParser public: XMLParser(const BehaviorTreeFactory& factory): factory_(factory) {} - void loadFromFile(const std::string& filename) noexcept(false); + void loadFromFile(const std::string& filename); - void loadFromText(const std::string& xml_text) noexcept(false); + void loadFromText(const std::string& xml_text); bool verifyXML(std::vector& error_messages) const noexcept(false); @@ -35,6 +35,30 @@ class XMLParser const BehaviorTreeFactory& factory_; }; +/** Helper function to do the most common steps all at once: +* 1) Create an instance of XMLParse and call loadFromText. +* 2) Instantiate the entire tree. +* 3) Assign the given Blackboard +* +* return: a pair containing the root node (first) and a vector with all the instantiated nodes (second). +*/ +std::pair> +buildTreeFromText(const BehaviorTreeFactory& factory, + const std::string& text, + const Blackboard::Ptr& blackboard = Blackboard::Ptr() ); + +/** Helper function to do the most common steps all at once: +* 1) Create an instance of XMLParse and call loadFromFile. +* 2) Instantiate the entire tree. +* 3) Assign the given Blackboard +* +* return: a pair containing the root node (first) and a vector with all the instantiated nodes (second). +*/ +std::pair> +buildTreeFromFile(const BehaviorTreeFactory& factory, + const std::string& filename, + const Blackboard::Ptr& blackboard = Blackboard::Ptr() ); + class XMLWriter { public: diff --git a/include/behavior_tree_logger/abstract_logger.h b/include/behavior_tree_logger/abstract_logger.h index b58e20a95..f903df48d 100644 --- a/include/behavior_tree_logger/abstract_logger.h +++ b/include/behavior_tree_logger/abstract_logger.h @@ -46,7 +46,8 @@ class StatusChangeLogger inline StatusChangeLogger::StatusChangeLogger(TreeNode* root_node) : enabled_(true), show_transition_to_idle_(true) { - applyRecursiveVisitor(root_node, [this](TreeNode* node) { + applyRecursiveVisitor(root_node, [this](TreeNode* node) + { subscribers_.push_back(node->subscribeToStatusChange( [this](TimePoint timestamp, const TreeNode& node, NodeStatus prev, NodeStatus status) { if (enabled_ && (status != NodeStatus::IDLE || show_transition_to_idle_)) diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index 4dfb37a88..b773ca539 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -93,4 +93,13 @@ void buildSerializedStatusSnapshot(TreeNode* root_node, SerializedTreeStatus& se applyRecursiveVisitor(root_node, visitor); } + +void assignBlackboardToEntireTree(TreeNode *root_node, const Blackboard::Ptr &bb) +{ + auto visitor = [bb](TreeNode* node) { + node->setBlackboard(bb); + }; + applyRecursiveVisitor(root_node, visitor); +} + } diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 0c67a28e3..b5ce79863 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -118,6 +118,16 @@ std::unique_ptr BehaviorTreeFactory::instantiateTreeNode(const std::st return node; } +const std::map &BehaviorTreeFactory::builders() const +{ + return builders_; +} + +const std::vector &BehaviorTreeFactory::models() const +{ + return treenode_models_; +} + void BehaviorTreeFactory::sortTreeNodeModel() { std::sort( treenode_models_.begin(), treenode_models_.end(), diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 51bfe7eae..3fcb090b4 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -481,4 +481,32 @@ std::string XMLWriter::writeXML(const TreeNode *root_node, bool compact_represen return std::string( printer.CStr(), printer.CStrSize()-1 ); } +std::pair > +buildTreeFromText(const BehaviorTreeFactory &factory, + const std::string &text, + const Blackboard::Ptr &blackboard) +{ + XMLParser parser(factory); + parser.loadFromText(text); + + std::vector nodes; + auto root = parser.instantiateTree(nodes); + assignBlackboardToEntireTree(root.get(), blackboard ); + return {root, nodes}; +} + +std::pair > +buildTreeFromFile(const BehaviorTreeFactory &factory, + const std::string &filename, + const Blackboard::Ptr &blackboard) +{ + XMLParser parser(factory); + parser.loadFromFile(filename); + + std::vector nodes; + auto root = parser.instantiateTree(nodes); + assignBlackboardToEntireTree(root.get(), blackboard ); + return {root, nodes}; +} + } From df2b8784ea4e36fc4ee191d90760bdea898bdfce Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 22 Aug 2018 15:03:10 +0200 Subject: [PATCH 092/125] polishing the API --- CMakeLists.txt | 5 ++ examples/simple_example.cpp | 17 +++-- examples/tutorial_blackboard.cpp | 2 +- examples/tutorial_factory_tree.cpp | 88 ++++++++++++++++++++++++ examples/tutorial_programmatic_tree.cpp | 84 ++++++++++++++++++++++ gtest/crossdoor_example.cpp | 8 +-- gtest/gtest_factory.cpp | 8 +-- gtest/include/crossdoor_dummy_nodes.h | 14 ++-- include/behavior_tree_core/bt_factory.h | 3 - include/behavior_tree_core/tree_node.h | 4 +- include/behavior_tree_core/xml_parsing.h | 14 ++-- src/bt_factory.cpp | 40 +++++------ src/xml_parsing.cpp | 30 ++++---- 13 files changed, 249 insertions(+), 68 deletions(-) create mode 100644 examples/tutorial_factory_tree.cpp create mode 100644 examples/tutorial_programmatic_tree.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 27e05a410..c8fe0e9b8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -140,6 +140,11 @@ target_link_libraries(simple_example ${BEHAVIOR_TRE_LIBRARIES} ) add_executable(tutorial_blackboard examples/tutorial_blackboard.cpp ) target_link_libraries(tutorial_blackboard ${BEHAVIOR_TRE_LIBRARIES} ) +add_executable(tutorial_programmatic_tree examples/tutorial_programmatic_tree.cpp ) +target_link_libraries(tutorial_programmatic_tree ${BEHAVIOR_TRE_LIBRARIES} ) + +add_executable(tutorial_factory_tree examples/tutorial_factory_tree.cpp ) +target_link_libraries(tutorial_factory_tree ${BEHAVIOR_TRE_LIBRARIES} ) ###################################################### # INSTALLATION OF LIBRARY AND EXECUTABLE diff --git a/examples/simple_example.cpp b/examples/simple_example.cpp index 43a3de815..83cc277bb 100644 --- a/examples/simple_example.cpp +++ b/examples/simple_example.cpp @@ -8,25 +8,30 @@ class BatteryCondition: public BT::ConditionNode { public: BatteryCondition(const std::string& name): BT::ConditionNode(name) {} - BT::NodeStatus tick() override { + BT::NodeStatus tick() override + { std::cout << "[ Battery: OK ]" << std::endl; - return BT::NodeStatus::SUCCESS; } + return BT::NodeStatus::SUCCESS; + } }; class TemperatureCondition: public BT::ConditionNode { public: TemperatureCondition(const std::string& name): BT::ConditionNode(name) {} - BT::NodeStatus tick() override { + BT::NodeStatus tick() override + { std::cout << "[ Temperature: OK ]" << std::endl; - return BT::NodeStatus::SUCCESS; } + return BT::NodeStatus::SUCCESS; + } }; class MoveAction: public BT::ActionNode { public: MoveAction(const std::string& name): BT::ActionNode(name) {} - BT::NodeStatus tick() override { + BT::NodeStatus tick() override + { std::cout << "[ Move: started ]" << std::endl; std::this_thread::sleep_for( std::chrono::milliseconds(80) ); std::cout << "[ Move: finished ]" << std::endl; @@ -79,7 +84,7 @@ int main(int argc, char** argv) factory.registerNodeType("Move"); auto res = buildTreeFromText(factory, xml_text_A); - const TreeNodePtr& root_node = res.first; + const TreeNode::Ptr& root_node = res.first; BT::StdCoutLogger logger_cout(root_node.get()); BT::FileLogger file_file(root_node.get(), "simple_trace.fbl", 32); diff --git a/examples/tutorial_blackboard.cpp b/examples/tutorial_blackboard.cpp index 4ab932780..d633a6f6f 100644 --- a/examples/tutorial_blackboard.cpp +++ b/examples/tutorial_blackboard.cpp @@ -146,7 +146,7 @@ int main() auto res = buildTreeFromText(factory, xml_text, blackboard); - const TreeNodePtr& root_node = res.first; + const TreeNode::Ptr& root_node = res.first; root_node->executeTick(); diff --git a/examples/tutorial_factory_tree.cpp b/examples/tutorial_factory_tree.cpp new file mode 100644 index 000000000..eaeaf3ae3 --- /dev/null +++ b/examples/tutorial_factory_tree.cpp @@ -0,0 +1,88 @@ +#include "behavior_tree_core/xml_parsing.h" +#include "behavior_tree_logger/bt_cout_logger.h" +#include "Blackboard/blackboard_local.h" + +using namespace BT; + +NodeStatus SimpleAction() +{ + std::cout << "SimpleActionFunc" << std::endl; + return NodeStatus::SUCCESS; +} + +class Foo +{ +public: + Foo(): _val(0) {} + + NodeStatus actionOne() + { + _val = 42; + std::cout << "Foo::actionOne -> set val to 42" << std::endl; + return NodeStatus::SUCCESS; + } + + NodeStatus actionTwo() + { + std::cout << "Foo::actionTwo -> reading val => "<< _val << std::endl; + _val = 0; + return NodeStatus::SUCCESS; + } + +private: + int _val; +}; + + +class CustomAction: public ActionNodeBase +{ +public: + CustomAction(const std::string& name): ActionNodeBase(name) {} + + NodeStatus tick() override + { + std::cout << "CustomAction: " << this->name() << std::endl; + return NodeStatus::SUCCESS; + } +}; + + +const std::string xml_text = R"( + + + + + + + + + + + + + + )"; + +int main() +{ + BehaviorTreeFactory factory; + + Foo foo; + + // This is the syntax to register SimpleActionNodes + factory.registerSimpleAction("SimpleAction", std::bind(SimpleAction) ); + factory.registerSimpleAction("ActionOne", std::bind( &Foo::actionOne, &foo)); + factory.registerSimpleAction("ActionTwo", std::bind( &Foo::actionTwo, &foo)); + + factory.registerNodeType("CustomAction"); + + auto res = buildTreeFromText(factory, xml_text); + const TreeNode::Ptr& root_node = res.first; + + // the tick is propagated to all the children. + // until one of the returns FAILURE or RUNNING. + // In this case all of the return SUCCESS + root_node->executeTick(); + + return 0; +} diff --git a/examples/tutorial_programmatic_tree.cpp b/examples/tutorial_programmatic_tree.cpp new file mode 100644 index 000000000..d1a8d0d9d --- /dev/null +++ b/examples/tutorial_programmatic_tree.cpp @@ -0,0 +1,84 @@ +#include "behavior_tree_core/xml_parsing.h" +#include "behavior_tree_logger/bt_cout_logger.h" +#include "Blackboard/blackboard_local.h" + +using namespace BT; + +NodeStatus SimpleAction() +{ + std::cout << "SimpleActionFunc" << std::endl; + return NodeStatus::SUCCESS; +} + +class Foo +{ +public: + Foo(): _val(0) {} + + NodeStatus actionOne() + { + _val = 42; + std::cout << "Foo::actionOne -> set val to 42" << std::endl; + return NodeStatus::SUCCESS; + } + + NodeStatus actionTwo() + { + std::cout << "Foo::actionTwo -> reading val => "<< _val << std::endl; + _val = 0; + return NodeStatus::SUCCESS; + } + +private: + int _val; +}; + + +class CustomAction: public ActionNodeBase +{ +public: + CustomAction(const std::string& name): ActionNodeBase(name) {} + + NodeStatus tick() override + { + std::cout << "CustomAction: " << this->name() << std::endl; + return NodeStatus::SUCCESS; + } +}; + + +int main() +{ + Foo foo; + + BT::SequenceNode sequence_root("sequence"); + + // Aimple funtions can be wrapped inside in ActionNodeBase + // using the SimpleActionNode + SimpleActionNode act_simple("simple_action", std::bind(SimpleAction) ); + + // SimpleActionNode warks also with class methods, using std::bind + SimpleActionNode act_1("action_one", std::bind( &Foo::actionOne, &foo) ); + SimpleActionNode act_2("action_two", std::bind( &Foo::actionTwo, &foo) ); + + // Nevertheless, the way to be able to use ALL the funtionality of a TreeNode + // is to create your own class that inherits from either: + // - ConditionNode (synchronous execution) + // - ActionNodeBase (synchronous execution) + // - ActionNode (asynchronous execution is a separate thread). + CustomAction act_custom("my_action"); + + // Add children to the sequence. + // they will be executed in the same order they are added. + sequence_root.addChild(&act_simple); + sequence_root.addChild(&act_1); + sequence_root.addChild(&act_2); + sequence_root.addChild(&act_custom); + + // the tick is propagated to all the children. + // until one of the returns FAILURE or RUNNING. + // In this case all of the return SUCCESS + sequence_root.executeTick(); + + return 0; +} diff --git a/gtest/crossdoor_example.cpp b/gtest/crossdoor_example.cpp index 38fb6f65e..44d440d72 100644 --- a/gtest/crossdoor_example.cpp +++ b/gtest/crossdoor_example.cpp @@ -18,8 +18,8 @@ const std::string xml_text = R"( - - + + @@ -55,8 +55,8 @@ int main(int argc, char** argv) XMLParser parser(factory); parser.loadFromText(xml_text); - std::vector nodes; - BT::TreeNodePtr root_node = parser.instantiateTree(nodes); + std::vector nodes; + BT::TreeNode::Ptr root_node = parser.instantiateTree(nodes); StdCoutLogger logger_cout(root_node.get()); MinitraceLogger logger_minitrace(root_node.get(), "bt_trace.json"); diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp index 5eed08b3b..c4bfdecaf 100644 --- a/gtest/gtest_factory.cpp +++ b/gtest/gtest_factory.cpp @@ -96,9 +96,9 @@ TEST(BehaviorTreeFactory, VerifyLargeTree) ASSERT_EQ(res, true); ASSERT_EQ(errors.size(), 0); - std::vector nodes; + std::vector nodes; - BT::TreeNodePtr root_node = parser.instantiateTree(nodes); + BT::TreeNode::Ptr root_node = parser.instantiateTree(nodes); BT::printTreeRecursively(root_node.get()); @@ -153,9 +153,9 @@ TEST(BehaviorTreeFactory, Subtree) ASSERT_EQ(res, true); ASSERT_EQ(errors.size(), 0); - std::vector nodes; + std::vector nodes; - BT::TreeNodePtr root_node = parser.instantiateTree( nodes); + BT::TreeNode::Ptr root_node = parser.instantiateTree( nodes); BT::printTreeRecursively(root_node.get()); ASSERT_EQ(root_node->name(), "root_selector"); diff --git a/gtest/include/crossdoor_dummy_nodes.h b/gtest/include/crossdoor_dummy_nodes.h index e4a79523c..83224711b 100644 --- a/gtest/include/crossdoor_dummy_nodes.h +++ b/gtest/include/crossdoor_dummy_nodes.h @@ -12,13 +12,13 @@ class CrossDoor door_open_ = true; door_locked_ = false; - factory.registerSimpleCondition("IsDoorOpen", [this]() { return IsDoorOpen(); }); - factory.registerSimpleAction("PassThroughDoor", [this]() { return PassThroughDoor(); }); - factory.registerSimpleAction("PassThroughWindow", [this]() { return PassThroughWindow(); }); - factory.registerSimpleAction("OpenDoor", [this]() { return OpenDoor(); }); - factory.registerSimpleAction("CloseDoor", [this]() { return CloseDoor(); }); - factory.registerSimpleCondition("IsDoorLocked", [this]() { return IsDoorLocked(); }); - factory.registerSimpleAction("UnlockDoor", [this]() { return UnlockDoor(); }); + factory.registerSimpleCondition("IsDoorOpen", std::bind(&CrossDoor::IsDoorOpen, this) ); + factory.registerSimpleAction("PassThroughDoor", std::bind(&CrossDoor::PassThroughDoor, this) ); + factory.registerSimpleAction("PassThroughWindow", std::bind(&CrossDoor::PassThroughWindow, this) ); + factory.registerSimpleAction("OpenDoor", std::bind(&CrossDoor::OpenDoor, this) ); + factory.registerSimpleAction("CloseDoor", std::bind(&CrossDoor::CloseDoor, this) ); + factory.registerSimpleCondition("IsDoorLocked", std::bind(&CrossDoor::IsDoorLocked, this) ); + factory.registerSimpleAction("UnlockDoor", std::bind(&CrossDoor::UnlockDoor, this) ); _multiplier = fast ? 1 : 10; } diff --git a/include/behavior_tree_core/bt_factory.h b/include/behavior_tree_core/bt_factory.h index 2a5416198..cd1581b13 100644 --- a/include/behavior_tree_core/bt_factory.h +++ b/include/behavior_tree_core/bt_factory.h @@ -49,13 +49,10 @@ class BehaviorTreeFactory */ void registerBuilder(const std::string& ID, NodeBuilder builder); - void registerSimpleAction(const std::string& ID, const std::function &tick_functor); void registerSimpleAction(const std::string& ID, const SimpleActionNode::TickFunctor &tick_functor); - void registerSimpleCondition(const std::string& ID, const std::function &tick_functor); void registerSimpleCondition(const std::string& ID, const SimpleConditionNode::TickFunctor &tick_functor); - void registerSimpleDecorator(const std::string& ID, const std::function &tick_functor); void registerSimpleDecorator(const std::string& ID, const SimpleDecoratorNode::TickFunctor &tick_functor); /** diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 77c7274be..535cdc548 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -52,6 +52,8 @@ class TreeNode TreeNode(const std::string& name, const NodeParameters& parameters); virtual ~TreeNode() = default; + typedef std::shared_ptr Ptr; + /// The method that will be executed to invoke tick(); and setStatus(); virtual BT::NodeStatus executeTick(); @@ -167,7 +169,7 @@ class TreeNode Blackboard::Ptr bb_; }; -typedef std::shared_ptr TreeNodePtr; + } diff --git a/include/behavior_tree_core/xml_parsing.h b/include/behavior_tree_core/xml_parsing.h index 665651488..f93c8646a 100644 --- a/include/behavior_tree_core/xml_parsing.h +++ b/include/behavior_tree_core/xml_parsing.h @@ -18,17 +18,17 @@ class XMLParser bool verifyXML(std::vector& error_messages) const noexcept(false); using NodeBuilder = - std::function; + std::function; - TreeNodePtr instantiateTree(std::vector& nodes); + TreeNode::Ptr instantiateTree(std::vector& nodes); private: //method to visit each node of a tree - TreeNodePtr treeParsing(const tinyxml2::XMLElement* root_element, + TreeNode::Ptr treeParsing(const tinyxml2::XMLElement* root_element, const NodeBuilder& node_builder, - std::vector& nodes, - const TreeNodePtr &root_parent); + std::vector& nodes, + const TreeNode::Ptr &root_parent); tinyxml2::XMLDocument doc_; @@ -42,7 +42,7 @@ class XMLParser * * return: a pair containing the root node (first) and a vector with all the instantiated nodes (second). */ -std::pair> +std::pair> buildTreeFromText(const BehaviorTreeFactory& factory, const std::string& text, const Blackboard::Ptr& blackboard = Blackboard::Ptr() ); @@ -54,7 +54,7 @@ buildTreeFromText(const BehaviorTreeFactory& factory, * * return: a pair containing the root node (first) and a vector with all the instantiated nodes (second). */ -std::pair> +std::pair> buildTreeFromFile(const BehaviorTreeFactory& factory, const std::string& filename, const Blackboard::Ptr& blackboard = Blackboard::Ptr() ); diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index b5ce79863..ca55fc27d 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -51,26 +51,26 @@ void BehaviorTreeFactory::registerBuilder(const std::string& ID, NodeBuilder bui builders_.insert(std::make_pair(ID, builder)); } -void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, - const std::function &tick_functor) -{ - auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; - registerSimpleCondition(ID, wrapper); -} - -void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, - const std::function &tick_functor) -{ - auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; - registerSimpleAction(ID, wrapper); -} - -void BehaviorTreeFactory::registerSimpleDecorator(const std::string& ID, - const std::function &tick_functor) -{ - auto wrapper = [tick_functor](NodeStatus status, const Blackboard::Ptr&){ return tick_functor(status); }; - registerSimpleDecorator(ID, wrapper); -} +//void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, +// const std::function &tick_functor) +//{ +// auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; +// registerSimpleCondition(ID, wrapper); +//} + +//void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, +// const std::function &tick_functor) +//{ +// auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; +// registerSimpleAction(ID, wrapper); +//} + +//void BehaviorTreeFactory::registerSimpleDecorator(const std::string& ID, +// const std::function &tick_functor) +//{ +// auto wrapper = [tick_functor](NodeStatus status, const Blackboard::Ptr&){ return tick_functor(status); }; +// registerSimpleDecorator(ID, wrapper); +//} void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, const SimpleConditionNode::TickFunctor &tick_functor) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 3fcb090b4..40c9ee937 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -231,7 +231,7 @@ bool XMLParser::verifyXML(std::vector& error_messages) const return is_valid; } -TreeNodePtr XMLParser::instantiateTree(std::vector& nodes) +TreeNode::Ptr XMLParser::instantiateTree(std::vector& nodes) { nodes.clear(); @@ -281,9 +281,9 @@ TreeNodePtr XMLParser::instantiateTree(std::vector& nodes) //-------------------------------------- NodeBuilder node_builder = [&](const std::string& ID, const std::string& name, - const NodeParameters& params, TreeNodePtr parent) -> TreeNodePtr + const NodeParameters& params, TreeNode::Ptr parent) -> TreeNode::Ptr { - TreeNodePtr child_node = factory_.instantiateTreeNode(ID, name, params); + TreeNode::Ptr child_node = factory_.instantiateTreeNode(ID, name, params); nodes.push_back(child_node); if (parent) { @@ -310,19 +310,19 @@ TreeNodePtr XMLParser::instantiateTree(std::vector& nodes) //-------------------------------------- auto root_element = bt_roots[main_tree_ID]->FirstChildElement(); - return treeParsing(root_element, node_builder, nodes, TreeNodePtr()); + return treeParsing(root_element, node_builder, nodes, TreeNode::Ptr()); } -TreeNodePtr BT::XMLParser::treeParsing(const XMLElement *root_element, +TreeNode::Ptr BT::XMLParser::treeParsing(const XMLElement *root_element, const NodeBuilder &node_builder, - std::vector &nodes, - const TreeNodePtr& root_parent) + std::vector &nodes, + const TreeNode::Ptr& root_parent) { using namespace tinyxml2; - std::function recursiveStep; + std::function recursiveStep; - recursiveStep = [&](const TreeNodePtr& parent, const tinyxml2::XMLElement* element) -> TreeNodePtr { + recursiveStep = [&](const TreeNode::Ptr& parent, const tinyxml2::XMLElement* element) -> TreeNode::Ptr { const std::string element_name = element->Name(); std::string node_ID; std::string node_alias; @@ -362,7 +362,7 @@ TreeNodePtr BT::XMLParser::treeParsing(const XMLElement *root_element, } } - TreeNodePtr node = node_builder(node_ID, node_alias, node_params, parent); + TreeNode::Ptr node = node_builder(node_ID, node_alias, node_params, parent); nodes.push_back(node); for (auto child_element = element->FirstChildElement(); child_element; @@ -375,7 +375,7 @@ TreeNodePtr BT::XMLParser::treeParsing(const XMLElement *root_element, }; // start recursion - TreeNodePtr root = recursiveStep(root_parent, root_element); + TreeNode::Ptr root = recursiveStep(root_parent, root_element); return root; } @@ -481,7 +481,7 @@ std::string XMLWriter::writeXML(const TreeNode *root_node, bool compact_represen return std::string( printer.CStr(), printer.CStrSize()-1 ); } -std::pair > +std::pair > buildTreeFromText(const BehaviorTreeFactory &factory, const std::string &text, const Blackboard::Ptr &blackboard) @@ -489,13 +489,13 @@ buildTreeFromText(const BehaviorTreeFactory &factory, XMLParser parser(factory); parser.loadFromText(text); - std::vector nodes; + std::vector nodes; auto root = parser.instantiateTree(nodes); assignBlackboardToEntireTree(root.get(), blackboard ); return {root, nodes}; } -std::pair > +std::pair > buildTreeFromFile(const BehaviorTreeFactory &factory, const std::string &filename, const Blackboard::Ptr &blackboard) @@ -503,7 +503,7 @@ buildTreeFromFile(const BehaviorTreeFactory &factory, XMLParser parser(factory); parser.loadFromFile(filename); - std::vector nodes; + std::vector nodes; auto root = parser.instantiateTree(nodes); assignBlackboardToEntireTree(root.get(), blackboard ); return {root, nodes}; From f005384dc0e6158baaeaae1d2c2143499cf003cf Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 22 Aug 2018 16:13:10 +0200 Subject: [PATCH 093/125] Changes in the Loggers, motivated by the new tutorial_sequence_star.cpp --- CMakeLists.txt | 27 ++-- examples/simple_example.cpp | 109 --------------- examples/tutorial_sequence_star.cpp | 128 ++++++++++++++++++ gtest/crossdoor_example.cpp | 2 +- include/behavior_tree_logger/bt_cout_logger.h | 40 ++---- .../bt_minitrace_logger.h | 55 ++------ .../behavior_tree_logger/bt_zmq_publisher.h | 1 + src/loggers/bt_cout_logger.cpp | 40 ++++++ src/{ => loggers}/bt_file_logger.cpp | 5 +- src/loggers/bt_minitrace_logger.cpp | 58 ++++++++ src/{ => loggers}/bt_zmq_publisher.cpp | 4 + 11 files changed, 270 insertions(+), 199 deletions(-) delete mode 100644 examples/simple_example.cpp create mode 100644 examples/tutorial_sequence_star.cpp create mode 100644 src/loggers/bt_cout_logger.cpp rename src/{ => loggers}/bt_file_logger.cpp (92%) create mode 100644 src/loggers/bt_minitrace_logger.cpp rename src/{ => loggers}/bt_zmq_publisher.cpp (98%) diff --git a/CMakeLists.txt b/CMakeLists.txt index c8fe0e9b8..a42570971 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -61,9 +61,12 @@ set(BT_Source src/behavior_tree.cpp src/xml_parsing.cpp - src/bt_file_logger.cpp - 3rdparty/tinyXML2/tinyxml2.cpp + src/loggers/bt_cout_logger.cpp + src/loggers/bt_file_logger.cpp + src/loggers/bt_minitrace_logger.cpp + + 3rdparty/tinyXML2/tinyxml2.cpp 3rdparty/minitrace/minitrace.cpp ) include_directories(include 3rdparty/) @@ -75,7 +78,7 @@ find_package(ZMQ) if( ZMQ_FOUND ) message(STATUS "ZeroMQ found.") add_definitions( -DZMQ_FOUND ) - set(BT_Source ${BT_Source} src/bt_zmq_publisher.cpp ) + set(BT_Source ${BT_Source} src/loggers/bt_zmq_publisher.cpp ) set(BEHAVIOR_TRE_LIBRARIES behavior_tree_core zmq) else() @@ -133,18 +136,16 @@ if( ZMQ_FOUND ) target_link_libraries(bt_recorder ${BEHAVIOR_TRE_LIBRARIES} ) endif() -add_executable(simple_example examples/simple_example.cpp ) -target_link_libraries(simple_example ${BEHAVIOR_TRE_LIBRARIES} ) - - -add_executable(tutorial_blackboard examples/tutorial_blackboard.cpp ) -target_link_libraries(tutorial_blackboard ${BEHAVIOR_TRE_LIBRARIES} ) +function(BuildExample filename) + add_executable(${filename} examples/${filename}.cpp ) + target_link_libraries(${filename} ${BEHAVIOR_TRE_LIBRARIES} ) +endfunction() -add_executable(tutorial_programmatic_tree examples/tutorial_programmatic_tree.cpp ) -target_link_libraries(tutorial_programmatic_tree ${BEHAVIOR_TRE_LIBRARIES} ) +BuildExample(tutorial_programmatic_tree) +BuildExample(tutorial_factory_tree) +BuildExample(tutorial_sequence_star) +BuildExample(tutorial_blackboard) -add_executable(tutorial_factory_tree examples/tutorial_factory_tree.cpp ) -target_link_libraries(tutorial_factory_tree ${BEHAVIOR_TRE_LIBRARIES} ) ###################################################### # INSTALLATION OF LIBRARY AND EXECUTABLE diff --git a/examples/simple_example.cpp b/examples/simple_example.cpp deleted file mode 100644 index 83cc277bb..000000000 --- a/examples/simple_example.cpp +++ /dev/null @@ -1,109 +0,0 @@ -#include "behavior_tree_core/xml_parsing.h" -#include "behavior_tree_logger/bt_cout_logger.h" -#include "behavior_tree_logger/bt_file_logger.h" - -// clang-format off - -class BatteryCondition: public BT::ConditionNode -{ -public: - BatteryCondition(const std::string& name): BT::ConditionNode(name) {} - BT::NodeStatus tick() override - { - std::cout << "[ Battery: OK ]" << std::endl; - return BT::NodeStatus::SUCCESS; - } -}; - -class TemperatureCondition: public BT::ConditionNode -{ -public: - TemperatureCondition(const std::string& name): BT::ConditionNode(name) {} - BT::NodeStatus tick() override - { - std::cout << "[ Temperature: OK ]" << std::endl; - return BT::NodeStatus::SUCCESS; - } -}; - -class MoveAction: public BT::ActionNode -{ -public: - MoveAction(const std::string& name): BT::ActionNode(name) {} - BT::NodeStatus tick() override - { - std::cout << "[ Move: started ]" << std::endl; - std::this_thread::sleep_for( std::chrono::milliseconds(80) ); - std::cout << "[ Move: finished ]" << std::endl; - return BT::NodeStatus::SUCCESS; - } -}; - - -const std::string xml_text_A = R"( - - - - - - - - - - - - - - - )"; - -const std::string xml_text_B = R"( - - - - - - - - - - - - - )"; - -// clang-format on - -int main(int argc, char** argv) -{ - using namespace BT; - - BT::BehaviorTreeFactory factory; - factory.registerNodeType("TemperatureOK"); - factory.registerNodeType("BatteryOK"); - factory.registerNodeType("Move"); - - auto res = buildTreeFromText(factory, xml_text_A); - const TreeNode::Ptr& root_node = res.first; - - BT::StdCoutLogger logger_cout(root_node.get()); - BT::FileLogger file_file(root_node.get(), "simple_trace.fbl", 32); - - std::cout << "\n------- First executeTick() --------" << std::endl; - root_node->executeTick(); - std::cout << "\n------- sleep --------" << std::endl; - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - std::cout << "\n------- Second executeTick() --------" << std::endl; - root_node->executeTick(); - std::cout << "\n------- sleep --------" << std::endl; - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - std::cout << "\n------- Third executeTick() --------" << std::endl; - root_node->executeTick(); - std::cout << std::endl; - - std::cout << "\n-------\n"; - BT::XMLWriter writer(factory); - std::cout << writer.writeXML( root_node.get() ) << std::endl; - - return 0; -} diff --git a/examples/tutorial_sequence_star.cpp b/examples/tutorial_sequence_star.cpp new file mode 100644 index 000000000..58a39a9b4 --- /dev/null +++ b/examples/tutorial_sequence_star.cpp @@ -0,0 +1,128 @@ +#include "behavior_tree_core/xml_parsing.h" +#include "behavior_tree_logger/bt_cout_logger.h" +#include "behavior_tree_logger/bt_file_logger.h" + +using namespace BT; + + +NodeStatus checkBattery() +{ + std::cout << "[ Battery: OK ]" << std::endl; + return NodeStatus::SUCCESS; +} + +NodeStatus CheckTemperature() +{ + std::cout << "[ Temperature: OK ]" << std::endl; + return NodeStatus::SUCCESS; +} + +// This is an asynchronous operation that will run in a separate thread +class MoveAction: public ActionNode +{ +public: + MoveAction(const std::string& name): ActionNode(name) {} + NodeStatus tick() override + { + std::cout << "[ Move: started ]" << std::endl; + std::this_thread::sleep_for( std::chrono::milliseconds(80) ); + std::cout << "[ Move: finished ]" << std::endl; + return NodeStatus::SUCCESS; + } +}; + +// clang-format off + +const std::string xml_text_sequence = R"( + + + + + + + + + + + + + )"; + +const std::string xml_text_sequence_star = R"( + + + + + + + + + + + + + )"; + +// clang-format on + +void Assert(bool condition) +{ + if( !condition ) throw std::runtime_error("this is not what I expected"); +} + +int main() +{ + BehaviorTreeFactory factory; + factory.registerSimpleCondition("TemperatureOK", std::bind( checkBattery )); + factory.registerSimpleCondition("BatteryOK", std::bind( CheckTemperature )); + factory.registerNodeType("Move"); + + // Loog at the state transitions and messages using either + // xml_text_sequence and xml_text_sequence_star + + // The main difference that you should notice is that the + // actions BatteryOK and TempearaturOK are executed at each tick() + // is Sequence is used and only once if SequenceStar is used. + + for(auto& xml_text: {xml_text_sequence, xml_text_sequence_star}) + { + std::cout << "\n------------ BUILDING A NEW TREE ------------\n\n" << std::endl; + + auto tree = buildTreeFromText(factory, xml_text); + TreeNode::Ptr root_node = tree.first; + + // This logger will show all the state transitions on console + StdCoutLogger logger_cout(root_node.get()); + + // This other logger will save the state transition in a custom file format + // simple_trace.fbl can be visualized using the command line tool [bt_log_cat] + FileLogger file_file(root_node.get(), "simple_trace.fbl", 32); + + NodeStatus status; + + std::cout << "\n------- First executeTick() --------" << std::endl; + status = root_node->executeTick(); + Assert( status == NodeStatus::RUNNING); + + std::cout << "\n------- sleep --------" << std::endl; + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + + std::cout << "\n------- Second executeTick() --------" << std::endl; + status = root_node->executeTick(); + Assert( status == NodeStatus::RUNNING); + + std::cout << "\n------- sleep --------" << std::endl; + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + + std::cout << "\n------- Third executeTick() --------" << std::endl; + status = root_node->executeTick(); + Assert( status == NodeStatus::SUCCESS); + + std::cout << std::endl; + + // The main difference that you should notice is that the + // actions BatteryOK and TempearaturOK are executed at each tick() + // is Sequence is used and only once if SequenceStar is used. + } + return 0; +} diff --git a/gtest/crossdoor_example.cpp b/gtest/crossdoor_example.cpp index 44d440d72..3deb2b0f0 100644 --- a/gtest/crossdoor_example.cpp +++ b/gtest/crossdoor_example.cpp @@ -43,7 +43,7 @@ const std::string xml_text = R"( // clang-format on -int main(int argc, char** argv) +int main() { using namespace BT; diff --git a/include/behavior_tree_logger/bt_cout_logger.h b/include/behavior_tree_logger/bt_cout_logger.h index d61579e7a..8ead63b12 100644 --- a/include/behavior_tree_logger/bt_cout_logger.h +++ b/include/behavior_tree_logger/bt_cout_logger.h @@ -18,36 +18,18 @@ namespace BT class StdCoutLogger : public StatusChangeLogger { + static std::atomic ref_count; + public: - StdCoutLogger(TreeNode* root_node) : StatusChangeLogger(root_node) - { - static bool first_instance = true; - if (first_instance) - { - first_instance = false; - } - else - { - throw std::logic_error("Only one instance of StdCoutLogger shall be created"); - } - } - - virtual void callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) override - { - using namespace std::chrono; - - constexpr const char* whitespaces = " "; - constexpr const size_t ws_count = 25; - - double since_epoch = duration(timestamp.time_since_epoch()).count(); - printf("[%.3f]: %s%s %s -> %s\n", since_epoch, node.name().c_str(), - &whitespaces[std::min(ws_count, node.name().size())], toStr(prev_status, true), toStr(status, true)); - } - - virtual void flush() override - { - std::cout << std::flush; - } + StdCoutLogger(TreeNode* root_node); + ~StdCoutLogger(); + + virtual void callback(TimePoint timestamp, + const TreeNode& node, + NodeStatus prev_status, + NodeStatus status) override; + + virtual void flush() override; }; } // end namespace diff --git a/include/behavior_tree_logger/bt_minitrace_logger.h b/include/behavior_tree_logger/bt_minitrace_logger.h index c89974b54..f4620e464 100644 --- a/include/behavior_tree_logger/bt_minitrace_logger.h +++ b/include/behavior_tree_logger/bt_minitrace_logger.h @@ -9,56 +9,19 @@ namespace BT { class MinitraceLogger : public StatusChangeLogger { - public: - MinitraceLogger(TreeNode* root_node, const char* filename_json) : StatusChangeLogger(root_node) - { - static bool first_instance = true; - if (first_instance) - { - first_instance = false; - } - else - { - throw std::logic_error("Only one instance of MinitraceLogger shall be created"); - } - minitrace::mtr_register_sigint_handler(); - minitrace::mtr_init(filename_json); - this->enableTransitionToIdle(true); - } - - virtual ~MinitraceLogger() override - { - minitrace::mtr_flush(); - minitrace::mtr_shutdown(); - } + static std::atomic ref_count; - virtual void callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) override - { - using namespace minitrace; - - const bool statusCompleted = (status == NodeStatus::SUCCESS || status == NodeStatus::FAILURE); + public: + MinitraceLogger(TreeNode* root_node, const char* filename_json); - const char* category = toStr(node.type()); - const char* name = node.name().c_str(); + virtual ~MinitraceLogger() override; - if (prev_status == NodeStatus::IDLE && statusCompleted) - { - MTR_INSTANT(category, name); - } - else if (status == NodeStatus::RUNNING) - { - MTR_BEGIN(category, name); - } - else if (prev_status == NodeStatus::RUNNING && statusCompleted) - { - MTR_END(category, name); - } - } + virtual void callback(TimePoint timestamp, + const TreeNode& node, + NodeStatus prev_status, + NodeStatus status) override; - virtual void flush() override - { - minitrace::mtr_flush(); - } + virtual void flush() override; private: TimePoint prev_time_; diff --git a/include/behavior_tree_logger/bt_zmq_publisher.h b/include/behavior_tree_logger/bt_zmq_publisher.h index 7f3db0393..229bad1b6 100644 --- a/include/behavior_tree_logger/bt_zmq_publisher.h +++ b/include/behavior_tree_logger/bt_zmq_publisher.h @@ -11,6 +11,7 @@ namespace BT { class PublisherZMQ : public StatusChangeLogger { + static std::atomic ref_count; public: PublisherZMQ(TreeNode* root_node, int max_msg_per_second = 25); diff --git a/src/loggers/bt_cout_logger.cpp b/src/loggers/bt_cout_logger.cpp new file mode 100644 index 000000000..26358972a --- /dev/null +++ b/src/loggers/bt_cout_logger.cpp @@ -0,0 +1,40 @@ +#include "behavior_tree_logger/bt_cout_logger.h" + +namespace BT +{ + +std::atomic StdCoutLogger::ref_count(false); + +StdCoutLogger::StdCoutLogger(TreeNode* root_node) : + StatusChangeLogger(root_node) +{ + bool expected = false; + if ( ! ref_count.compare_exchange_strong( expected, true) ) + { + throw std::logic_error("Only one instance of StdCoutLogger shall be created"); + } +} +StdCoutLogger::~StdCoutLogger() +{ + ref_count.store( false ); +} + +void StdCoutLogger::callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) +{ + using namespace std::chrono; + + constexpr const char* whitespaces = " "; + constexpr const size_t ws_count = 25; + + double since_epoch = duration(timestamp.time_since_epoch()).count(); + printf("[%.3f]: %s%s %s -> %s\n", since_epoch, node.name().c_str(), + &whitespaces[std::min(ws_count, node.name().size())], toStr(prev_status, true), toStr(status, true)); +} + +void StdCoutLogger::flush() +{ + std::cout << std::flush; +} + + +} // end namespace diff --git a/src/bt_file_logger.cpp b/src/loggers/bt_file_logger.cpp similarity index 92% rename from src/bt_file_logger.cpp rename to src/loggers/bt_file_logger.cpp index 7ed75eeb7..f07b3b31c 100644 --- a/src/bt_file_logger.cpp +++ b/src/loggers/bt_file_logger.cpp @@ -3,7 +3,10 @@ namespace BT { -FileLogger::FileLogger(BT::TreeNode* root_node, const char* filename, uint16_t buffer_size) + +FileLogger::FileLogger(BT::TreeNode* root_node, + const char* filename, + uint16_t buffer_size) : StatusChangeLogger(root_node), buffer_max_size_(buffer_size) { if (buffer_max_size_ != 0) diff --git a/src/loggers/bt_minitrace_logger.cpp b/src/loggers/bt_minitrace_logger.cpp new file mode 100644 index 000000000..8cebcb0dd --- /dev/null +++ b/src/loggers/bt_minitrace_logger.cpp @@ -0,0 +1,58 @@ + +#include "behavior_tree_logger/bt_minitrace_logger.h" + +namespace BT +{ + +std::atomic MinitraceLogger::ref_count(false); + +MinitraceLogger::MinitraceLogger(TreeNode* root_node, + const char* filename_json) : + StatusChangeLogger(root_node) +{ + bool expected = false; + if ( ! ref_count.compare_exchange_strong( expected, true) ) + { + throw std::logic_error("Only one instance of StdCoutLogger shall be created"); + } + + minitrace::mtr_register_sigint_handler(); + minitrace::mtr_init(filename_json); + this->enableTransitionToIdle(true); +} + +MinitraceLogger::~MinitraceLogger() +{ + minitrace::mtr_flush(); + minitrace::mtr_shutdown(); +} + +void MinitraceLogger::callback(TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) +{ + using namespace minitrace; + + const bool statusCompleted = (status == NodeStatus::SUCCESS || status == NodeStatus::FAILURE); + + const char* category = toStr(node.type()); + const char* name = node.name().c_str(); + + if (prev_status == NodeStatus::IDLE && statusCompleted) + { + MTR_INSTANT(category, name); + } + else if (status == NodeStatus::RUNNING) + { + MTR_BEGIN(category, name); + } + else if (prev_status == NodeStatus::RUNNING && statusCompleted) + { + MTR_END(category, name); + } +} + +void MinitraceLogger::flush() +{ + minitrace::mtr_flush(); +} +} // end namespace + diff --git a/src/bt_zmq_publisher.cpp b/src/loggers/bt_zmq_publisher.cpp similarity index 98% rename from src/bt_zmq_publisher.cpp rename to src/loggers/bt_zmq_publisher.cpp index ad031e72d..a4364d983 100644 --- a/src/bt_zmq_publisher.cpp +++ b/src/loggers/bt_zmq_publisher.cpp @@ -4,6 +4,10 @@ namespace BT { + +std::atomic PublisherZMQ::ref_count(false); + + void PublisherZMQ::createStatusBuffer() { status_buffer_.clear(); From 2da273158552776e9ae91f449efd9a7f92f99ba3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 24 Aug 2018 10:35:02 +0200 Subject: [PATCH 094/125] more example and documentation --- CMakeLists.txt | 5 +- .../crossdoor_dummy_nodes.h | 0 {gtest => examples}/crossdoor_example.cpp | 2 + examples/dummy_nodes.h | 65 +++++++++ examples/movebase_node.h | 85 ++++++++++++ examples/tutorial_blackboard.cpp | 124 ++++++------------ examples/tutorial_factory_tree.cpp | 62 ++------- examples/tutorial_programmatic_tree.cpp | 54 +------- examples/tutorial_sequence_star.cpp | 47 ++----- gtest/gtest_factory.cpp | 2 +- include/Blackboard/blackboard.h | 2 + include/Blackboard/blackboard_local.h | 1 - include/behavior_tree_core/tree_node.h | 32 +++-- 13 files changed, 241 insertions(+), 240 deletions(-) rename {gtest/include => examples}/crossdoor_dummy_nodes.h (100%) rename {gtest => examples}/crossdoor_example.cpp (99%) create mode 100644 examples/dummy_nodes.h create mode 100644 examples/movebase_node.h diff --git a/CMakeLists.txt b/CMakeLists.txt index a42570971..06f3758c9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -124,10 +124,6 @@ endif() # COMPILING EXAMPLES and TOOLS ###################################################### - -add_executable(crossdoor_example gtest/crossdoor_example.cpp ) -target_link_libraries(crossdoor_example ${BEHAVIOR_TRE_LIBRARIES} ) - add_executable(bt_log_cat tools/bt_log_cat.cpp ) target_link_libraries(bt_log_cat behavior_tree_core ) @@ -145,6 +141,7 @@ BuildExample(tutorial_programmatic_tree) BuildExample(tutorial_factory_tree) BuildExample(tutorial_sequence_star) BuildExample(tutorial_blackboard) +BuildExample(crossdoor_example) ###################################################### diff --git a/gtest/include/crossdoor_dummy_nodes.h b/examples/crossdoor_dummy_nodes.h similarity index 100% rename from gtest/include/crossdoor_dummy_nodes.h rename to examples/crossdoor_dummy_nodes.h diff --git a/gtest/crossdoor_example.cpp b/examples/crossdoor_example.cpp similarity index 99% rename from gtest/crossdoor_example.cpp rename to examples/crossdoor_example.cpp index 3deb2b0f0..df0a5264f 100644 --- a/gtest/crossdoor_example.cpp +++ b/examples/crossdoor_example.cpp @@ -79,7 +79,9 @@ int main() std::cout << "---------------" << std::endl; while (1) + { root_node->executeTick(); + } std::cout << "---------------" << std::endl; return 0; } diff --git a/examples/dummy_nodes.h b/examples/dummy_nodes.h new file mode 100644 index 000000000..dd2c6b38d --- /dev/null +++ b/examples/dummy_nodes.h @@ -0,0 +1,65 @@ +#ifndef SIMPLE_BT_NODES_H +#define SIMPLE_BT_NODES_H + +#include "behavior_tree_core/behavior_tree.h" + +inline BT::NodeStatus SayHello() +{ + std::cout << "Hello!!!" << std::endl; + return BT::NodeStatus::SUCCESS; +} + +inline BT::NodeStatus CheckBattery() +{ + std::cout << "[ Battery: OK ]" << std::endl; + return BT::NodeStatus::SUCCESS; +} + +inline BT::NodeStatus CheckTemperature() +{ + std::cout << "[ Temperature: OK ]" << std::endl; + return BT::NodeStatus::SUCCESS; +} + +//-------------------------------------- + +class Foo +{ +public: + Foo(): _val(0) {} + + BT::NodeStatus actionOne() + { + _val = 42; + std::cout << "Foo::actionOne -> set val to 42" << std::endl; + return BT::NodeStatus::SUCCESS; + } + + BT::NodeStatus actionTwo() + { + std::cout << "Foo::actionTwo -> reading val => "<< _val << std::endl; + _val = 0; + return BT::NodeStatus::SUCCESS; + } + +private: + int _val; +}; + +//-------------------------------------- + +class CustomAction: public BT::ActionNodeBase +{ +public: + CustomAction(const std::string& name): + BT::ActionNodeBase(name) {} + + BT::NodeStatus tick() override + { + std::cout << "CustomAction: " << this->name() << std::endl; + return BT::NodeStatus::SUCCESS; + } +}; + + +#endif // SIMPLE_BT_NODES_H diff --git a/examples/movebase_node.h b/examples/movebase_node.h new file mode 100644 index 000000000..d80472aef --- /dev/null +++ b/examples/movebase_node.h @@ -0,0 +1,85 @@ +#ifndef MOVEBASE_BT_NODES_H +#define MOVEBASE_BT_NODES_H + +#include "behavior_tree_core/behavior_tree.h" + +// Custom type +struct Pose2D +{ + double x,y,theta; +}; + +namespace BT{ + +// This template specialization is needed only if you want +// to AUTOMATICALLY convert a NodeParameter into a Pose2D +// In other words, implement it if you want to be able to do: +// +// TreeNode::getParam(key, ...) +// +template <> Pose2D convertFromString(const std::string& key) +{ + // three real numbers separated by semicolons + auto parts = BT::splitString(key, ';'); + if( parts.size() != 3) + { + throw std::runtime_error("invalid input)"); + } + else{ + Pose2D output; + output.x = convertFromString( parts[0] ); + output.y = convertFromString( parts[1] ); + output.theta = convertFromString( parts[2] ); + return output; + } +} + +} + +// This is an asynchronous operation that will run in a separate thread. +// It requires the NodeParameter "goal" + +class MoveBaseAction: public BT::ActionNode +{ +public: + // When your TreeNode requires a NodeParameter, use this + // kind of constructor + MoveBaseAction(const std::string& name, const BT::NodeParameters& params): + ActionNode(name, params) {} + + // This is mandatory to tell to the factory which parameter(s) + // are required + static const BT::NodeParameters& requiredNodeParameters() + { + static BT::NodeParameters params = {{"goal","0;0;0"}}; + return params; + } + + BT::NodeStatus tick() override + { + Pose2D goal; + + // retrieve the parameter using getParam() + if( getParam("goal", goal) ) + { + printf("[MoveBase] goal: x=%.f y=%.1f theta=%.2f\n", + goal.x, goal.y, goal.theta); + + std::this_thread::sleep_for( std::chrono::milliseconds(180) ); + + std::cout << "[ Move: finished ]" << std::endl; + return BT::NodeStatus::SUCCESS; + } + else{ + printf("The NodeParameter does not contain the key [goal] " + " or the blackboard does not contain the provided key\n"); + return BT::NodeStatus::FAILURE; + } + } +}; + + + + + +#endif // MOVEBASE_BT_NODES_H diff --git a/examples/tutorial_blackboard.cpp b/examples/tutorial_blackboard.cpp index d633a6f6f..167608d73 100644 --- a/examples/tutorial_blackboard.cpp +++ b/examples/tutorial_blackboard.cpp @@ -2,115 +2,61 @@ #include "behavior_tree_logger/bt_cout_logger.h" #include "Blackboard/blackboard_local.h" -using namespace BT; - -struct Pose2D -{ - double x,y,theta; -}; - -namespace BT{ - -// this template specialization is needed ONLY if you want -// to AUTOMATICALLY convert a NodeParameter into a Pose2D -template <> Pose2D convertFromString(const std::string& str) -{ - auto parts = BT::splitString(str, ';'); - if( parts.size() != 3) - { - throw std::runtime_error("invalid input)"); - } - else{ - Pose2D output; - output.x = convertFromString( parts[0] ); - output.y = convertFromString( parts[1] ); - output.theta = convertFromString( parts[2] ); - return output; - } -} +#include "movebase_node.h" -} - -//----------------------------------------- +using namespace BT; -// This action will read the desired robot position -// and store it on the BlackBoard (key: "GoalPose") -NodeStatus PullGoalPose(const std::shared_ptr& blackboard) +// Write into the blackboard key: [GoalPose] +NodeStatus CalculateGoalPose(const Blackboard::Ptr& blackboard) { //In this example we store a fixed value. In a real application // we would read it from an external source (GUI, fleet manager, etc.) Pose2D goal = { 1, 2, M_PI}; - // store it in the blackboard - blackboard->set("GoalPose", goal); + // RECOMMENDED: check if the blackboard is empty + if( blackboard ) + { + // store it in the blackboard + blackboard->set("GoalPose", goal); + } + + printf("[CalculateGoalPose]\n"); return NodeStatus::SUCCESS; } -// First approach: read ALWAYS from the same -// blackboard key: [GoalPose] -class MoveAction_A: public ActionNodeBase +// Read from the blackboard key: [GoalPose] +class PrintGoalPose: public ActionNodeBase { public: - MoveAction_A(const std::string& name): ActionNodeBase(name) {} + PrintGoalPose(const std::string& name): ActionNodeBase(name) {} NodeStatus tick() override { Pose2D goal; - if( blackboard()->get("GoalPose", goal) ) // return true if succesful - { - printf("[MoveBase] [Taget: x=%.ff y=%.1f theta=%.2f\n", - goal.x, goal.y, goal.theta); - return NodeStatus::SUCCESS; - } - else{ - printf("The blackboard does not contain the key [GoalPose]\n"); - return NodeStatus::FAILURE; - } - } -}; -// Second approach: read the goal from the NodeParameter "goal". -// This value can be static or point to the key of a blackboard. -// A pointer to a Blackboard entry is written as ${key} -class MoveAction_B: public ActionNodeBase -{ -public: - MoveAction_B(const std::string& name, const NodeParameters& params): - ActionNodeBase(name, params) {} - - NodeStatus tick() override - { - Pose2D goal; - if( getParam("goal", goal) ) + // RECOMMENDED: check if the blackboard is empty + if( blackboard() && blackboard()->get("GoalPose", goal) ) { - printf("[MoveBase] [Taget: x=%.ff y=%.1f theta=%.2f\n", + printf("[PrintGoalPose] x=%.f y=%.1f theta=%.2f\n", goal.x, goal.y, goal.theta); return NodeStatus::SUCCESS; } else{ - printf("The NodeParameter does not contain the key [goal] " - " or the blackboard does not contain the provided key\n"); + printf("The blackboard does not contain the key [GoalPose]\n"); return NodeStatus::FAILURE; } } - static const NodeParameters& requiredNodeParameters() - { - static NodeParameters params = {{"goal","0;0;0"}}; - return params; - } }; - - /** Example: simple sequence of 4 actions 1) Store a value of Pose2D in the key "GoalPose" of the blackboard. - 2) Call MoveAction_A. It will read "GoalPose" from the blackboard. - 3) Call MoveAction_B that reads the NodeParameter "goal". It's value "2;4;0" is converted + 2) Call PrintGoalPose. It will read "GoalPose" from the blackboard. + 3) Call MoveAction that reads the NodeParameter "goal". It's value "2;4;0" is converted to Pose2D using the function [ Pose2D convertFromString(const std::string& str) ]. - 4) Call MoveAction_B. It will read "GoalPose" from the blackboard . + 4) Call MoveAction. It will read "GoalPose" from the blackboard. */ const std::string xml_text = R"( @@ -118,12 +64,12 @@ const std::string xml_text = R"( - - - - - - + + + + + + @@ -137,18 +83,22 @@ int main() using namespace BT; BehaviorTreeFactory factory; - factory.registerSimpleAction("PullGoalPose", PullGoalPose); - factory.registerNodeType("MoveAction_A"); - factory.registerNodeType("MoveAction_B"); + factory.registerSimpleAction("CalculateGoalPose", CalculateGoalPose); + factory.registerNodeType("PrintGoalPose"); + factory.registerNodeType("MoveBase"); // create a Blackboard from BlackboardLocal (simple local storage) auto blackboard = Blackboard::create(); + // Important: when the object tree goes out of scope, all the TreeNodes are destroyed auto res = buildTreeFromText(factory, xml_text, blackboard); - const TreeNode::Ptr& root_node = res.first; - root_node->executeTick(); + NodeStatus status = NodeStatus::RUNNING; + while( status == NodeStatus::RUNNING ) + { + status = root_node->executeTick(); + } return 0; } diff --git a/examples/tutorial_factory_tree.cpp b/examples/tutorial_factory_tree.cpp index eaeaf3ae3..7aca8c7cb 100644 --- a/examples/tutorial_factory_tree.cpp +++ b/examples/tutorial_factory_tree.cpp @@ -1,61 +1,18 @@ #include "behavior_tree_core/xml_parsing.h" -#include "behavior_tree_logger/bt_cout_logger.h" #include "Blackboard/blackboard_local.h" +#include "dummy_nodes.h" using namespace BT; -NodeStatus SimpleAction() -{ - std::cout << "SimpleActionFunc" << std::endl; - return NodeStatus::SUCCESS; -} - -class Foo -{ -public: - Foo(): _val(0) {} - - NodeStatus actionOne() - { - _val = 42; - std::cout << "Foo::actionOne -> set val to 42" << std::endl; - return NodeStatus::SUCCESS; - } - - NodeStatus actionTwo() - { - std::cout << "Foo::actionTwo -> reading val => "<< _val << std::endl; - _val = 0; - return NodeStatus::SUCCESS; - } - -private: - int _val; -}; - - -class CustomAction: public ActionNodeBase -{ -public: - CustomAction(const std::string& name): ActionNodeBase(name) {} - - NodeStatus tick() override - { - std::cout << "CustomAction: " << this->name() << std::endl; - return NodeStatus::SUCCESS; - } -}; - - const std::string xml_text = R"( - - - + + + @@ -68,18 +25,19 @@ int main() BehaviorTreeFactory factory; Foo foo; - // This is the syntax to register SimpleActionNodes - factory.registerSimpleAction("SimpleAction", std::bind(SimpleAction) ); + factory.registerSimpleAction("SayHello", std::bind(SayHello) ); factory.registerSimpleAction("ActionOne", std::bind( &Foo::actionOne, &foo)); factory.registerSimpleAction("ActionTwo", std::bind( &Foo::actionTwo, &foo)); + // If you want to register a class that inherits from a TReeNode, use this method instead factory.registerNodeType("CustomAction"); - auto res = buildTreeFromText(factory, xml_text); - const TreeNode::Ptr& root_node = res.first; + // IMPORTANT: when the object tree goes out of scope, all the TreeNodes are destroyed + auto tree = buildTreeFromText(factory, xml_text); + const TreeNode::Ptr& root_node = tree.first; - // the tick is propagated to all the children. + // The tick is propagated to all the children. // until one of the returns FAILURE or RUNNING. // In this case all of the return SUCCESS root_node->executeTick(); diff --git a/examples/tutorial_programmatic_tree.cpp b/examples/tutorial_programmatic_tree.cpp index d1a8d0d9d..781f31bee 100644 --- a/examples/tutorial_programmatic_tree.cpp +++ b/examples/tutorial_programmatic_tree.cpp @@ -1,52 +1,8 @@ -#include "behavior_tree_core/xml_parsing.h" -#include "behavior_tree_logger/bt_cout_logger.h" #include "Blackboard/blackboard_local.h" +#include "dummy_nodes.h" using namespace BT; -NodeStatus SimpleAction() -{ - std::cout << "SimpleActionFunc" << std::endl; - return NodeStatus::SUCCESS; -} - -class Foo -{ -public: - Foo(): _val(0) {} - - NodeStatus actionOne() - { - _val = 42; - std::cout << "Foo::actionOne -> set val to 42" << std::endl; - return NodeStatus::SUCCESS; - } - - NodeStatus actionTwo() - { - std::cout << "Foo::actionTwo -> reading val => "<< _val << std::endl; - _val = 0; - return NodeStatus::SUCCESS; - } - -private: - int _val; -}; - - -class CustomAction: public ActionNodeBase -{ -public: - CustomAction(const std::string& name): ActionNodeBase(name) {} - - NodeStatus tick() override - { - std::cout << "CustomAction: " << this->name() << std::endl; - return NodeStatus::SUCCESS; - } -}; - - int main() { Foo foo; @@ -55,17 +11,17 @@ int main() // Aimple funtions can be wrapped inside in ActionNodeBase // using the SimpleActionNode - SimpleActionNode act_simple("simple_action", std::bind(SimpleAction) ); + SimpleActionNode act_simple("action_hello", std::bind(SayHello) ); // SimpleActionNode warks also with class methods, using std::bind SimpleActionNode act_1("action_one", std::bind( &Foo::actionOne, &foo) ); SimpleActionNode act_2("action_two", std::bind( &Foo::actionTwo, &foo) ); - // Nevertheless, the way to be able to use ALL the funtionality of a TreeNode - // is to create your own class that inherits from either: + // Nevertheless, to be able to use ALL the funtionalities of a TreeNode, + // your should create a class that inherits from either: // - ConditionNode (synchronous execution) // - ActionNodeBase (synchronous execution) - // - ActionNode (asynchronous execution is a separate thread). + // - ActionNode (asynchronous execution in a separate thread). CustomAction act_custom("my_action"); // Add children to the sequence. diff --git a/examples/tutorial_sequence_star.cpp b/examples/tutorial_sequence_star.cpp index 58a39a9b4..c682c9df5 100644 --- a/examples/tutorial_sequence_star.cpp +++ b/examples/tutorial_sequence_star.cpp @@ -2,34 +2,11 @@ #include "behavior_tree_logger/bt_cout_logger.h" #include "behavior_tree_logger/bt_file_logger.h" -using namespace BT; - - -NodeStatus checkBattery() -{ - std::cout << "[ Battery: OK ]" << std::endl; - return NodeStatus::SUCCESS; -} +#include "dummy_nodes.h" +#include "movebase_node.h" -NodeStatus CheckTemperature() -{ - std::cout << "[ Temperature: OK ]" << std::endl; - return NodeStatus::SUCCESS; -} +using namespace BT; -// This is an asynchronous operation that will run in a separate thread -class MoveAction: public ActionNode -{ -public: - MoveAction(const std::string& name): ActionNode(name) {} - NodeStatus tick() override - { - std::cout << "[ Move: started ]" << std::endl; - std::this_thread::sleep_for( std::chrono::milliseconds(80) ); - std::cout << "[ Move: finished ]" << std::endl; - return NodeStatus::SUCCESS; - } -}; // clang-format off @@ -41,7 +18,7 @@ const std::string xml_text_sequence = R"( - + @@ -56,7 +33,7 @@ const std::string xml_text_sequence_star = R"( - + @@ -73,16 +50,16 @@ void Assert(bool condition) int main() { BehaviorTreeFactory factory; - factory.registerSimpleCondition("TemperatureOK", std::bind( checkBattery )); + factory.registerSimpleCondition("TemperatureOK", std::bind( CheckBattery )); factory.registerSimpleCondition("BatteryOK", std::bind( CheckTemperature )); - factory.registerNodeType("Move"); + factory.registerNodeType("MoveBase"); // Loog at the state transitions and messages using either // xml_text_sequence and xml_text_sequence_star // The main difference that you should notice is that the // actions BatteryOK and TempearaturOK are executed at each tick() - // is Sequence is used and only once if SequenceStar is used. + // if Sequence is used, but only once if SequenceStar is used. for(auto& xml_text: {xml_text_sequence, xml_text_sequence_star}) { @@ -105,24 +82,20 @@ int main() Assert( status == NodeStatus::RUNNING); std::cout << "\n------- sleep --------" << std::endl; - std::this_thread::sleep_for(std::chrono::milliseconds(50)); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); std::cout << "\n------- Second executeTick() --------" << std::endl; status = root_node->executeTick(); Assert( status == NodeStatus::RUNNING); std::cout << "\n------- sleep --------" << std::endl; - std::this_thread::sleep_for(std::chrono::milliseconds(50)); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); std::cout << "\n------- Third executeTick() --------" << std::endl; status = root_node->executeTick(); Assert( status == NodeStatus::SUCCESS); std::cout << std::endl; - - // The main difference that you should notice is that the - // actions BatteryOK and TempearaturOK are executed at each tick() - // is Sequence is used and only once if SequenceStar is used. } return 0; } diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp index c4bfdecaf..9ebc503b0 100644 --- a/gtest/gtest_factory.cpp +++ b/gtest/gtest_factory.cpp @@ -2,7 +2,7 @@ #include "action_test_node.h" #include "condition_test_node.h" #include "behavior_tree_core/xml_parsing.h" -#include "crossdoor_dummy_nodes.h" +#include "../examples/crossdoor_dummy_nodes.h" // clang-format off diff --git a/include/Blackboard/blackboard.h b/include/Blackboard/blackboard.h index e50d5de10..d4787331d 100644 --- a/include/Blackboard/blackboard.h +++ b/include/Blackboard/blackboard.h @@ -55,6 +55,8 @@ class Blackboard /** Return true if the entry with the given key was found. * Note that this method may throw an exception if the cast to T failed. + * + * return true is succesful */ template bool get(const std::string& key, T& value) const { diff --git a/include/Blackboard/blackboard_local.h b/include/Blackboard/blackboard_local.h index c783b1370..06b928aa2 100644 --- a/include/Blackboard/blackboard_local.h +++ b/include/Blackboard/blackboard_local.h @@ -23,7 +23,6 @@ class BlackboardLocal: public BlackboardImpl storage_[key] = value; } - private: std::unordered_map storage_; diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 535cdc548..5194b6136 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -108,6 +108,8 @@ class TreeNode /// Method to be implemented by the user virtual BT::NodeStatus tick() = 0; + /** Get a parameter from the passed NodeParameters and convert it to type T. + */ template BT::optional getParam(const std::string& key) const { @@ -121,6 +123,10 @@ class TreeNode } } + /** Get a parameter from the passed NodeParameters and convert it to type T. + * + * return false either if there is no parameter with this key or if conversion failed. + */ template bool getParam(const std::string& key, T& destination) const { @@ -131,16 +137,24 @@ class TreeNode } const std::string& str = it->second; - // check if it follows this ${pattern}, if it does, search inside the blackboard - if( bb_ && str.size()>=4 && str[0] == '$' && str[1] == '{' && str.back() == '}') - { - const std::string stripped_key( &str[2], str.size()-3); - bool found = bb_->get(stripped_key, destination); - return found; + try{ + // check if it follows this ${pattern}, if it does, search inside the blackboard + if( bb_ && str.size()>=4 && str[0] == '$' && str[1] == '{' && str.back() == '}') + { + const std::string stripped_key( &str[2], str.size()-3); + bool found = bb_->get(stripped_key, destination); + return found; + } + else{ + destination = convertFromString(str.c_str()); + return true; + } } - else{ - destination = convertFromString(str.c_str()); - return true; + catch( std::runtime_error& err) + { + std::cout << "Exception at getParam(" << + key << "): " << err.what() << std::endl; + return false; } } From 090eb28a9c90662d6cd12fc507e12c3bb788741b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 12 Sep 2018 18:02:13 +0200 Subject: [PATCH 095/125] fixed tamplete specialization for bool --- include/Blackboard/blackboard.h | 12 ++++++++++++ include/SafeAny/convert_impl.hpp | 9 ++++++++- 2 files changed, 20 insertions(+), 1 deletion(-) diff --git a/include/Blackboard/blackboard.h b/include/Blackboard/blackboard.h index d4787331d..b2a5373b7 100644 --- a/include/Blackboard/blackboard.h +++ b/include/Blackboard/blackboard.h @@ -71,6 +71,18 @@ class Blackboard return true; } + template T get(const std::string& key) const + { + T value; + bool found = get(key, value); + if(!found) + { + throw std::runtime_error("Missing key"); + } + return value; + } + + /// Update the entry with the given key template void set(const std::string& key, const T& value) { diff --git a/include/SafeAny/convert_impl.hpp b/include/SafeAny/convert_impl.hpp index a8707076c..32000a1fc 100644 --- a/include/SafeAny/convert_impl.hpp +++ b/include/SafeAny/convert_impl.hpp @@ -177,7 +177,14 @@ template inline typename std::enable_if< !is_convertible_type::value, void>::type convertNumber( const SRC& , DST& ) { - throw std::runtime_error("Not convertible"); + static_assert(is_convertible_type::value,"Not convertible"); +} + +template inline +EnableIf< std::is_same> +convertNumber( const SRC& from, DST& target ) +{ + target = (from != 0); } From 2ec27d73011370c91b1fe68b69bea4f205c29019 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 12 Sep 2018 18:02:50 +0200 Subject: [PATCH 096/125] fixed loggers --- include/behavior_tree_logger/BT_logger.fbs | 7 + .../BT_logger_generated.h | 767 ++++++++++-------- .../bt_flatbuffer_helper.h | 31 +- src/loggers/bt_cout_logger.cpp | 3 +- 4 files changed, 454 insertions(+), 354 deletions(-) diff --git a/include/behavior_tree_logger/BT_logger.fbs b/include/behavior_tree_logger/BT_logger.fbs index 523f1d2cc..031998a18 100644 --- a/include/behavior_tree_logger/BT_logger.fbs +++ b/include/behavior_tree_logger/BT_logger.fbs @@ -21,6 +21,12 @@ struct Timestamp usec_since_epoch : uint64; } +table KeyValue +{ + key : string; + value : string; +} + table TreeNode { uid : uint16; @@ -29,6 +35,7 @@ table TreeNode status : Status; instance_name : string (required); registration_name : string (required); + params : [KeyValue]; } table BehaviorTree diff --git a/include/behavior_tree_logger/BT_logger_generated.h b/include/behavior_tree_logger/BT_logger_generated.h index 5ff58c9aa..ca8e5f6bd 100644 --- a/include/behavior_tree_logger/BT_logger_generated.h +++ b/include/behavior_tree_logger/BT_logger_generated.h @@ -1,14 +1,17 @@ // automatically generated by the FlatBuffers compiler, do not modify + #ifndef FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ #define FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ #include "flatbuffers/flatbuffers.h" -namespace BT_Serialization -{ +namespace BT_Serialization { + struct Timestamp; +struct KeyValue; + struct TreeNode; struct BehaviorTree; @@ -17,407 +20,477 @@ struct StatusChange; struct StatusChangeLog; -enum class Status : int8_t -{ - IDLE = 0, - RUNNING = 1, - SUCCESS = 2, - FAILURE = 3, - MIN = IDLE, - MAX = FAILURE +enum class Status : int8_t { + IDLE = 0, + RUNNING = 1, + SUCCESS = 2, + FAILURE = 3, + MIN = IDLE, + MAX = FAILURE }; -inline const Status (&EnumValuesStatus())[4] -{ - static const Status values[] = {Status::IDLE, Status::RUNNING, Status::SUCCESS, Status::FAILURE}; - return values; +inline const Status (&EnumValuesStatus())[4] { + static const Status values[] = { + Status::IDLE, + Status::RUNNING, + Status::SUCCESS, + Status::FAILURE + }; + return values; } -inline const char* const* EnumNamesStatus() -{ - static const char* const names[] = {"IDLE", "RUNNING", "SUCCESS", "FAILURE", nullptr}; - return names; +inline const char * const *EnumNamesStatus() { + static const char * const names[] = { + "IDLE", + "RUNNING", + "SUCCESS", + "FAILURE", + nullptr + }; + return names; } -inline const char* EnumNameStatus(Status e) -{ - const size_t index = static_cast(e); - return EnumNamesStatus()[index]; +inline const char *EnumNameStatus(Status e) { + const size_t index = static_cast(e); + return EnumNamesStatus()[index]; } -enum class Type : int8_t -{ - UNDEFINED = 0, - ACTION = 1, - CONDITION = 2, - CONTROL = 3, - DECORATOR = 4, - SUBTREE = 5, - MIN = UNDEFINED, - MAX = SUBTREE +enum class Type : int8_t { + UNDEFINED = 0, + ACTION = 1, + CONDITION = 2, + CONTROL = 3, + DECORATOR = 4, + SUBTREE = 5, + MIN = UNDEFINED, + MAX = SUBTREE }; -inline const Type (&EnumValuesType())[6] -{ - static const Type values[] = {Type::UNDEFINED, Type::ACTION, Type::CONDITION, - Type::CONTROL, Type::DECORATOR, Type::SUBTREE}; - return values; +inline const Type (&EnumValuesType())[6] { + static const Type values[] = { + Type::UNDEFINED, + Type::ACTION, + Type::CONDITION, + Type::CONTROL, + Type::DECORATOR, + Type::SUBTREE + }; + return values; } -inline const char* const* EnumNamesType() -{ - static const char* const names[] = {"UNDEFINED", "ACTION", "CONDITION", "CONTROL", "DECORATOR", "SUBTREE", nullptr}; - return names; +inline const char * const *EnumNamesType() { + static const char * const names[] = { + "UNDEFINED", + "ACTION", + "CONDITION", + "CONTROL", + "DECORATOR", + "SUBTREE", + nullptr + }; + return names; } -inline const char* EnumNameType(Type e) -{ - const size_t index = static_cast(e); - return EnumNamesType()[index]; +inline const char *EnumNameType(Type e) { + const size_t index = static_cast(e); + return EnumNamesType()[index]; } -FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) Timestamp FLATBUFFERS_FINAL_CLASS -{ - private: - uint64_t usec_since_epoch_; - - public: - Timestamp() - { - memset(this, 0, sizeof(Timestamp)); - } - Timestamp(uint64_t _usec_since_epoch) : usec_since_epoch_(flatbuffers::EndianScalar(_usec_since_epoch)) - { - } - uint64_t usec_since_epoch() const - { - return flatbuffers::EndianScalar(usec_since_epoch_); - } +FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) Timestamp FLATBUFFERS_FINAL_CLASS { + private: + uint64_t usec_since_epoch_; + + public: + Timestamp() { + memset(this, 0, sizeof(Timestamp)); + } + Timestamp(uint64_t _usec_since_epoch) + : usec_since_epoch_(flatbuffers::EndianScalar(_usec_since_epoch)) { + } + uint64_t usec_since_epoch() const { + return flatbuffers::EndianScalar(usec_since_epoch_); + } }; FLATBUFFERS_STRUCT_END(Timestamp, 8); -FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) StatusChange FLATBUFFERS_FINAL_CLASS -{ - private: - uint16_t uid_; - int8_t prev_status_; - int8_t status_; - int32_t padding0__; - Timestamp timestamp_; - - public: - StatusChange() - { - memset(this, 0, sizeof(StatusChange)); - } - StatusChange(uint16_t _uid, Status _prev_status, Status _status, const Timestamp& _timestamp) - : uid_(flatbuffers::EndianScalar(_uid)) - , prev_status_(flatbuffers::EndianScalar(static_cast(_prev_status))) - , status_(flatbuffers::EndianScalar(static_cast(_status))) - , padding0__(0) - , timestamp_(_timestamp) - { - (void)padding0__; - } - uint16_t uid() const - { - return flatbuffers::EndianScalar(uid_); - } - Status prev_status() const - { - return static_cast(flatbuffers::EndianScalar(prev_status_)); - } - Status status() const - { - return static_cast(flatbuffers::EndianScalar(status_)); - } - const Timestamp& timestamp() const - { - return timestamp_; - } +FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) StatusChange FLATBUFFERS_FINAL_CLASS { + private: + uint16_t uid_; + int8_t prev_status_; + int8_t status_; + int32_t padding0__; + Timestamp timestamp_; + + public: + StatusChange() { + memset(this, 0, sizeof(StatusChange)); + } + StatusChange(uint16_t _uid, Status _prev_status, Status _status, const Timestamp &_timestamp) + : uid_(flatbuffers::EndianScalar(_uid)), + prev_status_(flatbuffers::EndianScalar(static_cast(_prev_status))), + status_(flatbuffers::EndianScalar(static_cast(_status))), + padding0__(0), + timestamp_(_timestamp) { + (void)padding0__; + } + uint16_t uid() const { + return flatbuffers::EndianScalar(uid_); + } + Status prev_status() const { + return static_cast(flatbuffers::EndianScalar(prev_status_)); + } + Status status() const { + return static_cast(flatbuffers::EndianScalar(status_)); + } + const Timestamp ×tamp() const { + return timestamp_; + } }; FLATBUFFERS_STRUCT_END(StatusChange, 16); -struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table -{ - enum - { - VT_UID = 4, - VT_CHILDREN_UID = 6, - VT_TYPE = 8, - VT_STATUS = 10, - VT_INSTANCE_NAME = 12, - VT_REGISTRATION_NAME = 14 - }; - uint16_t uid() const - { - return GetField(VT_UID, 0); - } - const flatbuffers::Vector* children_uid() const - { - return GetPointer*>(VT_CHILDREN_UID); - } - Type type() const - { - return static_cast(GetField(VT_TYPE, 0)); - } - Status status() const - { - return static_cast(GetField(VT_STATUS, 0)); - } - const flatbuffers::String* instance_name() const - { - return GetPointer(VT_INSTANCE_NAME); - } - const flatbuffers::String* registration_name() const - { - return GetPointer(VT_REGISTRATION_NAME); - } - bool Verify(flatbuffers::Verifier& verifier) const - { - return VerifyTableStart(verifier) && VerifyField(verifier, VT_UID) && - VerifyOffset(verifier, VT_CHILDREN_UID) && verifier.Verify(children_uid()) && - VerifyField(verifier, VT_TYPE) && VerifyField(verifier, VT_STATUS) && - VerifyOffsetRequired(verifier, VT_INSTANCE_NAME) && verifier.Verify(instance_name()) && - VerifyOffsetRequired(verifier, VT_REGISTRATION_NAME) && verifier.Verify(registration_name()) && - verifier.EndTable(); - } +struct KeyValue FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + enum { + VT_KEY = 4, + VT_VALUE = 6 + }; + const flatbuffers::String *key() const { + return GetPointer(VT_KEY); + } + const flatbuffers::String *value() const { + return GetPointer(VT_VALUE); + } + bool Verify(flatbuffers::Verifier &verifier) const { + return VerifyTableStart(verifier) && + VerifyOffset(verifier, VT_KEY) && + verifier.Verify(key()) && + VerifyOffset(verifier, VT_VALUE) && + verifier.Verify(value()) && + verifier.EndTable(); + } +}; + +struct KeyValueBuilder { + flatbuffers::FlatBufferBuilder &fbb_; + flatbuffers::uoffset_t start_; + void add_key(flatbuffers::Offset key) { + fbb_.AddOffset(KeyValue::VT_KEY, key); + } + void add_value(flatbuffers::Offset value) { + fbb_.AddOffset(KeyValue::VT_VALUE, value); + } + explicit KeyValueBuilder(flatbuffers::FlatBufferBuilder &_fbb) + : fbb_(_fbb) { + start_ = fbb_.StartTable(); + } + KeyValueBuilder &operator=(const KeyValueBuilder &); + flatbuffers::Offset Finish() { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + return o; + } +}; + +inline flatbuffers::Offset CreateKeyValue( + flatbuffers::FlatBufferBuilder &_fbb, + flatbuffers::Offset key = 0, + flatbuffers::Offset value = 0) { + KeyValueBuilder builder_(_fbb); + builder_.add_value(value); + builder_.add_key(key); + return builder_.Finish(); +} + +inline flatbuffers::Offset CreateKeyValueDirect( + flatbuffers::FlatBufferBuilder &_fbb, + const char *key = nullptr, + const char *value = nullptr) { + return BT_Serialization::CreateKeyValue( + _fbb, + key ? _fbb.CreateString(key) : 0, + value ? _fbb.CreateString(value) : 0); +} + +struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + enum { + VT_UID = 4, + VT_CHILDREN_UID = 6, + VT_TYPE = 8, + VT_STATUS = 10, + VT_INSTANCE_NAME = 12, + VT_REGISTRATION_NAME = 14, + VT_PARAMS = 16 + }; + uint16_t uid() const { + return GetField(VT_UID, 0); + } + const flatbuffers::Vector *children_uid() const { + return GetPointer *>(VT_CHILDREN_UID); + } + Type type() const { + return static_cast(GetField(VT_TYPE, 0)); + } + Status status() const { + return static_cast(GetField(VT_STATUS, 0)); + } + const flatbuffers::String *instance_name() const { + return GetPointer(VT_INSTANCE_NAME); + } + const flatbuffers::String *registration_name() const { + return GetPointer(VT_REGISTRATION_NAME); + } + const flatbuffers::Vector> *params() const { + return GetPointer> *>(VT_PARAMS); + } + bool Verify(flatbuffers::Verifier &verifier) const { + return VerifyTableStart(verifier) && + VerifyField(verifier, VT_UID) && + VerifyOffset(verifier, VT_CHILDREN_UID) && + verifier.Verify(children_uid()) && + VerifyField(verifier, VT_TYPE) && + VerifyField(verifier, VT_STATUS) && + VerifyOffsetRequired(verifier, VT_INSTANCE_NAME) && + verifier.Verify(instance_name()) && + VerifyOffsetRequired(verifier, VT_REGISTRATION_NAME) && + verifier.Verify(registration_name()) && + VerifyOffset(verifier, VT_PARAMS) && + verifier.Verify(params()) && + verifier.VerifyVectorOfTables(params()) && + verifier.EndTable(); + } }; -struct TreeNodeBuilder -{ - flatbuffers::FlatBufferBuilder& fbb_; - flatbuffers::uoffset_t start_; - void add_uid(uint16_t uid) - { - fbb_.AddElement(TreeNode::VT_UID, uid, 0); - } - void add_children_uid(flatbuffers::Offset> children_uid) - { - fbb_.AddOffset(TreeNode::VT_CHILDREN_UID, children_uid); - } - void add_type(Type type) - { - fbb_.AddElement(TreeNode::VT_TYPE, static_cast(type), 0); - } - void add_status(Status status) - { - fbb_.AddElement(TreeNode::VT_STATUS, static_cast(status), 0); - } - void add_instance_name(flatbuffers::Offset instance_name) - { - fbb_.AddOffset(TreeNode::VT_INSTANCE_NAME, instance_name); - } - void add_registration_name(flatbuffers::Offset registration_name) - { - fbb_.AddOffset(TreeNode::VT_REGISTRATION_NAME, registration_name); - } - explicit TreeNodeBuilder(flatbuffers::FlatBufferBuilder& _fbb) : fbb_(_fbb) - { - start_ = fbb_.StartTable(); - } - TreeNodeBuilder& operator=(const TreeNodeBuilder&); - flatbuffers::Offset Finish() - { - const auto end = fbb_.EndTable(start_); - auto o = flatbuffers::Offset(end); - fbb_.Required(o, TreeNode::VT_INSTANCE_NAME); - fbb_.Required(o, TreeNode::VT_REGISTRATION_NAME); - return o; - } +struct TreeNodeBuilder { + flatbuffers::FlatBufferBuilder &fbb_; + flatbuffers::uoffset_t start_; + void add_uid(uint16_t uid) { + fbb_.AddElement(TreeNode::VT_UID, uid, 0); + } + void add_children_uid(flatbuffers::Offset> children_uid) { + fbb_.AddOffset(TreeNode::VT_CHILDREN_UID, children_uid); + } + void add_type(Type type) { + fbb_.AddElement(TreeNode::VT_TYPE, static_cast(type), 0); + } + void add_status(Status status) { + fbb_.AddElement(TreeNode::VT_STATUS, static_cast(status), 0); + } + void add_instance_name(flatbuffers::Offset instance_name) { + fbb_.AddOffset(TreeNode::VT_INSTANCE_NAME, instance_name); + } + void add_registration_name(flatbuffers::Offset registration_name) { + fbb_.AddOffset(TreeNode::VT_REGISTRATION_NAME, registration_name); + } + void add_params(flatbuffers::Offset>> params) { + fbb_.AddOffset(TreeNode::VT_PARAMS, params); + } + explicit TreeNodeBuilder(flatbuffers::FlatBufferBuilder &_fbb) + : fbb_(_fbb) { + start_ = fbb_.StartTable(); + } + TreeNodeBuilder &operator=(const TreeNodeBuilder &); + flatbuffers::Offset Finish() { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + fbb_.Required(o, TreeNode::VT_INSTANCE_NAME); + fbb_.Required(o, TreeNode::VT_REGISTRATION_NAME); + return o; + } }; -inline flatbuffers::Offset CreateTreeNode(flatbuffers::FlatBufferBuilder& _fbb, uint16_t uid = 0, - flatbuffers::Offset> children_uid = 0, - Type type = Type::UNDEFINED, Status status = Status::IDLE, - flatbuffers::Offset instance_name = 0, - flatbuffers::Offset registration_name = 0) -{ - TreeNodeBuilder builder_(_fbb); - builder_.add_registration_name(registration_name); - builder_.add_instance_name(instance_name); - builder_.add_children_uid(children_uid); - builder_.add_uid(uid); - builder_.add_status(status); - builder_.add_type(type); - return builder_.Finish(); +inline flatbuffers::Offset CreateTreeNode( + flatbuffers::FlatBufferBuilder &_fbb, + uint16_t uid = 0, + flatbuffers::Offset> children_uid = 0, + Type type = Type::UNDEFINED, + Status status = Status::IDLE, + flatbuffers::Offset instance_name = 0, + flatbuffers::Offset registration_name = 0, + flatbuffers::Offset>> params = 0) { + TreeNodeBuilder builder_(_fbb); + builder_.add_params(params); + builder_.add_registration_name(registration_name); + builder_.add_instance_name(instance_name); + builder_.add_children_uid(children_uid); + builder_.add_uid(uid); + builder_.add_status(status); + builder_.add_type(type); + return builder_.Finish(); } -inline flatbuffers::Offset CreateTreeNodeDirect(flatbuffers::FlatBufferBuilder& _fbb, uint16_t uid = 0, - const std::vector* children_uid = nullptr, - Type type = Type::UNDEFINED, Status status = Status::IDLE, - const char* instance_name = nullptr, - const char* registration_name = nullptr) -{ - return BT_Serialization::CreateTreeNode(_fbb, uid, children_uid ? _fbb.CreateVector(*children_uid) : 0, - type, status, instance_name ? _fbb.CreateString(instance_name) : 0, - registration_name ? _fbb.CreateString(registration_name) : 0); +inline flatbuffers::Offset CreateTreeNodeDirect( + flatbuffers::FlatBufferBuilder &_fbb, + uint16_t uid = 0, + const std::vector *children_uid = nullptr, + Type type = Type::UNDEFINED, + Status status = Status::IDLE, + const char *instance_name = nullptr, + const char *registration_name = nullptr, + const std::vector> *params = nullptr) { + return BT_Serialization::CreateTreeNode( + _fbb, + uid, + children_uid ? _fbb.CreateVector(*children_uid) : 0, + type, + status, + instance_name ? _fbb.CreateString(instance_name) : 0, + registration_name ? _fbb.CreateString(registration_name) : 0, + params ? _fbb.CreateVector>(*params) : 0); } -struct BehaviorTree FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table -{ - enum - { - VT_ROOT_UID = 4, - VT_NODES = 6 - }; - uint16_t root_uid() const - { - return GetField(VT_ROOT_UID, 0); - } - const flatbuffers::Vector>* nodes() const - { - return GetPointer>*>(VT_NODES); - } - bool Verify(flatbuffers::Verifier& verifier) const - { - return VerifyTableStart(verifier) && VerifyField(verifier, VT_ROOT_UID) && - VerifyOffset(verifier, VT_NODES) && verifier.Verify(nodes()) && verifier.VerifyVectorOfTables(nodes()) && - verifier.EndTable(); - } +struct BehaviorTree FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + enum { + VT_ROOT_UID = 4, + VT_NODES = 6 + }; + uint16_t root_uid() const { + return GetField(VT_ROOT_UID, 0); + } + const flatbuffers::Vector> *nodes() const { + return GetPointer> *>(VT_NODES); + } + bool Verify(flatbuffers::Verifier &verifier) const { + return VerifyTableStart(verifier) && + VerifyField(verifier, VT_ROOT_UID) && + VerifyOffset(verifier, VT_NODES) && + verifier.Verify(nodes()) && + verifier.VerifyVectorOfTables(nodes()) && + verifier.EndTable(); + } }; -struct BehaviorTreeBuilder -{ - flatbuffers::FlatBufferBuilder& fbb_; - flatbuffers::uoffset_t start_; - void add_root_uid(uint16_t root_uid) - { - fbb_.AddElement(BehaviorTree::VT_ROOT_UID, root_uid, 0); - } - void add_nodes(flatbuffers::Offset>> nodes) - { - fbb_.AddOffset(BehaviorTree::VT_NODES, nodes); - } - explicit BehaviorTreeBuilder(flatbuffers::FlatBufferBuilder& _fbb) : fbb_(_fbb) - { - start_ = fbb_.StartTable(); - } - BehaviorTreeBuilder& operator=(const BehaviorTreeBuilder&); - flatbuffers::Offset Finish() - { - const auto end = fbb_.EndTable(start_); - auto o = flatbuffers::Offset(end); - return o; - } +struct BehaviorTreeBuilder { + flatbuffers::FlatBufferBuilder &fbb_; + flatbuffers::uoffset_t start_; + void add_root_uid(uint16_t root_uid) { + fbb_.AddElement(BehaviorTree::VT_ROOT_UID, root_uid, 0); + } + void add_nodes(flatbuffers::Offset>> nodes) { + fbb_.AddOffset(BehaviorTree::VT_NODES, nodes); + } + explicit BehaviorTreeBuilder(flatbuffers::FlatBufferBuilder &_fbb) + : fbb_(_fbb) { + start_ = fbb_.StartTable(); + } + BehaviorTreeBuilder &operator=(const BehaviorTreeBuilder &); + flatbuffers::Offset Finish() { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + return o; + } }; -inline flatbuffers::Offset -CreateBehaviorTree(flatbuffers::FlatBufferBuilder& _fbb, uint16_t root_uid = 0, - flatbuffers::Offset>> nodes = 0) -{ - BehaviorTreeBuilder builder_(_fbb); - builder_.add_nodes(nodes); - builder_.add_root_uid(root_uid); - return builder_.Finish(); +inline flatbuffers::Offset CreateBehaviorTree( + flatbuffers::FlatBufferBuilder &_fbb, + uint16_t root_uid = 0, + flatbuffers::Offset>> nodes = 0) { + BehaviorTreeBuilder builder_(_fbb); + builder_.add_nodes(nodes); + builder_.add_root_uid(root_uid); + return builder_.Finish(); } -inline flatbuffers::Offset -CreateBehaviorTreeDirect(flatbuffers::FlatBufferBuilder& _fbb, uint16_t root_uid = 0, - const std::vector>* nodes = nullptr) -{ - return BT_Serialization::CreateBehaviorTree(_fbb, root_uid, - nodes ? _fbb.CreateVector>(*nodes) : 0); +inline flatbuffers::Offset CreateBehaviorTreeDirect( + flatbuffers::FlatBufferBuilder &_fbb, + uint16_t root_uid = 0, + const std::vector> *nodes = nullptr) { + return BT_Serialization::CreateBehaviorTree( + _fbb, + root_uid, + nodes ? _fbb.CreateVector>(*nodes) : 0); } -struct StatusChangeLog FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table -{ - enum - { - VT_BEHAVIOR_TREE = 4, - VT_STATE_CHANGES = 6 - }; - const BehaviorTree* behavior_tree() const - { - return GetPointer(VT_BEHAVIOR_TREE); - } - const flatbuffers::Vector* state_changes() const - { - return GetPointer*>(VT_STATE_CHANGES); - } - bool Verify(flatbuffers::Verifier& verifier) const - { - return VerifyTableStart(verifier) && VerifyOffset(verifier, VT_BEHAVIOR_TREE) && - verifier.VerifyTable(behavior_tree()) && VerifyOffset(verifier, VT_STATE_CHANGES) && - verifier.Verify(state_changes()) && verifier.EndTable(); - } +struct StatusChangeLog FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + enum { + VT_BEHAVIOR_TREE = 4, + VT_STATE_CHANGES = 6 + }; + const BehaviorTree *behavior_tree() const { + return GetPointer(VT_BEHAVIOR_TREE); + } + const flatbuffers::Vector *state_changes() const { + return GetPointer *>(VT_STATE_CHANGES); + } + bool Verify(flatbuffers::Verifier &verifier) const { + return VerifyTableStart(verifier) && + VerifyOffset(verifier, VT_BEHAVIOR_TREE) && + verifier.VerifyTable(behavior_tree()) && + VerifyOffset(verifier, VT_STATE_CHANGES) && + verifier.Verify(state_changes()) && + verifier.EndTable(); + } }; -struct StatusChangeLogBuilder -{ - flatbuffers::FlatBufferBuilder& fbb_; - flatbuffers::uoffset_t start_; - void add_behavior_tree(flatbuffers::Offset behavior_tree) - { - fbb_.AddOffset(StatusChangeLog::VT_BEHAVIOR_TREE, behavior_tree); - } - void add_state_changes(flatbuffers::Offset> state_changes) - { - fbb_.AddOffset(StatusChangeLog::VT_STATE_CHANGES, state_changes); - } - explicit StatusChangeLogBuilder(flatbuffers::FlatBufferBuilder& _fbb) : fbb_(_fbb) - { - start_ = fbb_.StartTable(); - } - StatusChangeLogBuilder& operator=(const StatusChangeLogBuilder&); - flatbuffers::Offset Finish() - { - const auto end = fbb_.EndTable(start_); - auto o = flatbuffers::Offset(end); - return o; - } +struct StatusChangeLogBuilder { + flatbuffers::FlatBufferBuilder &fbb_; + flatbuffers::uoffset_t start_; + void add_behavior_tree(flatbuffers::Offset behavior_tree) { + fbb_.AddOffset(StatusChangeLog::VT_BEHAVIOR_TREE, behavior_tree); + } + void add_state_changes(flatbuffers::Offset> state_changes) { + fbb_.AddOffset(StatusChangeLog::VT_STATE_CHANGES, state_changes); + } + explicit StatusChangeLogBuilder(flatbuffers::FlatBufferBuilder &_fbb) + : fbb_(_fbb) { + start_ = fbb_.StartTable(); + } + StatusChangeLogBuilder &operator=(const StatusChangeLogBuilder &); + flatbuffers::Offset Finish() { + const auto end = fbb_.EndTable(start_); + auto o = flatbuffers::Offset(end); + return o; + } }; -inline flatbuffers::Offset -CreateStatusChangeLog(flatbuffers::FlatBufferBuilder& _fbb, flatbuffers::Offset behavior_tree = 0, - flatbuffers::Offset> state_changes = 0) -{ - StatusChangeLogBuilder builder_(_fbb); - builder_.add_state_changes(state_changes); - builder_.add_behavior_tree(behavior_tree); - return builder_.Finish(); +inline flatbuffers::Offset CreateStatusChangeLog( + flatbuffers::FlatBufferBuilder &_fbb, + flatbuffers::Offset behavior_tree = 0, + flatbuffers::Offset> state_changes = 0) { + StatusChangeLogBuilder builder_(_fbb); + builder_.add_state_changes(state_changes); + builder_.add_behavior_tree(behavior_tree); + return builder_.Finish(); } -inline flatbuffers::Offset -CreateStatusChangeLogDirect(flatbuffers::FlatBufferBuilder& _fbb, flatbuffers::Offset behavior_tree = 0, - const std::vector* state_changes = nullptr) -{ - return BT_Serialization::CreateStatusChangeLog( - _fbb, behavior_tree, state_changes ? _fbb.CreateVectorOfStructs(*state_changes) : 0); +inline flatbuffers::Offset CreateStatusChangeLogDirect( + flatbuffers::FlatBufferBuilder &_fbb, + flatbuffers::Offset behavior_tree = 0, + const std::vector *state_changes = nullptr) { + return BT_Serialization::CreateStatusChangeLog( + _fbb, + behavior_tree, + state_changes ? _fbb.CreateVectorOfStructs(*state_changes) : 0); } -inline const BT_Serialization::BehaviorTree* GetBehaviorTree(const void* buf) -{ - return flatbuffers::GetRoot(buf); +inline const BT_Serialization::BehaviorTree *GetBehaviorTree(const void *buf) { + return flatbuffers::GetRoot(buf); } -inline const BT_Serialization::BehaviorTree* GetSizePrefixedBehaviorTree(const void* buf) -{ - return flatbuffers::GetSizePrefixedRoot(buf); +inline const BT_Serialization::BehaviorTree *GetSizePrefixedBehaviorTree(const void *buf) { + return flatbuffers::GetSizePrefixedRoot(buf); } -inline bool VerifyBehaviorTreeBuffer(flatbuffers::Verifier& verifier) -{ - return verifier.VerifyBuffer(nullptr); +inline bool VerifyBehaviorTreeBuffer( + flatbuffers::Verifier &verifier) { + return verifier.VerifyBuffer(nullptr); } -inline bool VerifySizePrefixedBehaviorTreeBuffer(flatbuffers::Verifier& verifier) -{ - return verifier.VerifySizePrefixedBuffer(nullptr); +inline bool VerifySizePrefixedBehaviorTreeBuffer( + flatbuffers::Verifier &verifier) { + return verifier.VerifySizePrefixedBuffer(nullptr); } -inline void FinishBehaviorTreeBuffer(flatbuffers::FlatBufferBuilder& fbb, - flatbuffers::Offset root) -{ - fbb.Finish(root); +inline void FinishBehaviorTreeBuffer( + flatbuffers::FlatBufferBuilder &fbb, + flatbuffers::Offset root) { + fbb.Finish(root); } -inline void FinishSizePrefixedBehaviorTreeBuffer(flatbuffers::FlatBufferBuilder& fbb, - flatbuffers::Offset root) -{ - fbb.FinishSizePrefixed(root); +inline void FinishSizePrefixedBehaviorTreeBuffer( + flatbuffers::FlatBufferBuilder &fbb, + flatbuffers::Offset root) { + fbb.FinishSizePrefixed(root); } -} // namespace BT_Serialization +} // namespace BT_Serialization -#endif // FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ +#endif // FLATBUFFERS_GENERATED_BTLOGGER_BT_SERIALIZATION_H_ diff --git a/include/behavior_tree_logger/bt_flatbuffer_helper.h b/include/behavior_tree_logger/bt_flatbuffer_helper.h index 7a6458a58..9120867d0 100644 --- a/include/behavior_tree_logger/bt_flatbuffer_helper.h +++ b/include/behavior_tree_logger/bt_flatbuffer_helper.h @@ -42,11 +42,13 @@ inline BT_Serialization::Status convertToFlatbuffers(NodeStatus type) return BT_Serialization::Status::IDLE; } -inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builder, BT::TreeNode* root_node) +inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builder, + BT::TreeNode* root_node) { std::vector> fb_nodes; - applyRecursiveVisitor(root_node, [&](TreeNode* node) { + applyRecursiveVisitor(root_node, [&](BT::TreeNode* node) + { std::vector children_uid; if (auto control = dynamic_cast(node)) { @@ -62,10 +64,27 @@ inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builde children_uid.push_back(child->UID()); } - fb_nodes.push_back(BT_Serialization::CreateTreeNode( - builder, node->UID(), builder.CreateVector(children_uid), convertToFlatbuffers(node->type()), - convertToFlatbuffers(node->status()), builder.CreateString(node->name().c_str()), - builder.CreateString(node->registrationName().c_str()))); + std::vector> params; + const NodeParameters & init_params = node->initializationParameters(); + for (const auto& it: init_params) + { + params.push_back( BT_Serialization::CreateKeyValueDirect( + builder, + it.first.c_str(), + it.second.c_str()) + ); + } + + auto tn = BT_Serialization::CreateTreeNode( + builder, node->UID(), + builder.CreateVector(children_uid), + convertToFlatbuffers(node->type()), + convertToFlatbuffers(node->status()), + builder.CreateString(node->name().c_str()), + builder.CreateString(node->registrationName().c_str()), + builder.CreateVector(params) ); + + fb_nodes.push_back(tn); }); auto behavior_tree = diff --git a/src/loggers/bt_cout_logger.cpp b/src/loggers/bt_cout_logger.cpp index 26358972a..37c35c998 100644 --- a/src/loggers/bt_cout_logger.cpp +++ b/src/loggers/bt_cout_logger.cpp @@ -27,8 +27,9 @@ void StdCoutLogger::callback(TimePoint timestamp, const TreeNode& node, NodeStat constexpr const size_t ws_count = 25; double since_epoch = duration(timestamp.time_since_epoch()).count(); - printf("[%.3f]: %s%s %s -> %s\n", since_epoch, node.name().c_str(), + printf("[%.3f]: %s%s %s -> %s", since_epoch, node.name().c_str(), &whitespaces[std::min(ws_count, node.name().size())], toStr(prev_status, true), toStr(status, true)); + std::cout << std::endl; } void StdCoutLogger::flush() From 0f780ec71e01a2a99918cd61c508e9b65567d085 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 12 Sep 2018 18:03:31 +0200 Subject: [PATCH 097/125] few changes in the examples and the core lib --- examples/crossdoor_dummy_nodes.h | 130 +++++++++--------- examples/crossdoor_example.cpp | 44 +++--- examples/dummy_nodes.h | 4 + examples/tutorial_blackboard.cpp | 5 + gtest/gtest_factory.cpp | 4 +- include/behavior_tree_core/action_node.h | 5 - include/behavior_tree_core/tree_node.h | 2 +- include/behavior_tree_core/xml_parsing.h | 15 +- .../behavior_tree_logger/abstract_logger.h | 6 +- src/xml_parsing.cpp | 10 +- 10 files changed, 108 insertions(+), 117 deletions(-) diff --git a/examples/crossdoor_dummy_nodes.h b/examples/crossdoor_dummy_nodes.h index 83224711b..206ac9949 100644 --- a/examples/crossdoor_dummy_nodes.h +++ b/examples/crossdoor_dummy_nodes.h @@ -2,82 +2,82 @@ using namespace BT; -class CrossDoor +namespace CrossDoor { - int _multiplier; - public: - CrossDoor(BT::BehaviorTreeFactory& factory, bool fast = true) - { - door_open_ = true; - door_locked_ = false; - - factory.registerSimpleCondition("IsDoorOpen", std::bind(&CrossDoor::IsDoorOpen, this) ); - factory.registerSimpleAction("PassThroughDoor", std::bind(&CrossDoor::PassThroughDoor, this) ); - factory.registerSimpleAction("PassThroughWindow", std::bind(&CrossDoor::PassThroughWindow, this) ); - factory.registerSimpleAction("OpenDoor", std::bind(&CrossDoor::OpenDoor, this) ); - factory.registerSimpleAction("CloseDoor", std::bind(&CrossDoor::CloseDoor, this) ); - factory.registerSimpleCondition("IsDoorLocked", std::bind(&CrossDoor::IsDoorLocked, this) ); - factory.registerSimpleAction("UnlockDoor", std::bind(&CrossDoor::UnlockDoor, this) ); - - _multiplier = fast ? 1 : 10; - } +BT::NodeStatus IsDoorOpen(const Blackboard::Ptr& blackboard) +{ + std::this_thread::sleep_for(std::chrono::milliseconds(500) ); + bool door_open = blackboard->get("door_open"); - BT::NodeStatus IsDoorOpen() - { - std::this_thread::sleep_for(std::chrono::milliseconds(50) * _multiplier); - return door_open_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; - } + return door_open ? NodeStatus::SUCCESS : NodeStatus::FAILURE; +} - BT::NodeStatus IsDoorLocked() - { - std::this_thread::sleep_for(std::chrono::milliseconds(50) * _multiplier); - return door_locked_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; - } +BT::NodeStatus IsDoorLocked(const Blackboard::Ptr& blackboard) +{ + std::this_thread::sleep_for(std::chrono::milliseconds(500) ); + bool door_locked = blackboard->get("door_locked"); - BT::NodeStatus UnlockDoor() - { - std::this_thread::sleep_for(std::chrono::milliseconds(200) * _multiplier); - door_locked_ = false; - return NodeStatus::SUCCESS; - } + return door_locked ? NodeStatus::SUCCESS : NodeStatus::FAILURE; +} - BT::NodeStatus PassThroughDoor() - { - std::this_thread::sleep_for(std::chrono::milliseconds(100) * _multiplier); - return door_open_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; - } +BT::NodeStatus UnlockDoor(const Blackboard::Ptr& blackboard) +{ + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + blackboard->set("door_locked", false); - BT::NodeStatus PassThroughWindow() - { - std::this_thread::sleep_for(std::chrono::milliseconds(100) * _multiplier); - return NodeStatus::SUCCESS; - } + return NodeStatus::SUCCESS; +} + +BT::NodeStatus PassThroughDoor(const Blackboard::Ptr& blackboard) +{ + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + bool door_open = blackboard->get("door_open"); + + return door_open ? NodeStatus::SUCCESS : NodeStatus::FAILURE; +} - BT::NodeStatus OpenDoor() +BT::NodeStatus PassThroughWindow(const Blackboard::Ptr& blackboard) +{ + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); + return NodeStatus::SUCCESS; +} + +BT::NodeStatus OpenDoor(const Blackboard::Ptr& blackboard) +{ + std::this_thread::sleep_for(std::chrono::milliseconds(2000)); + bool door_locked = blackboard->get("door_locked"); + + if (door_locked) { - std::this_thread::sleep_for(std::chrono::milliseconds(200) * _multiplier); - if (door_locked_) - return NodeStatus::FAILURE; - door_open_ = true; - return NodeStatus::SUCCESS; + return NodeStatus::FAILURE; } - BT::NodeStatus CloseDoor() + blackboard->set("door_open", true); + return NodeStatus::SUCCESS; +} + +BT::NodeStatus CloseDoor(const Blackboard::Ptr& blackboard) +{ + bool door_open = blackboard->get("door_open"); + + if (door_open) { - std::this_thread::sleep_for(std::chrono::milliseconds(150) * _multiplier); - if (door_open_) - { - door_open_ = false; - return NodeStatus::SUCCESS; - } - else - { - return NodeStatus::FAILURE; - } + std::this_thread::sleep_for(std::chrono::milliseconds(1500)); + blackboard->set("door_open", false); } + return NodeStatus::SUCCESS; +} + +void RegisterNodes(BT::BehaviorTreeFactory& factory) +{ + factory.registerSimpleCondition("IsDoorOpen", IsDoorOpen ); + factory.registerSimpleAction("PassThroughDoor", PassThroughDoor ); + factory.registerSimpleAction("PassThroughWindow", PassThroughWindow ); + factory.registerSimpleAction("OpenDoor", OpenDoor ); + factory.registerSimpleAction("CloseDoor", CloseDoor ); + factory.registerSimpleCondition("IsDoorLocked", IsDoorLocked ); + factory.registerSimpleAction("UnlockDoor", UnlockDoor ); +} - private: - bool door_open_; - bool door_locked_; -}; +} diff --git a/examples/crossdoor_example.cpp b/examples/crossdoor_example.cpp index df0a5264f..fa9641b03 100644 --- a/examples/crossdoor_example.cpp +++ b/examples/crossdoor_example.cpp @@ -3,6 +3,7 @@ #include "behavior_tree_logger/bt_cout_logger.h" #include "behavior_tree_logger/bt_minitrace_logger.h" #include "behavior_tree_logger/bt_file_logger.h" +#include "Blackboard/blackboard_local.h" #ifdef ZMQ_FOUND #include "behavior_tree_logger/bt_zmq_publisher.h" @@ -43,45 +44,36 @@ const std::string xml_text = R"( // clang-format on +using namespace BT; + int main() { - using namespace BT; - BT::BehaviorTreeFactory factory; + auto blackboard = Blackboard::create(); + blackboard->set("door_open", false); + blackboard->set("door_locked", true); // register all the actions into the factory - CrossDoor cross_door(factory, false); - - XMLParser parser(factory); - parser.loadFromText(xml_text); + CrossDoor::RegisterNodes(factory); - std::vector nodes; - BT::TreeNode::Ptr root_node = parser.instantiateTree(nodes); - - StdCoutLogger logger_cout(root_node.get()); - MinitraceLogger logger_minitrace(root_node.get(), "bt_trace.json"); - FileLogger logger_file(root_node.get(), "bt_trace.fbl", 32); + // Important: when the object tree goes out of scope, all the TreeNodes are destroyed + auto tree = buildTreeFromText(factory, xml_text, blackboard); + TreeNode* root_node = tree.first.get(); + StdCoutLogger logger_cout(root_node); + MinitraceLogger logger_minitrace(root_node, "bt_trace.json"); + FileLogger logger_file(root_node, "bt_trace.fbl", 32); #ifdef ZMQ_FOUND - PublisherZMQ publisher_zmq(root_node.get()); + PublisherZMQ publisher_zmq(root_node); #endif - cross_door.CloseDoor(); - - std::cout << "\n-------\n"; - XMLWriter writer(factory); - std::cout << writer.writeXML( root_node.get(), false) << std::endl; - + std::cout << writeXML( factory, root_node, false ) << std::endl; std::cout << "---------------" << std::endl; - root_node->executeTick(); - - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - std::cout << "---------------" << std::endl; - while (1) + // Keep on ticking until you get either a SUCCESS or FAILURE state + while( root_node->executeTick() == BT::NodeStatus::RUNNING) { - root_node->executeTick(); + // continue; } - std::cout << "---------------" << std::endl; return 0; } diff --git a/examples/dummy_nodes.h b/examples/dummy_nodes.h index dd2c6b38d..de8262c33 100644 --- a/examples/dummy_nodes.h +++ b/examples/dummy_nodes.h @@ -59,6 +59,10 @@ class CustomAction: public BT::ActionNodeBase std::cout << "CustomAction: " << this->name() << std::endl; return BT::NodeStatus::SUCCESS; } + virtual void halt() override + { + setStatus(BT::NodeStatus::IDLE); + } }; diff --git a/examples/tutorial_blackboard.cpp b/examples/tutorial_blackboard.cpp index 167608d73..75be27509 100644 --- a/examples/tutorial_blackboard.cpp +++ b/examples/tutorial_blackboard.cpp @@ -47,6 +47,11 @@ class PrintGoalPose: public ActionNodeBase return NodeStatus::FAILURE; } } + + virtual void halt() override + { + setStatus(NodeStatus::IDLE); + } }; diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp index 9ebc503b0..13d413ac8 100644 --- a/gtest/gtest_factory.cpp +++ b/gtest/gtest_factory.cpp @@ -80,7 +80,7 @@ const std::string xml_text_subtree = R"( TEST(BehaviorTreeFactory, VerifyLargeTree) { BT::BehaviorTreeFactory factory; - CrossDoor cross_door(factory); + CrossDoor::RegisterNodes(factory); BT::XMLParser parser(factory); parser.loadFromText(xml_text); @@ -137,7 +137,7 @@ TEST(BehaviorTreeFactory, VerifyLargeTree) TEST(BehaviorTreeFactory, Subtree) { BT::BehaviorTreeFactory factory; - CrossDoor cross_door(factory); + CrossDoor::RegisterNodes(factory); BT::XMLParser parser(factory); parser.loadFromText(xml_text_subtree); diff --git a/include/behavior_tree_core/action_node.h b/include/behavior_tree_core/action_node.h index d7937603b..4c2196767 100644 --- a/include/behavior_tree_core/action_node.h +++ b/include/behavior_tree_core/action_node.h @@ -30,11 +30,6 @@ class ActionNodeBase : public LeafNode { return NodeType::ACTION; } - - virtual void halt() override - { - setStatus(NodeStatus::IDLE); - } }; /** diff --git a/include/behavior_tree_core/tree_node.h b/include/behavior_tree_core/tree_node.h index 5194b6136..b7960d335 100644 --- a/include/behavior_tree_core/tree_node.h +++ b/include/behavior_tree_core/tree_node.h @@ -84,7 +84,7 @@ class TreeNode /** * @brief subscribeToStatusChange is used to attach a callback to a status change. - * AS soon as StatusChangeSubscriber goes out of scope (it is a shared_ptr) the callback + * When StatusChangeSubscriber goes out of scope (it is a shared_ptr) the callback * is unsubscribed automatically. * * @param callback. Must have signature void funcname(NodeStatus prev_status, NodeStatus new_status) diff --git a/include/behavior_tree_core/xml_parsing.h b/include/behavior_tree_core/xml_parsing.h index f93c8646a..9985b0737 100644 --- a/include/behavior_tree_core/xml_parsing.h +++ b/include/behavior_tree_core/xml_parsing.h @@ -59,19 +59,10 @@ buildTreeFromFile(const BehaviorTreeFactory& factory, const std::string& filename, const Blackboard::Ptr& blackboard = Blackboard::Ptr() ); -class XMLWriter -{ -public: - XMLWriter( const BehaviorTreeFactory& factory): - factory_(factory) - {} - - std::string writeXML(const TreeNode* root_node, bool compact_representation = false) const; +std::string writeXML(const BehaviorTreeFactory& factory, + const TreeNode* root_node, + bool compact_representation = false); -private: - const BehaviorTreeFactory& factory_; - -}; } diff --git a/include/behavior_tree_logger/abstract_logger.h b/include/behavior_tree_logger/abstract_logger.h index f903df48d..d1f9fd0b9 100644 --- a/include/behavior_tree_logger/abstract_logger.h +++ b/include/behavior_tree_logger/abstract_logger.h @@ -8,7 +8,7 @@ namespace BT class StatusChangeLogger { public: - StatusChangeLogger(TreeNode* root_node); + StatusChangeLogger(TreeNode *root_node); virtual ~StatusChangeLogger() = default; virtual void callback(BT::TimePoint timestamp, const TreeNode& node, NodeStatus prev_status, NodeStatus status) = 0; @@ -44,7 +44,9 @@ class StatusChangeLogger //-------------------------------------------- -inline StatusChangeLogger::StatusChangeLogger(TreeNode* root_node) : enabled_(true), show_transition_to_idle_(true) +inline StatusChangeLogger::StatusChangeLogger(TreeNode* root_node) : + enabled_(true), + show_transition_to_idle_(true) { applyRecursiveVisitor(root_node, [this](TreeNode* node) { diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 40c9ee937..1358b2987 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -379,7 +379,9 @@ TreeNode::Ptr BT::XMLParser::treeParsing(const XMLElement *root_element, return root; } -std::string XMLWriter::writeXML(const TreeNode *root_node, bool compact_representation) const +std::string writeXML(const BehaviorTreeFactory& factory, + const TreeNode *root_node, + bool compact_representation) { using namespace tinyxml2; @@ -395,7 +397,7 @@ std::string XMLWriter::writeXML(const TreeNode *root_node, bool compact_represen std::function recursiveVisitor; - recursiveVisitor = [&recursiveVisitor, &doc, compact_representation, this] + recursiveVisitor = [&recursiveVisitor, &doc, compact_representation,&factory] (const TreeNode* node, XMLElement* parent) -> void { std::string node_type = toStr(node->type()); @@ -409,7 +411,7 @@ std::string XMLWriter::writeXML(const TreeNode *root_node, bool compact_represen } else if(compact_representation) { - for(const auto& model: factory_.models() ) + for(const auto& model: factory.models() ) { if( model.registration_ID == node_ID) { @@ -456,7 +458,7 @@ std::string XMLWriter::writeXML(const TreeNode *root_node, bool compact_represen XMLElement* model_root = doc.NewElement("TreeNodesModel"); rootXML->InsertEndChild(model_root); - for( auto& model: factory_.models()) + for( auto& model: factory.models()) { if( model.type == NodeType::CONTROL) { From 4794fb4406cebaeb8dc93455998f8448607b5416 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 12 Sep 2018 18:08:41 +0200 Subject: [PATCH 098/125] more readable API --- examples/crossdoor_example.cpp | 16 ++++++++-------- examples/tutorial_blackboard.cpp | 5 ++--- examples/tutorial_factory_tree.cpp | 3 +-- examples/tutorial_sequence_star.cpp | 11 +++++------ include/behavior_tree_core/xml_parsing.h | 20 ++++++++++++-------- src/xml_parsing.cpp | 10 ++++------ 6 files changed, 32 insertions(+), 33 deletions(-) diff --git a/examples/crossdoor_example.cpp b/examples/crossdoor_example.cpp index fa9641b03..4bac616a8 100644 --- a/examples/crossdoor_example.cpp +++ b/examples/crossdoor_example.cpp @@ -58,22 +58,22 @@ int main() // Important: when the object tree goes out of scope, all the TreeNodes are destroyed auto tree = buildTreeFromText(factory, xml_text, blackboard); - TreeNode* root_node = tree.first.get(); - StdCoutLogger logger_cout(root_node); - MinitraceLogger logger_minitrace(root_node, "bt_trace.json"); - FileLogger logger_file(root_node, "bt_trace.fbl", 32); + StdCoutLogger logger_cout(tree.root_node); + MinitraceLogger logger_minitrace(tree.root_node, "bt_trace.json"); + FileLogger logger_file(tree.root_node, "bt_trace.fbl", 32); #ifdef ZMQ_FOUND - PublisherZMQ publisher_zmq(root_node); + PublisherZMQ publisher_zmq(tree.root_node); #endif - std::cout << writeXML( factory, root_node, false ) << std::endl; + std::cout << writeXML( factory, tree.root_node, false ) << std::endl; std::cout << "---------------" << std::endl; // Keep on ticking until you get either a SUCCESS or FAILURE state - while( root_node->executeTick() == BT::NodeStatus::RUNNING) + NodeStatus status = NodeStatus::RUNNING; + while( status == NodeStatus::RUNNING ) { - // continue; + status = tree.root_node->executeTick(); } return 0; } diff --git a/examples/tutorial_blackboard.cpp b/examples/tutorial_blackboard.cpp index 75be27509..e000b1402 100644 --- a/examples/tutorial_blackboard.cpp +++ b/examples/tutorial_blackboard.cpp @@ -96,13 +96,12 @@ int main() auto blackboard = Blackboard::create(); // Important: when the object tree goes out of scope, all the TreeNodes are destroyed - auto res = buildTreeFromText(factory, xml_text, blackboard); - const TreeNode::Ptr& root_node = res.first; + auto tree = buildTreeFromText(factory, xml_text, blackboard); NodeStatus status = NodeStatus::RUNNING; while( status == NodeStatus::RUNNING ) { - status = root_node->executeTick(); + status = tree.root_node->executeTick(); } return 0; diff --git a/examples/tutorial_factory_tree.cpp b/examples/tutorial_factory_tree.cpp index 7aca8c7cb..ac2bba0b7 100644 --- a/examples/tutorial_factory_tree.cpp +++ b/examples/tutorial_factory_tree.cpp @@ -35,12 +35,11 @@ int main() // IMPORTANT: when the object tree goes out of scope, all the TreeNodes are destroyed auto tree = buildTreeFromText(factory, xml_text); - const TreeNode::Ptr& root_node = tree.first; // The tick is propagated to all the children. // until one of the returns FAILURE or RUNNING. // In this case all of the return SUCCESS - root_node->executeTick(); + tree.root_node->executeTick(); return 0; } diff --git a/examples/tutorial_sequence_star.cpp b/examples/tutorial_sequence_star.cpp index c682c9df5..e79e7167d 100644 --- a/examples/tutorial_sequence_star.cpp +++ b/examples/tutorial_sequence_star.cpp @@ -66,33 +66,32 @@ int main() std::cout << "\n------------ BUILDING A NEW TREE ------------\n\n" << std::endl; auto tree = buildTreeFromText(factory, xml_text); - TreeNode::Ptr root_node = tree.first; // This logger will show all the state transitions on console - StdCoutLogger logger_cout(root_node.get()); + StdCoutLogger logger_cout(tree.root_node); // This other logger will save the state transition in a custom file format // simple_trace.fbl can be visualized using the command line tool [bt_log_cat] - FileLogger file_file(root_node.get(), "simple_trace.fbl", 32); + FileLogger file_file(tree.root_node, "simple_trace.fbl", 32); NodeStatus status; std::cout << "\n------- First executeTick() --------" << std::endl; - status = root_node->executeTick(); + status = tree.root_node->executeTick(); Assert( status == NodeStatus::RUNNING); std::cout << "\n------- sleep --------" << std::endl; std::this_thread::sleep_for(std::chrono::milliseconds(100)); std::cout << "\n------- Second executeTick() --------" << std::endl; - status = root_node->executeTick(); + status = tree.root_node->executeTick(); Assert( status == NodeStatus::RUNNING); std::cout << "\n------- sleep --------" << std::endl; std::this_thread::sleep_for(std::chrono::milliseconds(100)); std::cout << "\n------- Third executeTick() --------" << std::endl; - status = root_node->executeTick(); + status = tree.root_node->executeTick(); Assert( status == NodeStatus::SUCCESS); std::cout << std::endl; diff --git a/include/behavior_tree_core/xml_parsing.h b/include/behavior_tree_core/xml_parsing.h index 9985b0737..f5c8f7765 100644 --- a/include/behavior_tree_core/xml_parsing.h +++ b/include/behavior_tree_core/xml_parsing.h @@ -35,6 +35,12 @@ class XMLParser const BehaviorTreeFactory& factory_; }; +struct Tree +{ + TreeNode* root_node; + std::vector nodes; +}; + /** Helper function to do the most common steps all at once: * 1) Create an instance of XMLParse and call loadFromText. * 2) Instantiate the entire tree. @@ -42,10 +48,9 @@ class XMLParser * * return: a pair containing the root node (first) and a vector with all the instantiated nodes (second). */ -std::pair> -buildTreeFromText(const BehaviorTreeFactory& factory, - const std::string& text, - const Blackboard::Ptr& blackboard = Blackboard::Ptr() ); +Tree buildTreeFromText(const BehaviorTreeFactory& factory, + const std::string& text, + const Blackboard::Ptr& blackboard = Blackboard::Ptr() ); /** Helper function to do the most common steps all at once: * 1) Create an instance of XMLParse and call loadFromFile. @@ -54,10 +59,9 @@ buildTreeFromText(const BehaviorTreeFactory& factory, * * return: a pair containing the root node (first) and a vector with all the instantiated nodes (second). */ -std::pair> -buildTreeFromFile(const BehaviorTreeFactory& factory, - const std::string& filename, - const Blackboard::Ptr& blackboard = Blackboard::Ptr() ); +Tree buildTreeFromFile(const BehaviorTreeFactory& factory, + const std::string& filename, + const Blackboard::Ptr& blackboard = Blackboard::Ptr() ); std::string writeXML(const BehaviorTreeFactory& factory, const TreeNode* root_node, diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 1358b2987..15e772b8c 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -483,8 +483,7 @@ std::string writeXML(const BehaviorTreeFactory& factory, return std::string( printer.CStr(), printer.CStrSize()-1 ); } -std::pair > -buildTreeFromText(const BehaviorTreeFactory &factory, +Tree buildTreeFromText(const BehaviorTreeFactory &factory, const std::string &text, const Blackboard::Ptr &blackboard) { @@ -494,11 +493,10 @@ buildTreeFromText(const BehaviorTreeFactory &factory, std::vector nodes; auto root = parser.instantiateTree(nodes); assignBlackboardToEntireTree(root.get(), blackboard ); - return {root, nodes}; + return {root.get(), nodes}; } -std::pair > -buildTreeFromFile(const BehaviorTreeFactory &factory, +Tree buildTreeFromFile(const BehaviorTreeFactory &factory, const std::string &filename, const Blackboard::Ptr &blackboard) { @@ -508,7 +506,7 @@ buildTreeFromFile(const BehaviorTreeFactory &factory, std::vector nodes; auto root = parser.instantiateTree(nodes); assignBlackboardToEntireTree(root.get(), blackboard ); - return {root, nodes}; + return {root.get(), nodes}; } } From c559ef2ac14928d50c02f647e9247745f30b04b9 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 13 Sep 2018 09:11:27 +0200 Subject: [PATCH 099/125] backup --- examples/crossdoor_example.cpp | 57 ++++++++----------- include/behavior_tree_logger/bt_file_logger.h | 2 +- 2 files changed, 26 insertions(+), 33 deletions(-) diff --git a/examples/crossdoor_example.cpp b/examples/crossdoor_example.cpp index 4bac616a8..876834dae 100644 --- a/examples/crossdoor_example.cpp +++ b/examples/crossdoor_example.cpp @@ -4,42 +4,39 @@ #include "behavior_tree_logger/bt_minitrace_logger.h" #include "behavior_tree_logger/bt_file_logger.h" #include "Blackboard/blackboard_local.h" - -#ifdef ZMQ_FOUND #include "behavior_tree_logger/bt_zmq_publisher.h" -#endif // clang-format off const std::string xml_text = R"( - + - - + + - - - - + + + + - - - - - - - - - - + + + + + + + + + + - + - - + + - + )"; // clang-format on @@ -59,15 +56,11 @@ int main() // Important: when the object tree goes out of scope, all the TreeNodes are destroyed auto tree = buildTreeFromText(factory, xml_text, blackboard); - StdCoutLogger logger_cout(tree.root_node); + // Create some loggers + StdCoutLogger logger_cout(tree.root_node); MinitraceLogger logger_minitrace(tree.root_node, "bt_trace.json"); - FileLogger logger_file(tree.root_node, "bt_trace.fbl", 32); -#ifdef ZMQ_FOUND - PublisherZMQ publisher_zmq(tree.root_node); -#endif - - std::cout << writeXML( factory, tree.root_node, false ) << std::endl; - std::cout << "---------------" << std::endl; + FileLogger logger_file(tree.root_node, "bt_trace.fbl"); + PublisherZMQ publisher_zmq(tree.root_node); // Keep on ticking until you get either a SUCCESS or FAILURE state NodeStatus status = NodeStatus::RUNNING; diff --git a/include/behavior_tree_logger/bt_file_logger.h b/include/behavior_tree_logger/bt_file_logger.h index 21bd95ecc..aacfe9253 100644 --- a/include/behavior_tree_logger/bt_file_logger.h +++ b/include/behavior_tree_logger/bt_file_logger.h @@ -11,7 +11,7 @@ namespace BT class FileLogger : public StatusChangeLogger { public: - FileLogger(TreeNode* root_node, const char* filename, uint16_t buffer_size); + FileLogger(TreeNode* root_node, const char* filename, uint16_t buffer_size = 10); virtual ~FileLogger() override; From 2e6bcd8ea0eefb769c3f609ade47c3d03d3fa2d4 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 14 Sep 2018 09:23:30 +0200 Subject: [PATCH 100/125] fixing the example --- examples/crossdoor_example.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/examples/crossdoor_example.cpp b/examples/crossdoor_example.cpp index 876834dae..bc13e4e3d 100644 --- a/examples/crossdoor_example.cpp +++ b/examples/crossdoor_example.cpp @@ -13,14 +13,14 @@ const std::string xml_text = R"( - + - + @@ -29,11 +29,11 @@ const std::string xml_text = R"( - + - + @@ -46,6 +46,7 @@ using namespace BT; int main() { BT::BehaviorTreeFactory factory; + auto blackboard = Blackboard::create(); blackboard->set("door_open", false); blackboard->set("door_locked", true); From 9c41757fff11431b7f44d6df984996ebac5a6f9b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 14 Sep 2018 11:35:41 +0200 Subject: [PATCH 101/125] file moved and renamed --- CMakeLists.txt | 22 +++--- gtest/gtest_factory.cpp | 4 +- include/behavior_tree_core/behavior_tree.h | 22 +++--- .../{ => controls}/fallback_node.h | 0 .../fallback_node_with_memory.h | 0 .../{ => controls}/parallel_node.h | 0 .../{ => controls}/sequence_node.h | 0 .../sequence_node_with_memory.h | 0 .../decorators/always_failure_node.h | 70 +++++++++++++++++++ .../decorators/always_success_node.h | 70 +++++++++++++++++++ .../decorators/blackboard_precondition_node.h | 63 +++++++++++++++++ .../negation_node.h} | 6 +- .../repeat_node.h} | 8 +-- .../retry_node.h} | 8 +-- .../subtree_node.h} | 0 src/bt_factory.cpp | 13 +++- src/{ => controls}/fallback_node.cpp | 2 +- .../fallback_node_with_memory.cpp | 2 +- src/{ => controls}/parallel_node.cpp | 2 +- src/{ => controls}/sequence_node.cpp | 2 +- .../sequence_node_with_memory.cpp | 2 +- .../negation_node.cpp} | 6 +- .../repeat_node.cpp} | 10 +-- .../retry_node.cpp} | 10 +-- 24 files changed, 269 insertions(+), 53 deletions(-) rename include/behavior_tree_core/{ => controls}/fallback_node.h (100%) rename include/behavior_tree_core/{ => controls}/fallback_node_with_memory.h (100%) rename include/behavior_tree_core/{ => controls}/parallel_node.h (100%) rename include/behavior_tree_core/{ => controls}/sequence_node.h (100%) rename include/behavior_tree_core/{ => controls}/sequence_node_with_memory.h (100%) create mode 100644 include/behavior_tree_core/decorators/always_failure_node.h create mode 100644 include/behavior_tree_core/decorators/always_success_node.h create mode 100644 include/behavior_tree_core/decorators/blackboard_precondition_node.h rename include/behavior_tree_core/{decorator_negation_node.h => decorators/negation_node.h} (89%) rename include/behavior_tree_core/{decorator_repeat_node.h => decorators/repeat_node.h} (86%) rename include/behavior_tree_core/{decorator_retry_node.h => decorators/retry_node.h} (87%) rename include/behavior_tree_core/{decorator_subtree_node.h => decorators/subtree_node.h} (100%) rename src/{ => controls}/fallback_node.cpp (98%) rename src/{ => controls}/fallback_node_with_memory.cpp (98%) rename src/{ => controls}/parallel_node.cpp (98%) rename src/{ => controls}/sequence_node.cpp (98%) rename src/{ => controls}/sequence_node_with_memory.cpp (98%) rename src/{decorator_negation_node.cpp => decorators/negation_node.cpp} (90%) rename src/{decorator_repeat_node.cpp => decorators/repeat_node.cpp} (87%) rename src/{decorator_retry_node.cpp => decorators/retry_node.cpp} (87%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 06f3758c9..97333d555 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -43,25 +43,27 @@ set(BT_Source src/action_node.cpp src/basic_types.cpp src/decorator_node.cpp - src/decorator_negation_node.cpp - src/decorator_repeat_node.cpp - src/decorator_retry_node.cpp src/condition_node.cpp src/control_node.cpp src/exceptions.cpp src/leaf_node.cpp src/tick_engine.cpp - src/parallel_node.cpp - src/fallback_node.cpp - src/sequence_node.cpp - src/fallback_node_with_memory.cpp - src/sequence_node_with_memory.cpp - src/tree_node.cpp + src/tree_node.cpp src/bt_factory.cpp src/behavior_tree.cpp - src/xml_parsing.cpp + src/decorators/negation_node.cpp + src/decorators/repeat_node.cpp + src/decorators/retry_node.cpp + + src/controls/parallel_node.cpp + src/controls/fallback_node.cpp + src/controls/sequence_node.cpp + src/controls/fallback_node_with_memory.cpp + src/controls/sequence_node_with_memory.cpp + + src/loggers/bt_cout_logger.cpp src/loggers/bt_file_logger.cpp src/loggers/bt_minitrace_logger.cpp diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp index 13d413ac8..346a96c93 100644 --- a/gtest/gtest_factory.cpp +++ b/gtest/gtest_factory.cpp @@ -128,7 +128,7 @@ TEST(BehaviorTreeFactory, VerifyLargeTree) ASSERT_EQ(sequence_closed->child(2)->name(), "PassThroughDoor"); ASSERT_EQ(sequence_closed->child(3)->name(), "CloseDoor"); - auto decorator = dynamic_cast(sequence_closed->child(0)); + auto decorator = dynamic_cast(sequence_closed->child(0)); ASSERT_TRUE(decorator != nullptr); ASSERT_EQ(decorator->child()->name(), "IsDoorOpen"); @@ -178,7 +178,7 @@ TEST(BehaviorTreeFactory, Subtree) ASSERT_EQ(sequence->child(2)->name(), "PassThroughDoor"); ASSERT_EQ(sequence->child(3)->name(), "CloseDoor"); - auto decorator = dynamic_cast(sequence->child(0)); + auto decorator = dynamic_cast(sequence->child(0)); ASSERT_TRUE(decorator != nullptr); ASSERT_EQ(decorator->child()->name(), "IsDoorLocked"); diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index 942ef0abe..5d33c7376 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -14,20 +14,24 @@ #ifndef BEHAVIOR_TREE_H #define BEHAVIOR_TREE_H -#include "behavior_tree_core/parallel_node.h" -#include "behavior_tree_core/fallback_node.h" -#include "behavior_tree_core/sequence_node.h" +#include "behavior_tree_core/controls/parallel_node.h" +#include "behavior_tree_core/controls/fallback_node.h" +#include "behavior_tree_core/controls/sequence_node.h" -#include "behavior_tree_core/sequence_node_with_memory.h" -#include "behavior_tree_core/fallback_node_with_memory.h" +#include "behavior_tree_core/controls/sequence_node_with_memory.h" +#include "behavior_tree_core/controls/fallback_node_with_memory.h" #include "behavior_tree_core/action_node.h" #include "behavior_tree_core/condition_node.h" -#include "behavior_tree_core/decorator_negation_node.h" -#include "behavior_tree_core/decorator_retry_node.h" -#include "behavior_tree_core/decorator_repeat_node.h" -#include "behavior_tree_core/decorator_subtree_node.h" +#include "behavior_tree_core/decorators/negation_node.h" +#include "behavior_tree_core/decorators/retry_node.h" +#include "behavior_tree_core/decorators/repeat_node.h" +#include "behavior_tree_core/decorators/subtree_node.h" + +#include "behavior_tree_core/decorators/always_success_node.h" +#include "behavior_tree_core/decorators/always_failure_node.h" +#include "behavior_tree_core/decorators/blackboard_precondition_node.h" namespace BT { diff --git a/include/behavior_tree_core/fallback_node.h b/include/behavior_tree_core/controls/fallback_node.h similarity index 100% rename from include/behavior_tree_core/fallback_node.h rename to include/behavior_tree_core/controls/fallback_node.h diff --git a/include/behavior_tree_core/fallback_node_with_memory.h b/include/behavior_tree_core/controls/fallback_node_with_memory.h similarity index 100% rename from include/behavior_tree_core/fallback_node_with_memory.h rename to include/behavior_tree_core/controls/fallback_node_with_memory.h diff --git a/include/behavior_tree_core/parallel_node.h b/include/behavior_tree_core/controls/parallel_node.h similarity index 100% rename from include/behavior_tree_core/parallel_node.h rename to include/behavior_tree_core/controls/parallel_node.h diff --git a/include/behavior_tree_core/sequence_node.h b/include/behavior_tree_core/controls/sequence_node.h similarity index 100% rename from include/behavior_tree_core/sequence_node.h rename to include/behavior_tree_core/controls/sequence_node.h diff --git a/include/behavior_tree_core/sequence_node_with_memory.h b/include/behavior_tree_core/controls/sequence_node_with_memory.h similarity index 100% rename from include/behavior_tree_core/sequence_node_with_memory.h rename to include/behavior_tree_core/controls/sequence_node_with_memory.h diff --git a/include/behavior_tree_core/decorators/always_failure_node.h b/include/behavior_tree_core/decorators/always_failure_node.h new file mode 100644 index 000000000..f6b9378c8 --- /dev/null +++ b/include/behavior_tree_core/decorators/always_failure_node.h @@ -0,0 +1,70 @@ +/* Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef DECORATOR_ALWAYS_FAILURE_NODE_H +#define DECORATOR_ALWAYS_FAILURE_NODE_H + +#include "behavior_tree_core/decorator_node.h" + +namespace BT +{ +class AlwaysFailureNode : public DecoratorNode +{ + public: + AlwaysFailureNode(const std::string& name); + + virtual ~AlwaysFailureNode() override = default; + + private: + virtual BT::NodeStatus tick() override; +}; + +//------------ implementation ---------------------------- + +inline AlwaysFailureNode::AlwaysFailureNode(const std::string& name) : + DecoratorNode(name, NodeParameters()) +{ +} + +inline NodeStatus AlwaysFailureNode::tick() +{ + setStatus(NodeStatus::RUNNING); + + const NodeStatus child_state = child_node_->executeTick(); + + switch (child_state) + { + case NodeStatus::FAILURE: + case NodeStatus::SUCCESS: + { + child_node_->setStatus(NodeStatus::IDLE); + return NodeStatus::FAILURE; + } + break; + + case NodeStatus::RUNNING: + { + return NodeStatus::RUNNING; + } + break; + + default: + { + // TODO throw? + } +} + return status(); +} + +} + +#endif diff --git a/include/behavior_tree_core/decorators/always_success_node.h b/include/behavior_tree_core/decorators/always_success_node.h new file mode 100644 index 000000000..2e48cdb81 --- /dev/null +++ b/include/behavior_tree_core/decorators/always_success_node.h @@ -0,0 +1,70 @@ +/* Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef DECORATOR_ALWAYS_SUCCESS_NODE_H +#define DECORATOR_ALWAYS_SUCCESS_NODE_H + +#include "behavior_tree_core/decorator_node.h" + +namespace BT +{ +class AlwaysSuccessNode : public DecoratorNode +{ + public: + AlwaysSuccessNode(const std::string& name); + + virtual ~AlwaysSuccessNode() override = default; + + private: + virtual BT::NodeStatus tick() override; +}; + +//------------ implementation ---------------------------- + +inline AlwaysSuccessNode::AlwaysSuccessNode(const std::string& name) : + DecoratorNode(name, NodeParameters()) +{ +} + +inline NodeStatus AlwaysSuccessNode::tick() +{ + setStatus(NodeStatus::RUNNING); + + const NodeStatus child_state = child_node_->executeTick(); + + switch (child_state) + { + case NodeStatus::FAILURE: + case NodeStatus::SUCCESS: + { + child_node_->setStatus(NodeStatus::IDLE); + return NodeStatus::SUCCESS; + } + break; + + case NodeStatus::RUNNING: + { + return NodeStatus::RUNNING; + } + break; + + default: + { + // TODO throw? + } +} + return status(); +} + +} + +#endif diff --git a/include/behavior_tree_core/decorators/blackboard_precondition_node.h b/include/behavior_tree_core/decorators/blackboard_precondition_node.h new file mode 100644 index 000000000..0c8996e4d --- /dev/null +++ b/include/behavior_tree_core/decorators/blackboard_precondition_node.h @@ -0,0 +1,63 @@ +/* Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef DECORATOR_BLACKBOARD_PRECONDITION_NODE_H +#define DECORATOR_BLACKBOARD_PRECONDITION_NODE_H + +#include "behavior_tree_core/decorator_node.h" + +namespace BT +{ +template +class BlackboardPreconditionNode : public DecoratorNode +{ + public: + BlackboardPreconditionNode(const std::string& name, const NodeParameters& params): + DecoratorNode(name, params) + { + } + + virtual ~BlackboardPreconditionNode() override = default; + + static const NodeParameters& requiredNodeParameters() + { + static NodeParameters params = {{"key", ""}, {"expected", "*"}}; + return params; + } + + private: + + virtual BT::NodeStatus tick() override + { + std::string key; + T expected; + T value; + + setStatus(NodeStatus::RUNNING); + + if( blackboard() && //blackboard not null + getParam("key", key) && // parameter key provided + getParam("expected", expected) && // parameter expected provided + blackboard()->get(key,value) && // value found in blackboard + (value == expected || initializationParameters().at("expected") == "*") ) // is expected value or "*" + { + return child_node_->executeTick(); + } + else{ + return NodeStatus::FAILURE; + } + } +}; + +} + +#endif diff --git a/include/behavior_tree_core/decorator_negation_node.h b/include/behavior_tree_core/decorators/negation_node.h similarity index 89% rename from include/behavior_tree_core/decorator_negation_node.h rename to include/behavior_tree_core/decorators/negation_node.h index 0a3c5f03c..231a5a9a3 100644 --- a/include/behavior_tree_core/decorator_negation_node.h +++ b/include/behavior_tree_core/decorators/negation_node.h @@ -18,12 +18,12 @@ namespace BT { -class DecoratorNegationNode : public DecoratorNode +class NegationNode : public DecoratorNode { public: - DecoratorNegationNode(const std::string& name); + NegationNode(const std::string& name); - virtual ~DecoratorNegationNode() override = default; + virtual ~NegationNode() override = default; private: virtual BT::NodeStatus tick() override; diff --git a/include/behavior_tree_core/decorator_repeat_node.h b/include/behavior_tree_core/decorators/repeat_node.h similarity index 86% rename from include/behavior_tree_core/decorator_repeat_node.h rename to include/behavior_tree_core/decorators/repeat_node.h index e5bf71760..983afd925 100644 --- a/include/behavior_tree_core/decorator_repeat_node.h +++ b/include/behavior_tree_core/decorators/repeat_node.h @@ -18,15 +18,15 @@ namespace BT { -class DecoratorRepeatNode : public DecoratorNode +class RepeatNode : public DecoratorNode { public: // Constructor - DecoratorRepeatNode(const std::string& name, unsigned int NTries); + RepeatNode(const std::string& name, unsigned int NTries); - DecoratorRepeatNode(const std::string& name, const NodeParameters& params); + RepeatNode(const std::string& name, const NodeParameters& params); - virtual ~DecoratorRepeatNode() override = default; + virtual ~RepeatNode() override = default; static const NodeParameters& requiredNodeParameters() { diff --git a/include/behavior_tree_core/decorator_retry_node.h b/include/behavior_tree_core/decorators/retry_node.h similarity index 87% rename from include/behavior_tree_core/decorator_retry_node.h rename to include/behavior_tree_core/decorators/retry_node.h index f0ec0968c..17642bc78 100644 --- a/include/behavior_tree_core/decorator_retry_node.h +++ b/include/behavior_tree_core/decorators/retry_node.h @@ -18,15 +18,15 @@ namespace BT { -class DecoratorRetryNode : public DecoratorNode +class RetryNode : public DecoratorNode { public: // Constructor - DecoratorRetryNode(const std::string& name, unsigned int NTries); + RetryNode(const std::string& name, unsigned int NTries); - DecoratorRetryNode(const std::string& name, const NodeParameters& params); + RetryNode(const std::string& name, const NodeParameters& params); - virtual ~DecoratorRetryNode() override = default; + virtual ~RetryNode() override = default; static const NodeParameters& requiredNodeParameters() { diff --git a/include/behavior_tree_core/decorator_subtree_node.h b/include/behavior_tree_core/decorators/subtree_node.h similarity index 100% rename from include/behavior_tree_core/decorator_subtree_node.h rename to include/behavior_tree_core/decorators/subtree_node.h diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index ca55fc27d..93b69ebb3 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -22,11 +22,18 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("Sequence"); registerNodeType("SequenceStar"); - registerNodeType("Negation"); - registerNodeType("RetryUntilSuccesful"); - registerNodeType("Repeat"); + registerNodeType("Negation"); + registerNodeType("RetryUntilSuccesful"); + registerNodeType("Repeat"); + + registerNodeType("AlwaysSuccess"); + registerNodeType("AlwaysFailure"); registerNodeType("SubTree"); + + registerNodeType>("BlackboardCheckInt"); + registerNodeType>("BlackboardCheckDouble"); + registerNodeType>("BlackboardCheckString"); } bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID) diff --git a/src/fallback_node.cpp b/src/controls/fallback_node.cpp similarity index 98% rename from src/fallback_node.cpp rename to src/controls/fallback_node.cpp index 2658e8415..d8fc0bb89 100644 --- a/src/fallback_node.cpp +++ b/src/controls/fallback_node.cpp @@ -11,7 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree_core/fallback_node.h" +#include "behavior_tree_core/controls/fallback_node.h" namespace BT { diff --git a/src/fallback_node_with_memory.cpp b/src/controls/fallback_node_with_memory.cpp similarity index 98% rename from src/fallback_node_with_memory.cpp rename to src/controls/fallback_node_with_memory.cpp index 917f69837..e6976273c 100644 --- a/src/fallback_node_with_memory.cpp +++ b/src/controls/fallback_node_with_memory.cpp @@ -11,7 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree_core/fallback_node_with_memory.h" +#include "behavior_tree_core/controls/fallback_node_with_memory.h" namespace BT { diff --git a/src/parallel_node.cpp b/src/controls/parallel_node.cpp similarity index 98% rename from src/parallel_node.cpp rename to src/controls/parallel_node.cpp index 541d6a728..c7302155d 100644 --- a/src/parallel_node.cpp +++ b/src/controls/parallel_node.cpp @@ -11,7 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree_core/parallel_node.h" +#include "behavior_tree_core/controls/parallel_node.h" BT::ParallelNode::ParallelNode(const std::string& name, int threshold_M) : ControlNode::ControlNode(name, NodeParameters()), threshold_M_(threshold_M) diff --git a/src/sequence_node.cpp b/src/controls/sequence_node.cpp similarity index 98% rename from src/sequence_node.cpp rename to src/controls/sequence_node.cpp index 4750e9d97..b915791f4 100644 --- a/src/sequence_node.cpp +++ b/src/controls/sequence_node.cpp @@ -11,7 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree_core/sequence_node.h" +#include "behavior_tree_core/controls/sequence_node.h" BT::SequenceNode::SequenceNode(const std::string& name) : ControlNode::ControlNode(name, NodeParameters()) { diff --git a/src/sequence_node_with_memory.cpp b/src/controls/sequence_node_with_memory.cpp similarity index 98% rename from src/sequence_node_with_memory.cpp rename to src/controls/sequence_node_with_memory.cpp index 09504ed65..60c5f21ab 100644 --- a/src/sequence_node_with_memory.cpp +++ b/src/controls/sequence_node_with_memory.cpp @@ -11,7 +11,7 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree_core/sequence_node_with_memory.h" +#include "behavior_tree_core/controls/sequence_node_with_memory.h" namespace BT { diff --git a/src/decorator_negation_node.cpp b/src/decorators/negation_node.cpp similarity index 90% rename from src/decorator_negation_node.cpp rename to src/decorators/negation_node.cpp index 039719f19..8b329e684 100644 --- a/src/decorator_negation_node.cpp +++ b/src/decorators/negation_node.cpp @@ -11,15 +11,15 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree_core/decorator_negation_node.h" +#include "behavior_tree_core/decorators/negation_node.h" namespace BT { -DecoratorNegationNode::DecoratorNegationNode(const std::string& name) : DecoratorNode(name, NodeParameters()) +NegationNode::NegationNode(const std::string& name) : DecoratorNode(name, NodeParameters()) { } -NodeStatus DecoratorNegationNode::tick() +NodeStatus NegationNode::tick() { setStatus(NodeStatus::RUNNING); diff --git a/src/decorator_repeat_node.cpp b/src/decorators/repeat_node.cpp similarity index 87% rename from src/decorator_repeat_node.cpp rename to src/decorators/repeat_node.cpp index fa32583df..b881fde16 100644 --- a/src/decorator_repeat_node.cpp +++ b/src/decorators/repeat_node.cpp @@ -11,18 +11,18 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree_core/decorator_repeat_node.h" +#include "behavior_tree_core/decorators/repeat_node.h" namespace BT { -constexpr const char* DecoratorRepeatNode::NUM_CYCLES; +constexpr const char* RepeatNode::NUM_CYCLES; -DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, unsigned int NTries) +RepeatNode::RepeatNode(const std::string& name, unsigned int NTries) : DecoratorNode(name, {{NUM_CYCLES, std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) { } -DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, const NodeParameters& params) +RepeatNode::RepeatNode(const std::string& name, const NodeParameters& params) : DecoratorNode(name, params), NTries_(1), TryIndx_(0) { auto param = getParam(NUM_CYCLES); @@ -31,7 +31,7 @@ DecoratorRepeatNode::DecoratorRepeatNode(const std::string& name, const NodePara } } -NodeStatus DecoratorRepeatNode::tick() +NodeStatus RepeatNode::tick() { setStatus(NodeStatus::RUNNING); NodeStatus child_state = child_node_->executeTick(); diff --git a/src/decorator_retry_node.cpp b/src/decorators/retry_node.cpp similarity index 87% rename from src/decorator_retry_node.cpp rename to src/decorators/retry_node.cpp index 1913fadcc..c6345e2c5 100644 --- a/src/decorator_retry_node.cpp +++ b/src/decorators/retry_node.cpp @@ -11,18 +11,18 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree_core/decorator_retry_node.h" +#include "behavior_tree_core/decorators/retry_node.h" namespace BT { -constexpr const char* DecoratorRetryNode::NUM_ATTEMPTS; +constexpr const char* RetryNode::NUM_ATTEMPTS; -DecoratorRetryNode::DecoratorRetryNode(const std::string& name, unsigned int NTries) +RetryNode::RetryNode(const std::string& name, unsigned int NTries) : DecoratorNode(name, {{NUM_ATTEMPTS, std::to_string(NTries)}}), NTries_(NTries), TryIndx_(0) { } -DecoratorRetryNode::DecoratorRetryNode(const std::string& name, const NodeParameters& params) +RetryNode::RetryNode(const std::string& name, const NodeParameters& params) : DecoratorNode(name, params), NTries_(1), TryIndx_(0) { auto param = getParam(NUM_ATTEMPTS); @@ -31,7 +31,7 @@ DecoratorRetryNode::DecoratorRetryNode(const std::string& name, const NodeParame } } -NodeStatus DecoratorRetryNode::tick() +NodeStatus RetryNode::tick() { setStatus(NodeStatus::RUNNING); NodeStatus child_state = child_node_->executeTick(); From 8cddb5837639006bc0faed86d686bba2618b2970 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 14 Sep 2018 12:59:21 +0200 Subject: [PATCH 102/125] Update .travis.yml --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 47a2fe976..eb1b136fc 100644 --- a/.travis.yml +++ b/.travis.yml @@ -22,7 +22,7 @@ matrix: fast_finish: true before_install: - - sudo apt-get update && sudo apt-get --reinstall install -qq build-essential + - sudo apt-get update && sudo apt-get --reinstall install -qq build-essential libzmqpp-dev # GTest: see motivation here https://www.eriksmistad.no/getting-started-with-google-test-on-ubuntu/ - sudo apt-get --reinstall install -qq libgtest-dev cmake - cd /usr/src/gtest From 1782fea67bd2fd343fc1bd5f34277c38f07821c2 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 24 Sep 2018 17:02:34 +0200 Subject: [PATCH 103/125] Update contributors.txt --- contributors.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/contributors.txt b/contributors.txt index dd0a3a854..578b30da4 100644 --- a/contributors.txt +++ b/contributors.txt @@ -1,3 +1,4 @@ +Davide Faconti Michele Colledanchise Rocco Santomo From 36c30eafa946f3fada07f31dbca7376887f055f4 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 25 Sep 2018 16:02:04 +0200 Subject: [PATCH 104/125] fix related to #1 --- examples/crossdoor_example.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/examples/crossdoor_example.cpp b/examples/crossdoor_example.cpp index bc13e4e3d..5b34ae3fe 100644 --- a/examples/crossdoor_example.cpp +++ b/examples/crossdoor_example.cpp @@ -4,7 +4,10 @@ #include "behavior_tree_logger/bt_minitrace_logger.h" #include "behavior_tree_logger/bt_file_logger.h" #include "Blackboard/blackboard_local.h" + +#ifdef ZMQ_FOUND #include "behavior_tree_logger/bt_zmq_publisher.h" +#endif // clang-format off @@ -61,8 +64,10 @@ int main() StdCoutLogger logger_cout(tree.root_node); MinitraceLogger logger_minitrace(tree.root_node, "bt_trace.json"); FileLogger logger_file(tree.root_node, "bt_trace.fbl"); +#ifdef ZMQ_FOUND PublisherZMQ publisher_zmq(tree.root_node); - +#endif + // Keep on ticking until you get either a SUCCESS or FAILURE state NodeStatus status = NodeStatus::RUNNING; while( status == NodeStatus::RUNNING ) From e2b643a5d266ffc144e105f41d2d2d5d8e09d0c1 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 25 Sep 2018 16:07:00 +0200 Subject: [PATCH 105/125] fix related to #1 (compile with catkin) We don't want directory 3rdparty to be visible "outside" this project. For this reason we do not add it to this: catkin_package( INCLUDE_DIRS include ) --- CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 97333d555..6657dbc25 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -25,6 +25,8 @@ if(catkin_FOUND) INCLUDE_DIRS include LIBRARIES behavior_tree_core ) + include_directories(3rdparty) + else(catkin_FOUND) set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) From d0e83dea3027e219e623c4d0b9036ec2224dc5cb Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 25 Sep 2018 17:39:44 +0200 Subject: [PATCH 106/125] big change: support plugins loading --- CMakeLists.txt | 36 +- Doxyfile | 2480 +++++++++++++++++ contributors.txt | 1 - examples/CMakeLists.txt | 38 + examples/crossdoor_example.cpp | 4 +- examples/dummy_nodes.h | 69 - examples/t01_programmatic_tree.cpp | 50 + examples/t02_factory_tree.cpp | 76 + examples/t03_sequence_star.cpp | 153 + ...rial_blackboard.cpp => t04_blackboard.cpp} | 81 +- examples/tutorial_factory_tree.cpp | 45 - examples/tutorial_programmatic_tree.cpp | 40 - examples/tutorial_sequence_star.cpp | 100 - gtest/gtest_factory.cpp | 2 +- include/behavior_tree_core/action_node.h | 12 - include/behavior_tree_core/basic_types.h | 30 +- include/behavior_tree_core/behavior_tree.h | 4 +- include/behavior_tree_core/bt_factory.h | 47 +- .../controls/fallback_node.h | 18 + .../controls/fallback_node_with_memory.h | 19 + .../controls/sequence_node.h | 18 + .../controls/sequence_node_with_memory.h | 16 + .../decorators/always_failure_node.h | 32 +- .../decorators/always_success_node.h | 32 +- include/behavior_tree_core/platform.hpp | 124 + include/behavior_tree_core/shared_library.h | 146 + include/behavior_tree_core/tree_node.h | 1 + .../behavior_tree_logger/abstract_logger.h | 48 +- include/behavior_tree_logger/bt_cout_logger.h | 2 +- include/behavior_tree_logger/bt_file_logger.h | 2 +- .../bt_flatbuffer_helper.h | 8 +- .../bt_minitrace_logger.h | 2 +- .../behavior_tree_logger/bt_zmq_publisher.h | 2 +- sample_nodes/CMakeLists.txt | 14 + .../crossdoor_nodes.cpp | 42 +- sample_nodes/crossdoor_nodes.h | 31 + sample_nodes/dummy_nodes.cpp | 70 + sample_nodes/dummy_nodes.h | 86 + sample_nodes/movebase_node.cpp | 53 + {examples => sample_nodes}/movebase_node.h | 46 +- src/basic_types.cpp | 30 + src/bt_factory.cpp | 41 +- src/loggers/bt_cout_logger.cpp | 4 +- src/loggers/bt_file_logger.cpp | 2 +- src/loggers/bt_minitrace_logger.cpp | 2 +- src/loggers/bt_zmq_publisher.cpp | 2 +- src/shared_library.cpp | 25 + src/shared_library_UNIX.cpp | 108 + src/xml_parsing.cpp | 6 +- tools/bt_plugin_manifest.cpp | 54 + 50 files changed, 3876 insertions(+), 478 deletions(-) create mode 100644 Doxyfile create mode 100644 examples/CMakeLists.txt delete mode 100644 examples/dummy_nodes.h create mode 100644 examples/t01_programmatic_tree.cpp create mode 100644 examples/t02_factory_tree.cpp create mode 100644 examples/t03_sequence_star.cpp rename examples/{tutorial_blackboard.cpp => t04_blackboard.cpp} (68%) delete mode 100644 examples/tutorial_factory_tree.cpp delete mode 100644 examples/tutorial_programmatic_tree.cpp delete mode 100644 examples/tutorial_sequence_star.cpp create mode 100644 include/behavior_tree_core/platform.hpp create mode 100644 include/behavior_tree_core/shared_library.h create mode 100644 sample_nodes/CMakeLists.txt rename examples/crossdoor_dummy_nodes.h => sample_nodes/crossdoor_nodes.cpp (56%) create mode 100644 sample_nodes/crossdoor_nodes.h create mode 100644 sample_nodes/dummy_nodes.cpp create mode 100644 sample_nodes/dummy_nodes.h create mode 100644 sample_nodes/movebase_node.cpp rename {examples => sample_nodes}/movebase_node.h (59%) create mode 100644 src/shared_library.cpp create mode 100644 src/shared_library_UNIX.cpp create mode 100644 tools/bt_plugin_manifest.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 6657dbc25..9fed01d39 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,7 +30,8 @@ if(catkin_FOUND) else(catkin_FOUND) set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) - set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) + set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) + set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) find_package(GTest) include_directories(${GTEST_INCLUDE_DIRS}) @@ -54,6 +55,8 @@ set(BT_Source src/bt_factory.cpp src/behavior_tree.cpp src/xml_parsing.cpp + src/shared_library.cpp + src/shared_library_UNIX.cpp src/decorators/negation_node.cpp src/decorators/repeat_node.cpp @@ -75,7 +78,7 @@ set(BT_Source ) include_directories(include 3rdparty/) -set(BEHAVIOR_TRE_LIBRARIES behavior_tree_core) +set(BEHAVIOR_TREE_LIBRARIES behavior_tree_core) find_package(ZMQ) @@ -84,7 +87,7 @@ if( ZMQ_FOUND ) add_definitions( -DZMQ_FOUND ) set(BT_Source ${BT_Source} src/loggers/bt_zmq_publisher.cpp ) - set(BEHAVIOR_TRE_LIBRARIES behavior_tree_core zmq) + set(BEHAVIOR_TREE_LIBRARIES behavior_tree_core zmq) else() message(WARNING "ZeroMQ NOT found. Skipping the build of [PublisherZMQ] and [bt_recorder].") endif() @@ -93,6 +96,8 @@ endif() # COMPILING LIBRARY ###################################################### add_library(behavior_tree_core STATIC ${BT_Source} ) +target_compile_options(behavior_tree_core PRIVATE "-fPIC") +target_link_libraries(behavior_tree_core dl) ###################################################### @@ -120,7 +125,8 @@ elseif(GTEST_FOUND) target_link_libraries(behavior_tree_core_test behavior_tree_core ${GTEST_LIBRARIES} - ${GTEST_MAIN_LIBRARIES} ) + ${GTEST_MAIN_LIBRARIES} + crossdoor_nodes) endif() @@ -129,28 +135,18 @@ endif() ###################################################### add_executable(bt_log_cat tools/bt_log_cat.cpp ) -target_link_libraries(bt_log_cat behavior_tree_core ) +target_link_libraries(bt_log_cat ${BEHAVIOR_TREE_LIBRARIES} ) if( ZMQ_FOUND ) add_executable(bt_recorder tools/bt_recorder.cpp ) - target_link_libraries(bt_recorder ${BEHAVIOR_TRE_LIBRARIES} ) + target_link_libraries(bt_recorder ${BEHAVIOR_TREE_LIBRARIES} ) endif() -function(BuildExample filename) - add_executable(${filename} examples/${filename}.cpp ) - target_link_libraries(${filename} ${BEHAVIOR_TRE_LIBRARIES} ) -endfunction() +add_executable(bt_plugin_manifest tools/bt_plugin_manifest.cpp ) +target_link_libraries(bt_plugin_manifest ${BEHAVIOR_TREE_LIBRARIES} ) -BuildExample(tutorial_programmatic_tree) -BuildExample(tutorial_factory_tree) -BuildExample(tutorial_sequence_star) -BuildExample(tutorial_blackboard) -BuildExample(crossdoor_example) - -###################################################### -# INSTALLATION OF LIBRARY AND EXECUTABLE -###################################################### +add_subdirectory(sample_nodes) +add_subdirectory(examples) -#TODO diff --git a/Doxyfile b/Doxyfile new file mode 100644 index 000000000..8f51f6b83 --- /dev/null +++ b/Doxyfile @@ -0,0 +1,2480 @@ +# Doxyfile 1.8.11 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project. +# +# All text after a double hash (##) is considered a comment and is placed in +# front of the TAG it is preceding. +# +# All text after a single hash (#) is considered a comment and will be ignored. +# The format is: +# TAG = value [value, ...] +# For lists, items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (\" \"). + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all text +# before the first occurrence of this tag. Doxygen uses libiconv (or the iconv +# built into libc) for the transcoding. See http://www.gnu.org/software/libiconv +# for the list of possible encodings. +# The default value is: UTF-8. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by +# double-quotes, unless you are using Doxywizard) that should identify the +# project for which the documentation is generated. This name is used in the +# title of most generated pages and in a few other places. +# The default value is: My Project. + +PROJECT_NAME = BehaviorTree + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. This +# could be handy for archiving the generated documentation or if some version +# control system is used. + +PROJECT_NUMBER = + +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer a +# quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = "Core Library to create and execute Behavior Trees" + +# With the PROJECT_LOGO tag one can specify a logo or an icon that is included +# in the documentation. The maximum height of the logo should not exceed 55 +# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy +# the logo to the output directory. + +PROJECT_LOGO = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path +# into which the generated documentation will be written. If a relative path is +# entered, it will be relative to the location where doxygen was started. If +# left blank the current directory will be used. + +OUTPUT_DIRECTORY = /home/davide.faconti/ws_behavior_tree/src/Behavior-Tree/doc + +# If the CREATE_SUBDIRS tag is set to YES then doxygen will create 4096 sub- +# directories (in 2 levels) under the output directory of each output format and +# will distribute the generated files over these directories. Enabling this +# option can be useful when feeding doxygen a huge amount of source files, where +# putting all generated files in the same directory would otherwise causes +# performance problems for the file system. +# The default value is: NO. + +CREATE_SUBDIRS = YES + +# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII +# characters to appear in the names of generated files. If set to NO, non-ASCII +# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode +# U+3044. +# The default value is: NO. + +ALLOW_UNICODE_NAMES = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese, +# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States), +# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian, +# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages), +# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian, +# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian, +# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish, +# Ukrainian and Vietnamese. +# The default value is: English. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member +# descriptions after the members that are listed in the file and class +# documentation (similar to Javadoc). Set to NO to disable this. +# The default value is: YES. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES, doxygen will prepend the brief +# description of a member or function before the detailed description +# +# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. +# The default value is: YES. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator that is +# used to form the text in various listings. Each string in this list, if found +# as the leading text of the brief description, will be stripped from the text +# and the result, after processing the whole list, is used as the annotated +# text. Otherwise, the brief description is used as-is. If left blank, the +# following values are used ($name is automatically replaced with the name of +# the entity):The $name class, The $name widget, The $name file, is, provides, +# specifies, contains, represents, a, an and the. + +ABBREVIATE_BRIEF = "The $name class" \ + "The $name widget" \ + "The $name file" \ + is \ + provides \ + specifies \ + contains \ + represents \ + a \ + an \ + the + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# doxygen will generate a detailed section even if there is only a brief +# description. +# The default value is: NO. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. +# The default value is: NO. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES, doxygen will prepend the full path +# before files name in the file list and in the header files. If set to NO the +# shortest path that makes the file name unique will be used +# The default value is: YES. + +FULL_PATH_NAMES = YES + +# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. +# Stripping is only done if one of the specified strings matches the left-hand +# part of the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the path to +# strip. +# +# Note that you can specify absolute paths here, but also relative paths, which +# will be relative from the directory where doxygen is started. +# This tag requires that the tag FULL_PATH_NAMES is set to YES. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the +# path mentioned in the documentation of a class, which tells the reader which +# header file to include in order to use a class. If left blank only the name of +# the header file containing the class definition is used. Otherwise one should +# specify the list of include paths that are normally passed to the compiler +# using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but +# less readable) file names. This can be useful is your file systems doesn't +# support long names like on DOS, Mac, or CD-ROM. +# The default value is: NO. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the +# first line (until the first dot) of a Javadoc-style comment as the brief +# description. If set to NO, the Javadoc-style will behave just like regular Qt- +# style comments (thus requiring an explicit @brief command for a brief +# description.) +# The default value is: NO. + +JAVADOC_AUTOBRIEF = NO + +# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first +# line (until the first dot) of a Qt-style comment as the brief description. If +# set to NO, the Qt-style will behave just like regular Qt-style comments (thus +# requiring an explicit \brief command for a brief description.) +# The default value is: NO. + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a +# multi-line C++ special comment block (i.e. a block of //! or /// comments) as +# a brief description. This used to be the default behavior. The new default is +# to treat a multi-line C++ comment block as a detailed description. Set this +# tag to YES if you prefer the old behavior instead. +# +# Note that setting this tag to YES also means that rational rose comments are +# not recognized any more. +# The default value is: NO. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the +# documentation from any documented member that it re-implements. +# The default value is: YES. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES then doxygen will produce a new +# page for each member. If set to NO, the documentation of a member will be part +# of the file/class/namespace that contains it. +# The default value is: NO. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen +# uses this value to replace tabs by spaces in code fragments. +# Minimum value: 1, maximum value: 16, default value: 4. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that act as commands in +# the documentation. An alias has the form: +# name=value +# For example adding +# "sideeffect=@par Side Effects:\n" +# will allow you to put the command \sideeffect (or @sideeffect) in the +# documentation, which will result in a user-defined paragraph with heading +# "Side Effects:". You can put \n's in the value part of an alias to insert +# newlines. + +ALIASES = + +# This tag can be used to specify a number of word-keyword mappings (TCL only). +# A mapping has the form "name=value". For example adding "class=itcl::class" +# will allow you to use the command class in the itcl::class meaning. + +TCL_SUBST = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources +# only. Doxygen will then generate output that is more tailored for C. For +# instance, some of the names that are used will be different. The list of all +# members will be omitted, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or +# Python sources only. Doxygen will then generate output that is more tailored +# for that language. For instance, namespaces will be presented as packages, +# qualified scopes will look different, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources. Doxygen will then generate output that is tailored for Fortran. +# The default value is: NO. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for VHDL. +# The default value is: NO. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, and +# language is one of the parsers supported by doxygen: IDL, Java, Javascript, +# C#, C, C++, D, PHP, Objective-C, Python, Fortran (fixed format Fortran: +# FortranFixed, free formatted Fortran: FortranFree, unknown formatted Fortran: +# Fortran. In the later case the parser tries to guess whether the code is fixed +# or free formatted code, this is the default for Fortran type files), VHDL. For +# instance to make doxygen treat .inc files as Fortran files (default is PHP), +# and .f files as C (default is Fortran), use: inc=Fortran f=C. +# +# Note: For files without extension you can use no_extension as a placeholder. +# +# Note that for custom extensions you also need to set FILE_PATTERNS otherwise +# the files are not read by doxygen. + +EXTENSION_MAPPING = + +# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments +# according to the Markdown format, which allows for more readable +# documentation. See http://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you can +# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in +# case of backward compatibilities issues. +# The default value is: YES. + +MARKDOWN_SUPPORT = YES + +# When enabled doxygen tries to link words that correspond to documented +# classes, or namespaces to their corresponding documentation. Such a link can +# be prevented in individual cases by putting a % sign in front of the word or +# globally by setting AUTOLINK_SUPPORT to NO. +# The default value is: YES. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should set this +# tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); +# versus func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. +# The default value is: NO. + +BUILTIN_STL_SUPPORT = YES + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. +# The default value is: NO. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: +# http://www.riverbankcomputing.co.uk/software/sip/intro) sources only. Doxygen +# will parse them like normal C++ but will assume all classes use public instead +# of private inheritance when no explicit protection keyword is present. +# The default value is: NO. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate +# getter and setter methods for a property. Setting this option to YES will make +# doxygen to replace the get and set methods by a property in the documentation. +# This will only work if the methods are indeed getting or setting a simple +# type. If this is not the case, or you want to show the methods anyway, you +# should set this option to NO. +# The default value is: YES. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. +# The default value is: NO. + +DISTRIBUTE_GROUP_DOC = NO + +# If one adds a struct or class to a group and this option is enabled, then also +# any nested class or struct is added to the same group. By default this option +# is disabled and one has to add nested compounds explicitly via \ingroup. +# The default value is: NO. + +GROUP_NESTED_COMPOUNDS = NO + +# Set the SUBGROUPING tag to YES to allow class member groups of the same type +# (for instance a group of public functions) to be put as a subgroup of that +# type (e.g. under the Public Functions section). Set it to NO to prevent +# subgrouping. Alternatively, this can be done per class using the +# \nosubgrouping command. +# The default value is: YES. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions +# are shown inside the group in which they are included (e.g. using \ingroup) +# instead of on a separate page (for HTML and Man pages) or section (for LaTeX +# and RTF). +# +# Note that this feature does not work in combination with +# SEPARATE_MEMBER_PAGES. +# The default value is: NO. + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions +# with only public data fields or simple typedef fields will be shown inline in +# the documentation of the scope in which they are defined (i.e. file, +# namespace, or group documentation), provided this scope is documented. If set +# to NO, structs, classes, and unions are shown on a separate page (for HTML and +# Man pages) or section (for LaTeX and RTF). +# The default value is: NO. + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or +# enum is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically be +# useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. +# The default value is: NO. + +TYPEDEF_HIDES_STRUCT = NO + +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can be +# an expensive process and often the same symbol appears multiple times in the +# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small +# doxygen will become slower. If the cache is too large, memory is wasted. The +# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range +# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 +# symbols. At the end of a run doxygen will report the cache usage and suggest +# the optimal cache size from a speed point of view. +# Minimum value: 0, maximum value: 9, default value: 0. + +LOOKUP_CACHE_SIZE = 0 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES, doxygen will assume all entities in +# documentation are documented, even if no documentation was available. Private +# class members and static file members will be hidden unless the +# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. +# Note: This will also disable the warnings about undocumented members that are +# normally produced when WARNINGS is set to YES. +# The default value is: NO. + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will +# be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal +# scope will be included in the documentation. +# The default value is: NO. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be +# included in the documentation. +# The default value is: NO. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined +# locally in source files will be included in the documentation. If set to NO, +# only classes defined in header files are included. Does not have any effect +# for Java sources. +# The default value is: YES. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. If set to YES, local methods, +# which are defined in the implementation section but not in the interface are +# included in the documentation. If set to NO, only methods in the interface are +# included. +# The default value is: NO. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base name of +# the file that contains the anonymous namespace. By default anonymous namespace +# are hidden. +# The default value is: NO. + +EXTRACT_ANON_NSPACES = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all +# undocumented members inside documented classes or files. If set to NO these +# members will be included in the various overviews, but no documentation +# section is generated. This option has no effect if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. If set +# to NO, these classes will be included in the various overviews. This option +# has no effect if EXTRACT_ALL is enabled. +# The default value is: NO. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend +# (class|struct|union) declarations. If set to NO, these declarations will be +# included in the documentation. +# The default value is: NO. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any +# documentation blocks found inside the body of a function. If set to NO, these +# blocks will be appended to the function's detailed documentation block. +# The default value is: NO. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation that is typed after a +# \internal command is included. If the tag is set to NO then the documentation +# will be excluded. Set it to YES to include the internal documentation. +# The default value is: NO. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file +# names in lower-case letters. If set to YES, upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. +# The default value is: system dependent. + +CASE_SENSE_NAMES = NO + +# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with +# their full class and namespace scopes in the documentation. If set to YES, the +# scope will be hidden. +# The default value is: NO. + +HIDE_SCOPE_NAMES = NO + +# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will +# append additional text to a page's title, such as Class Reference. If set to +# YES the compound reference will be hidden. +# The default value is: NO. + +HIDE_COMPOUND_REFERENCE= NO + +# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of +# the files that are included by a file in the documentation of that file. +# The default value is: YES. + +SHOW_INCLUDE_FILES = YES + +# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each +# grouped member an include statement to the documentation, telling the reader +# which file to include in order to use the member. +# The default value is: NO. + +SHOW_GROUPED_MEMB_INC = NO + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include +# files with double quotes in the documentation rather than with sharp brackets. +# The default value is: NO. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the +# documentation for inline members. +# The default value is: YES. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the +# (detailed) documentation of file and class members alphabetically by member +# name. If set to NO, the members will appear in declaration order. +# The default value is: YES. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief +# descriptions of file, namespace and class members alphabetically by member +# name. If set to NO, the members will appear in declaration order. Note that +# this will also influence the order of the classes in the class list. +# The default value is: NO. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the +# (brief and detailed) documentation of class members so that constructors and +# destructors are listed first. If set to NO the constructors will appear in the +# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. +# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief +# member documentation. +# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting +# detailed member documentation. +# The default value is: NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy +# of group names into alphabetical order. If set to NO the group names will +# appear in their defined order. +# The default value is: NO. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by +# fully-qualified names, including namespaces. If set to NO, the class list will +# be sorted only by class name, not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the alphabetical +# list. +# The default value is: NO. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper +# type resolution of all parameters of a function it will reject a match between +# the prototype and the implementation of a member function even if there is +# only one candidate or it is obvious which candidate to choose by doing a +# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still +# accept a match between prototype and implementation in such cases. +# The default value is: NO. + +STRICT_PROTO_MATCHING = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or disable (NO) the todo +# list. This list is created by putting \todo commands in the documentation. +# The default value is: YES. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or disable (NO) the test +# list. This list is created by putting \test commands in the documentation. +# The default value is: YES. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or disable (NO) the bug +# list. This list is created by putting \bug commands in the documentation. +# The default value is: YES. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or disable (NO) +# the deprecated list. This list is created by putting \deprecated commands in +# the documentation. +# The default value is: YES. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional documentation +# sections, marked by \if ... \endif and \cond +# ... \endcond blocks. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the +# initial value of a variable or macro / define can have for it to appear in the +# documentation. If the initializer consists of more lines than specified here +# it will be hidden. Use a value of 0 to hide initializers completely. The +# appearance of the value of individual variables and macros / defines can be +# controlled using \showinitializer or \hideinitializer command in the +# documentation regardless of this setting. +# Minimum value: 0, maximum value: 10000, default value: 30. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at +# the bottom of the documentation of classes and structs. If set to YES, the +# list will mention the files that were used to generate the documentation. +# The default value is: YES. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This +# will remove the Files entry from the Quick Index and from the Folder Tree View +# (if specified). +# The default value is: YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces +# page. This will remove the Namespaces entry from the Quick Index and from the +# Folder Tree View (if specified). +# The default value is: YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command command input-file, where command is the value of the +# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided +# by doxygen. Whatever the program writes to standard output is used as the file +# version. For an example see the documentation. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. You can +# optionally specify a file name after the option, if omitted DoxygenLayout.xml +# will be used as the name of the layout file. +# +# Note that if you run doxygen from a directory containing a file called +# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE +# tag is left empty. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files containing +# the reference definitions. This must be a list of .bib files. The .bib +# extension is automatically appended if omitted. This requires the bibtex tool +# to be installed. See also http://en.wikipedia.org/wiki/BibTeX for more info. +# For LaTeX the style of the bibliography can be controlled using +# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the +# search path. See also \cite for info how to create references. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# Configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated to +# standard output by doxygen. If QUIET is set to YES this implies that the +# messages are off. +# The default value is: NO. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES +# this implies that the warnings are on. +# +# Tip: Turn warnings on while writing the documentation. +# The default value is: YES. + +WARNINGS = YES + +# If the WARN_IF_UNDOCUMENTED tag is set to YES then doxygen will generate +# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag +# will automatically be disabled. +# The default value is: YES. + +WARN_IF_UNDOCUMENTED = YES + +# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some parameters +# in a documented function, or documenting parameters that don't exist or using +# markup commands wrongly. +# The default value is: YES. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that +# are documented, but have no documentation for their parameters or return +# value. If set to NO, doxygen will only warn about wrong or incomplete +# parameter documentation, but not about the absence of documentation. +# The default value is: NO. + +WARN_NO_PARAMDOC = NO + +# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when +# a warning is encountered. +# The default value is: NO. + +WARN_AS_ERROR = NO + +# The WARN_FORMAT tag determines the format of the warning messages that doxygen +# can produce. The string should contain the $file, $line, and $text tags, which +# will be replaced by the file and line number from which the warning originated +# and the warning text. Optionally the format may contain $version, which will +# be replaced by the version of the file (if it could be obtained via +# FILE_VERSION_FILTER) +# The default value is: $file:$line: $text. + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning and error +# messages should be written. If left blank the output is written to standard +# error (stderr). + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# Configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag is used to specify the files and/or directories that contain +# documented source files. You may enter file names like myfile.cpp or +# directories like /usr/src/myproject. Separate the files or directories with +# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING +# Note: If this tag is empty the current directory is searched. + +INPUT = /home/davide.faconti/ws_behavior_tree/src/Behavior-Tree/include + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses +# libiconv (or the iconv built into libc) for the transcoding. See the libiconv +# documentation (see: http://www.gnu.org/software/libiconv) for the list of +# possible encodings. +# The default value is: UTF-8. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and +# *.h) to filter out the source-files in the directories. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# read by doxygen. +# +# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, +# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, +# *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, +# *.m, *.markdown, *.md, *.mm, *.dox, *.py, *.pyw, *.f90, *.f, *.for, *.tcl, +# *.vhd, *.vhdl, *.ucf, *.qsf, *.as and *.js. + +FILE_PATTERNS = *.c \ + *.cc \ + *.cxx \ + *.cpp \ + *.c++ \ + *.java \ + *.ii \ + *.ixx \ + *.ipp \ + *.i++ \ + *.inl \ + *.idl \ + *.ddl \ + *.odl \ + *.h \ + *.hh \ + *.hxx \ + *.hpp \ + *.h++ \ + *.cs \ + *.d \ + *.php \ + *.php4 \ + *.php5 \ + *.phtml \ + *.inc \ + *.m \ + *.markdown \ + *.md \ + *.mm \ + *.dox \ + *.py \ + *.pyw \ + *.f90 \ + *.f \ + *.for \ + *.tcl \ + *.vhd \ + *.vhdl \ + *.ucf \ + *.qsf \ + *.as \ + *.js + +# The RECURSIVE tag can be used to specify whether or not subdirectories should +# be searched for input files as well. +# The default value is: NO. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. +# +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = /home/davide.faconti/ws_behavior_tree/src/Behavior-Tree/3rdparty \ + /home/davide.faconti/ws_behavior_tree/src/Behavior-Tree/gtest + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. +# The default value is: NO. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test +# +# Note that the wildcards are matched against the file with absolute path, so to +# exclude all test directories use the pattern */test/* + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or directories +# that contain example code fragments that are included (see the \include +# command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and +# *.h) to filter out the source-files in the directories. If left blank all +# files are included. + +EXAMPLE_PATTERNS = * + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude commands +# irrespective of the value of the RECURSIVE tag. +# The default value is: NO. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or directories +# that contain images that are to be included in the documentation (see the +# \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command: +# +# +# +# where is the value of the INPUT_FILTER tag, and is the +# name of an input file. Doxygen will then use the output that the filter +# program writes to standard output. If FILTER_PATTERNS is specified, this tag +# will be ignored. +# +# Note that the filter must not add or remove lines; it is applied before the +# code is scanned, but not when the output code is generated. If lines are added +# or removed, the anchors will not be placed correctly. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: pattern=filter +# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how +# filters are used. If the FILTER_PATTERNS tag is empty or if none of the +# patterns match the file name, INPUT_FILTER is applied. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will also be used to filter the input files that are used for +# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). +# The default value is: NO. + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and +# it is also possible to disable source filtering for a specific pattern using +# *.ext= (so without naming a filter). +# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. + +FILTER_SOURCE_PATTERNS = + +# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that +# is part of the input, its contents will be placed on the main page +# (index.html). This can be useful if you have a project on for instance GitHub +# and want to reuse the introduction page also for the doxygen output. + +USE_MDFILE_AS_MAINPAGE = + +#--------------------------------------------------------------------------- +# Configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will be +# generated. Documented entities will be cross-referenced with these sources. +# +# Note: To get rid of all source code in the generated output, make sure that +# also VERBATIM_HEADERS is set to NO. +# The default value is: NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body of functions, +# classes and enums directly into the documentation. +# The default value is: NO. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any +# special comment blocks from generated source code fragments. Normal C, C++ and +# Fortran comments will always remain visible. +# The default value is: YES. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES then for each documented +# function all documented functions referencing it will be listed. +# The default value is: NO. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES then for each documented function +# all documented entities called/used by that function will be listed. +# The default value is: NO. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set +# to YES then the hyperlinks from functions in REFERENCES_RELATION and +# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will +# link to the documentation. +# The default value is: YES. + +REFERENCES_LINK_SOURCE = YES + +# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the +# source code will show a tooltip with additional information such as prototype, +# brief description and links to the definition and documentation. Since this +# will make the HTML file larger and loading of large files a bit slower, you +# can opt to disable this feature. +# The default value is: YES. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +SOURCE_TOOLTIPS = YES + +# If the USE_HTAGS tag is set to YES then the references to source code will +# point to the HTML generated by the htags(1) tool instead of doxygen built-in +# source browser. The htags tool is part of GNU's global source tagging system +# (see http://www.gnu.org/software/global/global.html). You will need version +# 4.8.6 or higher. +# +# To use it do the following: +# - Install the latest version of global +# - Enable SOURCE_BROWSER and USE_HTAGS in the config file +# - Make sure the INPUT points to the root of the source tree +# - Run doxygen as normal +# +# Doxygen will invoke htags (and that will in turn invoke gtags), so these +# tools must be available from the command line (i.e. in the search path). +# +# The result: instead of the source browser generated by doxygen, the links to +# source code will now point to the output of htags. +# The default value is: NO. +# This tag requires that the tag SOURCE_BROWSER is set to YES. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a +# verbatim copy of the header file for each class for which an include is +# specified. Set to NO to disable this. +# See also: Section \class. +# The default value is: YES. + +VERBATIM_HEADERS = YES + +# If the CLANG_ASSISTED_PARSING tag is set to YES then doxygen will use the +# clang parser (see: http://clang.llvm.org/) for more accurate parsing at the +# cost of reduced performance. This can be particularly helpful with template +# rich C++ code for which doxygen's built-in parser lacks the necessary type +# information. +# Note: The availability of this option depends on whether or not doxygen was +# generated with the -Duse-libclang=ON option for CMake. +# The default value is: NO. + +CLANG_ASSISTED_PARSING = YES + +# If clang assisted parsing is enabled you can provide the compiler with command +# line options that you would normally use when invoking the compiler. Note that +# the include paths will already be set by doxygen for the files and directories +# specified with INPUT and INCLUDE_PATH. +# This tag requires that the tag CLANG_ASSISTED_PARSING is set to YES. + +CLANG_OPTIONS = + +#--------------------------------------------------------------------------- +# Configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all +# compounds will be generated. Enable this if the project contains a lot of +# classes, structs, unions or interfaces. +# The default value is: YES. + +ALPHABETICAL_INDEX = YES + +# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in +# which the alphabetical index list will be split. +# Minimum value: 1, maximum value: 20, default value: 5. +# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all classes will +# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag +# can be used to specify a prefix (or a list of prefixes) that should be ignored +# while generating the index headers. +# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output +# The default value is: YES. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a +# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of +# it. +# The default directory is: html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each +# generated HTML page (for example: .htm, .php, .asp). +# The default value is: .html. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a user-defined HTML header file for +# each generated HTML page. If the tag is left blank doxygen will generate a +# standard header. +# +# To get valid HTML the header file that includes any scripts and style sheets +# that doxygen needs, which is dependent on the configuration options used (e.g. +# the setting GENERATE_TREEVIEW). It is highly recommended to start with a +# default header using +# doxygen -w html new_header.html new_footer.html new_stylesheet.css +# YourConfigFile +# and then modify the file new_header.html. See also section "Doxygen usage" +# for information on how to generate the default header that doxygen normally +# uses. +# Note: The header is subject to change so you typically have to regenerate the +# default header when upgrading to a newer version of doxygen. For a description +# of the possible markers and block names see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each +# generated HTML page. If the tag is left blank doxygen will generate a standard +# footer. See HTML_HEADER for more information on how to generate a default +# footer and what special commands can be used inside the footer. See also +# section "Doxygen usage" for information on how to generate the default footer +# that doxygen normally uses. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style +# sheet that is used by each HTML page. It can be used to fine-tune the look of +# the HTML output. If left blank doxygen will generate a default style sheet. +# See also section "Doxygen usage" for information on how to generate the style +# sheet that doxygen normally uses. +# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as +# it is more robust and this tag (HTML_STYLESHEET) will in the future become +# obsolete. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_STYLESHEET = + +# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined +# cascading style sheets that are included after the standard style sheets +# created by doxygen. Using this option one can overrule certain style aspects. +# This is preferred over using HTML_STYLESHEET since it does not replace the +# standard style sheet and is therefore more robust against future updates. +# Doxygen will copy the style sheet files to the output directory. +# Note: The order of the extra style sheet files is of importance (e.g. the last +# style sheet in the list overrules the setting of the previous ones in the +# list). For an example see the documentation. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_STYLESHEET = + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that the +# files will be copied as-is; there are no commands or markers available. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen +# will adjust the colors in the style sheet and background images according to +# this color. Hue is specified as an angle on a colorwheel, see +# http://en.wikipedia.org/wiki/Hue for more information. For instance the value +# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 +# purple, and 360 is red again. +# Minimum value: 0, maximum value: 359, default value: 220. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors +# in the HTML output. For a value of 0 the output will use grayscales only. A +# value of 255 will produce the most vivid colors. +# Minimum value: 0, maximum value: 255, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the +# luminance component of the colors in the HTML output. Values below 100 +# gradually make the output lighter, whereas values above 100 make the output +# darker. The value divided by 100 is the actual gamma applied, so 80 represents +# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not +# change the gamma. +# Minimum value: 40, maximum value: 240, default value: 80. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting this +# to YES can help to show when doxygen was last run and thus if the +# documentation is up to date. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_TIMESTAMP = NO + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries +# shown in the various tree structured indices initially; the user can expand +# and collapse entries dynamically later on. Doxygen will expand the tree to +# such a level that at most the specified number of entries are visible (unless +# a fully collapsed tree already exceeds this amount). So setting the number of +# entries 1 will produce a full collapsed tree by default. 0 is a special value +# representing an infinite number of entries and will result in a full expanded +# tree by default. +# Minimum value: 0, maximum value: 9999, default value: 100. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files will be +# generated that can be used as input for Apple's Xcode 3 integrated development +# environment (see: http://developer.apple.com/tools/xcode/), introduced with +# OSX 10.5 (Leopard). To create a documentation set, doxygen will generate a +# Makefile in the HTML output directory. Running make will produce the docset in +# that directory and running make install will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at +# startup. See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html +# for more information. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_DOCSET = NO + +# This tag determines the name of the docset feed. A documentation feed provides +# an umbrella under which multiple documentation sets from a single provider +# (such as a company or product suite) can be grouped. +# The default value is: Doxygen generated docs. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# This tag specifies a string that should uniquely identify the documentation +# set bundle. This should be a reverse domain-name style string, e.g. +# com.mycompany.MyDocSet. Doxygen will append .docset to the name. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify +# the documentation publisher. This should be a reverse domain-name style +# string, e.g. com.mycompany.MyDocSet.documentation. +# The default value is: org.doxygen.Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. +# The default value is: Publisher. +# This tag requires that the tag GENERATE_DOCSET is set to YES. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three +# additional HTML index files: index.hhp, index.hhc, and index.hhk. The +# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop +# (see: http://www.microsoft.com/en-us/download/details.aspx?id=21138) on +# Windows. +# +# The HTML Help Workshop contains a compiler that can convert all HTML output +# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML +# files are now used as the Windows 98 help format, and will replace the old +# Windows help format (.hlp) on all Windows platforms in the future. Compressed +# HTML files also contain an index, a table of contents, and you can search for +# words in the documentation. The HTML workshop also contains a viewer for +# compressed HTML files. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_HTMLHELP = NO + +# The CHM_FILE tag can be used to specify the file name of the resulting .chm +# file. You can add a path in front of the file if the result should not be +# written to the html output directory. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_FILE = + +# The HHC_LOCATION tag can be used to specify the location (absolute path +# including file name) of the HTML help compiler (hhc.exe). If non-empty, +# doxygen will try to run the HTML help compiler on the generated index.hhp. +# The file has to be specified with full path. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +HHC_LOCATION = + +# The GENERATE_CHI flag controls if a separate .chi index file is generated +# (YES) or that it should be included in the master .chm file (NO). +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +GENERATE_CHI = NO + +# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc) +# and project file content. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +CHM_INDEX_ENCODING = + +# The BINARY_TOC flag controls whether a binary table of contents is generated +# (YES) or a normal table of contents (NO) in the .chm file. Furthermore it +# enables the Previous and Next buttons. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members to +# the table of contents of the HTML help documentation and to the tree view. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTMLHELP is set to YES. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that +# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help +# (.qch) of the generated HTML documentation. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify +# the file name of the resulting .qch file. The path specified is relative to +# the HTML output folder. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help +# Project output. For more information please see Qt Help Project / Namespace +# (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#namespace). +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt +# Help Project output. For more information please see Qt Help Project / Virtual +# Folders (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#virtual- +# folders). +# The default value is: doc. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_VIRTUAL_FOLDER = doc + +# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom +# filter to add. For more information please see Qt Help Project / Custom +# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- +# filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see Qt Help Project / Custom +# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- +# filters). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's filter section matches. Qt Help Project / Filter Attributes (see: +# http://qt-project.org/doc/qt-4.8/qthelpproject.html#filter-attributes). +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHP_SECT_FILTER_ATTRS = + +# The QHG_LOCATION tag can be used to specify the location of Qt's +# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the +# generated .qhp file. +# This tag requires that the tag GENERATE_QHP is set to YES. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be +# generated, together with the HTML files, they form an Eclipse help plugin. To +# install this plugin and make it available under the help contents menu in +# Eclipse, the contents of the directory containing the HTML and XML files needs +# to be copied into the plugins directory of eclipse. The name of the directory +# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. +# After copying Eclipse needs to be restarted before the help appears. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the Eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have this +# name. Each documentation set should have its own identifier. +# The default value is: org.doxygen.Project. +# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# If you want full control over the layout of the generated HTML pages it might +# be necessary to disable the index and replace it with your own. The +# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top +# of each HTML page. A value of NO enables the index and the value YES disables +# it. Since the tabs in the index contain the same information as the navigation +# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +DISABLE_INDEX = NO + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. If the tag +# value is set to YES, a side panel will be generated containing a tree-like +# index structure (just like the one that is generated for HTML Help). For this +# to work a browser that supports JavaScript, DHTML, CSS and frames is required +# (i.e. any modern browser). Windows users are probably better off using the +# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can +# further fine-tune the look of the index. As an example, the default style +# sheet generated by doxygen has an example that shows how to put an image at +# the root of the tree instead of the PROJECT_NAME. Since the tree basically has +# the same information as the tab index, you could consider setting +# DISABLE_INDEX to YES when enabling this option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +GENERATE_TREEVIEW = YES + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that +# doxygen will group on one line in the generated HTML documentation. +# +# Note that a value of 0 will completely suppress the enum values from appearing +# in the overview section. +# Minimum value: 0, maximum value: 20, default value: 4. +# This tag requires that the tag GENERATE_HTML is set to YES. + +ENUM_VALUES_PER_LINE = 4 + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used +# to set the initial width (in pixels) of the frame in which the tree is shown. +# Minimum value: 0, maximum value: 1500, default value: 250. +# This tag requires that the tag GENERATE_HTML is set to YES. + +TREEVIEW_WIDTH = 250 + +# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to +# external symbols imported via tag files in a separate window. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +EXT_LINKS_IN_WINDOW = NO + +# Use this tag to change the font size of LaTeX formulas included as images in +# the HTML documentation. When you change the font size after a successful +# doxygen run you need to manually remove any form_*.png images from the HTML +# output directory to force them to be regenerated. +# Minimum value: 8, maximum value: 50, default value: 10. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_FONTSIZE = 10 + +# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# generated for formulas are transparent PNGs. Transparent PNGs are not +# supported properly for IE 6.0, but are supported on all modern browsers. +# +# Note that when changing this option you need to delete any form_*.png files in +# the HTML output directory before the changes have effect. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +FORMULA_TRANSPARENT = YES + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see +# http://www.mathjax.org) which uses client side Javascript for the rendering +# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX +# installed or if you want to formulas look prettier in the HTML output. When +# enabled you may also need to install MathJax separately and configure the path +# to it using the MATHJAX_RELPATH option. +# The default value is: NO. +# This tag requires that the tag GENERATE_HTML is set to YES. + +USE_MATHJAX = NO + +# When MathJax is enabled you can set the default output format to be used for +# the MathJax output. See the MathJax site (see: +# http://docs.mathjax.org/en/latest/output.html) for more details. +# Possible values are: HTML-CSS (which is slower, but has the best +# compatibility), NativeMML (i.e. MathML) and SVG. +# The default value is: HTML-CSS. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_FORMAT = HTML-CSS + +# When MathJax is enabled you need to specify the location relative to the HTML +# output directory using the MATHJAX_RELPATH option. The destination directory +# should contain the MathJax.js script. For instance, if the mathjax directory +# is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax +# Content Delivery Network so you can quickly see the result without installing +# MathJax. However, it is strongly recommended to install a local copy of +# MathJax from http://www.mathjax.org before deployment. +# The default value is: http://cdn.mathjax.org/mathjax/latest. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest + +# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax +# extension names that should be enabled during MathJax rendering. For example +# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_EXTENSIONS = + +# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces +# of code that will be used on startup of the MathJax code. See the MathJax site +# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an +# example see the documentation. +# This tag requires that the tag USE_MATHJAX is set to YES. + +MATHJAX_CODEFILE = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box for +# the HTML output. The underlying search engine uses javascript and DHTML and +# should work on any modern browser. Note that when using HTML help +# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) +# there is already a search function so this one should typically be disabled. +# For large projects the javascript based search engine can be slow, then +# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to +# search using the keyboard; to jump to the search box use + S +# (what the is depends on the OS and browser, but it is typically +# , / @@ -58,7 +57,7 @@ int main() factory.registerSimpleAction("CloseGripper", std::bind( &GripperInterface::close, &gripper)); factory.registerNodeType("ApproachObject"); - factory.registerNodeType("SaySomething"); + #else // Load dynamically a plugin and register the TreeNodes it contains factory.registerFromPlugin("./libdummy_nodes.so"); diff --git a/examples/t03_sequence_star.cpp b/examples/t03_sequence_star.cpp index ba861e93d..25a398ef7 100644 --- a/examples/t03_sequence_star.cpp +++ b/examples/t03_sequence_star.cpp @@ -1,6 +1,4 @@ #include "behavior_tree_core/xml_parsing.h" -#include "behavior_tree_logger/bt_cout_logger.h" -#include "behavior_tree_logger/bt_file_logger.h" #include "dummy_nodes.h" #include "movebase_node.h" @@ -26,7 +24,9 @@ const std::string xml_text_sequence = R"( + + @@ -39,9 +39,11 @@ const std::string xml_text_sequence_star = R"( - - - + + + + + @@ -57,10 +59,13 @@ void Assert(bool condition) int main() { + using namespace DummyNodes; + BehaviorTreeFactory factory; - factory.registerSimpleCondition("TemperatureOK", std::bind( DummyNodes::CheckBattery )); - factory.registerSimpleCondition("BatteryOK", std::bind( DummyNodes::CheckTemperature )); + factory.registerSimpleCondition("TemperatureOK", std::bind( CheckBattery )); + factory.registerSimpleCondition("BatteryOK", std::bind( CheckTemperature )); factory.registerNodeType("MoveBase"); + factory.registerNodeType("SaySomething"); // Compare the state transitions and messages using either // xml_text_sequence and xml_text_sequence_star @@ -75,15 +80,6 @@ int main() auto tree = buildTreeFromText(factory, xml_text); - // This logger will show all the state transitions on console - StdCoutLogger logger_cout(tree.root_node); - logger_cout.enableTransitionToIdle(false);// make the log less verbose - logger_cout.seTimestampType( TimestampType::RELATIVE ); - - // FileLogger will save the state transitions in a custom file format - // simple_trace.fbl, that can be visualized using the command line tool [bt_log_cat] - FileLogger logger_file(tree.root_node, "simple_trace.fbl"); - NodeStatus status; std::cout << "\n--- 1st executeTick() ---" << std::endl; @@ -111,43 +107,35 @@ int main() ------------ BUILDING A NEW TREE ------------ --- 1st executeTick() --- -[0.000]: root IDLE -> RUNNING [ Temperature: OK ] -[0.000]: BatteryOK IDLE -> SUCCESS [ Battery: OK ] -[0.000]: TemperatureOK IDLE -> SUCCESS -[0.000]: MoveBase IDLE -> RUNNING +Robot says: "mission started..." [ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.00 --- 2nd executeTick() --- [ Temperature: OK ] [ Battery: OK ] [ MoveBase: FINISHED ] -[0.253]: MoveBase RUNNING -> SUCCESS --- 3rd executeTick() --- [ Temperature: OK ] [ Battery: OK ] -[0.301]: root RUNNING -> SUCCESS +Robot says: "mission completed!" ------------ BUILDING A NEW TREE ------------ --- 1st executeTick() --- -[0.000]: root IDLE -> RUNNING [ Temperature: OK ] -[0.000]: BatteryOK IDLE -> SUCCESS [ Battery: OK ] -[0.000]: TemperatureOK IDLE -> SUCCESS -[0.000]: MoveBase IDLE -> RUNNING +Robot says: "mission started..." [ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.00 --- 2nd executeTick() --- [ MoveBase: FINISHED ] -[0.254]: MoveBase RUNNING -> SUCCESS --- 3rd executeTick() --- -[0.301]: root RUNNING -> SUCCESS +Robot says: "mission completed!" */ From ec3d37cff466871d4fb88c7f9bbfbd9ad3b59295 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 9 Oct 2018 12:23:26 +0200 Subject: [PATCH 117/125] Adding deadline decorator --- CMakeLists.txt | 2 + gtest/gtest_decorator.cpp | 70 +++++ include/behavior_tree_core/behavior_tree.h | 1 + .../decorators/deadline_node.h | 40 +++ .../decorators/timer_queue.h | 242 ++++++++++++++++++ src/bt_factory.cpp | 2 + src/decorators/deadline_node.cpp | 66 +++++ 7 files changed, 423 insertions(+) create mode 100644 gtest/gtest_decorator.cpp create mode 100644 include/behavior_tree_core/decorators/deadline_node.h create mode 100644 include/behavior_tree_core/decorators/timer_queue.h create mode 100644 src/decorators/deadline_node.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 83c1b195d..cf3188435 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -61,6 +61,7 @@ set(BT_Source src/decorators/negation_node.cpp src/decorators/repeat_node.cpp src/decorators/retry_node.cpp + src/decorators/deadline_node.cpp src/controls/parallel_node.cpp src/controls/fallback_node.cpp @@ -111,6 +112,7 @@ set(BT_Tests gtest/gtest_parallel.cpp gtest/gtest_fallback.cpp gtest/gtest_factory.cpp + gtest/gtest_decorator.cpp ) if(catkin_FOUND AND CATKIN_ENABLE_TESTING) diff --git a/gtest/gtest_decorator.cpp b/gtest/gtest_decorator.cpp new file mode 100644 index 000000000..0df213129 --- /dev/null +++ b/gtest/gtest_decorator.cpp @@ -0,0 +1,70 @@ +/* Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#include +#include "action_test_node.h" +#include "condition_test_node.h" +#include "behavior_tree_core/behavior_tree.h" + +using BT::NodeStatus; + + +struct DeadlineTest : testing::Test +{ + BT::DeadlineNode root; + BT::AsyncActionTest action; + + DeadlineTest() + : root("deadline", 250) + , action("action") + { + root.setChild(&action); + } + ~DeadlineTest() + { + haltAllActions(&root); + } +}; + + +/****************TESTS START HERE***************************/ + +TEST_F(DeadlineTest, DeadlineTriggeredTest) +{ + BT::NodeStatus state = root.executeTick(); + // deadline in 250 ms + action.setTime(3); + + ASSERT_EQ(NodeStatus::RUNNING, action.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(std::chrono::milliseconds(350)); + state = root.executeTick(); + ASSERT_EQ(NodeStatus::IDLE, action.status()); + ASSERT_EQ(NodeStatus::FAILURE, state); +} + +TEST_F(DeadlineTest, DeadlineNotTriggeredTest) +{ + BT::NodeStatus state = root.executeTick(); + // deadline in 250 ms + action.setTime(2); + + ASSERT_EQ(NodeStatus::RUNNING, action.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(std::chrono::milliseconds(350)); + state = root.executeTick(); + ASSERT_EQ(NodeStatus::IDLE, action.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); +} + diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index beb674b6e..d5aed928d 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -32,6 +32,7 @@ #include "behavior_tree_core/decorators/always_success_node.h" #include "behavior_tree_core/decorators/always_failure_node.h" #include "behavior_tree_core/decorators/blackboard_precondition_node.h" +#include "behavior_tree_core/decorators/deadline_node.h" namespace BT { diff --git a/include/behavior_tree_core/decorators/deadline_node.h b/include/behavior_tree_core/decorators/deadline_node.h new file mode 100644 index 000000000..e82f4ab42 --- /dev/null +++ b/include/behavior_tree_core/decorators/deadline_node.h @@ -0,0 +1,40 @@ +#ifndef DEADLINE_NODE_H +#define DEADLINE_NODE_H + +#include "behavior_tree_core/decorator_node.h" +#include +#include "timer_queue.h" + +namespace BT +{ +class DeadlineNode : public DecoratorNode +{ + public: + + DeadlineNode(const std::string& name, unsigned milliseconds); + + DeadlineNode(const std::string& name,const NodeParameters& params); + + static const NodeParameters& requiredNodeParameters() + { + static NodeParameters params = {{"msec", "0"}}; + return params; + } + + private: + static TimerQueue& timer() + { + static TimerQueue timer_queue; + return timer_queue; + } + + virtual BT::NodeStatus tick() override; + + std::atomic child_halted_; + uint64_t timer_id_; + + unsigned msec_; +}; +} + +#endif // DEADLINE_NODE_H diff --git a/include/behavior_tree_core/decorators/timer_queue.h b/include/behavior_tree_core/decorators/timer_queue.h new file mode 100644 index 000000000..bf0a3af6e --- /dev/null +++ b/include/behavior_tree_core/decorators/timer_queue.h @@ -0,0 +1,242 @@ +#ifndef TIMERQUEUE_H +#define TIMERQUEUE_H + +#include +#include +#include +#include +#include +#include + +namespace BT { + +// http://www.crazygaze.com/blog/2016/03/24/portable-c-timer-queue/ + +namespace details { + +class Semaphore { +public: + Semaphore(unsigned int count = 0) : m_count(count) {} + + void notify() { + std::unique_lock lock(m_mtx); + m_count++; + m_cv.notify_one(); + } + + void wait() { + std::unique_lock lock(m_mtx); + m_cv.wait(lock, [this]() { return m_count > 0; }); + m_count--; + } + + template + bool waitUntil(const std::chrono::time_point& point) { + std::unique_lock lock(m_mtx); + if (!m_cv.wait_until(lock, point, [this]() { return m_count > 0; })) + return false; + m_count--; + return true; + } + +private: + std::mutex m_mtx; + std::condition_variable m_cv; + unsigned int m_count; +}; + +} + + + +// Timer Queue +// +// Allows execution of handlers at a specified time in the future +// Guarantees: +// - All handlers are executed ONCE, even if canceled (aborted parameter will +//be set to true) +// - If TimerQueue is destroyed, it will cancel all handlers. +// - Handlers are ALWAYS executed in the Timer Queue worker thread. +// - Handlers execution order is NOT guaranteed +// +class TimerQueue { +public: + TimerQueue() { + m_th = std::thread([this] { run(); }); + } + + ~TimerQueue() { + cancelAll(); + // Abusing the timer queue to trigger the shutdown. + add( std::chrono::milliseconds(0), [this](bool) { m_finish = true; }); + m_th.join(); + } + + //! Adds a new timer + // \return + // Returns the ID of the new timer. You can use this ID to cancel the + // timer + uint64_t add(std::chrono::milliseconds milliseconds, + std::function handler) + { + WorkItem item; + item.end = Clock::now() + milliseconds; + item.handler = std::move(handler); + + std::unique_lock lk(m_mtx); + uint64_t id = ++m_idcounter; + item.id = id; + m_items.push(std::move(item)); + lk.unlock(); + + // Something changed, so wake up timer thread + m_checkWork.notify(); + return id; + } + + //! Cancels the specified timer + // \return + // 1 if the timer was cancelled. + // 0 if you were too late to cancel (or the timer ID was never valid to + // start with) + size_t cancel(uint64_t id) { + // Instead of removing the item from the container (thus breaking the + // heap integrity), we set the item as having no handler, and put + // that handler on a new item at the top for immediate execution + // The timer thread will then ignore the original item, since it has no + // handler. + std::unique_lock lk(m_mtx); + for (auto&& item : m_items.getContainer()) { + if (item.id == id && item.handler) { + WorkItem newItem; + // Zero time, so it stays at the top for immediate execution + newItem.end = Clock::time_point(); + newItem.id = 0; // Means it is a canceled item + // Move the handler from item to newitem. + // Also, we need to manually set the handler to nullptr, since + // the standard does not guarantee moving an std::function will + // empty it. Some STL implementation will empty it, others will + // not. + newItem.handler = std::move(item.handler); + item.handler = nullptr; + m_items.push(std::move(newItem)); + + lk.unlock(); + // Something changed, so wake up timer thread + m_checkWork.notify(); + return 1; + } + } + return 0; + } + + //! Cancels all timers + // \return + // The number of timers cancelled + size_t cancelAll() { + // Setting all "end" to 0 (for immediate execution) is ok, + // since it maintains the heap integrity + std::unique_lock lk(m_mtx); + for (auto&& item : m_items.getContainer()) { + if (item.id) { + item.end = Clock::time_point(); + item.id = 0; + } + } + auto ret = m_items.size(); + + lk.unlock(); + m_checkWork.notify(); + return ret; + } + +private: + using Clock = std::chrono::steady_clock; + TimerQueue(const TimerQueue&) = delete; + TimerQueue& operator=(const TimerQueue&) = delete; + + void run() + { + while (!m_finish) { + auto end = calcWaitTime(); + if (end.first) { + // Timers found, so wait until it expires (or something else + // changes) + m_checkWork.waitUntil(end.second); + } else { + // No timers exist, so wait forever until something changes + m_checkWork.wait(); + } + + // Check and execute as much work as possible, such as, all expired + // timers + checkWork(); + } + + // If we are shutting down, we should not have any items left, + // since the shutdown cancels all items + assert(m_items.size() == 0); + } + + std::pair calcWaitTime() + { + std::lock_guard lk(m_mtx); + while (m_items.size()) + { + if (m_items.top().handler) + { + // Item present, so return the new wait time + return std::make_pair(true, m_items.top().end); + } + else{ + // Discard empty handlers (they were cancelled) + m_items.pop(); + } + } + + // No items found, so return no wait time (causes the thread to wait + // indefinitely) + return std::make_pair(false, Clock::time_point()); + } + + void checkWork() { + std::unique_lock lk(m_mtx); + while (m_items.size() && m_items.top().end <= Clock::now()) { + WorkItem item(std::move(m_items.top())); + m_items.pop(); + + lk.unlock(); + if (item.handler) + item.handler(item.id == 0); + lk.lock(); + } + } + + details::Semaphore m_checkWork; + std::thread m_th; + bool m_finish = false; + uint64_t m_idcounter = 0; + + struct WorkItem { + Clock::time_point end; + uint64_t id; // id==0 means it was cancelled + std::function handler; + bool operator>(const WorkItem& other) const { + return end > other.end; + } + }; + + std::mutex m_mtx; + // Inheriting from priority_queue, so we can access the internal container + class Queue : public std::priority_queue, + std::greater> { + public: + std::vector& getContainer() { + return this->c; + } + } m_items; +}; + +} + +#endif // TIMERQUEUE_H diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index b1ff14a38..6d3a89328 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -38,6 +38,8 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType>("BlackboardCheckInt"); registerNodeType>("BlackboardCheckDouble"); registerNodeType>("BlackboardCheckString"); + + registerNodeType("Deadline"); } bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID) diff --git a/src/decorators/deadline_node.cpp b/src/decorators/deadline_node.cpp new file mode 100644 index 000000000..8fad201b3 --- /dev/null +++ b/src/decorators/deadline_node.cpp @@ -0,0 +1,66 @@ +#include "behavior_tree_core/decorators/deadline_node.h" + +namespace BT { + +DeadlineNode::DeadlineNode(const std::string &name, + unsigned milliseconds): + DecoratorNode(name, {}), + child_halted_(false), + msec_(milliseconds) +{ + +} + +DeadlineNode::DeadlineNode(const std::string &name, + const BT::NodeParameters ¶ms) : + DecoratorNode(name, params), + child_halted_(false), + msec_(0) +{ + auto param = getParam("msec"); + if( param ) + { + msec_ = param.value(); + } +} + +NodeStatus DeadlineNode::tick() +{ + if( status() == NodeStatus::IDLE ) + { + setStatus(NodeStatus::RUNNING); + child_halted_ = false; + + if( msec_ > 0 ) + { + timer_id_ = timer().add( std::chrono::milliseconds(msec_), + [this](bool aborted) + { + if( !aborted && child()->status() == NodeStatus::RUNNING ) + { + child()->halt(); + child()->setStatus( NodeStatus::IDLE ); + child_halted_ = true; + } + }); + } + } + + if( child_halted_ ) + { + setStatus( NodeStatus::FAILURE ); + } + else{ + auto child_status = child()->executeTick() ; + if( child_status != NodeStatus::RUNNING) + { + child()->setStatus(NodeStatus::IDLE); + timer().cancel( timer_id_ ); + } + setStatus(child_status); + } + + return status(); +} + +} From 295eb1f12324bd2f2a24750adb27f646577c3abd Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 9 Oct 2018 13:51:49 +0200 Subject: [PATCH 118/125] simplified policy of nodes with memory --- include/behavior_tree_core/basic_types.h | 14 +--- .../controls/fallback_node.h | 19 ++--- .../controls/fallback_node_with_memory.h | 34 ++------ .../controls/sequence_node.h | 19 ++--- .../controls/sequence_node_with_memory.h | 24 +++--- src/basic_types.cpp | 72 ++++++++-------- src/controls/fallback_node_with_memory.cpp | 64 ++++++--------- src/controls/sequence_node_with_memory.cpp | 82 ++++++++++--------- 8 files changed, 143 insertions(+), 185 deletions(-) diff --git a/include/behavior_tree_core/basic_types.h b/include/behavior_tree_core/basic_types.h index 29cb144d5..baca24d78 100644 --- a/include/behavior_tree_core/basic_types.h +++ b/include/behavior_tree_core/basic_types.h @@ -48,12 +48,7 @@ enum FailurePolicy FAIL_ON_ONE, FAIL_ON_ALL }; -enum ResetPolicy -{ - ON_SUCCESS_OR_FAILURE, - ON_SUCCESS, - ON_FAILURE -}; + // Enumerates the options for when a parallel node is considered to have succeeded: // - "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); std::ostream& operator<<(std::ostream& os, const BT::NodeType& type); -/** - * @brief toStr converts ResetPolicy to string. - */ -const char* toStr(const BT::ResetPolicy& policy); - -std::ostream& operator<<(std::ostream& os, const BT::ResetPolicy& type); - // small utility, unless you want to use std::vector splitString(const std::string& strToSplit, char delimeter); diff --git a/include/behavior_tree_core/controls/fallback_node.h b/include/behavior_tree_core/controls/fallback_node.h index 9af435e49..ddb79eff8 100644 --- a/include/behavior_tree_core/controls/fallback_node.h +++ b/include/behavior_tree_core/controls/fallback_node.h @@ -20,20 +20,17 @@ namespace BT { /** - * @brief The FallbackNode is used when you want to evaluate different "strategies". + * @brief The FallbackNode is used to try different strategies, + * until one succeed. + * If any child returns RUNNING, previous children will be ticked again. * - * This control node ticks its children UNTIL one of them returns SUCCESS. + * - If all the children return FAILURE, this node returns FAILURE. * - * In that case it return SUCCESS, otherwise it return FAILURE. - * If it finds a child returning RUNNING, it returns RUNNING and it restarts from the first child. + * - If a child returns RUNNING, this node returns RUNNING. + * The loop is restarted, but already completed children are not halted. + * This generally implies that ConditionNode are ticked again. * - * If you don't want to restart from the first child, use FallbackNodeWithMemory instead. - * - * Example: three children, A, B and C - * - * 1) A returns FAILURE. Continue. - * 2) B returns RUNNING, Restart from A - * 3) A returns FAILURE again but B return SUCCESS. Stop and return SUCCESS. + * - If a child returns SUCCESS, stop the loop and returns SUCCESS. * */ class FallbackNode : public ControlNode diff --git a/include/behavior_tree_core/controls/fallback_node_with_memory.h b/include/behavior_tree_core/controls/fallback_node_with_memory.h index a9a4a4985..90903b19a 100644 --- a/include/behavior_tree_core/controls/fallback_node_with_memory.h +++ b/include/behavior_tree_core/controls/fallback_node_with_memory.h @@ -20,46 +20,28 @@ namespace BT { /** - * @brief The FallbackNodeWithMemory is used when you want to evaluate different "strategies". + * @brief The FallbackNodeWithMemory is used to try different strategies, + * until one succeed. + * If any child returns RUNNING, previous children will NOT be ticked again. * - * This control node ticks its children UNTIL one of them returns SUCCESS. + * - If all the children return FAILURE, this node returns FAILURE. * - * In that case it returns SUCCESS, otherwise it returns FAILURE. - * If a child return RUNNING, this node returns RUNNING and at the next tick it will continue - * from the same index. - * It is recommended for asynchronous children which may return RUNNING. - * - * Example: three children, A, B and C - * - * 1) A returns FAILURE. Continue. - * 2) B returns RUNNING. Stop and return RUNNING. - * 3) B is ticked again but it returns SUCCESS. Stop and return SUCCESS. + * - If a child returns RUNNING, this node returns RUNNING. + * Loop is NOT restarted, the same running child will be ticked again. * + * - If a child returns SUCCESS, stop the loop and returns SUCCESS. */ class FallbackNodeWithMemory : public ControlNode { public: - FallbackNodeWithMemory(const std::string& name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); - - // Reset policy passed by parameter [reset_policy] - FallbackNodeWithMemory(const std::string&, const NodeParameters& params); - - virtual ~FallbackNodeWithMemory() override = default; + FallbackNodeWithMemory(const std::string& name); virtual void halt() override; - static const NodeParameters& requiredNodeParameters() - { - static NodeParameters params = {{RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)}}; - return params; - } - private: unsigned int current_child_idx_; - ResetPolicy reset_policy_; - constexpr static const char* RESET_POLICY = "reset_policy"; virtual BT::NodeStatus tick() override; }; } diff --git a/include/behavior_tree_core/controls/sequence_node.h b/include/behavior_tree_core/controls/sequence_node.h index b0617b149..9aa9c1131 100644 --- a/include/behavior_tree_core/controls/sequence_node.h +++ b/include/behavior_tree_core/controls/sequence_node.h @@ -19,22 +19,17 @@ namespace BT { /** - * @brief The SequenceNode is used to execute a sequence of synchronous children. + * @brief The SequenceNode is used to execute a sequence of children. + * If any child returns RUNNING, previous children will be ticked again. * - * This control node ticks its children AS LONG AS they returns SUCCESS. + * - If all the children return SUCCESS, this node returns SUCCESS. * - * If all the children return SUCCESS, the sequence is SUCCESS. - * If any return FAILURE, the sequence returns FAILURE and it starts from the beginning. - * If a child returns RUNNING, this node returns RUNNING and at the next tick it will continue - * from the same index. - * It is recommended for asynchronous children which may return RUNNING. + * - If a child returns RUNNING, this node returns RUNNING. + * The loop is restarted, but already completed children are not halted. + * This generally implies that ConditionNode are ticked again. * - * Example: three children, A , B and C + * - If a child returns FAILURE, stop the loop and returns FAILURE. * - * 1) A returns SUCCESS. Continue. - * 2) B returns RUNNING. Stop and return RUNNING. - * 3) A is ticked again and return SUCCESS. B is ticked and retuns SUCCESS. Continue. - * 4) C returns SUCCESS. The entire sequence returns SUCCESS. */ class SequenceNode : public ControlNode { diff --git a/include/behavior_tree_core/controls/sequence_node_with_memory.h b/include/behavior_tree_core/controls/sequence_node_with_memory.h index 53415e4e6..c958af242 100644 --- a/include/behavior_tree_core/controls/sequence_node_with_memory.h +++ b/include/behavior_tree_core/controls/sequence_node_with_memory.h @@ -20,24 +20,23 @@ namespace BT { /** - * @brief The SequenceNode is used to execute a sequence of asynchronous children. + * @brief The SequenceNodeWithMemory is used to execute a sequence of children. + * If any child returns RUNNING, previous children are not ticked again. * - * Tick all the children as long as they return SUCCESS. - * If any child return FAILURE, stop the sequence and return FAILURE. - * If any child return RUNNING, stop the sequence, return RUNNING. Restart from the same child + * - If all the children return SUCCESS, this node returns SUCCESS. * - * Example: three children, A , B and C + * - If a child returns RUNNING, this node returns RUNNING. + * Loop is NOT restarted, the same running child will be ticked again. + * + * - If a child returns FAILURE, stop the loop and returns FAILURE. + * Restart the loop only if (reset_on_failure == true) * - * 1) A returns SUCCESS. Continue. - * 2) B returns RUNNING. Stop and return RUNNING. - * 3) B is ticked and retuns SUCCESS. Continue. - * 4) C returns SUCCESS. The entire sequence returns SUCCESS. */ class SequenceNodeWithMemory : public ControlNode { public: - SequenceNodeWithMemory(const std::string& name, ResetPolicy reset_policy = BT::ON_SUCCESS_OR_FAILURE); + SequenceNodeWithMemory(const std::string& name, bool reset_on_failure = true); // Reset policy passed by parameter [reset_policy] SequenceNodeWithMemory(const std::string& name, const NodeParameters& params); @@ -48,15 +47,14 @@ class SequenceNodeWithMemory : public ControlNode static const NodeParameters& requiredNodeParameters() { - static NodeParameters params = {{RESET_POLICY, toStr(BT::ON_SUCCESS_OR_FAILURE)}}; + static NodeParameters params = {{"reset_on_failure", "true"}}; return params; } private: unsigned int current_child_idx_; - ResetPolicy reset_policy_; + bool reset_on_failure_; - static constexpr const char* RESET_POLICY = "reset_policy"; virtual BT::NodeStatus tick() override; }; } diff --git a/src/basic_types.cpp b/src/basic_types.cpp index f984cb28d..3d7dc3a26 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -63,21 +63,6 @@ const char* toStr(const NodeType& type) } } -const char* toStr(const ResetPolicy& policy) -{ - switch (policy) - { - case ResetPolicy::ON_FAILURE: - return "ON_FAILURE"; - case ResetPolicy::ON_SUCCESS: - return "ON_SUCCESS"; - case ResetPolicy::ON_SUCCESS_OR_FAILURE: - return "ON_SUCCESS_OR_FAILURE"; - default: - return "Undefined"; - } -} - template <> std::string convertFromString(const std::string& str) { @@ -110,45 +95,73 @@ double convertFromString(const std::string& str) } template <> -NodeStatus convertFromString(const std::string& str) +bool convertFromString(const std::string& str) { - for (auto status : {NodeStatus::IDLE, NodeStatus::RUNNING, NodeStatus::SUCCESS, NodeStatus::FAILURE}) + if( str.size() == 1) { - if (std::strcmp(toStr(status), str.c_str()) == 0) + if ( str[0] == '0'){ + return false; + } + else if( str[0] == '1'){ + return true; + } + else{ + std::runtime_error("invalid bool conversion"); + } + } + else if( str.size() == 4) + { + if( str == "true" || str == "TRUE" || str == "True") { - return status; + return true; + } + else{ + std::runtime_error("invalid bool conversion"); } } - throw std::invalid_argument(std::string("Cannot convert this to NodeStatus: ") + str); + else if( str.size() == 5) + { + if( str == "false" || str == "FALSE" || str == "False") + { + return false; + } + else{ + std::runtime_error("invalid bool conversion"); + } + } + + std::runtime_error("invalid bool conversion"); + return false; } template <> -NodeType convertFromString(const std::string& str) +NodeStatus convertFromString(const std::string& str) { - for (auto status : {NodeType::ACTION, NodeType::CONDITION, NodeType::CONTROL, NodeType::DECORATOR, - NodeType::SUBTREE, NodeType::UNDEFINED}) + for (auto status : {NodeStatus::IDLE, NodeStatus::RUNNING, NodeStatus::SUCCESS, NodeStatus::FAILURE}) { if (std::strcmp(toStr(status), str.c_str()) == 0) { return status; } } - throw std::invalid_argument(std::string("Cannot convert this to NodeType: ") + str); + throw std::invalid_argument(std::string("Cannot convert this to NodeStatus: ") + str); } template <> -ResetPolicy convertFromString(const std::string& str) +NodeType convertFromString(const std::string& str) { - for (auto status : {ResetPolicy::ON_SUCCESS, ResetPolicy::ON_SUCCESS_OR_FAILURE, ResetPolicy::ON_FAILURE}) + for (auto status : {NodeType::ACTION, NodeType::CONDITION, NodeType::CONTROL, NodeType::DECORATOR, + NodeType::SUBTREE, NodeType::UNDEFINED}) { if (std::strcmp(toStr(status), str.c_str()) == 0) { return status; } } - throw std::invalid_argument(std::string("Cannot convert this to ResetPolicy: ") + str); + throw std::invalid_argument(std::string("Cannot convert this to NodeType: ") + str); } + std::ostream &operator<<(std::ostream &os, const NodeType &type) { os << toStr(type); @@ -161,11 +174,6 @@ std::ostream &operator<<(std::ostream &os, const NodeStatus &status) return os; } -std::ostream &operator<<(std::ostream &os, const ResetPolicy &type) -{ - os << toStr(type); - return os; -} std::vector splitString(const std::string &strToSplit, char delimeter) { diff --git a/src/controls/fallback_node_with_memory.cpp b/src/controls/fallback_node_with_memory.cpp index e6976273c..8f17e498a 100644 --- a/src/controls/fallback_node_with_memory.cpp +++ b/src/controls/fallback_node_with_memory.cpp @@ -15,24 +15,13 @@ namespace BT { -constexpr const char* FallbackNodeWithMemory::RESET_POLICY; -FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string& name, ResetPolicy reset_policy) - : ControlNode::ControlNode(name, {{RESET_POLICY, toStr(reset_policy)}}) +FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string& name) + : ControlNode::ControlNode(name, {}) , current_child_idx_(0) - , reset_policy_(reset_policy) { } -FallbackNodeWithMemory::FallbackNodeWithMemory(const std::string& name, const NodeParameters& params) - : ControlNode::ControlNode(name, params), current_child_idx_(0), reset_policy_(ON_SUCCESS_OR_FAILURE) -{ - auto param = getParam(RESET_POLICY); - if(param){ - reset_policy_ = param.value(); - } -} - NodeStatus FallbackNodeWithMemory::tick() { // Vector size initialization. N_of_children_ could change at runtime if you edit the tree @@ -40,48 +29,47 @@ NodeStatus FallbackNodeWithMemory::tick() setStatus(NodeStatus::RUNNING); - // Routing the ticks according to the fallback node's (with memory) logic: while (current_child_idx_ < N_of_children) { TreeNode* current_child_node = children_nodes_[current_child_idx_]; - const NodeStatus child_status = current_child_node->executeTick(); - if (child_status != NodeStatus::FAILURE) + switch( child_status ) { - // If the child status is not success, return the status - if (child_status == NodeStatus::SUCCESS && reset_policy_ != ON_FAILURE) + case NodeStatus::RUNNING:{ + return child_status; + } + case NodeStatus::SUCCESS : { for (unsigned t = 0; t <= current_child_idx_; t++) { children_nodes_[t]->setStatus(NodeStatus::IDLE); } current_child_idx_ = 0; + return child_status; } - return child_status; - } - else if (current_child_idx_ != N_of_children - 1) - { - // If the child status is failure, continue to the next child - // (if any, hence if(current_child_ != N_of_children_ - 1) ) in the for loop (if any). - current_child_idx_++; - } - else - { - // If it the last child. - if (child_status == NodeStatus::FAILURE && reset_policy_ != ON_SUCCESS) + case NodeStatus::FAILURE: { - for (unsigned t = 0; t <= current_child_idx_; t++) - { - children_nodes_[t]->setStatus(NodeStatus::IDLE); - } - // if it the last child and it has returned failure, reset the memory - current_child_idx_ = 0; + current_child_idx_++; + }break; + + case NodeStatus::IDLE: + { + throw std::runtime_error("This is not supposed to happen"); } - return child_status; + } // end switch + }// end while loop + + // The entire while loop completed. This means that all the children returned FAILURE. + if (current_child_idx_ == N_of_children) + { + for (unsigned t = 0; t < N_of_children; t++) + { + children_nodes_[t]->setStatus(NodeStatus::IDLE); } + current_child_idx_ = 0; } - throw std::runtime_error("This is not supposed to happen"); + return NodeStatus::FAILURE; } void FallbackNodeWithMemory::halt() diff --git a/src/controls/sequence_node_with_memory.cpp b/src/controls/sequence_node_with_memory.cpp index 60c5f21ab..a61ce6431 100644 --- a/src/controls/sequence_node_with_memory.cpp +++ b/src/controls/sequence_node_with_memory.cpp @@ -15,21 +15,22 @@ namespace BT { -constexpr const char* SequenceNodeWithMemory::RESET_POLICY; -SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, ResetPolicy reset_policy) - : ControlNode::ControlNode(name, {{RESET_POLICY, toStr(reset_policy)}}) +SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, bool reset_on_failure) + : ControlNode::ControlNode(name, SequenceNodeWithMemory::requiredNodeParameters() ) , current_child_idx_(0) - , reset_policy_(reset_policy) + , reset_on_failure_(reset_on_failure) { } SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, const NodeParameters& params) - : ControlNode::ControlNode(name, params), current_child_idx_(0), reset_policy_(ON_SUCCESS_OR_FAILURE) + : ControlNode::ControlNode(name, params) + , current_child_idx_(0) + , reset_on_failure_(false) { - auto param = getParam(RESET_POLICY); + auto param = getParam("reset_on_failure"); if(param){ - reset_policy_ = param.value(); + reset_on_failure_ = param.value(); } } @@ -40,53 +41,54 @@ NodeStatus SequenceNodeWithMemory::tick() setStatus(NodeStatus::RUNNING); - // Routing the ticks according to the sequence node's (with memory) logic: while (current_child_idx_ < N_of_children) { - /* Ticking an action is different from ticking a condition. An action executed some portion of code in another thread. - We want this thread detached so we can cancel its execution (when the action no longer receive ticks). - Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree. - For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response. - */ TreeNode* current_child_node = children_nodes_[current_child_idx_]; - const NodeStatus child_status = current_child_node->executeTick(); - if (child_status != NodeStatus::SUCCESS) + switch( child_status ) { - // If the child status is not success, return the status - if (child_status == NodeStatus::FAILURE && reset_policy_ != ON_SUCCESS) + case NodeStatus::RUNNING:{ + return child_status; + } + case NodeStatus::FAILURE: { - for (unsigned t = 0; t <= current_child_idx_; t++) + if (reset_on_failure_) { - children_nodes_[t]->setStatus(NodeStatus::IDLE); + for (unsigned t = 0; t <= current_child_idx_; t++) + { + children_nodes_[t]->setStatus(NodeStatus::IDLE); + } + current_child_idx_ = 0; } - current_child_idx_ = 0; + else{ // just reset this child to try again + current_child_node->setStatus(NodeStatus::IDLE); + } + return child_status; } - return child_status; - } - else if (current_child_idx_ < N_of_children - 1) - { - // If the child status is success, continue to the next child - // (if any, hence if(current_child_ != N_of_children_ - 1) ) in the for loop (if any). - current_child_idx_++; - } - else - { - // if it the last child. - if (child_status == NodeStatus::SUCCESS || reset_policy_ != ON_FAILURE) + case NodeStatus::SUCCESS: { - // if it the last child and it has returned SUCCESS, reset the memory - for (unsigned t = 0; t <= current_child_idx_; t++) - { - children_nodes_[t]->setStatus(NodeStatus::IDLE); - } - current_child_idx_ = 0; + current_child_idx_++; + }break; + + case NodeStatus::IDLE: + { + throw std::runtime_error("This is not supposed to happen"); } - return child_status; + } // end switch + }// end while loop + + + // The entire while loop completed. This means that all the children returned SUCCESS. + if (current_child_idx_ == N_of_children) + { + for (unsigned t = 0; t < N_of_children; t++) + { + children_nodes_[t]->setStatus(NodeStatus::IDLE); } + current_child_idx_ = 0; } - throw std::runtime_error("This is not supposed to happen"); + return NodeStatus::SUCCESS; } void SequenceNodeWithMemory::halt() From b4338026c55c1506130080a82e12213f47d65796 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 11 Oct 2018 14:42:08 +0200 Subject: [PATCH 119/125] Update README.md --- README.md | 130 +++++++++++++----------------------------------------- 1 file changed, 31 insertions(+), 99 deletions(-) diff --git a/README.md b/README.md index d84d6bd6c..f7f0dc3a2 100644 --- a/README.md +++ b/README.md @@ -1,14 +1,26 @@ -NEWS! ------------ -The Preprint of our book titled "**Behavior Trees in Robotics and AI**" is available here: https://arxiv.org/abs/1709.00084 +# About this library -portfolio_view BT++ -==== -![License MIT](https://img.shields.io/dub/l/vibe-d.svg) ![Version](https://img.shields.io/badge/version-v1.4-green.svg) -
-A behavior tree library in `C++`. +This __C++__ library provides a framework to create BehaviorTrees. +It was designed to be flexible, easy to use and fast. -REFERENCE +Even if our main use-case is __robotics__, you can use this library to build +__AI for games__, or to replace Finite State Machines in you application. + +__BehaviorTree.CPP__ has many interesting features, when compared to other implementations: + +- It makes asynchronous Actions, i.e. non-blocking, a first-class citizen. +- It allows the creation of trees at run-time, using a textual representation (XML). +- You can link staticaly you custom TreeNodes or convert them into plugins +which are loaded at run-time. +- It includes a __logging/profiling__ infrastructure that allows the user +to visualize, record, replay and analyze state transitions. + +Documentation +------------ + +https://eurecat.github.io/BehaviorTree.CPP + +Reference ------------ Please refer to the following paper when using the library: @@ -29,100 +41,20 @@ bibtex entry: `ISSN={1552-3098},`
`month={April},}`
-DEPENDENCIES ------------- - -Regarding visualization purposes: -* [OpenGL](https://www.opengl.org/) -* [Glut](https://www.opengl.org/resources/libraries/glut/) - -Regarding tests: -* [GTests](https://github.com/google/googletest) - -BT NODES SUPPORT ----------------- -**Fallback:** Fallback nodes are used to find and execute the first child that does not fail. A Selector node will return immediately with a status code of success or running when one of its children returns success or running. The children are ticked in order of importance, from `left` to `right`. - -**Sequence:** Sequence nodes are used to find and execute the first child that has not yet succeeded. A sequence node will return immediately with a status code of `failure` or `running` when one of its children returns failure or running. The children are ticked in order, from `left` to `right`. - -**Parallel:** The parallel node ticks its children in parallel and returns success if `M ≤ N` children return success, it returns failure if `N − M + 1` children return failure, and it returns running otherwise. - -**Decorator:** The decorator node manipulates the return status of its child according to the policy defined by the user (e.g. it inverts the success/failure status of the child). In this library the decorators implemented are the two common ones: *Decorator Retry* which retries the execution of a node if this fails; and *Decorator Negation* That inverts the Success/Failure outcome. - -**Action:** An Action node performs an action, and returns Success if the action is completed, Failure if it can not be completed and Running if completion is under way. - -**Condition:** A Condition node determines if a desired condition `c` has been met. Conditions are technically a subset of the Actions, but are given a separate category and graphical symbol to improve readability of the BT and emphasize the fact that they never return running and do not change any internal states/variables of the BT. - -A user manual is available in the project folder ([BTppUserManual.pdf](https://github.com/miccol/Behavior-Tree/blob/master/BTppUserManual.pdf)). - -SETUP ------------ - -The first step to use BT++ is to retrieve its source code. You can either download it -here (https://github.com/miccol/Behavior-Tree) or clone the repository: + +# Aknowledgement -`$ cd /path/to/folder`
-`$ git clone https://github.com/miccol/Behavior−Tree.git` +This project is one of the main components of [MOOD2Be](https://eurecat.org/es/portfolio-items/mood2be/), +and it is developed at [Eurecat](https://eurecat.org) by Davide Faconti. -Once you have the repository, compile the library: +MOOD2Be is one of the six **Integrated Technical Projects (ITPs)** selected from the +[RobMoSys first open call](https://robmosys.eu/itp/) +. +It received funding from the European Union’s Horizon 2020 Research and Innovation Programme +under the RobMoSys project. -`$ cd /path/to/folder/`
-`$ mkdir ./build`
-`$ cd build`
-`$ cmake ..`
-`$ make`
- - -**NOTE** -In case you get the following error: - -`CMake Error: The following variables are used in this project, but they are set to NOTFOUND. -Please set them or make sure they are set and tested correctly in the CMake files: -GLUT_Xmu_LIBRARY (ADVANCED)` - -please see solution [here](https://ubuntuforums.org/archive/index.php/t-1703770.html). Thanks [miquelramirez](https://github.com/miquelramirez) for this. - - -Check the installation by running a sample example. - -`$ cd /path/to/folder/`
-`$ cd build/sample`
-`$ ./btpp_example`
- -INSTALL THE LIBRARY SYSTEM-WIDE (tested on Ubuntu 14.04 and 16.04) -------------------------------- - -If you would like to install the library system-wide, then run: - -`$ cd /path/to/folder/`
-`$ cd build`
-`$ sudo make install`
- -On Ubuntu, this will install the library (libbtpp.so) in `/usr/local/lib`.
-In an external project, just call in your CMakeLists 'find_package(BTpp)' to find the library.
-The include directory is defined as `BTpp_INCLUDE_DIRS` and the libraries to link as `BTpp_LIBRARIES`.
-The repository [my-behavior-tree-project](https://github.com/miccol/my-behavior-tree-project) shows an example on how to use the library once system-wide installed. - - -CREATE YOUR OWN ACTION NODE ------- -1) Implement your action node class extending the abstract class `BT::ActionNode`. -2) Implement the method `BT::ReturnStatus Tick()` with the code you want to execute while the action is running. Use the method `is_halted()` to check if the action has been prempted. When the execution of your action finished, return `BT::SUCCESS` or `BT::FAILURE` accordingly. -3) Implement the method `void Halt()` with the code you want to execute when the action gets preempted (halted). -See the file `src/example.cpp` for an example. - -CREATE YOUR OWN CONDITION NODE ------- -1) Implement your condition node class extending the abstract class `BT::ConditionNode`. -2) Implement the method `BT::ReturnStatus Tick()` with the code you want to execute to check the condition. Return `BT::SUCCESS` or `BT::FAILURE` accordingly. -See the file `src/example.cpp` for an example. - - -NOTES -------- -In case you are puzzled about why a sequence (or fallback) node with 2 or more actions as children never get past the first action, see [this](https://github.com/miccol/ROS-Behavior-Tree/issues/16) discussion. -LICENSE +License ------- The MIT License (MIT) From be22a471386e851e54a15803a2850b8e8bdc9b4e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 15 Oct 2018 10:21:16 +0200 Subject: [PATCH 120/125] Readme updated --- README.md | 26 +++++++++++++++++--------- 1 file changed, 17 insertions(+), 9 deletions(-) diff --git a/README.md b/README.md index f7f0dc3a2..bc7d1044d 100644 --- a/README.md +++ b/README.md @@ -24,9 +24,10 @@ Reference ------------ Please refer to the following paper when using the library: -**How Behavior Trees Modularize Hybrid Control Systems and Generalize Sequential Behavior Compositions, the Subsumption Architecture, and Decision Trees.** Michele Colledanchise and Petter Ogren. IEEE Transaction on Robotics 2017. +**How Behavior Trees Modularize Hybrid Control Systems and Generalize Sequential Behavior Compositions, the Subsumption Architecture, +and Decision Trees.** Michele Colledanchise and Petter Ogren. IEEE Transaction on Robotics 2017. -bibtex entry: +Bibtex entry: `@ARTICLE{TRO17Colledanchise,`
`author={M. Colledanchise and P. Ögren},`
@@ -41,18 +42,25 @@ bibtex entry: `ISSN={1552-3098},`
`month={April},}`
+Further readings +--------------- + +The book Behavior Trees in Robotics and AI, published by CRC Press Taylor & Francis, is available for purchase +(ebook and hardcover) on the CRC Press Store or Amazon. The Preprint version (free) is available here: https://arxiv.org/abs/1709.00084 + +Tutorials available at https://btirai.github.io/ -# Aknowledgement +Aknowledgement +------------ +This library is the result of the join effort between **Eurecat** (main autjor, Davide Faconti) and the +**Italian Institute of Technology** (Michele Colledanchise). -This project is one of the main components of [MOOD2Be](https://eurecat.org/es/portfolio-items/mood2be/), +It is one of the main components of [MOOD2Be](https://eurecat.org/es/portfolio-items/mood2be/), and it is developed at [Eurecat](https://eurecat.org) by Davide Faconti. MOOD2Be is one of the six **Integrated Technical Projects (ITPs)** selected from the -[RobMoSys first open call](https://robmosys.eu/itp/) -. -It received funding from the European Union’s Horizon 2020 Research and Innovation Programme -under the RobMoSys project. - +[RobMoSys first open call](https://robmosys.eu/itp/) and it received funding from the European +Union’s Horizon 2020 Research and Innovation Programme. License ------- From 8ac2ca9123fd3afb5adaf7b579f7a1b39139e197 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 15 Oct 2018 10:21:33 +0200 Subject: [PATCH 121/125] default value of reset_on_failure_ set to true --- src/controls/sequence_node_with_memory.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/src/controls/sequence_node_with_memory.cpp b/src/controls/sequence_node_with_memory.cpp index a61ce6431..6d9783035 100644 --- a/src/controls/sequence_node_with_memory.cpp +++ b/src/controls/sequence_node_with_memory.cpp @@ -26,12 +26,9 @@ SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, bool res SequenceNodeWithMemory::SequenceNodeWithMemory(const std::string& name, const NodeParameters& params) : ControlNode::ControlNode(name, params) , current_child_idx_(0) - , reset_on_failure_(false) + , reset_on_failure_(true) { - auto param = getParam("reset_on_failure"); - if(param){ - reset_on_failure_ = param.value(); - } + getParam("reset_on_failure", reset_on_failure_); } NodeStatus SequenceNodeWithMemory::tick() From e085949e72b41d6753d4221e8ab39e3b7505f047 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 16 Oct 2018 11:28:27 +0200 Subject: [PATCH 122/125] Docs added --- docs/BT_basics.md | 56 ++-- docs/ControlNode.md | 26 -- docs/DecoratorNode.md | 14 +- docs/FallbackNode.md | 94 ++++-- docs/NodeParameters.md | 3 + docs/SequenceNode.md | 173 ++++------ docs/getting_started.md | 58 ++++ docs/images/CrossDoorSubtree.png | Bin 0 -> 5745 bytes docs/images/ReadTheDocs.png | Bin 0 -> 11024 bytes docs/images/SequenceStar.png | Bin 8038 -> 8528 bytes docs/index.md | 11 +- docs/tutorial_A_create_trees.md | 230 ++++++++++++++ docs/tutorial_B_node_parameters.md | 201 ++++++++++++ docs/tutorial_C_blackboard.md | 112 +++++++ docs/tutorial_D_subtrees.md | 60 ++++ docs/tutorial_E_plugins.md | 129 ++++++++ docs/tutorial_F_loggers.md | 87 +++++ docs/uml/CrossDoorSubtree.uxf | 299 ++++++++++++++++++ docs/uml/Reactive.uxf | 260 +++++++++++++++ docs/uml/ReadTheDocs.uxf | 153 +++++++++ docs/uml/SequenceStar.uxf | 35 +- examples/broken_sequence.cpp | 92 ++++++ examples/crossdoor_example.cpp | 44 ++- examples/t04_blackboard.cpp | 52 +-- include/Blackboard/blackboard.h | 11 +- include/SafeAny/safe_any.hpp | 2 + .../actions/always_failure_node.h | 39 +++ .../actions/always_success_node.h | 38 +++ .../actions/set_blackboard_node.h | 54 ++++ include/behavior_tree_core/behavior_tree.h | 8 +- ...ys_failure_node.h => force_failure_node.h} | 17 - ...ys_success_node.h => force_success_node.h} | 16 - mkdocs.yml | 20 +- sample_nodes/dummy_nodes.cpp | 11 +- sample_nodes/movebase_node.cpp | 20 +- src/bt_factory.cpp | 1 + tools/bt_plugin_manifest.cpp | 4 +- 37 files changed, 2071 insertions(+), 359 deletions(-) delete mode 100644 docs/ControlNode.md create mode 100644 docs/NodeParameters.md create mode 100644 docs/images/CrossDoorSubtree.png create mode 100644 docs/images/ReadTheDocs.png create mode 100644 docs/tutorial_A_create_trees.md create mode 100644 docs/tutorial_B_node_parameters.md create mode 100644 docs/tutorial_C_blackboard.md create mode 100644 docs/tutorial_D_subtrees.md create mode 100644 docs/tutorial_E_plugins.md create mode 100644 docs/tutorial_F_loggers.md create mode 100644 docs/uml/CrossDoorSubtree.uxf create mode 100644 docs/uml/Reactive.uxf create mode 100644 docs/uml/ReadTheDocs.uxf create mode 100644 examples/broken_sequence.cpp create mode 100644 include/behavior_tree_core/actions/always_failure_node.h create mode 100644 include/behavior_tree_core/actions/always_success_node.h create mode 100644 include/behavior_tree_core/actions/set_blackboard_node.h rename include/behavior_tree_core/decorators/{always_failure_node.h => force_failure_node.h} (85%) rename include/behavior_tree_core/decorators/{always_success_node.h => force_success_node.h} (85%) diff --git a/docs/BT_basics.md b/docs/BT_basics.md index c9a0bc1c8..86a45d0fe 100644 --- a/docs/BT_basics.md +++ b/docs/BT_basics.md @@ -10,12 +10,12 @@ our coordinating component interacts with the rest of the system. For instance, in a service-oriented architecture, the leaves would contain the "client" code that triggers an action. -All the other nodes of the tree, those which are not leaves, control the +The other nodes of the tree, those which are not leaves, control the "flow of execution". To better understand how this flow takes place , imagine a signal, that we will further call "__tick__" that is executed at the __root__ of the tree and propagates through -the branches until it reaches a leave. +the branches until it reaches one or multiple leaves. The result of a tick can be either: @@ -23,58 +23,63 @@ The result of a tick can be either: - __FAILURE__ - __RUNNING__ + The first two, as their names suggest, inform their parent that their operation was a success or a failure. -The latter usually means that the execution of the TreeNode is not completed -and it needs more time to return a valid result. + +RUNNING is returned by asynchronous nodes when their execution is not completed +and they needs more time to return a valid result. + +This C++ library provides also the status __IDLE__; it means that the node is ready to +start. The result of a node is propagated back to the parent, that will decide -which child should be ticked next or will return a result itself. +which child should be ticked next or will return a result to its own parent. ## Types of nodes __ControlNodes__ are nodes which can have 1 to N children. Once a tick is received, this tick may be propagated to one or more of the children. -__DecoratorNodes__ can have only a single child. +__DecoratorNodes__ is similar to the ControlNode, but it can have only a single child. __ActionNodes__ are leaves and do not have children. The user should implement -their own ActionNodes that perform the actual task. +their own ActionNodes to perform the actual task. -__ConditionNodes__ are equivalent to ActionNodes, with the exeption that -they are alwais aotmic (they should not return RUNNING) and they should not +__ConditionNodes__ are equivalent to ActionNodes, but +they are always atomic, i.e. they must not return RUNNING. They should not alter the state of the system. ![UML hierarchy](images/TypeHierarchy.png) -!!! note - Actions and Conditions differ only in terms of __semantic__. - From an implementation point of view they are the same. ## Learn by example -To better understand how a BehaviorTrees work let's focus on some practical +To better understand how a BehaviorTrees work, let's focus on some practical examples. For the sake of simplicity we will not take into account what happens when an action returns RUNNING. We will assume that each Action is executed atomically and synchronously. -In future sections we will more thoughtfully analyze asynchronous actions. + ### Sequence Let's illustrate how a BT works using the most basic and frequently used ControlNode: the [SequenceNode](SequenceNode.md). +The children of a ControlNode are always __ordered__; it is up to the ControlNode +to consider this order or not. + +In the graphical representation, the order of execution is __from left to right__. + ![Simple Sequence: fridge](images/SequenceBasic.png) -It is important to notice that the children of a ControlNode are __ordered__. -In this case the order of execution is __from left to right__. -A Sequence works as described next: +In short: - If a child returns SUCCESS, tick the next one. - If a child returns FAILURE, then no more children are ticked and the Sequence returns FAILURE. -- If all the children return SUCCESS, then the Fallback returns SUCCESS too. +- If all the children return SUCCESS, then the Sequence returns SUCCESS too. ??? warning "Exercise: find the bug! Expand to read the answer." If the action __GrabBeer__ fails, the door of the @@ -87,7 +92,7 @@ The goal of a [DecoratorNode](DecoratorNode.md) is either to transform the resul from the child, to terminate the child, or repeat ticking of the child, depending on the type of Decorator. -You can create your own Decorators too. +You can create your own Decorators. ![Simple Decorator: Enter Room](images/DecoratorEnterRoom.png) @@ -116,18 +121,17 @@ __But__ there is an error. Can you find it? ### Fallback -[FallbackNodes](FallbackNode.md), known also as __"Selector"__ in the literature, -Is a node that is used to express, as the name suggests, fallback strategies, -ie. what to do if a child return FAILURE. +[FallbackNodes](FallbackNode.md), known also as __"Selector"__, +are nodes that can express, as the name suggests, fallback strategies, +ie. what to do next if a child returns FAILURE. -In short, it ticks the children in order, as usual from left to right and: +In short, it ticks the children in order and: - If a child returns FAILURE, tick the next one. - If a child returns SUCCESS, then no more children are ticked and the Fallback returns SUCCESS. - If all the children return FAILURE, then the Fallback returns FAILURE too. In the next example, you can see how Sequence and Fallbacks can be combined: - ![FallbackNodes](images/FallbackBasic.png) @@ -162,11 +166,11 @@ returns FAILURE. Both the trees will close the door of the fridge, eventually, but: - the tree on the __left__ side will always return SUCCESS if we managed to - open and clode the fridge. + open and close the fridge. - the tree on the __right__ side will return SUCCESS if the beer was there, FAILURE otherwise. -We can easily double-check that everything works as usual if __GrabBeer__ returns SUCCESS. +Everything works as expected if __GrabBeer__ returns SUCCESS. ![FetchBeer success](images/FetchBeer2.png) diff --git a/docs/ControlNode.md b/docs/ControlNode.md deleted file mode 100644 index d96b32000..000000000 --- a/docs/ControlNode.md +++ /dev/null @@ -1,26 +0,0 @@ -# ControlNodes - -ControlNodes can have multiple children. Children are always __ordered__ -and it is up to the ControlNode itself to decide if and when a child should -be ticked. - -## SequenceNode - -The SequenceNode is used to execute the children in a sequence. - -It ticks its children __as long as__ they returns SUCCESS. - -- Before ticking the first child, Sequence becomes __RUNNING__. -- If a child return __SUCCESS__, it ticks the next child. -- If the __last__ child returns __SUCCESS__ too, all the children are halted and - the Sequence returns __SUCCESS__. -- If a child returns __RUNNING__, Sequence suspends and returns __RUNNING__. -- If a child returns __FAILURE__, Sequence stops and returns __FAILURE__. - - - - - - - - diff --git a/docs/DecoratorNode.md b/docs/DecoratorNode.md index b8425e0d1..8d65c4ae4 100644 --- a/docs/DecoratorNode.md +++ b/docs/DecoratorNode.md @@ -5,7 +5,7 @@ A decorator is a node that can have only a single child. It is up to the Decorator to decide if, when and how many times the child should be ticked. -## InverterNode +## NegationNode Tick the child once and return SUCCESS if the child failed or FAILURE if the child succeeded. @@ -26,7 +26,7 @@ Otherwise, it returns always FAILURE. ## RepeatNode -Tick the child up to N times, where N is passed as a [NodeParameter](NodeParameter.md), +Tick the child up to N times, where N is passed as a [NodeParameter](NodeParameters.md), as long as the child returns SUCCESS. Interrupt the loop if the child returns FAILURE and, in that case, return FAILURE too. @@ -35,19 +35,11 @@ If the child returns RUNNING, this node returns RUNNING too. ## RetryNode -Tick the child up to N times, where N is passed as a [NodeParameter](NodeParameter.md), +Tick the child up to N times, where N is passed as a [NodeParameter](NodeParameters.md), as long as the child returns FAILURE. Interrupt the loop if the child returns SUCCESS and, in that case, return SUCCESS too. If the child returns RUNNING, this node returns RUNNING too. -## RetryNode - -Tick the child up to N times, where N is passed as a [NodeParameter](NodeParameter.md), -as long as the child returns FAILURE. - -Interrupt the loop if the child returns SUCCESS and, in that case, return SUCCESS too. - -If the child returns RUNNING, this node returns RUNNING too. diff --git a/docs/FallbackNode.md b/docs/FallbackNode.md index 0cfa738fe..f3dadd7b2 100644 --- a/docs/FallbackNode.md +++ b/docs/FallbackNode.md @@ -4,63 +4,103 @@ This family of nodes are known as "Selector" or, sometimes, "Priority" in other frameworks. Its purpose is to try different strategies, until we find one that "works". -Currently, there is only a single type of node called "FallbackNode". +Currently the framework provides two kinds of nodes: -## FallbackNode +- FallbackNode +- FallbackStarNode + +They share the following rules: -The SequenceNode is used to execute the children in a sequence. +- Before ticking the first child, the node status becomes __RUNNING__. -- Before ticking the first child, Fallback becomes __RUNNING__. - If a child returns __FAILURE__, it ticks the next child. + - If the __last__ child returns __FAILURE__ too, all the children are halted and - the Sequence returns __FAILURE__. -- If a child returns __RUNNING__, Fallback suspends and returns __RUNNING__. -- If a child returns __SUCCESS__, Fallback stops and returns __SUCCESS__. + the sequence returns __FAILURE__. + +- If a child returns __SUCCESS__, it stops and returns __SUCCESS__. + All the children are halted. + + +## FallbackNode + +If a child returns __RUNNING__: + +- FallbackNode returns __RUNNING__. +- The loop is restarted and all the previous children are ticked again __unless + they are ActionNodes__. + __Example__: -Try different strategies to open the door. Check first if it is open already. +Try different strategies to open the door. Check first if the door is open. ![FallbackNode](images/FallbackSimplified.png) ??? example "See the pseudocode" ``` c++ - // At the beginning, start from first child - if( state != RUNNING) { - index = 0; + status = RUNNING; + + for (int index=0; index < number_of_children; index++) + { + child_status = child[index]->tick(); + + if( child_status == RUNNING ) { + // Suspend execution and return RUNNING. + // At the next tick, index will be the same. + return RUNNING; + } + else if( child_status == SUCCESS ) { + // Suspend execution and return SUCCESS. + // index is reset and children are halted. + HaltAllChildren(); + return SUCCESS; + } } - state = RUNNING; + // all the children returned FAILURE. Return FAILURE too. + HaltAllChildren(); + return FAILURE; + ``` + +## FallbackStarNode + +If a child returns __RUNNING__: + +- FallbackStarNode returns __RUNNING__. +- The loop is __not__ restarted and none of the previous children is ticked. + +??? example "See the pseudocode" + ``` c++ + // index is initialized to 0 in the constructor + status = RUNNING; while( index < number_of_children ) { - child_state = child[index]->tick(); + child_status = child[index]->tick(); - if( child_state == RUNNING ) { + if( child_status == RUNNING ) { // Suspend execution and return RUNNING. // At the next tick, index will be the same. - state = RUNNING; - return state; + return RUNNING; } - else if( child_state == FAILURE ) { + else if( child_status == FAILURE ) { // continue the while loop index++; } - else if( child_state == SUCCESS ) { + else if( child_status == SUCCESS ) { // Suspend execution and return SUCCESS. - // index is reset and children are halted. - state = SUCCESS; + // At the next tick, index will be the same. + HaltAllChildren(); index = 0; - HaltAllChildren(); - return state; + return SUCCESS; } } - // all the children returned failure. Return FAILURE too. - state = FAILURE; + // all the children returned FAILURE. Return FAILURE too. + index = 0; HaltAllChildren(); - return state; - - + return FAILURE; + ``` diff --git a/docs/NodeParameters.md b/docs/NodeParameters.md new file mode 100644 index 000000000..4756bce28 --- /dev/null +++ b/docs/NodeParameters.md @@ -0,0 +1,3 @@ +# NodeParameters + + diff --git a/docs/SequenceNode.md b/docs/SequenceNode.md index 74f383028..0e94fbd2b 100644 --- a/docs/SequenceNode.md +++ b/docs/SequenceNode.md @@ -1,192 +1,131 @@ # Sequences -A __Sequence__ ticks all it's children, from left to right, as long as -they return SUCCESS. If any child returns FAILURE, the sequence is suspended. +A __Sequence__ ticks all it's children as long as +they return SUCCESS. If any child returns FAILURE, the sequence is aborted. -Here we introduce different kinds of TreeNodes: +Currently the framework provides two kinds of nodes: - SequenceNode - SequenceStarNode -- SequenceAllNode -The best way to determine which one should be used is to ask yourself: - Q: "What should I do if one of the childs returns FAILURE?" +They share the following rules: -Use __SequenceNode__ if you answer is: +- Before ticking the first child, the node status becomes __RUNNING__. - A: "Restart the entire sequence" - -Use __SequenceStarNode__ if, instead, the answer is: - - - A: "Try again to execute the failed child. - Do not re-tick children which succeeded already." - -Last, use __SequenceAllNode__ when you want all the children to be ticked at least -once. If any of them failed, the SequenceAllNode returns FAILURE. - -The shared logic is: - -- Before ticking the first child, SequenceNode becomes __RUNNING__. - If a child returns __SUCCESS__, it ticks the next child. -- If the __last__ child returns __SUCCESS__ too, all the children are halted and - the SequenceNode returns __SUCCESS__. -- If a child returns __RUNNING__, the sequence suspends and returns __RUNNING__. -The next time it is ticked, it will tick the same child again. -The three Sequences differ in what they do if a child returns FAILURE. +- If the __last__ child returns __SUCCESS__ too, all the children are halted and + the sequence returns __SUCCESS__. + + ## SequenceNode -If a child returns FAILURE, the sequence returns FAILURE. -Reset the index and halt all the children. -The entire sequence will be executed again at the next tick. +- If a child returns FAILURE, the sequence returns FAILURE. + The index is reset and all the children are halted. + +- If a child returns RUNNING: + - the sequence returns RUNNING. + - the loop is restarted and all the previous children are ticked again __unless + they are ActionNodes__. + __Example__: This tree represents the behavior of a sniper in a computer game. If any of these conditions/actions fails, the entire sequence is executed again from the beginning. +A running actions will be interrupted if __isEnemyVisible__ becomes +false (i.e. it returns FAILURE). + ![SequenceNode](images/SequenceNode.png) ??? example "See the pseudocode" ``` c++ - // At the beginning, start from first child - if( state != RUNNING) { - index = 0; - } - state = RUNNING; + status = RUNNING; - while( index < number_of_children ) + for (int index=0; index < number_of_children; index++) { - child_state = child[index]->tick(); + child_status = child[index]->tick(); - if( child_state == RUNNING ) { + if( child_status == RUNNING ) { // Suspend execution and return RUNNING. // At the next tick, index will be the same. - state = RUNNING; - return state; + return RUNNING; } - else if( child_state == SUCCESS ) { - // continue the while loop - index++; - } - else if( child_state == FAILURE ) { + else if( child_status == FAILURE ) { // Suspend execution and return FAILURE. // index is reset and children are halted. - state = FAILURE; - index = 0; HaltAllChildren(); - return state; + return FAILURE; } } // all the children returned success. Return SUCCESS too. - state = SUCCESS; HaltAllChildren(); - return state; + return SUCCESS; ``` ## SequenceStarNode -If a child returns FAILURE, the sequence returns FAILURE. At the next tick, -the failed child is executed again. +Use this ControlNode when you don't want to tick a child more than once. + +You can customize its behavior using the [NodeParameter](NodeParameters.md) "reset_on_failure". + +- If a child returns FAILURE, the sequence returns FAILURE. + + - [reset_on_failure = "true"]: (default) the loop is restarted. + - [reset_on_failure = "false"]: the same failed child is executed again. + +- If a child returns RUNNING, the sequence returns RUNNING. + The same child will be ticked again. __Example__: -This is a patrolling agent/robot that must visit locations A, B and C only once. +This is a patrolling agent/robot that must visit locations A, B and C __only once__. If the action __GoTo(B)__ fails, __GoTo(A)__ will not be ticked again. -On the other hand, __isBatteryOK__ is visited at every tick, because its parent is a normal SequenceNode. +On the other hand, __isBatteryOK__ must be checked at every tick, +for this reason its parent must be a SequenceNode. ![SequenceStar](images/SequenceStar.png) ??? example "See the pseudocode" ``` c++ - // index is initialized to 0 in the constructor - state = RUNNING; + status = RUNNING; while( index < number_of_children ) { - child_state = child[index]->tick(); + child_status = child[index]->tick(); - if( child_state == RUNNING ) { + if( child_status == RUNNING ) { // Suspend execution and return RUNNING. // At the next tick, index will be the same. - state = RUNNING; - return state; + return RUNNING; } - else if( child_state == SUCCESS ) { + else if( child_status == SUCCESS ) { // continue the while loop index++; } - else if( child_state == FAILURE ) { + else if( child_status == FAILURE ) { // Suspend execution and return FAILURE. // At the next tick, index will be the same. - state = FAILURE; - return state; + if( reset_on_failure ) + { + HaltAllChildren(); + index = 0; + } + return FAILURE; } } // all the children returned success. Return SUCCESS too. - state = SUCCESS; - HaltAllChildren(); - return state; - ``` - - -## SequenceAllNode - -All the children are executed at least once. -If __any__ child returned FAILURE, -the sequence is __not__ interrupted but the sequence itself will return FAILURE. - -__Example__: - -If the door of the fridge was succesfully opened, grab a beer. -__CloseFridge__ is always executed, even when _GrabBeer_ failed. - - -![SequenceAll](images/SequenceAll.png) - -??? example "See the pseudocode" - ``` c++ - if( state != RUNNING) { - index = 0; - at_least_one_failure = false; - } - state = RUNNING; - - while( index < number_of_children ) - { - child_state = child[index]->tick(); - - if( child_state == RUNNING ) { - // Suspend execution and return RUNNING. - // At the next tick, index will be the same. - state = RUNNING; - return state; - } - else if( child_state == SUCCESS ) { - index++; - } - else if( child_state == FAILURE ) { - index++; - at_least_one_failure = true; - } - } - // If any child failed, the entire sequence fails. - state = at_least_one_failure ? FAILURE : SUCCESS; + index = 0; HaltAllChildren(); - return state; + return SUCCESS; ``` - - - - - diff --git a/docs/getting_started.md b/docs/getting_started.md index 8b1378917..d5ac2d700 100644 --- a/docs/getting_started.md +++ b/docs/getting_started.md @@ -1 +1,59 @@ +# Getting started + +__BehaviorTree.CPP__ is a C++ library that can be easily integrated into +your favourite distributed middleware, such as __ROS__ or __SmartSoft__. + +You can also statically link it into your application (for example a game). + +There are some main concepts that you need to understand first. + +## Nodes vs Trees + +The user must create his/her own ActionNodes and ConditionNodes (LeafNodes) and this +library helps you to compose them easily into trees. + +Think about the LeafNodes as the building blocks that you need to compose +a complex system. + +By definition, your custom Nodes are (or should be) highly reusable. +Therefore, some wrapping interfaces might be needed at the beginning to adapt your +legacy code. + + +## The tick() callbacks + +Any TreeNode can be seen as a mechanism to invoke a __callback__, i.e. to +__run a piece of code__. What this callback does is up to you. + +In most of the __following examples__, our Actions just +print messages on the screen of sleep for a certain amount of time to simulate +a long calculation. + +## Inheritance vs dependency injection. + +To create a custom TreeNode, you should inherit from the proper class. + +For instance, to create your own synchronous Action, you should inherit from the +class __ActionNodeBase__. + +Alternatively, we provided a mechanism to create a TreeNode passing a +__function pointer__ to a wrapper (dependency injection). + +This approach reduces the amount of boilerplate in your code but has also +some limitations; the most important one is that TreeNodes created using +function pointers can not support [NodeParameters](NodeParameters.md). + +## NodeParameters + +NodeParameters are conceptually similar to the arguments of a function. + +They are passed statically when the tree is instantiated. + +They are expressed as a list of __key/value__ pairs, where both the the +key and the value are strings. + +This is not surprising, since NodeParameters are usually parsed from file. + +The library provides some methods and utility functions to correctly convert +values from string to the desired C++ type. diff --git a/docs/images/CrossDoorSubtree.png b/docs/images/CrossDoorSubtree.png new file mode 100644 index 0000000000000000000000000000000000000000..b42e1f0c4dd0946bf18973ad6861e8eacbf0d1e9 GIT binary patch literal 5745 zcmaJ_2T;@9vPVSG0HSp1O{#<{p$RCxSE&I+Ke`Y|XptsWnj|z)X@UYu73q)wf~%geuf`O@9por>yIp6X0_DldQf^5vCinY%``;K+!G&#Q`b4fS2kBh%Wbs9#+^cR6jDedyr!8;FL!1jdZ zJasw;4D5~TPV0D7C^Tj?^6Nx8rDMumAbKMXo{&N|s=M@OK z3s*g3Xf#$P=OP)5HDq-ECL6-w&XBia%ZLU(Tu>DHhaoKcot~^M%A1TPLRwdjgSjwO z?S7mkk}e`pSo>9?Pyh|hht*s^O+UXu^-6jkAE5aDK_r@uxby2avQ0=*n0}Y_ceaMUsyHB-`f+P@k+SNCu={?jHZrtE|*%b2?WFoxPM_e=z%dZs;kxSpbHr2w% zoq;&C+x;j3*6^I~s@=r~@rMYD=vjKKb0Zmt_D7vlpK`s&M!+I8fq<(0;poV;#o&LO z{@Zm?N?GG?XA3pIyoT|_JWSGm;Tk{k?R};92N(1IG2zm$PUds|)-a$CR9SzXu`@BD zOqDjsnt|ZS5np%gZG8}37cF|bWhhwR&#QG}>22W(+&{aM3!D{4`xmI|e$F1QLKi)p~J z=wy}7XoWJ6G3=Jprt`D^h^MAyBrqX@Yu39m`#S=HPinuaHMaTHho|Xd`_mB>^@jeK z{)8QtcD%&4IbJE))z^FDL@D&UZ|0s3abAslAT`oR4>t+~I(<_65w#x#9D4_su+Bl( z>P-i00^4v>A5Di+UPXVNey#mB42Zxjd*Lmh_JMvD8z_|b4pI|uiZpr+>yt$A`3Mb7 zv@kRL=784)RomeWksx~#TN(Frmr-lZa^DgRS2@g0BDK&@dT6Z0^4U)X_)g$vR%5mZ z#-}YJf`DbR?aJO!_U0#zt|~cYzFWA1x4T25Enwd^AY3Y_TJuS@v9s1$ zD5*Y~lcpp9*ZeQ+dI_v2058g4lZoR=!c(v=F51pq`Kl5s*D1Cdr{ssmCyU{fS1U6= z02t)y?otJ#tw5AzzA8+&x9zxln>teCbf5j&Ec)aq8hvoW-g`o>K){LLgUB=Df*!ao zEb>%VFzRsc#Ny`B_w?iLB@iFvBy{It<7$TnB*(3Ncn5j99(DU7F{;No;woK-`vz_B z&X~s{mA)zN8e|@cV;chbfU{>fxRrC-jxaIk1A?Y|$kdi-< zuO^`Eap28Yn}{OS4kb(N@GL-~GgS~c@+1Lf_cXf}mQsRbCiN2mPs5@8(-hs(6on7+ zLD8x?K?#P9+K|h=$V9bu~p5+lYzp0tVZiqEL!$ScemDv zNVDoCamk!#Nbca$=}I55iy7S@3s)hWQXdU?FX&NEw8@Jqe>dm_N{>zK#gY`QVI3$~ z_Wq~XrD9|C=%xx|*2M>Ly!5Kf>kp#TGg9)qTJ5gt>1`C!y6DwE{ubxkwzRp%Io+P; z{aXIT5dTnq9&cHi`*GV`O*<}e5i3@`NIjhdn<;m&HC+#$VsG@7}OGM2b^_bziAm0t6$E5=SH`WL& zeWOrp$4MvQbbH8UE_^>^PNV(m5@n0GmV2_}aBr=9C&ggvXMYoXOHYv!1?^DmUsG#) zc*t1Pbu6|5X=hqj222J*Q~%0vCf`aM=R3*!>HXoPtuN2nq@d2?-qPQlgd)nXu|rMB zt=k~O+rp>c!m5UTl+HD>@BrtV6#KY*T+={3_HJpKJ~zqBRfdq9dyQ00(lsX z7x>YVF>x_JMF;J>(i17w@|kZ;?tPG-%U8$P$o?X?>^&wykun@>V(Zb0+iiQ5Bv)WPtc)eBON;(l*30SpT_j_II^QrF8?UE9}b8* z=b|O!Hv3tF6l)NDh!p@HL;9-;{Ed@!1WvqBZ8vGqQ;-8kbSc;v}w4dub;$?S73bsJ1 zzkU0BomTCYMXZ(K^}#1G4?;U>#z+ENm2$qY4i)!l&zi^$Pat#;mxy}v%SNV*?(CHE zAPcLWR}q5(FRmC+nk6XC(yi4{Sb_WXjZr7!#&|Sy1Ut8wlZBP*IqQd`GN}=ezRN}4 zp%DE%aqoGONvI6W@2atQ4@gs1EoP`NHk>On<-oA~yy(HS%&rZK-K*+PSr039CsI&< zKYB!S+rpej>6Zl^9lhA_3tpB-A2*pE ztFCu`hP+Tw0f&iVe{mua51|$=20@>9?3buV%-)X(ugE+fK+++ezEQg5juatAH%Ue} z=~enIlE3J-Ct?5ie=UQSP_XAIG8LU(1v4WJx<}HE$qEzOJtdT)SXqF3!bl6Tgub2h z5Y*>&T7#fC=7{t0@-Z<;wasn0X&ehJ=^a7xMU0RDE&B6*#c;(1!g(i;nTp#kQR*oe z-}}$X&%6I9x2Q<~fY``tP9%#Bx%ULbSK-IxDS?)EHE&hAezF!fy5C$G4;;fG8Bxi^ z-DJnQYXggwj-GqLP+{Ue-$^7_aHn zAnGIjN}Y#4XVhj;bGww)mVbgGUO`xCPJPA>zqH*iL!z%@vE|HK?#-M1wd1lOT{dx( zgwel~Hr@&wT)iRD9Jxn*SH7{*7t5 z?km{dnp5(rxTc)W{9o8*b~=nw3+>YW_fgd5Syv|>555(e^O`kK#md^n<8KA>utPdy zCH+sO>^iv~>Kk6!4SsS6l64wO=eC_caZE0%)GiX0+<#E<$tfZ*;8Lr8+8^8IFVBXu zlIs6-PXE(VVzAXnGH0q!GYahx`c%B2eZ;1|b9wX2NR1Z6Hinh=c`H+9+oSrJL(o~F zK5pt=$VX`|Tr5D5!)ZVPqb6Kow@{~SmD;npi*^oN#kPd$vv9pCb^poSS@M14x|ab)YwoQl!AwP|_8%HP#oqbBCaz1zuIuTc&8wPDSXZBaJ!$D1SlgUJnE@ zy1%r+AMuT?#Ic#SOw^$$@I9B;PT>2WhU}jBb1g@PAVZhCBzq5}!>XX~fKZOZDjQH$ z7g#k~QeTw_HZ3voaTI7tH3X>~?eZ6Fab}1++2GUCjY-8wBk0UGPqQvYq-wIuVOo?i_?>%f!S&NB9>(aE%OR#5e{dGf-guGk4Ev#5qY*yS? z^(pF_VTdIjCsczT%^q%qVb`ky-RjAYC@PY(D~*9A+dJU$QbSu)JW!zK{b=^r#sQ4a zyTFnLvL&Te+zIa6_5$T>m@}@p)0l-Lhw;sY5{Nk4)SsYx~+Cen9CwLyaU60 zxV+acht23NW(o_t$|aUZyX6Oje~G0L4xGE8(&YVpQxC+`xVuA)i zw_8w&NBrNK-xm9mEX-eAkx9n%^x`WrATW%*GW75PMNI6b+L{+sHaQoZiDJG0Ml$Nz z&&j3szNWcb_mEf`tgOt{37oZtxea{pFQTv*rsG*6w0`y>!h%fY)A<6=l~icgy5 zr?u2uui9=7Vd&``-e^tE(n@O!oVrAPTlgv3fz#3R{4-hu61TBR*`i|+2XA>qKt5gJ zvg>nD{F{dXUp>E9M8`x~LVpHdFLf$3^y5?P#k6N+}bt;U>5qo!tnE-if^RDi<-3&6h^F|`G4PFX;g z^flfUtfa<`6k?38dnr8M!2l_eokli=i}Nw^+&&FMLqA+7Jp z0_-ktXd6>#*ylA7LL>v_2BHp?bmvl^XQhwi@3YHOtZi878u^HK&IhqAG5ts>UU$^$ zOAs|vDAueUY5Y);r@|P#8Y1)5`|hSsYr?13JaLg~E90*@cx?r?wv`5Q7d3yf{_>_J zF77>*s7Q`)nAPH2(bn|SwW@a3S8P?_;Flb znO?~`<##a63)vODqC&2@&f%Lg>N!Ww0UEM!3313ZxZZ#eZII2I?yir-*WaR>miUh8 zp>vdih%5krJ%iDbC=m?!uvUsW5Akp{V_Q3=^rw$xrfa>G?CeSp29tQ>(DPSiI1rdS z3y&rY+|V|Rj~l)t>BwE`AP%oSGWcB`M{SA=N2(rCNgb4JT?+ffpW$^CzQ1x$iW#k# znCGM$`H3{129{Dv64cmtdt)sa1*I6~kgJbfT)#ZlsqNpNH9IDdK>v3#^RLm;KU13j z*i+71B@CQF)xlS$9&NKu9jwIe<=$F%d|O-O{qDB5*{^wuZ)UIQn;#RG@-5R|(;UP}d>Q7ClKGQM?@XbCqeIWZ$EeUfhku+!M zZsbD^@A(Y5!D!8lnRH(6bv3%PSySGjhZx}sFS9$YH29pd;(u#*v$KB>wd>1iM)-jX zbAgNpLU+Npr*Gw{l|zL!j9rIe?uU;(yXG#O<^4FK6R!noP>vViN%;zLm;rRSvR4l$eFH@wN?Q*UZpG>X)EdE07BdwP#jdZw#G0se`ACq8+eMT35wj2M= zM5~9_rxKVJ-SHPpjY;ncU5lCYuUbk|?2W5$_89j&{|q?-Vr4q+nrG^oe<;+BF2mN5sYOe>*O9HC`pgv8zLULY3h|ws zB{G+GBx$PHeW2WLJB`**Z7RZuX`QSC!EC13$!B0$LFg>X>|deTePJ0o=UC%6Z4WKv zc^vi?C^(_y;lO~Mn*Zt5FoRJ9c*+6T8&VP*mU;-z8qgjkM0hR8W}rR=3I6Fl{OH5+ zS45r^3Wiy#lM4{e^kdiO)t0lUvC)DyDhmzRf_TTx$_t{)ukAK1HQG8g$yUNRQ)QID0X*AJ$9z literal 0 HcmV?d00001 diff --git a/docs/images/ReadTheDocs.png b/docs/images/ReadTheDocs.png new file mode 100644 index 0000000000000000000000000000000000000000..e2a2241f8cb05e6ae743b554f044e002b2fa45bc GIT binary patch literal 11024 zcmai)1z42b*7pZN=};OZ1QY}W1*N+?XXp~75s(n1MFBw(>5^0gh7t)$K@pLVlA%LI zxwZFlCDZCVoy!74dynJqY*dp{DyuG|^J#0dI2@wcZ zgsOrp(sy(v!yid$e;mOXa)BVpROi{F`*_3z*IDNtwGtN(q0OnwuW*%=ASd*zjp`@* zJ6$Kx7;owld}=D{h6=e_0`4Tb;sRu$H6}Ndftbq)j|1m}cTjNGv7NoVz{7NkU5Q|K zfwiuNt_H!4F8|a$vIq`U=|jh~W|>b*=@%lB*w zKgJxL-EZ%46L68I>z>N6s;H^SiEc6{CMH@2Zc%sOkjfwsA?QDwkwN{{j8%_NLsTcs@g(S7a1HJq`ahIRO>O* zna5ZcXof>^t-PuwWq*KL(U|2T|^{>_0d$&L3AcHGqaT6rUPHH zxaTYkkI%eL;Y6G-*?*=ZadFWplogFemzvdDJ2|1N(igtHf54#%|MmFz=xj>_xn;Ta zY1KGj};jv?q&bNfq_HwBfJfIolPhmM1DI z3g5$9BHh?+LK(kW_TkL~rtZ@)o@7#6O1@U@vv})EWleX5c+fvKJ~6tH&gp3XH7pInLu5~JroGfud|*!o4eN( z))c$)QwluU=rY}aU+?iRUAhG8skOBg7M6CFlq5V6Br+j0y7=($FfA=@ch@(%_B@&W zV6ict?DBB=1J*~z6?O|z1@H{Jzq{XEn>^ZF_-fyixiZ<9-tzrnM8wX3Ma7y`vJXo( z4uKytS{knY+B>ZEoD-pOqb;hWOZ?v4&Mwpd=%>f#m&>4W8pFX_T3 zOO_{Zs;kLJNsnfdEw9t0h|Zc+EO23-x5aiv)7KG;YJM z?_d7v`r+LJ^U1*8BKKe3Gxs|RbYD=Ilo{s8EnOhuVhDlQiNg6KApJeM{QVj>YSD4~ zmfL+}Heuq&eZZ{1MfIbV0iuOc_%5MsXu+vI<{hFD=u*s_xR zwX55UGIO?-3BDE?>UP$H!MyRV9$>vNBo)n^mzLF@TnlX1jRtA|GG(#KgqFz(9BR zYRTKlj?T^(b9Q!i`@6fpd?jL4Dj^ysCDHf|!h|cbolWla_V$jBiOJ85b2}-P5L7gD zJx@0GIhOt1yLS@IZm=J}fB)W-C2e0iGdI^Zy{;6)+~~75NhVA}N9W6S&%J*nACr-h z!EaWR?QIYg^zQ9jpP-;1b8~Z5)%GX!f`et2+F!&1_bYX{x;i`cxf2CayV~0$#b!pc ze7%U&UGZdneSKB(^z!tKb#>3u(9ke2sD0_^=VoN=iy4B_(*W!=s~<^*%iv9Z?-Qb#@OZkr_l`DZYj@wieS6a_X`CR`$}cK1 zHP!e)VY?Vnhk4(O-Lo;wlDR=KjKX~E?D9+278VwBJz4pjJsIN4rfUmd^S%6FW{=V@ z3ez++HrfiLDp?P`IW=#9e`eh9hHXazBnp`CSFc{x`>chBhripI^dBf5A2)-=_wl1b zm|Tutp@*j@Y<|rzV)uT(9CY34?d^U2`gK$kQKFjn_OdZKIr%>FR(o__g!-j;Q86() zdwaopjPV;eOKNNnk%>rd^Ve4QVYR~3C@NZ_wG7ZTG*s^S(%DH&L?j?AEG#GpzjS>0 zl4pOBgM%RK!v*>9N3B0#{?sC8 z5TVT^dOtnx9TdFJmXyn(2n#WR{kV@wFCZl)U07IfYurjIFTdmE@`fFMBK zfB)2^r2F${0&;R6clSrp(HYllKIN$=4>(oD#PsAUKK{M2p{o#bCYD-;g^rt(lM}Wl z4^L-L&sv7hWU872txh3QRaLdTyj+5rUqHZP{YR?=Gx^LJlq@RSk`65ii39$2 z`t)f?a4dnFu`;YO*W^%$O_-u2Y`7|ka<~!l^iSZH zhiC*ztMIs_ToDEO)YXLdA=rDYxa3b^?`hU?pg#5I8}uZcp(`7j#=*7+f$`5~u^-9( z*VXqrh`(<9Kdx$IbJG$1qaEzqR`aZfh=^VIV;!!5U*B+^O3i<$y(v)8y>)z#vikLF zI+D3uGd^-6A_f=brdO{%b#xG2T0E}3`OtdN^h{*_nJd4L+BpA_488>`PaW*31o-*w zL+aQZ`HXX-a{pMFRNGJnmBxv8I;M^Cacf^+AB4n4KSf9LxA^?ipFVveWfXeCBtAGk zKK|*G-SOcbs0BCTy|3ERnp#@SR^%j}bf7jO6>?*wk89BA#hJsM+hf)1z76nGR{lYO zfnpqoY8~O<#pd1rju?7 zZ(4o}jUxwV=ZcC79v&VW(Yz{V5x+eM5wR-QZ+)hKwC2C#>NoAPI=-;H+%@CT*wDZS z68~E>j-jEUpkRe+{H2Me;H)FI#rL>5J+;@aqHJ&8l+~V{oAdYgpPQQ-!e9~;61q~Z z*&OX})oFdq&d!b?XVHuIoa?r=SUK2UF|Br?@5Fp=Fp!jxc&S&YS6Ez7KtN1POiGHW z%Pozc92wdB5JsGVLKzq&J$TR(Ny(X@W()h;*H=WnuGIR1YX8uXPiN8<6bcm`9W8xw z2(kU@K@vF$>c;i!>stgfyegH(*;xVJVbNfx26t1BD#6C4sGesKxx+{AGN?|#R>FTrj6``9f?sy-4GI*thr+|+m*U0 z%ckn_zfx*>Ddqb9*3#xJ3yaM3bjYHNH$)+Ue|@1;xO9PKG7bl}q#?e=1V4{b1L z6ce*}3I0=#_94q)NzewFhp@K_h?rz4V5~?sjC|Yk$~SNN=Unci#qzl?u`50C{r!_r zGP!3CBq#PoPp{iJ3fa0&OJQ+2hhEs#OiAgC_v3V!oz5`yoe~(;q9=XD^@~(Qih6o_ zw{E?RiHWJG@RXI6jd*%hQ1HcQK7)hi5Q>*WRY_TSWABif#{f2}Bp4v8qNwAE;bGsU z!4lBN?+#Y$&Gi#O3{;G0nID>*xS5!Yg2PkQhTPlFEqd?w&*!3^1*X#=1Panio0?8w zPQ@kenvkDYjRPkN%cqO9qPqH(Q06;I=ZpdDkm~e`oE#i#0`}e{Cl5iGQ16*p_w8zV zWuH&p3gU%R>$ytY ARAE(2|AHd*%fvmj+N+!8;W!bhXm-`adXo}x09&9x+HC>>B z=_o<>rtBf>e(|2SVW7LdP=!x?dZHLG4K=@Mjw_24tNg~my~QFF%9=N zuCJDD%zk-c2PSKM?+`SO#9nfS?Wg+0sEVUd3iIBY5C_9Aifxxm`DZgC!{?G2=RNSGhaJPtEwT1 z-%<*gL^reeezPuV^X8`4Y=4m$uX6o)Ff@sF*ox=kS1Z@ajhqokxJ3RBAi zIg=sjFQgg=LLHj2s~)J#G`e=}8e8lmV@-Bd0a4Kr4CV$WXMP>_CC16A%yDjIs;TLZ zL78(NC0y2zi;ss`m!6ge_LY%=VSmzptuH$4-=vqHVyedM{CrAAMoC{u=?!zk@@E{P z&V$8Z-V2c2d3vzsw4|k*w#8fD(1%YVo;-SFg^j%{KilK?y^7o>>JphpUl;=n87wg^ zoH{w2lg3&wvA(1$rca(c5xPD4(adP5{Hx!$g6_*8U{W=d+~_7sO7qc1-82PgQ*=jr z`})?F?cHY}YE$8XrKW;ZnVFr9!wR&;bh2T<+*#^wP^@wLD@P-q+RDLV|*x-rh$)9`n!dH_7FIy2?NE^5VI6FvF=l zpj6d3&haJlP!a8{PIP9LRvD?pb#-@V3fL0Gv`ug9y?_6HAlv((^tyTa&FqOq`EZgu zckbk5ve->2C)K&j$%X20-3m7PUNvNKu-?XU<6Q9JdfSkNfAqdN5~;A`ezHC0h9}!Q zExMdvIf$!V?mWa7t8&ZQI(Pkb=rKEIU3XIQD{kD!r(kS{aSw`YZEcSZrcR{Xzag04 zFCELjgpe>H8o+-t|KQluH6=U6$aizT4>a$c#evIIrxAg~$UI822pd<|%;(RaxLw3S zpthC_pXv}GHYq9a&S0(ORUJRvGe48)bQG?DF%?_zx=?5A_9)x!g>8<(X_?@NAnVee z7wOk5yZQx93}W2Ch{`mDch30v`K^w<nt-tEmogA2i4^SwC$UN4IaK4mNv zze;0Kd>@^S&NNIMoVVl6$+&Kzh+QEE-1`M;xMC(W>H%DGKG&~bg0WK&;BlxjO9wso z+eo#BjMwEelxq6<&03d;>&w+LKY+I&`C8G(RXk+oow~Rcs+C z+-rFHjN@A|>IoMRTL5Q{a;CdlT5MqIz$M|y79i1Y-n>alN*WwA;2vk9zOp3E)TK1a zKL+mNDZStjNqB=_yma z_maUTD#swq1huw}a)hA}uDt9+ynOLt(IjkuhBDe#T}7#qH)&Vr;c5-j?Ch*sUfh1* z>bR)bQGcF#*}Hvi)i|3^Pinmu;!4LiNu2X=1h3LCguvurOwnv7!gciO4xG`hTfid9 z%jBFMM-JY^eYQw!A4%St%MJK8B_##o+=mZxK0ZFP*p?zABk2Y0NIHe)=?9|*nCOVX z*k_|HkcmoOg626H^Ijl(?Rc-67d;!b&Rtl%;mmSH-7tWQ24&vphZ!15?wk=56}>(6 zE~EBmo%d2W3H=+_39;?|Ue03bb_Tkloo>>PMW^@);m3riaBm42;_Bc1pVc!fD_xlx zk6IkXVH^g6FuC)Ay;Ytq%}NM-=JRA^IEcTapuZy?Ebjh)VW0nsf+Xn_?l-QV#*sWr z6t?^5noJ3rzf9(w7aqsyznc5YlKu&+non&I67Ku-ND1AKxY}&hjHlSkbeSYGzaPGu zgs_GXaUDULi1q6a9|D9hF)=xVkIzFDMP?Wo6XWCU4Z~uK<+^rFx2IS@Q1IyR5J>oZ z-wOzrV^U+Gp`jopS4XRe@lTU9JAGiyInXXz;^uR6TdT0|85|lK0+|I;NI}8DJnUGL z;v?MoH!%wFe&K3SaWOAGegq|_7FS|NTwL6*U+&Q^U;F#{%6k}e(KcXl= zd!iS0HvimWOlWRF!FVlgb@g-sTeS#d&6KO(0l?Sc0rFa!nE}Z-dPM6C^pac__qA!F z4);22ZDLwJa3vxUE#;M!0f)PHBK9=Wu16kAg6ss;>Xm}h)$L3&w_) z&x|5cK|~1=h>{TpcE}`X*Hz^_l$M?j85HD=KRb`0prE-k7-ra9nbN_`ZKq^VGMs>W z_7;oE&NDG-YH09TzANtG)+l){?$iDCYeh@(pWuWKWovJ*te|jS{4PlZZnh~?AZqk+ zXImTRrAx0$OG{tB?wy!0cRr!=f4g6(pD)&>_7@IWS~O_#UK#|;`QyhA*!Zv-QI6ji zF-5@G%=m`d+a1AR>=!tJ_hF0u{PE+*krB}Kjr+G0<8A>TS77_@Q7f18%;Irv*8_a= zkJjrDvvatwHq$BS$^d&iD_klM;6g`-f`}-)jObq_nZFj*-^(=rxE6B1hc&8%FS&F5 z4s9R>Q5Y9qhzTmIZ_1*Hmxt%zYu52C7nj4KrsJyO;^Gq*Itv6a1XhAjE^cnWlcSx$ zfB+3mO`w8PpwOqMD;)ZA4-W&V$Pgy<3bEAtxcBbe1HW{cm)ESy2@^%l1C11TC8~kL z0(IFrz0StY4uY#|dR@m1Kn#B(JPIgYz!YI6zOr&f3KvKXA))H*Y*se5A1`90&Jo~o zNg^OTD3=%jM7cfLklHf`7`!K4SUamqOtInHlJ%s)ojMNNo98L2AK2ayo%MAe0dP=lmRESRcXT zIy%_#nbOCT?RqY{@iCGzna^CW2t&t%2Ryg*g|kChn`{w<3@ZEUymaNzG~5ge_?kK6 z=+d352Jm}!#wz&=fENT3^LTT&m)Rr?F;A$3*vd@~-}XEIg!P%al@l6cdq z=8qc-oW2P@3*W{P9}MDFHrdLS2y|5kHFcHl&#Q?zf&>xRzvIT?h@TR1i1@1)ey2&W z{me!m6aV>1RMQ!G|G?9qh;Wd3v~<|-hX+;m-2m{S{vR)0T_A(NDB%S(A@MU6rRN(E z1q}@W@Epn-eiK22-q-`8yJ_as|KUSu&)nG9n5mJGh?tlO5Hw?BLcCLyl$0$Z66eXf z`zDpRsHA*+Z`QH(|Ufx znZ|pIY&R_!3Zb&HIC*x7YBvB2JbU&mBqU@qUcdGR9A9@-fnMj^k;M;H!T$v2}g_$R5{9xAds6I8b&-I+egGDf|_~shyYv= z;I-I{{FcLd`7*mnTQKs=D=SbR_Tv!F(HVYQFHh@XV>2DiC~VjLyf$F(_kFMPEE2xG zb73T#_e%@_qD%&CXu@KQZ|69t>SlOcC4@KNv;|VE?I{yPHQp;%!0BZsCSn*(JvQfc z0gOYg2@XD4t(>OeGxJ^O&l?^dhFa-MP|nTc{lKo_sX!G|KtLd60c4+)l#~RsHpjUV z)3;AYXZ|C<6U}l%xsNtdfqdSY9DyLp#-0U$`~f~vN{Sf+X~hKP=~)47f*`W!)-+w3 zK$RFY9q%szLpz2>A=4HW6=`Qm>_K&L^V0+f_YuP~3lQy7RnE!z`S!w|&JGSnbzTeN zYYl={PADpBYHI8bzV+V=J8>`HzTJU@zqGXE?BoPNot=$s9`zsmO0I-x-kW_9yag%IK31@jEg?6#}x ztNyj|+6pMhKv}}j;+`$65|GL^rOf}}nq-2eVRAQZZ81l2@agKeZ~6K7n5{^gzkRdv zTdj2b3e_Ar?WDxS$X4s<^8f}fP!P; z9twpS9^M5`rf)CdUjlWsr5~-2ne0lJCcA_DISJUfxaL8kbV)#IebR5K1W;F#GLg@h zv>QN>!%P1U%(UVI(-g-s<8cqXQ$_|;6%-Y&HAY28YXXsxG)AFLqwc#Fc7RYWL~duJ z!$}#Temz)thBc~Aq+!qFz z-d^{;-?sexWo}JJN%umSCH)41N+3DT&(Ht<{Tuc}c=(yw*sAL4aI}mz+6hb#1Z2qq z^!&VoR92I9YZPqR{lnF>sD-+>6;qRhp$;xC1E0SR4puibG~^Tc0OhFkdG`Hicq z*3=vT?Y1sFQkmWsv>5m^2tNMX3Qa*r`>!<9VWNQ>*;rfqp>YcSn9d=;u+3%L>Dk#& z#jB(Ul&&N$nD&9Sf7YS6>$F^5SHb_O#%->zgLfz_D&pbg_44ttxAXY@Q`M{JK_)U$ zuaJrW4=B5&f3E&`Q}9%Ozn%>aC1pI|$64#8p|YWTQ}dz5jHB(zF~iTWNuc~)m#Qj_ zL}_U~Ei2=fOifOPAaV;P(aw&BiYg&JT|Mq6rpOS0Hkj%7_^;b5V>bj;Ra8JR0arNt zxD|T&$I_WEO@jEg^*K`N-`LBdfF0krA3r?yHy6OliRI1o;jOLAA(cF9o5_{ld5s|*SGg$Z`}@d zcR}a&%}r><_| z!=8o0^fP#jYimH~{SR>GOgpwb?T8K1| z!H34e7j;krx)2ooU~K{s($IJUF<(h3ys&VARTl-NDS8sgF?CCG^9%@zOiU|lYi>7h zeqUQ_a>Ag8hmBG-w!s?(NqzhUOCEa!f`j95hCet}=yn=t1Bmb)i98^lpy;xHE54FU zt4i7laKP7m?UU8|wfTg9tBZ)ip(dO0nmZ6swY0Rn4x6^=&pmlW3&)$h?%tjCs2%9U z1$N*L0Z33V{kr41t&fC)8{6ww2tq{yc3%VOhF-&TCG#5R>Tszrm0zz^`p{d);hFBe zQd}AweYW}j-fOvJM+b*z?YGi}-7Mg!6iDU0fOl}>3nm2?v#{%UN@k{onOWD9j^A-5 zNHeqNkk4WMATI|82m5U#@fyE@^D|%+R;8Qw`mxI$Vj5I&3Z|qFe?5?4eWsQNkXWw} z$x5M9HUZR4R73)GgalwyOE1t+LV>4iZhqUwrscWUojZl4rLPQ9fmlO|nD1dvO2!^5 z0IlRM@*Hl1(;hktaMWk(*RO0c8vlyY>gv02vIpjE*|fmfzR=d|$oV<~-^LOZvq{TE z6$M8I454zB3|KWPEsbHZVp(HNhc;v|zs^^J*%R@!no&P=dwUyDJ#<<>>xnQc3Jyu= zPC2|TFR%4k%Y@TYH;U@&OgPR#g@P1le?tQlOJC`uot&Lth%b+6_w$Ux=STO~1pWUw zK5?Ebzp4uJ`Ll}iEW^nTs-7DtVp=*>?U&;lYF`z=a< zX>j|MPhJ)jdL`EvvcXVY#qtTm#3CII9=|-wi#!9e5zEPL8z5RZx^^vj z1QeVKhrqRKeRNHr>JwEs%=iqssNeu!vKo?$3J&oM(28;V!O-iox%HF-h-oYy)e$o7ye`~f%q_i?IhN;rYEFX&Nw{(h<-qePGkg%utJBIFF~ if1ahlGKL1^F?oJ!_szJ7(>Bl$LRC>qp;XQ)^nU;kt_cPJ literal 0 HcmV?d00001 diff --git a/docs/images/SequenceStar.png b/docs/images/SequenceStar.png index b250307b5d794faa773c00c2111d737316aabd1a..212f7702667799f36a6f45f982812b2a5caa8d58 100644 GIT binary patch literal 8528 zcmZWvcOcaN|G!WnIgX5M&Isvb6H3ONnLRVYN%qK|b@r&UM|MIIxe$@;O-MG`$;x)- z@1@W8`~9u=AIH7NYdqi2@pwF*7x6${=_=`UQV0Zc6@`@7f2J zhtN$9r9(_iJU*lG6MUs`S1@qbc0#**TDV$6v>!ipcei%6eD;k50%3)q1gXuwQ8_pUK?Dc7!#LALL9z^o7~nm8Yj5_mJ%Q2#b^4qq{ejkEt7A$p~o0BV=S`R zvcKlt*juL6t(w{^?uBY_9s?uIIcm~p*Z9K?94|CVmrX-2-zV!}o4D^45C!G7*}&oY z&Q`a}vi$c(Ehy!9AP~ANaW*0d1W5;h+-(F)geC1 z;?TXXmKPTnXJ#l_SW5MZDQO_Bq@r>N)*q#2)BXJ}zrWv*m91}WZSC&vzG+<9+}zB1 z8Cb`ep?X@<_NBn zCE2sh{rx3p@xcO(v){#~zp4lhzc85Bv>Dm*)2#gJ&$F^YaF(oxQ!}*kb9Q^)0AvJY*ZtlL)7pLPGUpnPH9$p?EWQm@bh{$ApU?6^LAtEBe zUCYR5?0b#yR9aekd2K1v zcYVGi9&LS_`XUM8921SdimCw|)^XPi@~)&rO+%yJW6eliJyyLy%42l|*C(T*nUI{U z@9$q%#48~o@$~6aP3nc^W&F5P{U+Y826K4m1BF86h@-5T1Lv4S2MqZ2^!1bD%L(^73E59@pL=LA=@^_VV%hatL0)mqT6!&9+!3FLQ(MGq|2sZ*~yv+3pUd7JhkBy^iwKsg_b7dJ%?g~|q= z*0$K=&^z7wj`dnST=~W91lBjI0D(U<)$bjF&#f5~Jc%;gS z<));Fh)A(s$=24^tg|>98=F!rqhKPpUA`caj%|Ktc@UgpBv<06VfpKn_ZrVl^27PG z?3*X+bY_FI%vXc|L@*kvp-DmXH+uhPSpVMM)H7nlfqO zwDFFHhUUFl{nY3vp5^R7$=kd7M2GAak^o6(&MqzOe|n7X@9)=;J=sa*(+9ScyMI5K z-!LvCBjzW>{3^|qJH4^Hob)6G>F*@F2=Wz;muOhEMMu zg6ljLSgLAj_9vSKcpv<+$k(d29efiWPHZPpe|CB_`Pp-6aq+!z)q0HB6h(x5I5Pwh zXSqR-_Y1JFnE7DYMz<4{Tj;&LnE&R@>A~C!2L}h|WRM@wo|*j~KLsuXVMa@BJ~Dk$ zftbVBdWFWwCpaO$LPjfWFrSGautnlb%5@louES-Oen#K|NL=^saDY2rB9#6_gK@qh zV=eoLJxL%w7UZ+%cfiTSpPfI7h%;yORs5t9WJ>2uaefD@#h>VO#=O3Zo+Re*8G0s` zzt{dXm>0Mc%s+EJf)BV6vJSi3`1AZ*5EgSj+}BNCa2iYqyVOSvRviuh`{b{X2BF4> z1m?rAH-pQ-X~D5R`B`6ASNA+!Xj|5DMvqHos22?Ok55icUb}V;INa8J$JEqRJeOMT z{uLsExylDT)Wk$`Ip4;|jd`d^L*!(#WMfO|?Ox$kBFEG;@zlC4D=UbYBlXJC+(WB-^f;WZba$d?<4ZKEWW@he)X7z~;WrM8T5znnn z4VIHPyt14DWs$MBv&*Zp6%h_l0jo4NW;nU|@neKMdy&pzw@@E4U+btI4eL0tE0WA` zG&vhD3+(JH{Ph?)(*8hK_vy-ylH6SO620`SEHfP)I0dnsoZM@z8#fJrp9z;3<}Heh zjg0{t0Donc@iPDx(A3n_`FrT;aV09}YZaLYBrE3&+4NFJwSX!`l5PM)Bk0O;I9z$T z@bwtIVr$$e2%+1ls=SGzVPPuyT6rxvF)-@Z_VyK0(#J(ZPbz>xc@w|&GUQ1+qJ2H&%;IW-uS5HsAZ?ds)a?-K6NtO+)DXcOtJwc za9D|PmE-wSmO^Y65SXYJNpVq;g!``t%F2-q<_1-clfQ?G+bT2|B`-anIohb#K%q2? zbT&6Pi}g!mBO{-kFYy;5XcX_cK7mqIB_kv2?(3TdB?^St=Z!B?4ZBgfJfi7!<_*u{ zxiyj!651EGs-^>s*|C0`Ewq=OH?Z|p)nzCv=c0RGPfYMYp}aDgTE$G;?ycj;pCd>= z1poN)11ftA_Ut(QrLL$b0;1?RRZCAxOG`oV5{ngtEkw0gdV3V>VXeE`OY7q*MYq~m z=9@`i^b)bRXquKsJlsaE-X zupCOr$2=}iIW?pe^xnfoL|!mmV^%kL81Vus;hde7`!0iAL3&S#xY|FR-$?$>o%Z<- zs~I`1hbIP$^H%IIN}4M$v<6Ji$mp#O?}97-h3qLY>N-(IM#g8)4H{yibTKF9)~S_| zN}UJ{fDP)My<80qaH(`*vG_RHZBGIG&S2*2Xfk#hs+dq=5p1{W?A%~IMleB96V4M} zIP|(GVxnFn=@xfHgfz<5*6O!TT$*xP8WKffSn)P1mrlLyonu48`~c^`fSkKzxeJG3 z)%u55{r&S((mRc-s77TKl@Pg^N{4YtwX^tV!P;hKEa13yO~eGtIG*IQ$4^Pz9>+N! zb*p`-xY_)dnifxcgFG14z$0S-H|v#lKie2Qe*D;LDZ|sx-(P|; zwzPBugv$8H$m2DYQnUK?wY8IlWHT-5r>i3$va?y4U(ixg<_tY?c;)M|IwBaE3*hYr zQsZNy^4s!q8>u_5Bm<{hD-CgleEL4JXzN{jFCVSI_); z!538Mq@<)e-~CRj+vD{gYiiQE7RWd07e-ETG0|{t^_OpX2m0?tMxh?D8`jluqw?9A zncl4j^st{@QyUm$ zVd%BtiJWmiK1M1kmRerD%GuHJx;k}!0sHkXaN!~3`b4!`#xjm3z2eR5*Kiq`sjjZ5 zrWs5~2*`aCxjWx~{E*pfrrOzC8?U0hX*54GBj~*~A995j0MdAwQc{D7`@|A~r+!Fe zcyV!YR@QXVP2=eG=-k5jc`Gck`Oyc`D_72T3S=uPD(LG$a_Z>nDz2fTxQ+?9_sF02SfoBms!6fohx1WKR!#ZX9V@38snH0)*Vi#^9D@b% z`_tS#J#|IbuSUdjIXZ%K{r&R!zttq2gTh-D<9VMvX@9HR+!f_44u@kHCALx+4ftZb zd0UqU!FOkId48_T&^>M7ps!@q;IP@%3GIUz1~`ATvv_k`*y`9t5}ZDXHV-xLpoa|( zSR%y#6u$&8`r6tWfMnXBZcdwy0DFkpkC?B9T)ceQtj4`4KVP9>&|%_JKTpQVULz=q z&!0aBl`%a%T}4@Wu{YyrIWKIUT0uccY1((kPf9>wJ;>z=1>3aWcF$Oa-LgZfs>ed- zHQcQlKm67^L!4^8`%-TPX-Mw-_wP5B0bmE%c&B36l;J@$lu?|5l5z%NX>tEoj%5%v zOq2lDipDvxIEm^eacB9J*VfiLT@sRK?+4g;s;V$F^ip2%ntmgoG$Qd~^9u_L7hW*O zX;VM#n#Wfv=3$ld0lax(a{sknvA=M0SIL^tA7f+VuDQ)<1&7I+r@%pe5Nyqav2-qM zg@%S+5Um(sGkSVnwGEkim$vcM)z#1Gw0-Ad!~jeMCi$~gH7(=yCws%d7(~Ind-ssY z_Ar(JBsTz?PW`zG8q&J}KcwBZj$GF4eq1pIz^G{Y+Un}+{Jby-5RlieYpW%HiHMGN zcXLxwQ_JW14PY7Ogwvf$ok9VUz`1V zjJe|T3ksmQ*}$DEjMg?bveMEd-4?r#hU6&>wwi19Y2iP)jLQ(U$edjQP@ zHB?}*O*Z=1?%~#!>+^7Tc#w%-U(% z2Vjj1YNJ8XuWx`IWB^07kR>K2X1+jc0s2C3_PL|8^EMid8@)7WIN-n6ohoFrF;yq3 zSA@e24iAfQbKCU3l6aH!ZExl{H#Zl+dH<8$;rkmqq9P)j_+z#&_QHZE1VPx3w*2pK zIBhtrzmMuN+(J2j3)Bg~1B;4m0poS8p5P~RfX~g&MmO!{yR>Jo@L%kW`j9(HhgWwMxG{~ch=jx_NZ4~PWJM>7hF5^En+2Zi#>K_O z#>RqAK%I@!bv6N=MZsaXWKlfvaiuf~s#6W$x=la;Fo z!R%@o81TR%ZVL&4#V#)|@3?Le1hcZS1v7iyUR$sJ^yvVPcbKZJ#`kNlFo-#Vuyhe; zWMRpA_}PPAMauv1qddEdhX;Bjum5pwUf$%ygx4KYclVE*H{L23+S=Q{61LUS)lD2d z1)2lMC@OH+htXAFySkIT@i&&+XobY&L2SKbRFW8=1!WzB^2bYmcg80cny z{3t9VW6BkOjfRF?Kb3~F+rEz1j?XG21luRe{q*VUx{Tu;Dirb;cYVymP$8Rer2O|M z10%@qPuO9*{3T6gWyv?CslnWrcr8Rj!*>if%1ZATCcqf@oYDY6B!r=hF_dyZ+WFJT zR|;s!c)==R8i+6r8N56zh5hswf3IN^9FGMWY}c4=rGq=7<+QNkSX6mryDuJR!=n9B z!p(=gsEP{RzDt-XQ_u>G|l8RPP~^i|2;K#8{(gWg%o6_K+|U!Ej&L z1colzdNX>-M}pPD|HCqE^kPr?e%Gyf@QS~F{aSx^vH<{mgP&v+9a$(4y6TU&x_~22 zfD#U9n$lX82uoI<%JQy`w}ds~!NZ3-o?;5fz8XOkD#1t%f23Vh^u0SZ!G)l_;BYv3ES* z@6V0m>J$e&s)odddSd7bvaPHQGmsV&dpmF_%iel@Kt|DXv`TpBz!jXHw;g5Kf-6w} zkQ}3)2}=i?bCi^nk3M*fS2|GPlVc>Mq`>?M%K3L$y*BFhLtVN9!eMBK5dQo)lUn4C z&%k&2y;U|>Z&`fLkM2iwz5APNsi}2c!SrFbbEOKW*Q`e`#->^Yj$cBbucnNKJxsi4d3*ZTf9l8TR-SyxZs> z&$-)p*vNiAU{bGi*v8r#=&3+Yd_bMA!wV82I|m21TH3t%oCzpt(}8Do%K4prefqqK zq#=){YQ2FW671Nqs?F0Gm%9@ZHT(OiK3I@F$E0fM=p+Evj>Te=lev?-u91eA2mpBw zl*TzhNx&p!WzP=4)LfBH~HxOi4+hHT4SaLBG%~0TM1uR11dwA);NR1JWskOr8XP#AKIW6ms2D)QCu*Lm6axl5c6@wXUJgh$S8|t`*GvddXGn+$d<*C4 zlv7%iT%SL_*Q84hD0KoR)dfI^XU_vj0@@^T!GkbUYk9*to};; zL%@kog#2v)P)qbayDlh4<^um!%=2EaUINngIr!Syaj&T&2OBhx2G$rI9eq-fmKjTX z?V3WLo#3hZwWy)-P+%2lms?_D$(e&d)1;!L3`WQ`Lg*N>3i}^h-KM{(NK-JEs+@wY ztQ7T8*HBbcR8Y7m4W(D7f?fLBekfl91-b-Jq!thL&JnbGJNKq?$_-$@)+q5pH*iO|9f=g-yO+Nf>Cn^n-{_~F#l}EkNxjlqH=1C zYCmY2AGz4t-e8YF#^xcls27AObMLOc0Gjycw;J_VTO2uToua3av2CIfZ18TG265WE z>5McWkb+#u&O0ignev}j%S(j05J0z=$r-(XmV)<_32UN^knc*m`PqFL*2KoY!WtJ2 zXSbE|+IB1iX&r+hqKQgONT7znW`F-SGBixh$T-<-V>#O`4Xp4;SdMW+0iif zNBgRh&-IyDCMg&Uma@G%UIhs3G!T#gDgv}mRHee}S_+gt!WMIKi4-djU%MHHp+Js2 zAR!^aO4R6rn8-4a#Q{-i{a#Ze2{^;z z;=l$Qx%V7fT=+aIoJ<2A))`GNbh=-Ew##HHZ$*KUhsE=@UI0olQd#*?I|Ut`7kGqba^b911(kOnw3 zgV5^a=i%w;tRD3EDI^_F5mvhi*5*n9TRhOdzzK_pu`5us0?7sdyHvsuBzxQ*4Jtb1 z0tE32`agSKROvveYi((Xk?-KBb41zOuL5P}d>{e^u+Q#qE4u{2*`Gdn!Fh!~1#OIc zXc`)N3YsJ|Dnd7LWo6$$t7ml~?n4@>xjt6dVcSGtxUX-cM{F8&a1`K|`?&xqk_93- zu#CR`Fev$;SbhKgT`&S}iYWgIK>GPhS{^JI*GMF1lKg1XmkBx^0d7E(tTqWaJ@%H5 zo2h^5@9*#9<6~?*UT)n*(Gff_HN{LtrEO&71B7Lu_xkRy*KPMo`R=XK7bE2wyHRRt z56i70mNQH1PmS2I&f>4Y1cAFl`fr#v&YL`}tU*mPL_|cZ)AiGz>cQ3k0Rg2*`;96J zi7YHCqIdWIXjGD(J`P+`ow)x=#mOSzs>^`BQ=l$=GI_7VI|)oQRIE?g5ghmG)$w<2 z4gc*PF+hlcK(yEl5AvT1d2p!48w4V@o?3kvJS7sg&mL=IA8n~{SU857miFlA zX#Dxfhhk)!V^wA4)E9r>rqHXTAp}^)$8ejTw5PkjbPq58b6ls2LdI5IQ`r_7? zgWUclD!E^QTsxI9d^{q;!r}6{4KY&g?(XeY<$HS`a!3bW2P(lYUq=Zf+tvJzjj{CRphh867Wk~jOeQ8LS5{VHSXO@j=3$_D$jis4 zf<*q=+RELav9Vcd5J?8%cM2$;aDb|+s<1=0N5J{8YTH#+RkYO9Ksl}heYfy=uVh4Y zNU9KMo&tAeqbUatPA`O>sPzU?01jv%#l>B-O{)Qc2rf=eYoN%to&X12@qAEUUhWFu zTsXW*V*|Y9?Ck85qkSRhH`X{B4hjFm9YFLh`0s`*!eHoF6M?>t4#9wg4l7WtT3@_D zk@4{W7PR&pD)VP=5Aa6Wv*Yc%N^HwyLqkK?W8UQCG<-ZO?SK5XxS0NTR($++a{ci| z>_=6!y@FOUoT{ZGz0HGX^P1qv=mgAQI?LKH77b%k)3m!yg{jeEM|m z+Y{CCO*3@y?@F@WfoN7%h9D1{1G&R)_&s5kJg3NWkdWXaK!5IZtLqkUPJkI3 z8X7>)KXp#Q*8RtI1yCj|k`bb<8%GK`58zx}Q+2+>!^55@hr8*b4sxnsi~;o^%x)iO z9)K=sj5w%7ubG~qu0bF`mrDU{Sga{!hal+sg90V-g&n1tFn9Kh5&}_#{r8Us{$Jyt bi{=c9dDJ32fW03K_6k8MsLQ{XGk^A9K96Ym literal 8038 zcmZ{J1yod9`0pTsNQtC?k|QycfPi#&iik8y4BaJ-igXC$&>;;X(gR2tgfN7pq)2yz zzyQPBc<=wN7wer_>&(nK`|LP-f8Q^5q>h#{2_YRJ1Og#ZRZ-A|KyZA(?^c2<;2h;l z)CRtAJ>*pN2nYx!XSIKWzhs_@2A+>x;GRCu+^r#xY`r`^t=%nO{Dbb3&Y=)=RCshlikWZQEwg0-biK0X_xkhZX|S!-qhSIR9M>=>{YCpKDRC z$?lDfk24c=Fp)=gcXyLr3qkeBm@!{z9x z|DTQB{e2HlPfrhzba9`Lx+PX>{TZSZl$33=u1(F&tys)@U!PXt%FG3}uC7ibz4y=I z;dG-9pX5^g>37R>q2>{|jg8Oo&a5he&Fw+PK%O$6QB5%lr60_fs?jm)Dj_L(hS)xFh>IIT$vKhT z9UUE0QzkcV+`#a9w$k*_;nqH+T-@HyMj(d9#*Tk~d4)$r-PYMTq-fKhbw?1c0f)ma zEiLWrR&y1jiJw@XjhPcC;-6oE3A!RhefOZ*{n>&xeRVTI{)^qn%Q30&CYv|=Ax{j< z%(mv|<@th-XTxp!G6u@?wUPWf^okFEmYdr|F-ZC?tgWf>wI2QQSB_`c)Gd1P{++CCJE&LJfbJ!r&A{0uPi)(#tr1a$E#HdVIQu2J-XQqIoySKNjrNzwrK^O`BpM@@p zs9Y0M)8O;NCk*k*KXuH_x98^M2r8@B{rFOZ@a?OstNr&Dx+iCc>eValY^mvaI0c(V zeZYyp{w}CB=IJ^1bi2n7sn*U-U)&3M@!~~8LxZV4=?56(H@1broQ<2Co0T>1{rmUL z&CU7wP${XPuEe{Z3355EZf>fYnq?&=1FN2duUTNQC|=BNC!@b-@cjHd4Y$G0?=QHS zT0XO1@q&Ycm$q&d_lBe+($m+swz81Of^95aF<}dF$f<)j41quhI*fAL*x2wUudlD4 zw$qs37ZTzxP%98%VfotC6^UL{Qc&QaBrN2(dsh)kF8biX@$vD-cy;*bYp|9Sqp3lk zE5{v6^!!$SFbCqTmI>p+9JE+l^BqqDMgnkMKP zj1%x*q_PSBzIpZk8?hj=KPx<43a7EXpSCq*@p3Cdf#oXBJ03x@o=tJMqM{<#laDoZ zbrQpmC+CL$sN1d4e}Ktpr0BnO9WUxui!uP*^<#e zV@*xX_wV0@97aP!Ll01k4IazhTT_NQI&V@^j=>xdy_QqB!DM+w>8`Q_LwRvAhot0m zNSh9&P$1@@r>7@77~4==OJzqXV~kG>6%}B}e+crH8RtL0Xen-~xLZl60cCsDTLg7vag~7W>${~rAT7Ggw3wQhm^^$aizaOTJnL#pMHZ=018TbB zmwb~|ss7WaL9_&ewmBPvbdZGmf=W~_=#Hn@o#s8T9?Htf4g`1%dLDw{GBP$^&HJ&& zN=bN^ylc{>l_x=^=K>qqo^*7@w$_M9*E=>WDk7xY;BB|wd6I7t&ks53W z73h3tJWZs64y`dR%n}DSG(Mi1ob0nZrwHoREivFu(u0u@5WG==e);l+JTkP)x+ivY zRKM0J@br(95y@j1Qoj_b0?o5{1=`$S>J_X^$3?#A9*gRxq@=w4!1Xsk zIMAM$m|yo>PGKQJ^`fE0Udhw5 zCO%%<+xw5sFdzA0b8oJq)h~&?;0t9Vrjhn`|4T-<|g zREC(B8kC&Jq<&}iTX;m~E(c{)NJt1s8-s(oL#4#Y>TB!%Jd%NFDg|u=3D12KV(C?t zJEL>ATiMOb+P=IvK7J$VpVjX`bc4x!mvmB`qZ?v zoQSRY#f|`0)jh)p{ zp^f7BxB`?#?XI08w4tHxTb|2b+`btcoQRO8qwjik&Fae)a>k1fD;tIaaN@2WXl!hL z&0B7xVdcm8yhZ2+Jp4o=8Wj)00sF4C5h(v|0S_z7_w!R*bV_XZTO{)O)t6<)b>1r% zMY!ihEiF=PY;0iZRDGqx{zG?)%%JGCR!iO0(UE$GLDZWjIlfN z?n^!D$b%9AeEU2O_j62iu5x@t>3a3z(Jxlzc<-_y8PJDLnU3KfGNE6SQBA%Sw21NI zo^Rnd?vkszy9>M&GKfv9|9i;Zq+>M?NuzV$VKQt^yNY+SGKG>-!nl8#!r$M*MLUdy z)!REX_j|>&{wNa@Gc}F1HH<#(C0p{{%U^D;H_Ux+L}G<-7q@BWfD0-6^G~kV;l5s(vlAwzJfM3d3sA-2pR|C zVYp1XiHV;M?LW0CU%$b=KAI3kI5;3{WMl>t!rHy=ZW0STuzFf%j5klo)&w+{|HqjL2>n%H5?+P|y3ui6`TcfIF@@$666Op!5d zIh&hrkM5^7F)f)14z4u2h$0z=hkTZSiPWvD&6f_g-lmTB+gnf^7%3f2HrL(SqKsBN z-y^~xdaKw0i0Tz*qgyOWRksa5tRu+i>rLN)8h*FH{IQJWQ4u$3Y2&tr-r)OaIxxc61`}h`ztN zrclI6!%G%?L9=-Ux0coxy|6^?CWT}+H1$kl1$P*Y`QdH6GHBaN=g z_NJQ$tD|s&T33!dUvni8A@vuh$8Ic0a^ds{g@w;Aq}~g-igw0RRHlqgN|&BtyaepX zpH)YOUmLFk=#~UyO-55;Ze$L?1nma%gU{E^y}Z1foSZJsw}XL(Xsol|nrf)FAAuF} zP~5upeD>?>r6qWoexu)^z0x$s5xuauh=-34bd`{h5HcxAD_z)WXkSV@DwlUn`ZAFsA)Jy}Zk_V&(GiXEIm--97xP-tko z#rWjp4SHe6jj_t3t!YcO!{uiLL_{9$?%h2-`5bEiKtta|Qn1qnKLld{eF7qEwbBz5 zEz-)&WyclD0&+12D|QzG-^7N6hhHKC#EDk!dvCf(ozo;W4bAe#M#kH>!_ zWEo3yb93|Z0P4OTukS|@hkq;CDCn;~ZCPDi1q3DZO)HpaT3Xs3KUTrQbP<=9!%<^9 zJG+kC=vx*R7Pdp(EE58#>k|U<>HGk=`Nx%mABW9?Zh~R0xxMP{R{OckDwCO!k>Yj) zWSEsOywV^OlPBI-mMY=9w>8}uD^U;^N2;ye4?5n3U|(OB>S%0jZ*K<)V!F;{rZl{z zvNEA_zIm>WWao;EHMg;~n3!0oTu#D;>vI#?`&&p znmhkS1VL6hBAG)esi>~M{t66)pb`xL*pgJd+5Pdcu?3oB=l6R7A4H=arayUU_KP!@ zo3~2Y4MK&}H)m%nEjvjIQGixPw_Eu8`{O#iRkK!52t^<$lF_jd5l=DgegXT8fC*c) zMF7sr3$)%k$Ol}MgofOsfVxSaA3O@=s#AZwxVSjq5o;+{jsH#nqqQ7dMRYe|`ohg4j=(QUrNY5LQl zS8u?_0b6))8Zt34F+Cl9ro{$HIXa?c3_KVBt_sj$uU@`%=k}N|m{`md^(b7uF+DNy z$!@67=a(=0{rd+UvGmltll71kizbbDD;t|3guDK_wkrX#QV)PiUS4Mofm+@nojDf{ z>>K`67Rx~!%)u(?GdaQ4prD}O6SVo(uV$ixtpq?u!5h`i6!SV<8xi-}lJGlN(Xp}* zH5km6OF+D-c$2%KUyfZ^&L-kstl1UhWa~~jpyjt{lfF3V2Z^}C;KL26@Q3KhRe);kxNW`3!gtbO@04q&K7inknl1Dl=m}US|A}Prmtd1W)e!M242|5^1zD-(m z3itMwl=cE~1;)$6qgkfkpDis7*a{SSbv%sf-gj7@wws%qzP>)liqD?q0HK9m6iDTM z@F1mg-q0f7Q!LY{ti^jXO}9jkgHlRLDj^{Oh^Ol$B-WJ%!p@Di#XLDcwM=B(CiVB2 znZN9~&>j^E5K~c6UAw`cp{~BZv0(xbMNaNzELudbV+{XNXK{1um5#6~#k}dV0@cEh zS{V-p92wsMs0O+2J-DD&pkFFPrzs;7qQOQ)LXs&JC>BK71Qa4G>nm&)tPD>n4tMR5 z^({goBD?cM6{vbLZ>FR_>NPg{Wj7fG<7J8iX{?Z{sG>rrXsFAoDkKDwb1BlMr>9r( z5JF^P;^JIj8Npz{$dKVH9z zc=dqn0{;T5)n?t)eNSX%s=)&!2Io%J1yjdP)LH#Y9$m&f_0V8eHBm(n*>)r3yK2k?Ef{@k(G2=Qh{lSiF;qJ zG44E<5KiZzBwX%IzjQ2d8^;dgc%)?_pe*C;s0W>Xz?*b*{E(SBoy23DuUnFrXK8J1 zZD#fhIK9~8PU%0WWb6;_7&Ara&90!QVV1FBepiS8Y)%4hN#X+hJO&pRmuuIqxwvct z_r#0w`oxTBn8j7S>=$y-o2niW`8@Aq^kCzk4u5)eIb97P=h<#w;XJp*Y(Rseq zL;KCArr-3#-n0xTU#!vZ+Asx@AufH>1@@F(J8QVr7{RVB9H4wU)ef5>0q-WX`v9;Y zJ7?#u-A2~~Wne#i`Xp9Z^YLRJh_9VHn;tZ!0U~6o3WF&s6Bdj^^=|Xnqt**Ak)q$S zEQt|Nzp88DAT)W5QMblE_xEoP7O3}hf<%frJ*EHX0cm7PjL0uj7{nJWM4?bSJ3Gb2 z#eggTi5C|a2TXGSEisWDfZ_pn$KAt&o}M0PCP@j27`F-HZ42aPz-15lhPVJFQB_q1 zd;+LoA6HjUk-;a=)mn$2DJ0(8zrfvIi^`a7q5DnIk6Y-$T-a$qd)=V%2He7M3ub!d zya5FTgzZ2fWRRR1SknnSgeT!Qa7^$dgz1H5C%DV~R5)FXqx^w3a$aB9eoiJY1R8+uJ_M$b#e!`gd!V)psoZ;Vg z_x3Og2yMWGZ+78GAb@BDEO+PV$j8(3HgFS7c>8;L?i)hOa(Fy|bUc~~p85InXMol! z*t=---c-}n-1Jb7RA51LX=O{rs?Z(N7?_)9Bat8}in;ufP^fCHsjbya6)5=dVFP$b zKpwXQUtn#r15pk?c@c_(bb4%pf*!y;#yEh^vQtNoJE8zQ1EP9poZ^49b-26xta==P z%IVRz%_!i3ZSCz1pFYLW3BiPgQH6!@&&zqbB^enRNqpv71P@E}0-dFOwx&R$WlF^V z?fQT`(rSIQ?8!$HS?H;{uI^yEOUnrmG^eMh)#Hu~@gl&FLwo05;Ro(`$`3FD+~eipDyvSmOCKAqP@M zDGh>gz!t%8VjGRnH$Vb`0P(P0PJawNOg1($`d5uLn8d045lOtbh6P?BJUSY8M;ryr zi2mDI=*6^ejnDKGHn0=G3WroL0aOP>Nm5c02;76QS7Xa>cLBWzNDUt? zDk?f!#d)HyA4e;QpK$-)i4@p>J35+a4Q_o_4N2JGPi$#v0lMN`?BKT&SPn{T2;grD zG6HY~n`eg1DMP<;*Vlvjx-~b;O5^4oi;1#vzla*8$M8WcCZc$i|c4bKK`GoBkslY0LV63(!nk0?)~L{?TiPNb*6x$_u6o$ zo+wnQ=XLxiS}^cyEOrvWtGNJq8%lmXy*Fq+R-{lX)9=rQAqX-xc;!TsuZNzVUc4d* z1z?xAnM6iKO;lN
Oxh8m+7&1>8*~I8H4WP;o*Uuvq_W_tA4m0{JA`U zfhY0#Uf7pqCcN?S@vT1FSw%(5V1xGO2Sa%rkbwd;4T`$C4XdocX4>NJ(V+QHTCx6L~XbN QxC2pD)Kd5;_w?oe0yfx%*8l(j diff --git a/docs/index.md b/docs/index.md index 7f143d951..a04ff7855 100644 --- a/docs/index.md +++ b/docs/index.md @@ -18,6 +18,9 @@ which are loaded at run-time. - It includes a __logging/profiling__ infrastructure that allows the user to visualize, record, replay and analyze state transitions. +![ReadTheDocs](images/ReadTheDocs.png) + + ## The problem Many software systems, being robotics a notable example, are inherently @@ -42,17 +45,17 @@ If we don't keep these concepts in mind from the very beginning, we create software modules/components which are highly coupled to a particular application, instead of being reusable. -Frequently ,the concern of __Coordination__ is mixed with __Computation__. +Frequently, the concern of __Coordination__ is mixed with __Computation__. In other words, people address the problems of coordinating actions and take decisions locally. -The business logic becomes "spread" in many locations and it is hard for the developer -to reason about it and to debug errors in the control flow. +The business logic becomes "spread" in many locations and it is __hard for the developer +to reason about it and to debug errors__ in the control flow. To achieve strong separation of concerns it is better to centralize the business logic in a single location. -Finite State Machines were created specifically with this goal in mind, but in +__Finite State Machines__ were created specifically with this goal in mind, but in the recent years __Behavior Trees__ gained popularity, especially in the game industry. diff --git a/docs/tutorial_A_create_trees.md b/docs/tutorial_A_create_trees.md new file mode 100644 index 000000000..9ff7120cf --- /dev/null +++ b/docs/tutorial_A_create_trees.md @@ -0,0 +1,230 @@ +# How to create a BehaviorTree + +You have mainly two ways to create Behavior Trees. + +- __Statically__, at compilation time. +- __Dynamically__, at run-time, i.e. parsing a file. + +You are __strongly encourage to use the latter approach__, but we will describe +the former for the sake of completeness. + +## How to create your own ActionNodes + +You can find the source code here: [dummy_nodes.h](../sample_nodes/dummy_nodes.h) + +The default (and recommended) way to create a TreeNode is by inheritance. + +``` c++ +// Example of custom ActionNodeBase (synchronous Action) +class ApproachObject: public BT::ActionNodeBase +{ +public: + ApproachObject(const std::string& name): + BT::ActionNodeBase(name) {} + + // You must override this virtual function + BT::NodeStatus tick() override + { + std::cout << "ApproachObject: " << this->name() << std::endl; + return BT::NodeStatus::SUCCESS; + } + + // You must override this virtual function + virtual void halt() override + { + // Do nothing. This is used by asynchronous nodes only. + } +}; +``` + +As you can see: + +- Any instance of a TreeNode has a name. This identifier is meant to be user-readable and it + doesn't need to be unique. + +- The method __tick()__ is the place where the actual Action takes place. +It must return a NodeStatus, i.e. RUNNING, SUCCESS or FAILURE. + +- The method __halt()__ is used to stop an asynchronous Action. ApproachObject +doesn't need it. + + +Alternatively, we can use __dependecy injection__ to create a TreeNode given +a function pointer. + +The only requirement of the functor is to have either one of these signatures: + +``` c++ + BT::NodeStatus myFunction() + BT::NodeStatus myFunction(BT::TreeNode& self) +``` + +For example: + + +``` c++ +using namespace BT; + +NodeStatus SayHello() { + std::cout << "Robot says Hello" << std::endl; + return NodeStatus::SUCCESS; +} + +class GripperInterface +{ +public: + GripperInterface(): _open(true) {} + + NodeStatus open() { + _open = true; + std::cout << "GripperInterface::open" << std::endl; + return NodeStatus::SUCCESS; + } + + NodeStatus close() { + std::cout << "GripperInterface::close" << std::endl; + _open = false; + return NodeStatus::SUCCESS; + } + +private: + bool _open; +}; + +``` + +We can build a `SimpleActionNode` from any of these functors: + +- SayHello() +- GripperInterface::open() +- GripperInterface::close() + +## A static Tree + +Let's create instances of our TreeNodes and compose them into a tree. + +- `BT::SequenceNode` is a built-in ControlNode provided by the library. +- `BT::SimpleActionNode` is a synchronous ActionNode created passing a functor. +- `DummyNodes::ApproachObject` is our user-defined ActionNode. + +``` c++ +#include "dummy_nodes.h" + +int main() +{ + using namespace BT; + using namespace DummyNodes; + + GripperInterface gi; + + SequenceNode sequence_root("sequence"); + SimpleActionNode say_hello("action_hello", std::bind(SayHello) ); + SimpleActionNode open_gripper("open_gripper", + std::bind( &GripperInterface::open, &gi) ); + SimpleActionNode close_gripper("close_gripper", + std::bind( &GripperInterface::close, &gi) ); + ApproachObject approach_object("approach_object"); + + // Add children to the sequence. + // They will be executed in the same order they are added. + sequence_root.addChild(&say_hello); + sequence_root.addChild(&open_gripper); + sequence_root.addChild(&approach_object); + sequence_root.addChild(&close_gripper); + + sequence_root.executeTick(); + return 0; +} + +/* Expected output: + + Robot says: "Hello!!!" + GripperInterface::open + ApproachObject: approach_object + GripperInterface::close +*/ + +``` + +## A dynamically created Tree + +Give the following XML stored in the file __my_tree.xml__ + +``` XML + + + + + + + + + + +``` + +Note that the following syntax is also valid: + +``` XML + + + + + + + + + + +``` + +We must first register our custom TreeNodes into the `BehaviorTreeFactory` + and then load the XML from file or text. + +The identifier used in the XML must coincide with those used to register +the TreeNodes. + +The attribute "name" represent the name of the instance and it is optional. + + +``` c++ +#include "behavior_tree_core/xml_parsing.h" +#include "Blackboard/blackboard_local.h" +#include "dummy_nodes.h" + +int main() +{ + using namespace BT; + using namespace DummyNodes; + + GripperInterface gi; + BehaviorTreeFactory factory; + + factory.registerSimpleAction("SayHello", std::bind(SayHello) ); + factory.registerSimpleAction("OpenGripper", + std::bind( &GripperInterface::open, &gi)); + factory.registerSimpleAction("CloseGripper", + std::bind( &GripperInterface::close, &gi)); + + factory.registerNodeType("ApproachObject"); + + // IMPORTANT: when the object "tree" goes out of scope, + // all the TreeNodes instances are destroyed + auto tree = buildTreeFromFile(factory, "./my_tree.xml"); + + tree.root_node->executeTick(); + return 0; +} + +/* Expected output: + + Robot says: "Hello!!!" + GripperInterface::open + ApproachObject: approach_object + GripperInterface::close +*/ + +``` + + + diff --git a/docs/tutorial_B_node_parameters.md b/docs/tutorial_B_node_parameters.md new file mode 100644 index 000000000..5b1a27d2a --- /dev/null +++ b/docs/tutorial_B_node_parameters.md @@ -0,0 +1,201 @@ +# How to use NodeParameters + +NodeParameters are like arguments passed to a function. + +They are a map of __key/value__ pairs (both strings) that are usually +parsed from file. + +To create a TreeNodes that accepts NodeParameters, you must follow these rules: + +- Use inheritance. NodeParameters are __not supported__ by *SimpleActionNodes* nor + *SimpleConditionNodes*. + +- You must provide a constructor with the following signature: + +``` c++ +MyAction(const std::string& name, const BT::NodeParameters& params) +``` + +- The following static member function must be defined: + +``` c++ +static const BT::NodeParameters& requiredNodeParameters() +``` + + +## Example: an Action requiring the parameter "message" + +`SaySomething` is a simple synchronous ActionNodeBase which will print the +string passed in the NodeParameter called "message". + +Please note: + +- The constructor signature. + +- The __static__ method `requiredNodeParameters()` contains a single key/value pair. + The string "default message" is the default value. + +- Parameters must be accessed using the method `getParam()`, preferably in the +`tick()` method. + +``` c++ hl_lines="5 9 18" +class SaySomething: public ActionNodeBase +{ +public: + // There must be a constructor with this signature + SaySomething(const std::string& name, const NodeParameters& params): + ActionNodeBase(name, params) {} + + // It is mandatory to define this static method. + static const NodeParameters& requiredNodeParameters() + { + static NodeParameters params = {{"message","default message"}}; + return params; + } + + virtual NodeStatus tick() override + { + std::string msg; + if( getParam("message", msg) == false ) + { + // if getParam failed, use the default value + msg = requiredNodeParameters().at("message"); + } + std::cout << "Robot says: " << msg << std::endl; + return BT::NodeStatus::SUCCESS; + } + virtual void halt() override {} +}; +``` + + +## Example: conversion to user defined C++ types + +In the next example we have a user defined type `Pose2D`. + +``` c++ +struct Pose2D +{ + double x,y,theta; +}; +``` + +If we want the method `getParam()` to be able to parse a string +and store its value into a Pose2D, we must provide our own specialization +of `convertFromString()`. + +In this case, we want to represent Pose2D as three real numbers separated by +semicolons. + +``` c++ hl_lines="6" +// use this namespace +namespace BT{ + +// This template specialization is needed if you want +// to AUTOMATICALLY convert a NodeParameter into a Pose2D +template <> Pose2D BT::convertFromString(const std::string& key) +{ + // Three real numbers separated by semicolons. + // You may use if you prefer + auto parts = BT::splitString(key, ';'); + if( parts.size() != 3) + { + throw std::runtime_error("invalid input)"); + } + else{ + Pose2D output; + output.x = convertFromString( parts[0] ); + output.y = convertFromString( parts[1] ); + output.theta = convertFromString( parts[2] ); + return output; + } +} + +} // end naespace +``` + +We now define a __asynchronous__ ActionNode called __MoveBaseAction__. + +The method `getParam()` will call the function `convertFromString()` under the hood; +alternatively, we can use the latter directly, for instance to convert the default +string "0;0;0" into a Pose2D. + +``` c++ hl_lines="20 21 22 23 24" +// This is an asynchronous operation that will run in a separate thread. +// It requires the NodeParameter "goal". +// If the key is not provided, the default value "0;0;0" is used instead. +class MoveBaseAction: public ActionNode +{ +public: + + MoveBaseAction(const std::string& name, const NodeParameters& params): + ActionNode(name, params) {} + + static const BT::NodeParameters& requiredNodeParameters() + { + static BT::NodeParameters params = {{"goal","0;0;0"}}; + return params; + } + + virtual NodeStatus tick() override + { + Pose2D goal; + if( getParam("goal", goal) == false ) + { + auto default_goal = requiredNodeParameters().at("goal"); + goal = BT::convertFromString( default_goal_value ); + } + + printf("[ MoveBase: STARTED ]. goal: x=%.f y=%.1f theta=%.2f\n", + goal.x, goal.y, goal.theta); + + halt_requested_ = false; + + int count = 0; + // "compute" for 250 milliseconds or until halt_requested_ + while( !halt_requested_ && count++ < 25) + { + SleepMilliseconds(10); + } + + std::cout << "[ MoveBase: FINISHED ]" << std::endl; + return halt_requested_ ? NodeStatus::FAILURE : + NodeStatus::SUCCESS; + } + + virtual void halt() override + { + halt_requested_ = true; + } +private: + bool halt_requested_; +}; + +``` + +## NodeParameters in the XML + + +To pass the parameter in the XML, use an attribute +with the same name: + +``` XML + + + + + +``` + +Expected output: + + + [ MoveBase: STARTED ]: goal: x=41.2 y=13.5 theta=0.7 + [ MoveBase: FINISHED ] + Robot says: Destination reached + Robot says: default message + + + + + diff --git a/docs/tutorial_C_blackboard.md b/docs/tutorial_C_blackboard.md new file mode 100644 index 000000000..6d72e6d7b --- /dev/null +++ b/docs/tutorial_C_blackboard.md @@ -0,0 +1,112 @@ +# Blackboards + +The blackboard is a a __key/value__ storage that can be shared by all the Nodes +of a tree. + +The __key__ is a string whilst the __value__ is a type-erased container (called `SafeAny::Any`) +that allows the user to store any C++ object and to cast it back to its original form. + +Contrariwise to `boost::any` and `std::any`, this container will also try to +avoid common overflow and underflow errors. + +You can't cast a negative number into an `unsigned integer`, +nor a very large number that exceeds 2^8 into a `char`. + +If the __value__ is stored as a string, it will use `convertFromString()` +to cast it to the type T (see [previous example](tutorial_B_node_parameters.md)); + +The user can create his/her own Blackboards backend; it is possible, for instance, +to create a persistent blackboard using a database. + +## Assign a blackboard to a tree + +Let's start with the a `SimpleActionNode` that writes into the blackboard. + +``` c++ +// Write into the blackboard key: [GoalPose] +// Use this function to create a SimpleActionNode +NodeStatus CalculateGoalPose(TreeNode& self) +{ + const Pose2D mygoal = { 1, 2, 3.14}; + + // RECOMMENDED: check if the blackboard is nullptr first + if( self.blackboard() ) + { + // store it in the blackboard + self.blackboard()->set("GoalPose", mygoal); + return NodeStatus::SUCCESS; + } + else{ + // No blackboard passed to this node. + return NodeStatus::FAILURE; + } +} +``` + +Let's consider the following XML tree definition: + +``` XML + + + + + + + + + + +``` + +The root SequenceStar will execute four actions: + +- `CalculateGoalPose` writes into the blackboard key "GoalPose". +- The syntax `${...}` tells to `MoveBase` to read the goal from the key "GoalPose" in the blackboard. +- Alternatively, you can write a key/value pair into the blackboard using the built-in action `SetBlackboard`. +- Similar to step 2. Pose2D is retrieved from "OtherGoal". + +!!! note + For your information, __GoalPose__ is stored as a type erased Pose2D. + + On the other hand, __OtherGoal__ is stored as a std::string, but is converted + to Pose2D by the method `getParam()` using the function `convertFromString()`. + +In the following code sample we can see two equivalent ways to assign a +Blackboard to a tree. + +``` c++ hl_lines="13 14 15 16" +int main() +{ + using namespace BT; + + BehaviorTreeFactory factory; + factory.registerSimpleAction("CalculateGoalPose", CalculateGoalPose); + factory.registerNodeType("MoveBase"); + + // create a Blackboard from BlackboardLocal (simple, not persistent, local storage) + auto blackboard = Blackboard::create(); + + // Important: when the object tree goes out of scope, all the TreeNodes are destroyed + auto tree = buildTreeFromText(factory, xml_text, blackboard); + // alternatively: + // auto tree = buildTreeFromText(factory, xml_text); + // assignBlackboardToEntireTree( tree.root_node, blackboard ); + + NodeStatus status = NodeStatus::RUNNING; + while( status == NodeStatus::RUNNING ) + { + status = tree.root_node->executeTick(); + SleepMS(1); // optional sleep to avoid "busy loops" + } + return 0; +} + +/* Expected output + +[ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.14 +[ MoveBase: FINISHED ] +[ MoveBase: STARTED ]. goal: x=-1 y=3.0 theta=0.50 +[ MoveBase: FINISHED ] +*/ + +``` diff --git a/docs/tutorial_D_subtrees.md b/docs/tutorial_D_subtrees.md new file mode 100644 index 000000000..4ebbbd243 --- /dev/null +++ b/docs/tutorial_D_subtrees.md @@ -0,0 +1,60 @@ + + +One of the main advantages of Behavior Trees is that they are __intrinsically +hierarchical__. + +You might have noticed that it is always possible to raise the level of +abstraction looking one node up in the hierarchy of the tree. + +In the [Introduction](BT_basics.md) we presented this tree: + +![FallbackNodes](images/FallbackBasic.png) + +The Sequence called "Unlock" can be seen as an entire subtree; from the point +of view of its parent, that subtree can have an arbitrary +level of complexity. + +__BehaviorTree.CPP__ provides a way to create reusable and composable Subtrees +that can be included as nodes of a larger and more complex tree. + +## Example: subtrees in XML + +To define and insert a Subtree you __don't need to modify your + c++ code__, nor your existing TreeNodes implementations. + +Multiple BehaviorTrees can be created and composed in the XML itself. + + +``` XML hl_lines="21" + + + + + + + + + + + + + + + + + + + + + + + + + + +``` + +The corresponding graphical representation is: + +![CrossDoorSubtree](images/CrossDoorSubtree.png) + diff --git a/docs/tutorial_E_plugins.md b/docs/tutorial_E_plugins.md new file mode 100644 index 000000000..896023301 --- /dev/null +++ b/docs/tutorial_E_plugins.md @@ -0,0 +1,129 @@ +# Plugins + +In the previous examples we linked the user-defined nodes where included +and linked statically into out projects. + +We used the `BehaviorTreeFactory` to registed manualy these custom TreeNodes. + +Alternatively, we can load user-defined TreeNodes at run-time using +pre-compiled __dynamic shared libraries, i.e. plugins__. + +# Example + +Let's consider the [first tutorial](tutorial_A_create_trees.md). + +To do this we must encapsulate the registration of multiple TreeNodes into a single +function like this: + +``` c++ +// This is a macro. Just deal with it. +BT_REGISTER_NODES(factory) +{ + static GripperInterface gi; // we can't have more than instance + + factory.registerSimpleAction("SayHello", std::bind(SayHello) ); + factory.registerSimpleAction("OpenGripper", + std::bind( &GripperInterface::open, &gi)); + factory.registerSimpleAction("CloseGripper", + std::bind( &GripperInterface::close, &gi)); + factory.registerNodeType("ApproachObject"); + factory.registerNodeType("SaySomething"); +} +``` + +!!! note + This function must be placed in __.cpp__ file, not the header file. + +In this particular example we assume that BT_REGISTER_NODES and +the definitions of our custom TreeNodes are all defined in the file __dummy_nodes.cpp__. + +If you compile the plugin using __cmake__, add the argument `SHARED` to +`add_library`. + +```cmake +#your CMakeLists.txt +add_library(dummy_nodes SHARED dummy_nodes.cpp ) +``` + +In Linux the file __libdummy_nodes.so__ will be created. + +The [first tutorial](tutorial_A_create_trees.md) becomes, as a result, much simpler: + + +```c++ hl_lines="3 25" +#include "behavior_tree_core/xml_parsing.h" +#include "Blackboard/blackboard_local.h" +// #include "dummy_nodes.h" YOU DON'T NEED THIS ANYMORE + +using namespace BT; + +const std::string xml_text = R"( + + + + + + + + + + +)"; + +int main() +{ + using namespace BT; + + BehaviorTreeFactory factory; + factory.registerFromPlugin("./libdummy_nodes.so"); + + auto tree = buildTreeFromText(factory, xml_text); + + tree.root_node->executeTick(); + return 0; +} +/* Expected output: + + Robot says: "Hello!!!" + GripperInterface::open + ApproachObject: approach_object + GripperInterface::close +*/ + +``` + +## Display the manifest of a plugin + +BehaviorTree.CPP provides a command line tool called +__bt_plugin_manifest__. + +It shows all user-defind TreeNodes +registered into the plugin and their corresponding NodeParameters. + + +``` +$> ./bt_plugin_manifest ./libdummy_nodes.so + +--------------- +ApproachObject [Action] + NodeParameters: 0 +--------------- +CloseGripper [Action] + NodeParameters: 0 +--------------- +OpenGripper [Action] + NodeParameters: 0 +--------------- +SayHello [Action] + NodeParameters: 0 +--------------- +SaySomething [Action] + NodeParameters: 1: + - [Key]: "message" / [Default]: "" +``` + + + + + + diff --git a/docs/tutorial_F_loggers.md b/docs/tutorial_F_loggers.md new file mode 100644 index 000000000..b033c54ab --- /dev/null +++ b/docs/tutorial_F_loggers.md @@ -0,0 +1,87 @@ + +__BehaviorTree.CPP__ provides an extensible set of Loggers, i.e. +a mechanism to record and/or display all the state transitions in out tree. + + +## Example + +In this example we attach multiple loggers are attached to a tree. + +To do this, we pass the root of the tree. + +```c++ hl_lines="21 22 23 25" +#include "behavior_tree_core/xml_parsing.h" +#include "behavior_tree_logger/bt_cout_logger.h" +#include "behavior_tree_logger/bt_minitrace_logger.h" +#include "behavior_tree_logger/bt_file_logger.h" + +#ifdef ZMQ_FOUND +#include "behavior_tree_logger/bt_zmq_publisher.h" +#endif + +using namespace BT; + +int main() +{ + BT::BehaviorTreeFactory factory; + // Load and register all the Custom TreeNodes from plugin + factory.registerFromPlugin("./libcrossdoor_nodes.so"); + + auto tree = buildTreeFromFile(factory, "crossdoor.xml"); + + // Create some loggers. + StdCoutLogger logger_cout(tree.root_node); + FileLogger logger_file(tree.root_node, "bt_trace.fbl"); + MinitraceLogger logger_minitrace(tree.root_node, "bt_trace.json"); +#ifdef ZMQ_FOUND + PublisherZMQ publisher_zmq(tree.root_node); +#endif + + // Keep on ticking until you get either a SUCCESS or FAILURE + NodeStatus status = NodeStatus::RUNNING; + while( status == NodeStatus::RUNNING ) + { + status = tree.root_node->executeTick(); + CrossDoor::SleepMS(1); // optional sleep to avoid "busy loops" + } + return 0; +} + +``` + +## StdCoutLogger + +Simply print the state transition on __std::cout__. + + +## FileLogger + +Store the state transitions (and their timestamp) in the bynary file +called "bt_trace.fbl". + +To bisualize the contect of this file, you can use the command line tool +__bt_log_cat__. + +## MinitraceLogger + +This logger store in a JSON file format the state duration. Its goal is to +show the time required by a TreeNode to complete its tick() operation. + +This tracing format can be visualized in __Chrome__ tracer viewer:that +you can access typing this in the address bar: __chrome://tracing__. + +For more information, refer to: [MiniTrace (GitHub)](https://github.com/hrydgard/minitrace) + +## PublisherZMQ + +Publish state transitions in real-time using [ZMQ](http://zeromq.org/). + +You can record them using the command line tool __bt_recorder__. + + + + + + + + diff --git a/docs/uml/CrossDoorSubtree.uxf b/docs/uml/CrossDoorSubtree.uxf new file mode 100644 index 000000000..c8869274a --- /dev/null +++ b/docs/uml/CrossDoorSubtree.uxf @@ -0,0 +1,299 @@ + + 10 + + UMLClass + + 270 + 140 + 100 + 30 + + Fallback + + + + + UMLClass + + 270 + 540 + 100 + 30 + + OpenDoor + + + + UMLClass + + 380 + 220 + 160 + 30 + + PassThroughWindow + + + + Relation + + 310 + 160 + 150 + 80 + + lt=- + 130.0;60.0;10.0;10.0 + + + UMLClass + + 250 + 460 + 150 + 40 + + RetryUntilSuccesful +(num_attempts=4) + + + + Relation + + 310 + 110 + 30 + 50 + + lt=- + 10.0;30.0;10.0;10.0 + + + UMLUseCase + + 70 + 280 + 120 + 30 + + isDoorOpen? + + + + Relation + + 190 + 160 + 150 + 80 + + lt=- + 10.0;60.0;130.0;10.0 + + + Relation + + 310 + 410 + 30 + 70 + + lt=- + 10.0;50.0;10.0;10.0 + + + Relation + + 190 + 410 + 150 + 80 + + lt=- + 10.0;60.0;130.0;10.0 + + + UMLClass + + 270 + 390 + 100 + 30 + + Sequence + + + + + UMLClass + + 160 + 470 + 80 + 30 + + Negation + + + + UMLUseCase + + 140 + 530 + 120 + 40 + + isDoorOpen? + + + + Relation + + 190 + 490 + 30 + 60 + + lt=- + 10.0;40.0;10.0;10.0 + + + UMLClass + + 260 + 340 + 120 + 30 + + *DoorClosed* +bg=gray + + + + Relation + + 310 + 360 + 30 + 50 + + lt=- + 10.0;30.0;10.0;10.0 + + + UMLClass + + 260 + 90 + 120 + 30 + + *MainTree* +bg=gray + + + + + + Relation + + 310 + 490 + 30 + 70 + + lt=- + 10.0;50.0;10.0;10.0 + + + UMLClass + + 410 + 470 + 140 + 30 + + PassThroughDoor + + + + Relation + + 310 + 410 + 190 + 80 + + lt=- + 170.0;60.0;10.0;10.0 + + + UMLClass + + 150 + 220 + 100 + 30 + + Sequence + + + + + UMLClass + + 200 + 280 + 140 + 30 + + PassThroughDoor + + + + Relation + + 120 + 240 + 100 + 60 + + lt=- + 80.0;10.0;10.0;40.0 + + + Relation + + 190 + 240 + 100 + 60 + + lt=- + 10.0;10.0;80.0;40.0 + + + UMLClass + + 260 + 210 + 110 + 40 + + Subtree: +*DoorClosed* +fg=blue + + + + Relation + + 310 + 160 + 30 + 70 + + lt=- + 10.0;50.0;10.0;10.0 + + diff --git a/docs/uml/Reactive.uxf b/docs/uml/Reactive.uxf new file mode 100644 index 000000000..eb60589f3 --- /dev/null +++ b/docs/uml/Reactive.uxf @@ -0,0 +1,260 @@ + + 10 + + UMLClass + + 360 + 100 + 100 + 30 + + Sequence + + + + UMLClass + + 160 + 270 + 100 + 30 + + PickObject + + + + UMLClass + + 490 + 370 + 140 + 30 + + AssembleObject + + + + UMLClass + + 700 + 270 + 100 + 30 + + PlaceObject + + + + UMLClass + + 360 + 200 + 100 + 30 + + Parallel + + + + UMLUseCase + + 360 + 370 + 120 + 40 + + Object +Assembled + + + + Relation + + 410 + 310 + 80 + 80 + + lt=- + 10.0;60.0;60.0;10.0 + + + Relation + + 460 + 310 + 120 + 80 + + lt=- + 100.0;60.0;10.0;10.0 + + + UMLUseCase + + 30 + 270 + 120 + 40 + + Object +Picked + + + + UMLUseCase + + 570 + 270 + 120 + 40 + + Object +Placed + + + + UMLClass + + 120 + 200 + 100 + 30 + + Fallback + + + + UMLClass + + 650 + 200 + 100 + 30 + + Parallel + + + + Relation + + 620 + 220 + 100 + 70 + + lt=- + 10.0;50.0;80.0;10.0 + + + Relation + + 690 + 220 + 80 + 70 + + lt=- + 60.0;50.0;10.0;10.0 + + + Relation + + 80 + 220 + 110 + 70 + + lt=- + 10.0;50.0;90.0;10.0 + + + Relation + + 160 + 220 + 70 + 70 + + lt=- + 50.0;50.0;10.0;10.0 + + + Relation + + 160 + 120 + 270 + 100 + + lt=- + 10.0;80.0;250.0;10.0 + + + Relation + + 400 + 120 + 30 + 100 + + lt=- + 10.0;80.0;10.0;10.0 + + + Relation + + 400 + 120 + 320 + 100 + + lt=- + 300.0;80.0;10.0;10.0 + + + UMLUseCase + + 290 + 290 + 120 + 40 + + Object +Picked + + + + Relation + + 340 + 220 + 90 + 90 + + lt=- + 10.0;70.0;70.0;10.0 + + + UMLClass + + 420 + 290 + 100 + 30 + + Fallback + + + + Relation + + 400 + 220 + 80 + 90 + + lt=- + 60.0;70.0;10.0;10.0 + + diff --git a/docs/uml/ReadTheDocs.uxf b/docs/uml/ReadTheDocs.uxf new file mode 100644 index 000000000..363b8b169 --- /dev/null +++ b/docs/uml/ReadTheDocs.uxf @@ -0,0 +1,153 @@ + + 10 + + UMLClass + + 290 + 100 + 100 + 30 + + Sequence + + + + + UMLClass + + 350 + 160 + 160 + 40 + + Build Awesome +Robot Behaviors + + + + Relation + + 330 + 120 + 100 + 60 + + lt=- + 80.0;40.0;10.0;10.0 + + + UMLClass + + 180 + 160 + 150 + 40 + + RetryUntilSuccesful + + + + Relation + + 330 + 70 + 30 + 50 + + lt=- + 10.0;30.0;10.0;10.0 + + + UMLUseCase + + 130 + 280 + 110 + 30 + + isItClear? + + + + Relation + + 240 + 120 + 120 + 60 + + lt=- + 10.0;40.0;100.0;10.0 + + + Relation + + 240 + 190 + 30 + 50 + + lt=- + 10.0;30.0;10.0;10.0 + + + UMLClass + + 280 + 50 + 120 + 30 + + *BehaviorTree* +bg=gray + + + + + + UMLClass + + 200 + 220 + 100 + 30 + + Fallback + + + + + UMLClass + + 260 + 280 + 120 + 40 + + Read +Documentation + + + + Relation + + 170 + 240 + 100 + 60 + + lt=- + 80.0;10.0;15.0;40.0 + + + Relation + + 240 + 240 + 100 + 60 + + lt=- + 10.0;10.0;80.0;40.0 + + diff --git a/docs/uml/SequenceStar.uxf b/docs/uml/SequenceStar.uxf index 8f79d3eda..5232545c2 100644 --- a/docs/uml/SequenceStar.uxf +++ b/docs/uml/SequenceStar.uxf @@ -5,10 +5,11 @@ 260 110 - 120 - 30 + 180 + 40 SequenceStar +reset_on_failure="false" fg=blue @@ -16,7 +17,7 @@ fg=blue UMLClass - 160 + 190 180 100 40 @@ -28,40 +29,40 @@ fg=blue Relation - 200 - 130 + 230 + 140 140 - 70 + 60 lt=- - 10.0;50.0;120.0;10.0 + 10.0;40.0;120.0;10.0 Relation - 310 - 130 + 340 + 140 30 - 70 + 60 lt=- - 10.0;50.0;10.0;10.0 + 10.0;40.0;10.0;10.0 Relation - 310 - 130 + 340 + 140 140 - 70 + 60 lt=- - 120.0;50.0;10.0;10.0 + 120.0;40.0;10.0;10.0 UMLClass - 270 + 300 180 100 40 @@ -73,7 +74,7 @@ fg=blue UMLClass - 380 + 410 180 100 40 diff --git a/examples/broken_sequence.cpp b/examples/broken_sequence.cpp new file mode 100644 index 000000000..e380da95c --- /dev/null +++ b/examples/broken_sequence.cpp @@ -0,0 +1,92 @@ +#include "Blackboard/blackboard_local.h" +#include "behavior_tree_core/behavior_tree.h" +#include "behavior_tree_core/bt_factory.h" + +using namespace BT; + + +NodeStatus SayHello() +{ + printf("hello\n"); + return NodeStatus::SUCCESS; +} + +class ActionTestNode : public ActionNode +{ + public: + ActionTestNode(const std::string& name): ActionNode(name) + { } + + NodeStatus tick() override + { + time_ = 5; + stop_loop_ = false; + int i = 0; + while (!stop_loop_ && i++ < time_) + { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + return NodeStatus::SUCCESS; + } + + virtual void halt() override + { + stop_loop_ = true; + setStatus(NodeStatus::IDLE); + } + + + private: + int time_; + std::atomic_bool stop_loop_; +}; + +int main() +{ + BT::SequenceNode root("root"); + BT::SimpleActionNode action1("say_hello", std::bind(SayHello) ); + ActionTestNode action2("async_action"); + + root.addChild(&action1); + root.addChild(&action2); + + int count = 0; + + NodeStatus status = NodeStatus::RUNNING; + + while( status == NodeStatus::RUNNING) + { + status = root.executeTick(); + + std::cout << count++ << " : " << + root.status() << " / " << + action1.status() << " / " << + action2.status() << std::endl; + + std::this_thread::sleep_for( std::chrono::milliseconds(100)); + } + + haltAllActions(&root); + + return 0; +} +// Output +/* + +hello +0 : RUNNING / SUCCESS / RUNNING +hello +1 : RUNNING / SUCCESS / RUNNING +hello +2 : RUNNING / SUCCESS / RUNNING +hello +3 : RUNNING / SUCCESS / RUNNING +hello +4 : RUNNING / SUCCESS / RUNNING +hello +5 : SUCCESS / IDLE / IDLE + +*/ + + + diff --git a/examples/crossdoor_example.cpp b/examples/crossdoor_example.cpp index 601c52e99..b54f0d277 100644 --- a/examples/crossdoor_example.cpp +++ b/examples/crossdoor_example.cpp @@ -12,33 +12,31 @@ // clang-format off const std::string xml_text = R"( - - - + + + + + + + + + + + + + + - - + - - + + - - - - - - - - - - - - - - - + + + - + )"; diff --git a/examples/t04_blackboard.cpp b/examples/t04_blackboard.cpp index 581f35e05..46830f5b0 100644 --- a/examples/t04_blackboard.cpp +++ b/examples/t04_blackboard.cpp @@ -13,10 +13,10 @@ using namespace BT; * * The tree is a Sequence of 4 actions - * 1) Store a value of Pose2D in the key "GoalPose" of the blackboard. - * 2) Call PrintGoalPose. It will read "GoalPose" from the blackboard. - * 3) Call MoveAction. The NodeParameter "goal" is provided by the XML itself at the beginning. - * 4) Call MoveAction. The NodeParameter "goal" will be read from the Blackboard at run-time. + * 1) Store a value of Pose2D in the key "GoalPose" of the blackboard using the action CalculateGoalPose. + * 2) Call MoveAction. The NodeParameter "goal" will be read from the Blackboard at run-time. + * 3) Use the built-in action SetBlackboard to write the key "OtherGoal". + * 4) Call MoveAction. The NodeParameter "goal" will be read from the Blackboard entry "OtherGoal". * */ @@ -24,62 +24,36 @@ using namespace BT; const std::string xml_text = R"( - - - + + - )"; // clang-format on // Write into the blackboard key: [GoalPose] -// Use this function signature to create a SimpleAction that needs the blackboard +// Use this function to create a SimpleActionNode that can access the blackboard NodeStatus CalculateGoalPose(TreeNode& self) { const Pose2D mygoal = { 1, 2, M_PI}; - // RECOMMENDED: check if the blackboard is nullptr + // RECOMMENDED: check if the blackboard is nullptr first if( self.blackboard() ) { // store it in the blackboard self.blackboard()->set("GoalPose", mygoal); + return NodeStatus::SUCCESS; } - - printf("[CalculateGoalPose]\n"); - return NodeStatus::SUCCESS; -} - -// Read from the blackboard key: [GoalPose] -class PrintGoalPose: public ActionNodeBase -{ -public: - PrintGoalPose(const std::string& name): ActionNodeBase(name) {} - - NodeStatus tick() override - { - Pose2D goal; - // RECOMMENDED: check if the blackboard is empty - if( blackboard() && blackboard()->get("GoalPose", goal) ) - { - printf("[PrintGoalPose] x=%.f y=%.1f theta=%.2f\n", - goal.x, goal.y, goal.theta); - return NodeStatus::SUCCESS; - } - else{ - printf("The blackboard does not contain the key [GoalPose]\n"); - return NodeStatus::FAILURE; - } + else{ + return NodeStatus::FAILURE; } - - virtual void halt() override { setStatus(NodeStatus::IDLE); } -}; +} int main() { @@ -87,7 +61,6 @@ int main() BehaviorTreeFactory factory; factory.registerSimpleAction("CalculateGoalPose", CalculateGoalPose); - factory.registerNodeType("PrintGoalPose"); factory.registerNodeType("MoveBase"); // create a Blackboard from BlackboardLocal (simple, not persistent, local storage) @@ -102,6 +75,5 @@ int main() status = tree.root_node->executeTick(); SleepMS(1); // optional sleep to avoid "busy loops" } - return 0; } diff --git a/include/Blackboard/blackboard.h b/include/Blackboard/blackboard.h index b2a5373b7..1ff6c2d56 100644 --- a/include/Blackboard/blackboard.h +++ b/include/Blackboard/blackboard.h @@ -10,6 +10,8 @@ #include #include +template T convertFromString(const std::string& str); + namespace BT{ // This is the "backend" of the blackboard. @@ -67,7 +69,14 @@ class Blackboard const SafeAny::Any* val = impl_->get(key); if( !val ){ return false; } - value = val->cast(); + if( !std::is_same::value && + ( val->type() == typeid(SafeAny::SimpleString) || val->type() == typeid(std::string)) ) + { + value = convertFromString( val->cast() ); + } + else{ + value = val->cast(); + } return true; } diff --git a/include/SafeAny/safe_any.hpp b/include/SafeAny/safe_any.hpp index b05c7a8e8..c1d094035 100644 --- a/include/SafeAny/safe_any.hpp +++ b/include/SafeAny/safe_any.hpp @@ -77,6 +77,8 @@ class Any } } + const std::type_info& type() const noexcept { return _any.type(); } + private: linb::any _any; diff --git a/include/behavior_tree_core/actions/always_failure_node.h b/include/behavior_tree_core/actions/always_failure_node.h new file mode 100644 index 000000000..fd4b876bb --- /dev/null +++ b/include/behavior_tree_core/actions/always_failure_node.h @@ -0,0 +1,39 @@ +/* Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef ACTION_ALWAYS_FAILURE_NODE_H +#define ACTION_ALWAYS_FAILURE_NODE_H + + +#include "behavior_tree_core/action_node.h" + +namespace BT +{ + +class AlwaysFailure : public ActionNodeBase +{ + public: + AlwaysFailure(const std::string& name): + ActionNodeBase(name, NodeParameters()) + { } + + private: + virtual BT::NodeStatus tick() override + { + return NodeStatus::FAILURE; + } + virtual void halt() override {} +}; + +} + +#endif diff --git a/include/behavior_tree_core/actions/always_success_node.h b/include/behavior_tree_core/actions/always_success_node.h new file mode 100644 index 000000000..3d0d59204 --- /dev/null +++ b/include/behavior_tree_core/actions/always_success_node.h @@ -0,0 +1,38 @@ +/* Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef ACTION_ALWAYS_SUCCESS_NODE_H +#define ACTION_ALWAYS_SUCCESS_NODE_H + +#include "behavior_tree_core/action_node.h" + +namespace BT +{ + +class AlwaysSuccess : public ActionNodeBase +{ + public: + AlwaysSuccess(const std::string& name): + ActionNodeBase(name, NodeParameters()) + { } + + private: + virtual BT::NodeStatus tick() override + { + return NodeStatus::SUCCESS; + } + virtual void halt() override {} +}; + +} + +#endif diff --git a/include/behavior_tree_core/actions/set_blackboard_node.h b/include/behavior_tree_core/actions/set_blackboard_node.h new file mode 100644 index 000000000..b58ca6a57 --- /dev/null +++ b/include/behavior_tree_core/actions/set_blackboard_node.h @@ -0,0 +1,54 @@ +/* Copyright (C) 2018 Davide Faconti - All Rights Reserved +* +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, +* 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: +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef ACTION_SETBLACKBOARD_NODE_H +#define ACTION_SETBLACKBOARD_NODE_H + +#include "behavior_tree_core/action_node.h" + + +namespace BT +{ + +class SetBlackboard : public ActionNodeBase +{ + public: + SetBlackboard(const std::string& name, const NodeParameters& params): + ActionNodeBase(name, params) + { } + + static const NodeParameters& requiredNodeParameters() + { + static NodeParameters params = {{"key", ""}, {"value", ""}}; + return params; + } + + private: + virtual BT::NodeStatus tick() override + { + std::string key; + if( !blackboard() || !getParam("key",key) || key.empty()){ + return NodeStatus::FAILURE; + } + else{ + std::string value; + getParam("value",value); + blackboard()->set(key,value); + return NodeStatus::SUCCESS; + } + } + virtual void halt() override {} +}; + +} + +#endif diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index d5aed928d..19503766c 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -29,8 +29,12 @@ #include "behavior_tree_core/decorators/repeat_node.h" #include "behavior_tree_core/decorators/subtree_node.h" -#include "behavior_tree_core/decorators/always_success_node.h" -#include "behavior_tree_core/decorators/always_failure_node.h" +#include "behavior_tree_core/actions/always_success_node.h" +#include "behavior_tree_core/actions/always_failure_node.h" +#include "behavior_tree_core/actions/set_blackboard_node.h" + +#include "behavior_tree_core/decorators/force_success_node.h" +#include "behavior_tree_core/decorators/force_failure_node.h" #include "behavior_tree_core/decorators/blackboard_precondition_node.h" #include "behavior_tree_core/decorators/deadline_node.h" diff --git a/include/behavior_tree_core/decorators/always_failure_node.h b/include/behavior_tree_core/decorators/force_failure_node.h similarity index 85% rename from include/behavior_tree_core/decorators/always_failure_node.h rename to include/behavior_tree_core/decorators/force_failure_node.h index 30ac83aa0..4d0c4b71a 100644 --- a/include/behavior_tree_core/decorators/always_failure_node.h +++ b/include/behavior_tree_core/decorators/force_failure_node.h @@ -14,7 +14,6 @@ #define DECORATOR_ALWAYS_FAILURE_NODE_H #include "behavior_tree_core/decorator_node.h" -#include "behavior_tree_core/action_node.h" namespace BT { @@ -29,24 +28,8 @@ class ForceFailureDecorator : public DecoratorNode virtual BT::NodeStatus tick() override; }; -class AlwaysFailure : public ActionNodeBase -{ - public: - AlwaysFailure(const std::string& name): - ActionNodeBase(name, NodeParameters()) - { } - - private: - virtual BT::NodeStatus tick() override - { - return NodeStatus::FAILURE; - } - virtual void halt() override {} -}; - //------------ implementation ---------------------------- - inline NodeStatus ForceFailureDecorator::tick() { setStatus(NodeStatus::RUNNING); diff --git a/include/behavior_tree_core/decorators/always_success_node.h b/include/behavior_tree_core/decorators/force_success_node.h similarity index 85% rename from include/behavior_tree_core/decorators/always_success_node.h rename to include/behavior_tree_core/decorators/force_success_node.h index cc5998a9a..0b9d8b315 100644 --- a/include/behavior_tree_core/decorators/always_success_node.h +++ b/include/behavior_tree_core/decorators/force_success_node.h @@ -14,7 +14,6 @@ #define DECORATOR_ALWAYS_SUCCESS_NODE_H #include "behavior_tree_core/decorator_node.h" -#include "behavior_tree_core/action_node.h" namespace BT { @@ -29,21 +28,6 @@ class ForceSuccessDecorator : public DecoratorNode virtual BT::NodeStatus tick() override; }; -class AlwaysSuccess : public ActionNodeBase -{ - public: - AlwaysSuccess(const std::string& name): - ActionNodeBase(name, NodeParameters()) - { } - - private: - virtual BT::NodeStatus tick() override - { - return NodeStatus::SUCCESS; - } - virtual void halt() override {} -}; - //------------ implementation ---------------------------- diff --git a/mkdocs.yml b/mkdocs.yml index 70618a951..bc7c158cb 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -11,10 +11,10 @@ theme: feature: tabs: true palette: - primary: indigo + primary: blue accent: indigo font: - text: Roboto + text: Ubuntu code: Roboto Mono repo_name: 'Eurecat/BehaviorTree.CPP' @@ -31,12 +31,16 @@ markdown_extensions: pages: - Home: index.md - Learn the basics: - - The Basics: BT_basics.md + - Introduction: BT_basics.md - Sequence Nodes: SequenceNode.md - Fallback Nodes: FallbackNode.md - Decorators Nodes: DecoratorNode.md - - The BlackBoard: BlackBoard.md - - Getting Started: - - How to use the library: getting_started.md - - BT at run-time: getting_started.md - - Examples: getting_started.md + - Tutorials: + - Getting started: getting_started.md + - Create a Tree: tutorial_A_create_trees.md + - Add NodeParameters: tutorial_B_node_parameters.md + - Use Blackboards: tutorial_C_blackboard.md + - Compose with Subtrees: tutorial_D_subtrees.md + - Create a Plugin: tutorial_E_plugins.md + - Log state transitions: tutorial_F_loggers.md + diff --git a/sample_nodes/dummy_nodes.cpp b/sample_nodes/dummy_nodes.cpp index a0f213617..ba1ee05a8 100644 --- a/sample_nodes/dummy_nodes.cpp +++ b/sample_nodes/dummy_nodes.cpp @@ -57,14 +57,13 @@ void ApproachObject::halt() BT::NodeStatus SaySomething::tick() { std::string msg; - if( getParam("message", msg) ) + if( getParam("message", msg) == false ) { - std::cout << "Robot says: \"" << msg << "\"" <("goal", goal); - - // You might want to create a node that fails if a mandatory parameter is missing. - -// if( !goal_passed ) -// { -// printf("The NodeParameter does not contain the key [goal] " -// " or the blackboard does not contain the provided key\n"); -// return BT::NodeStatus::FAILURE; -// } - - // In this case, if "goal" was not passed, the default value is used instead. - if( !goal_passed ) + if( getParam("goal", goal) == false ) { - auto& default_goal_value = requiredNodeParameters().begin()->second; + auto default_goal_value = requiredNodeParameters().at("goal"); + // use the convertFromString function goal = BT::convertFromString( default_goal_value ); } + printf("[ MoveBase: STARTED ]. goal: x=%.f y=%.1f theta=%.2f\n", goal.x, goal.y, goal.theta); diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 6d3a89328..df6b46bad 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -32,6 +32,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("AlwaysSuccess"); registerNodeType("AlwaysFailure"); + registerNodeType("SetBlackboard"); registerNodeType("SubTree"); diff --git a/tools/bt_plugin_manifest.cpp b/tools/bt_plugin_manifest.cpp index da018ecfb..2d9a0e65e 100644 --- a/tools/bt_plugin_manifest.cpp +++ b/tools/bt_plugin_manifest.cpp @@ -43,8 +43,8 @@ int main(int argc, char* argv[]) for( auto& param: params) { - std::cout << " - [Key]: " << param.first << " / Default value: " - << param.second << std::endl; + std::cout << " - [Key]: \"" << param.first << "\" / [Default]: \"" + << param.second << "\"" << std::endl; } } From c9f0c2c0123e6fe8c920f2be616a106a4ed05421 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 16 Oct 2018 11:51:31 +0200 Subject: [PATCH 123/125] Renaming: Negation->Inverter and Deadline->Timeout --- CMakeLists.txt | 4 +- docs/BT_basics.md | 4 +- docs/DecoratorNode.md | 2 +- docs/images/CrossDoorSubtree.png | Bin 5745 -> 21352 bytes docs/images/DecoratorEnterRoom.png | Bin 8321 -> 10346 bytes docs/images/TypeHierarchy.png | Bin 3258 -> 9742 bytes docs/tutorial_D_subtrees.md | 4 +- docs/uml/CrossDoorSubtree.uxf | 2 +- docs/uml/EnterRoom.uxf | 2 +- docs/uml/EnterRoom2.uxf | 2 +- docs/uml/Sequence2.uxf | 2 +- docs/uml/TypeHierarchy.uxf | 56 +++++++++--------- examples/crossdoor_example.cpp | 4 +- gtest/gtest_decorator.cpp | 2 +- gtest/gtest_factory.cpp | 12 ++-- include/behavior_tree_core/behavior_tree.h | 6 +- ...ition_node.h => blackboard_precondition.h} | 0 .../{negation_node.h => inverter_node.h} | 12 ++-- .../{deadline_node.h => timeout_node.h} | 10 ++-- src/bt_factory.cpp | 26 +------- .../{negation_node.cpp => inverter_node.cpp} | 6 +- .../{deadline_node.cpp => timeout_node.cpp} | 8 +-- 22 files changed, 71 insertions(+), 93 deletions(-) rename include/behavior_tree_core/decorators/{blackboard_precondition_node.h => blackboard_precondition.h} (100%) rename include/behavior_tree_core/decorators/{negation_node.h => inverter_node.h} (82%) rename include/behavior_tree_core/decorators/{deadline_node.h => timeout_node.h} (69%) rename src/decorators/{negation_node.cpp => inverter_node.cpp} (92%) rename src/decorators/{deadline_node.cpp => timeout_node.cpp} (87%) diff --git a/CMakeLists.txt b/CMakeLists.txt index cf3188435..5cfcda41c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -58,10 +58,10 @@ set(BT_Source src/shared_library.cpp src/shared_library_UNIX.cpp - src/decorators/negation_node.cpp + src/decorators/inverter_node.cpp src/decorators/repeat_node.cpp src/decorators/retry_node.cpp - src/decorators/deadline_node.cpp + src/decorators/timeout_node.cpp src/controls/parallel_node.cpp src/controls/fallback_node.cpp diff --git a/docs/BT_basics.md b/docs/BT_basics.md index 86a45d0fe..c1cc2e39d 100644 --- a/docs/BT_basics.md +++ b/docs/BT_basics.md @@ -96,8 +96,8 @@ You can create your own Decorators. ![Simple Decorator: Enter Room](images/DecoratorEnterRoom.png) -The node __Negation__ is a Decorator that inverts -the result returned by its child; Negation followed by the node called +The node __Inverter__ is a Decorator that inverts +the result returned by its child; Inverter followed by the node called __DoorOpen__ is therefore equivalent to "Is the door closed?". diff --git a/docs/DecoratorNode.md b/docs/DecoratorNode.md index 8d65c4ae4..cf9ef9c96 100644 --- a/docs/DecoratorNode.md +++ b/docs/DecoratorNode.md @@ -5,7 +5,7 @@ A decorator is a node that can have only a single child. It is up to the Decorator to decide if, when and how many times the child should be ticked. -## NegationNode +## InverterNode Tick the child once and return SUCCESS if the child failed or FAILURE if the child succeeded. diff --git a/docs/images/CrossDoorSubtree.png b/docs/images/CrossDoorSubtree.png index b42e1f0c4dd0946bf18973ad6861e8eacbf0d1e9..33526c2404ba647b49ede1187f46a2b172f3a1ab 100644 GIT binary patch literal 21352 zcmd43XH-;O)-?*EfT)OoAX!iWk(@IM0*YjiBuTPFB}fL9Bv~crBp_0RB1i_6BsmvJ zKqONH$r-*?+IGKhcYkBtG4B0wYjpESQFYEfXYak%TyxHK0+khIFAz`?U}0fhxPR}i zDi#*@I{beV{}jA)|D#|${0GND^1eDgKK|&W(hvBR$WdC$QO(ZG(fP5xDVCarlcS@l zz45E=vshSHvF_i!qwX@YH0G(R=5!+QtLte<)+;CarIy5J((!I?o;jt9N$YMl4)t5lGxyd@qzeYt;~FoM|cG|mO5pNWo)@!GK zz43YEDe~;+B0*|Gen~5m;Kt0%%pt-TS^=M~5(lcPsut4dD4Ckhe0-Q&Nb{N0@$0`G z=;NS1*tnV4LonWy*K|7j%ioB$9QxNo4_xfPanw@ zTt|duL{rHgl)k+(c5r;K+NZR$GB%2!^LnDez(dlv7siX%ApBzH?CDpDiHT>h30@p&4^2Vp2->INBPV@H$w2b>>`AQPC&6 ziO!<-u_|W{y-Hp&G0&zD3iGaHy*jU&J#<8L^e4xK-u8BR;l2XhiuF#B)p^It_wV0} zxo>Zx2Um}FCM3KL1rL~Eh8*?OvgDsRI*LAD(z<{D{`2RbGBT#7TOz2G$Vf=0W@nqG z*1mrIicb#*H`Sh9pJ_AY)`r`bt(2mOzc&+O&~8BIrcae1L712%;*1&`JULqRUL7o$ zILA>UBaT0dIIk3j zpSq2Zis5%%pDrmW!MjK+C?q6(_bzX;;aH^;=4c1YW%c#-Lez>{T36h)quP#)%j~{% zFvhuVWoBoeJAEpnuQ=qC#f^DiY^&y}wfW;s?P9Yvm+B@GQgU(UUnls^RXQ?6^Ps@hv> zHRvcjR^z@CMki70xS+bNf|W;*#MwPrbFfmC;<-JXo#M6l;|ENz=i1Lke)lIF90eS; zy9|7MTQEa|mZhg&er|3ypZw~#l!2vlIa{0D8H@MH=NH(!6rmc@Cn30AG-u`SFrCMO zWeu?ajfM3>3-8Y+`;Rv;+pv=1yC@cG%>%v@+p=z5BjgoVN*LPE9^&(*mJ-r1<}q6koTB+V zR?Nr#=ioWzP7rdlNK>WKhQI_vvGSqQ-OqU9{jE6Q>bjBi&DdJ0B)GzXR06i`v0U{n zEjcjBDk>^+nMEzy@7}!=6%}<6O;%?at8mDU3l_GYeqC25k<#Vt;P60E(YAWXVXkuv zJ!l6Lx~rTzMk$VEGrL#7%~#sz=I)*%`0Qs(1QSb?Wy`x8NF-9m{4p(w~F?OkO_ZixCeu_g#jbKoX|p4Hh-suybq@ zGKFVT>l@u76e489X#?-3Ga4U#dwZ?@S4c?6=g*%R$@w6FK*UJcFB-0P-RMq}dLSp4 zd@_su+R1{;@$2n?6Y>aJ7Z~b7UpDNwg!;+N#R2rrgtwi&ka1JUV_H01T>Toi(iZ8< zq@>mRi@7o}+Xdc7R$a+rdwYATIix97Nb z>-hM1zwVtocW&Ic0b9Ar98QaMPSE@K5Q6Uh&T7|;z4zgotbTxCB{x@Bz6xeL zyVb-*YBgkXRMcfEsw%q)aSv)k>65Ngj@|Ea3JUBbC0}Xe);yj3ntI3QHS*YT``v=` zgy-ONy1l(U95W><%Jiej{zjL?#VedwxwtNQqF=nbc@>p%3k5N3dTtK3pst=?-R{qG z4o04E<*GT6Z8LJ$-%U@OIFL!JsJppUhKFAaZ-#`?uDjnC86DkfQsjh2(WBDzehj`% zRk(kh_)z9E^Dk_TaIP{5yJS&;;H7p%; zH@4QO!rOfPn*G@XJ7US>iIW3w$SbH~qjLK5uqEQ}WcNWN!NbD~rxM8bJ~{S%uTMJI1`ik{^o-2O7S{zN|!F+ta0L=!YN(N+ov0ZZ&%%9WtEqc8>w-3wy>E0*%<8e>Xke# zE_DRnE5+=#&dzaIs($Cljf{=S*>rpz)IYbT!G@$dvj3pWT>X4`&dnrtQMT zizh2ptDVVWxqS=D8fQvS*dt**_8+tZu$#Z*V4FU?ZAFvH#;Z+ON*ehPJJ0EbhKZt3 ze^H(j4s-4)Bbv|L?HmE0ED?S1)!bK*JnpeR`sYW@tey##T+l(|{yFYYiMCL`>Ysmy z6silAEI<1FC&+D1(QE;q+%ZS-mS=LzQ}bxNr%Z~QqS%(ReGx&4RCR0M%V zo>X>k^o%mvI*;nM_GJh>Dy5!6B~lH-7fc@(;=|UYI-|kF9-u?e`tb!y*b!@4pK$s1 z-{TnSRa*ZY%@-D}M?xi2pHLUzu&}MI;Oxu1NJS~_%kjQ2n%mu})FWoU2cCA>>9xHD zlhyB2cI)7^-4^PX`#qR?hlSTO-JN4P0xybKuA;u^(v(q;WEv&;7g>@AC|?64yrUP2qz zjMP%MPC97V*dQbH1fkUo%=ksa37%6c0)N^YmhFM6$BP6!%Gk<`g_E#F%q+8tasYPNUAx zbPG&eFD;$^jQw*(kye6HNXVpvl9>3FUj0ZKVkDV4wLlts<8`CaHrsIj?kut_n^v56 z>unshBz{!vy%v+mJhqt?#pR(j>+)kdvFr3Ni36Dl=Z5VG>9RaLm_P+Cy*;)-CjkK#ff&`? zoJ8u@fvDC_esOYo^{1Q=^@{0TT_ei`qGDv9l&U}D;`0(MeQwj2!8&@In+cWY5WcK+ zQ0&A#$1H_#{-L${S|rg_z(fZ32B|8KxoQHxig~B9a8d=*Yxo-{#E?s(G9?PmPFDm-&qC_m;R4i8)WTAJt znhJ^w3wtryXU<%|`r>KD`$qys#!|TFuL{`lixDI-K#+e?k(l_6%I=N8_*LIGHSR56 z{oWULe>1soflXID+*~<}ac1Vdok7NB>xc|21RgBcxAL*KSH8QF?d+@^Wk%(#ZZ4RI zD51(1@+?lRBx#7I}uCh{M|8bW5o^k)~n#rEM z{TyMB<$XoMz`(t>5W6}B#pLUh7g{=QJcxO>Gk#!Po_p(U+i?7Lu4cr;+tgw$7ksRf_DpjdC?sQY#-8kfV< zC@lO~XTC#VqS}6@^(7A8$B!TL4eG?LPzXLNlwt9Ut;2K2^F0}Wo(~TXqi$(_YLeIq zP0=y9VfGbi+`K8r%A}{K=iuNFM^E5q^wsxl`y(kPc}=^#(b3Uj-AB)Me?6w7qk~a7 zJMX{&`xo>=cDDu%s;a6+M@CvrxcBq1Wa@rx1;px5(qHG}8yFlM?Ci{UULA+5ros}n z?{I-m{Cj6-=fHr|!S=F3{uLc`QdVjHNlA5ewNi>WsWj9xo{;gv!omO;|15dZw=z-J zC9kHdOHDzsu(Z@ZwFcwfULG~Kyy}if7@;~#fA;KIhPSUXoZ0M*jMCLvN=r+l=in(`vkCENGy{&Cyd%Lr(tb~Xg_)R|2L?)8w9K_B=}mt9_(I?(nWq5&(jA4+?&;~-{E#6V z4woRn!=sj`K~7HI+|W?SL4X_&G_HX=MJnz3pWw8e*UQU`ir@MJ%x6x{-edq>dV0G2 z1(R?mHTP@u*98T4qsL3DVHuGI-X-w+xi-}dC%sNgBV_M;bo*O-yGdBm_wTv_0s==` z0{gu>d7l7B>*PhJe+alpCoC+CLZJvwpW45bS6f?aQ0FxwVa11wv|X%;74}uAxfYa; zdx3JZPf0?BbPHWjXD^sIT4tw4x-}IpK}gAq56JB@nu3BtGVSSXdt3s)4FvEI#ntuZ z?(XglH}Y%IF)=(x&c@AQV(HF%#xgQ85y;LWUdeBn4`O0f;DVj(?bGSPuW%Wi93SDf znP`(5)oe7nDJUr1x$`Brpq7%H+?=xmZrNRiOBW88eqm)R zn4Dv=Z03T|SpO*n8kqS@(kc&P*cI;GOJ!!Er~lH_F9g)n`wk5ab!Sl1&}>!N!c@hFI7Me( zl3YZiLpx3F>`s1s!SOLIV*S|GB<#?|k?STM94YULDPTgw!?UU0o0^(JaRX~^bI5kA zlB>9(x%r&mSLtA~%=hoVS2zTi{$2BYe0=*E)YQ~)ip`6s0gZ0se1X?Ivi`UiR>|(c z#EGIxe{0mO1?wZ2xENM#Nr}{eE1^zm=Xjm)6WnA;r7@-QRwl>Bd{-OP7-PQK5tv2?&D1!wWuq`0%?f z$@yZUnXju|=XDf9!2{P4TgW5)<_1bZq1z=g4w>(LwGcCR$9r=r5a;fx^h1b~7x>(j zBBA75pp+=M2B4ekGP>jF`Qt#RJdInV1h;P8a^IX+(bk4Iad@y=2TLny;RLSd2?FgM zlpzy3Qt6c2(;|O_H#a@)xU-^Xw%Zs?9yj*d^a-nofwJn_K$F7=^qv?7uQWK zQLI5kmObgHqo*gw&hXDk$;GA%A3sHZM7-Z#&DQrUwQ6(=rxokB*|W{U512xFobR4Hd)5`5S2i!60$ZqT-0jx&>(j1b+zoEI4Q_^phB`Vruu^Pn zmP4ro(lavVI+GrRziXR;SpkYfoh6DgRE9l9DV{fQ&$->A=7zAa8w8#*y9ty9FOy>8 z6;T(?Vk#tSsOel=OUuGUowtTYv{y?cOeY;WmSi zJoW=-x5+0@`d?pC52y96R+b}>#^*B)sz4iC?p?mz|Ggse-rY49^%QY+M_#AJ{^AP7 zlq^Z99CH0seUG=4LhtrBHVJ~#KiJi#y;p5TMN^9IhDSY#(c0PCf<4!5SxU~Xdxh8H z&9Mmyqr9NkVYy6(O76g;Pu6QYI|6*&sz|S2KkjI14njRTdpouG-3%tGMc%uft(eqn z!3#g%-MenqwExJihRYrL9QCG#hHj>az1`jSSy_v#T3OLewF24M*$2D3zg$F-T8W2qPSLElQ2NN^ z7}-mbHS4VguLhd@DY;&;+{&;WOP2{rwYENftr@M-{x#rYHoJk>^K%oL`f2!S>+9`0 zbkQ?-xT?O&6cp-Cd`@$OQSox26jDcfH{_mG^baA`@1K46P`a@}*;o1IO;Tx<32&uK zlA)B+W0jcyg;EaKBE1%RZ%9Z;(1y<~F77vy8_X+3LluAJ%D1@ixhIC|oE} zhxJ(Mgx1JWZ=JEaTsKX#aLpoA%lp?02H(YTy}IJp z4Aa8}=G_$%ZjK}wv3>^SzhY*bR~0WwE;zXt=Z68nF zJo@pokx_;#7RmOx$iu)u5}!gOdUNT%hi6NXY1hh)`zNQ0%LFE$;s;3WZ_@j|G4Q_O z`zFPU!S_v?)Jg0+S1dLn5)w5nEzF*#^V+3nXSedX+M4Db#~N9*V4ea}-EAb(a1*`^qqpM4kDvuH^CVDk+x)x6Rw#NM|{q*{b1mi)MxVOLkD2RxKcT<~OG+g%n_5KP6 zb%hH~XtGiVCh3&%=%g{!4Yk`7!nG@@V#oJO=m`l;MtD^pJt!)=XY|vcDU433_8{!3 zU_)O-^(Ju|^ZIg`$>A=e405O>(8N6ABMb4Bdv2Roeefbo+g{hyyuGO%eewnGI$zXz z3Q4!^>%nAi&z$?VGUnaRXGz-9#Z>SA_Se(i3_J?1SJV=U;>Ww;XI6&pc%3AzsJh5{41Y?p^zcts&y6A-Qu%U zm#|XRjs!v!{s*mEBF@f_orge#WO!#@i@iz~oG|k4G*vJ0D1|#~SP|LRI8Kd^A3iYC z(@z30(nlIKj@s3+5eF73V11?r)F`a2txdwDc%G1Or7yb+h&?MSE1=`dI}_t#Vgf>O zuq^VNudqb1+_+&1a>1#WhQmdsec4KL8+)6~p)yk8KR5O;e2thpKM$xxNL#0%prG2r z^)^relwvs_FZ5<&V`FD!wg2I1Djeo8JPn6_NHPVM#rY)8<-i5IOZcY;^YunSHh7Rl zA_>esHxCa`hL800Lg7=lt;Tc;H_Ku#itzv!Z09|@^XK2G7n3+`-d7y4%}RBh$4V_7 zf6m%FVI;oU4(x4BX^D(?@Lo3$PPb_qNz=McL0zNAd>l3qJjt3=|2P1!AIaOxc3gCB zW>}S{9KVW^Th0IZ4aklu#HW9J1%X3Pll|x4^CsPAjq}3>{+tF*S?c)em~11>92W~Y z9_Lj1=ijMQl1w3&l1l%cvW90~^&g`&s+n47{qyhJ0o?;4kGuaK%C@F^Vm%QC{6edY zY~BvZ3fG~Pz}|n>=QtYm0&YVIYLs&S(a3oiED<{I+!5RI8Mq4O|8rH#Ec=& zsqMCR@MX!a^S5Kdwt#V5TwDZI2AI6oRyn9RRC8EZSR93uAa6mPLlP4ewIE?*VF75T zu&m5`t&x0rX{lT{|I5iSkZ>O2DP40_<>mONL1_B%^QV!yITKm%!b{Zd+Ec+H*}OO{ zR(3YF#^*2cY0;N2UxsX7W;@1mpmzWM*`yzi>)b*Q0t)V3|7l;L%U%W~6N9{d{e0U)c{dDdJ+crsxvKO-r!uH70@On9zP@wO~NLUnv%QC!mEb3RzQ9t!E z)uB2DF674#!vJKROfLkZQKP{Qo zT~x5LurQ2RfNPh@cwB2gZ7)>w6$UHc?e6LdY4JQ2fBR3XQEA6`dAxZRWWH+7JW<`# zNlDFndgU#v+L^W zVq#+I>P`wD*N-5jFJh&3ol4>y7#IMJOw?`jgDyLO%3o`102Q(mO7!*hagVMi$=tu+ z(j{>s@9hqBxdm@LASrki7IL1G@t8yVF35xYk;H~-Yi%tmE(Q=6pOAoFU6pwJ)fYZP zN0*XcK?CsuPT;yU1eI|Zh=i|SzlK8qmp^wncp4d|g=ev)HE6*L)GE|NnmOu#TvGe0 zK{p$U41t@6K(JQmdV!b&UjpF}gv$nD;4T)8YSPn<`mz+NoL31iT+pj@%mLAY-yp)^ z<&!5*fV^k)Em?}RxfS9>m_4Q#WYZiYgOI{ALOslan*!zIHJOkf8+$kA%K*QJIp;*BypA|#wv$Msmr zWMyPlM$0ZrT*7(nG^MJh)*MPjPD!bwt6Oc>L8%tA{NpPH8H5-2ofR?f<7&n1jjb)1 zkiu_9H-pld7ke^fVYr|?+|tZ1=_gQgqm(FB++562{|EsL0*pIcA%s3ePR^GVJUv2F z9X-7fJT@F_CC1d`wytpfjdZJUfkb8!yud;9X(** zWh*2+2YJyf9$4{j-|hkG223sYn$wd9yC)UGpxd#ul#jn2D{up$Wfzy-cs{FGZ9tx;+;Mq%c~w;hVKgF}*`gl1h2i1h;5LAF;3E)oho}P2 zXR6*L!f&6@y+|icihmjwi083ZK~Bz1W@eYI0Zl4zC5Q_5t`l=98MsXPt*_hrJPE-} zHPrW9N~_~F=;`T(kV^ZRpyLLh2-?4W>sH!R$&f)d@5gc(LwbyxlntZq!CVdhK8>B7 zT~{q*7G_pK1s+0*+l^N@G&DpvR`%c;29K&Og^K%ZN5;eqLUzBPKhvM1)}Bj*krC&c z4F76~{9-H|99^TMA{-n_xdUY65TN`k!Xl;UNiW zL{NJkwK{pW+6XEetWV`)jpOq?7D^C1VCt__xBB2+jMb#~<(wcRl{PgoIgN|UouoL| zl`^=BdedS87cqiI=ka58b>chiq19kM9|ggz^H0 zw75toOMq?H@g^kNMw;eexl;TLxxH*&a^Yv(wY+Dk?qS z73zRV0iIJw6b0nK7Z17=QPATVbVR)H^)mX1yW_{4v%f{uNI@kGTdYRJyHjgAFB zPNs!;bxqB=pFi!FNBDx9EB{R_-DFDOeEbzyIzGx!oxJfP(_qMPIWMDww%}e@R#w93 zIra26>*OHb7n^lddLDd|$q;(>v*E`VpREU3#DUYW&L~4?;U{t6du^otqeqWaRGxwC z3+s4+d|Dyz??Cf4a>c~N;BvngY1w_pvVP_sWU4-88n4F9H}6X!@|^X^1;GEKGFzKF zh_b7FQ$K%#!yzHD=*)jFAf+d=WSB{1q@~BIUHkfPKWG$|#(WttfG)dc9V$bX$JL-Y+S=M~o(+R|HofLDTg@8^z^AfOF^=05LOO1C7o{FaH0GXKBZ093 zc^ve|*^UHrMJD%%ysuOAa3~i1;j6y z3*gCk1^TeDbb4KE?({v(?n@GNwFe^GQE3f0JK$HUmR1=S)N<6J%z-E@_I&Be(MBGm zUhm|I&r%qD^2MxW%f(Rpitm7a_Q}1$H3Lx7tTQpEZ(-iR&3z_HQ+}+vObsZUGiS~K zm;f667Be$GFohu@hh5&s*GLJF?%21RE%KyJZ`v+Ln?8}s^ntDqV}Okax^ zu~K&5Wim4TYL_+ONnvd;v#_kMt(^tq9FX|HrghSB{MJjctOA`pL6>)21j;SHuuz#X zV(;L<-OUZOiyU>9h!)la&peu+@QJ$PeJe=y@B+Yk=gvzlRziGy0GSkgmJsd9W7=#o zHDwXkP}m3t)CD7CYU&U0eKGgI29nGcRbYt%KK<>z{@T&>q9WByRj#w0Zx$%{tz+xz zyc3R2UTVoAaCphf1`J-bZ2`fxyR3G!Z3oB|kg;kG0)ZeU@N=xC5}lu@lMu@Y4nEh{ zJ7-_PI&m5*fp+6inGAK7g=WarK-+*7CO!S@kC(6~ZeLBE8tv=jVPKGCi3)1`iLwg8 z!E&rdxt$wn1ET|AtN{yNK zPmAFH8?(`89$o8Gg{*`DKB3(s4MxwNJh}M^2l55m>${K@Nv#7=YTDWrmIEx-c${aF zIRDrY|CbE}3@}%H|GXSmG<_8>G6_nGG&9rt)=vV1_wx4Dh!#Lyq(nsBBL(hI54E?q z8+h%_0PqDsSmU-u9NY-mu94{!#!2(0Z3b>5An<))7^^G?K0>j8f#l^|6f%TV)y3I+a`V@Q!_>0{XSbjoa#z^0h5R|Sw1YHL3wY6#&iptoI;v>mT*IX?`= zkhBVzvoPx6Sk+FtbTD%e@RH;Q%uT;NjB%kIbXCGNCi@TL8;TBr_9cm#UK`!oy|l)4Q55l>f4nyUEkHn1qRQ6yG93=ILr@- z$wJ=89(V6H_?{(+RpH{|q9!zl@(6BA6|fPXY(@pC73Jm6A26#mh11bpzU&0LV3+v8 z5{RC{N%=)Z+#DR?LR>O*ZR-=BJ7b539#L|QQ)`gN?%-2^Iw3are|1!@o8J+yRvjBz7Eg#lQ zc2*Wx@E+z4Ky(L=;Pq>KC=Vp>J%7FpD-)_Ja0EhPJcimXLFc~O{6Stu=0)&SG-(Bp zLFf^F{BNeszaGo~jD!A9H?Rsf*)yGU9W8GB|IxUKah+{ps=tk zSsFlZb`!OrI$M@jmX`}MGWvU}%o>;mwLME~BtjbwAd}y|r6(l-;Q9}^%6ZLrGr zU-5(QJ>I=O0%E_3scDjgx449aL8j_5#J?y_eR^L(5fKTGU1fJxwyj*CJlR05t;xJ7eQMmwedBn(FF;!orIj5vD3;EWe5K zrliNIrpnxBtN<2nHc{DCuQgF&%so3GA47fghA6$qqP49J2pOvqtDeLg0=&GO;o8wM z_&r^Yp4;2op?F0c1XwrJUYIk=$3C6wq}gBlHCYci$=b09_FS^KXS}Q1`tNP zLgLn~2X!W`Ma-LdIC5Ft1IBu3%JK>P9U!fbkB`^aPu1*$z#C(4U!gnrq0MoQu zwjxwM?ME~ZSuiJtIh?kyfIRi5HZbL;_(TQcLnzwXu7D18Gp22>J+9cIhXGvg<^gvy zMz=LIH9>a;k(@@@5pp0n`Q=l@;m+VCTmrnfEdSfl+Fkel5;?hm^U8N16)9AN!>Vt z$^y7NI2By?WdgsUT?pHS*E436iwS+AkFV3pA>a**%d9iq8lg_Ozke&la%fGnAwlme z8$tfOT^wgXXmg-7XmCGL3mZxJIqS?!_w$f{e3rBSr~L=M24S2V8ZaPHJE8uMMoBM; zZvm!lL#hk)3mfavVGbIg*jWT-)o`aHfw13y-LS~Cx4;YfbC`gzyoYURG+ZbOW+d2Z zg=6`d1D?-onWr{@A+^xb1`Mgx$oz|#bNF0-a$s*U7wmKt8uM%YfAVo{L(2|*RVJ>MM6O#UgYdl(|83LjwSY z7Y&j+NXw2rtKlOQh#queZoHVI%v%fF!cmSz>4epcLIGKagq%NjZfaw1h#UU+S@;g- zkB8^w5O3eU1y2hzk^y+51>PCuhRQQ(4MAD~ggFsWFv2|S-)F%}D#e_|2J^Wui;gSy z%tkeA&et(l)}35=4>R~}%!NrkLaV|t+(aY;FCz)_^3P$e5`~31hL)BlJB&T=0%mwF z?0G7LGa%d)(!~50Zc5)JkzhU*n+tP69M~Xdj~$;293Hp}M#RN2=lPs1KKpG?Fak& z;8d?nO~o3;%iGFNUv5jY$jc}lkH!q%nSR;HiP?w-Ij%1vDuIn`GjubBACa9l4q5!|XfXxWFgxi-a?TZOyVgV5iL;Bm+IK$W`*~-vR!cn zr&Ef@dJA}w03HJ0cZGr?N11uV`C5S%l7Wrw0!=oo$k5fvA!$UMlRk}QiCt2Ka`C56 z+dzVVGT{iFAaZh++>aks<54CJCY~vh&yZLQ6&QzRq@y{BlZBO)VdJ;&Vio=@b*PoQH#SM+}t~uMk%mV zl@=GHAzvp7IYi2tPKEax3hjq4FE2x-W?|`VNMXPG3&Y%w4i8sUR@zR~CV9F{bx2<1 zU}p~t32}V>e0I$RoPm&Yc`Ea?#%p`{IM~>1);FXbK4#Ft0xRaNpm`LSqxD2=mU`Q) z$qhKSxNPWFgLDQzArX|9yMSznVQnwVLz;sEHa$h=?%jE&DNJ7)K;P);-mcOwK6qfT zg1Qw>1RYb-va(c3J?e-D*WZB~bGB(8<`n*t5EqxDkqblwaDZC=2_vke(m?6h3>BsU zG|tMJ1%l*tP>_*0)BaHfwZ~ zk?~h%hC4b7JzGG;!Ln~}>AQ4IW@)0XZY_v{#@4b}nRM&xISycQioKJrqN=WfG*_cw ztY?rS?zu8v(-r~&{$IwvF+OV`5m{m}+;f}Y6*VnAO4NL2b2Gy5|R1W7k+47(20)L zn(3g#%roEsx(1*jluWg?$+m9brA^Qw3~%o9hWpS8UYtlGXn`tnSu-+ofq8{s`CcMZ zF0(gfuxZxS*$!@nz_`m4rcV)yaTF9NFq;_>d>B*)3oKO8*io>}Y;QV333wiLmX7vz zYHpKn7>Z(gWU&C((G>Cpr+CT<1R6Tn&>-homd4ZGD=Vi`YM-&!UQgnOt|TDz0L(Iz z27w8}tUNn=4n(jI5;MS0{OWzc!B^owTWw(sx@ft>93csKyT^=W7E&I}EiVJE?sIvb zQLkV_W)=-iL(X9S1m}V-G&uFx(WvEOTRg@Ve$1-NoylwoosPgGZyHzVuFTKFkrY8} z@3EM+-+K>kwIF+EXNl)av0iq8J)Ye3^mkaIjweozQjR}Ekqh2w*qY#R1wxloMC1`m z)XEStqlJ*bhn#QVEXkECvC+{Q+S>P1iYNdaI@xBHs*oh0M-R4Ki(@~Xrd(|f=|N>(`^b_&S5|4f_}gHf3v57eRshjJTNe= zOMG)}4T8x)3fKR_l_uMhG6LtM!4RnpaM?rL;Ge|3#b8~|z`O}^JnVw9mDK?QYE&3C zYJbrpbFiqhUYv&~;>ot8h*xd9_a5}W(bCdFVgO(sc*gn3ttCxE*C$6`0}~QPL41G- zZA&cm1Hb=$z-O+jH9O$LF}5Z^FMRR@D<&8fy}XWrl6sUORlcTXHBQMAwYa&^2RL*b ztlbTPBvzJ|%G}F|(8UYj4q^#VyRZX|jErbSUBGndnWntExu9l->4wGk`wAJbPbr*Q z2n@Jwa~qke3$k>c@B0>FGd;nc2K9ex*Gj6Azp-t7FTz#iyBS#He*kp?QtopW^kZ}L zIW)QoBHiYuqvSWRP6GKoIX&H(9vQmBKD!1?$93Yf;msSre%+Ik>!mYY%%l*dwS(LTn?lrc z-%(0RN>cLFL44u)vi6=J?+1@^Nc>~VTc1I*SWZq(y9v~GAkcCj#m>Y_tq)ppPzjjF z^VtQUeX-FCzCGSLz;{d%w|9C$X>#8nRizep|kS(M+YgMJTP8WZZAW7ZK2thIzWVz9rT z^iKyO&~3PVf3?<7eReBHFen%6@>mzT!z`)RxqxZ&%YP`V^c{7&aajYF5QKhfkPcxQ zfU%k@dvd9Bb92F*C@p=4rdBfTO~r?Ia9?`oM;`d-ebnB7?l3?s{Gy`N2l7?1K&LXL zc=Y1lP@@fJijrFxqJn$@$pCi-VCFvTnzQs!WKqHT1h9o(T!h;9W8Er6jqay2gWW}&d}Y=<{3q$( z&72&_Nl9H?TtvIbK7H;9!c|0rh;FP^ojL7hpt11Zd>5GT;4y6_MIREKMUOd-nx09Pb#mGQQ?#EvQM^S!oTJJ#H7o7Y{XdI0cV?EoVR@H1k69 zDrAA(pTQi83H-|tl_LX35dyXov6TlEd%1V!RtAJ%~*53I!cTV}pYNkT7xw^vj<;L9{>-g560fU{~w*e zxAfkaR4`*&HW=O}3OmVV^k9B6yyd-x0znc~ZbE87%q)O;XqNnx{BQkrD~twB=ehYd zFK-zFl?i8P4(8hP*0$niyWrZ{-$Kxk+ngxcGru%X#|GK7;`wsCPTp~|#4$Y)J}~%g zqEPG@8i=WxoAM6pm`fylYk$b#TV7GoGpF7yYYnaYJuy5^vQ7@i$j)!yU`sHJjhb;T z!tztiDG4<`0{#dx5O{b82DZQ%)}7KmKT{-wr^AA}8H6#ztFu7;{>R#~d3)Q+hvc{O z*V@L$lzSKs;wqXf#GwFX7Wm2FnE@D%?aRzPnL%GuL8CFSF_E}*f-ibJx#DZG<*fGU zec3i>fZq((+*dkt>gArD>ser@FXc9gc zzH63GOyBS$kpNh%435F+;j3BTOn`9O+h27XQPvLl52~Y&1D0J$A^xTn?GYS`?>-?M>ury|pZI~m*5?gC-@^XJ<~ll#W2 z-z)mc>aMjiQ?vVc(>?4rm+V2*E)h*}p zFW}3zw;6pwncm;uXE&%#Pp!#G(;>1S}SpjXn;Q#opXm7~}14sq0 z5S`%D&xtodWU2GmTZg|{l#T#;iH*JTAg><6MIAJb!+CV8T~s78V2Q&5IIcT`E2RNE zIH*>j1p%38QL5u7d5M;G{MBU_kZQmL2Y3tG;z5Yn2X7gLX9YNmFg2=9o(4!(AT$Xn zJ;$Wm7kjEN*$Iwj=O2|BPC&*16g^mAU{@qEdg$&a;Hv5y2P;|J`9q^Q$t9G5l&PZq zn|s%BcODITS1@+razz~Hl3%_IJaF-MR&r0Y-X#8vvW7?B12jEsl?M;1zKXE@vG95q zFFl%yP!ex}$^e|0@l`>0V(w9$yLgd~$4nk%DYR#;;gKx!KI+TYSaCcHcfIXVQqYU; zk2K1NTt=E=h%b6=^H)>uXGUl`eX+p?TZ6uN>z372Liwj_Ku_eo>>{W7IOX+9kfiBj z>FSfqL!DSOm;Nh%|NptL`CCx^`}`CP$M^e0&F z>qS8cW{HyXmI=HoiGPW}4^qVYfO(1M&z`|A;7R~7-x;zs{EB~iXaq}-A|RdF`ph|& zn>Y8M!3HQVFt5&2XVd-K^ALXCXv9TR3t!q~g~K>vy0b7(&Zt1Bv%pS0+68hLRL4!@ zeX3WkQNN9_mirIq%gF=p0)XYH*?b4;kvL6605%@psjH~TF7+Dw89C@{0u>!(O%;{5 z%FF;**ETobOJREc9K$yD4nJvUf=vhx2KE3*!z@v);B|YP}s=vfd$7(=o*AHH9I>?MoRj$LKj*S;d4q#T~INDrq4Zg4V49Mn!>_gP}XGC zc@Yp0z+HkW1yUUNOdvNSo_7G9_1dWoTnFGkwXZmYdJQfEh&~uDw1|)p_|fbrfU6NW zMZl+^3G918+c4c(+;$fQ~tEPeRdXXg+ju7L{-`;U7SRLV!yE?hCAIr%QI?4SwnLw>$~ z)$?T_wt;i10O>Q|ga5S<+(amV>tSYq0}Al-qeo#Ap;0qX62lRwKnDWduvM4(v;tsJ zc!wnLE>xi2CfwQ%IHXkF)JDkik`mHUY@O8LanV!+V#)ht$2&@H1}OiYnObuLVar#cJ(8avl_)QOH>U)YGI?+#u#6ayBb0a(x)R4- z=V+j>5xI~E_cgn2em7(9T-Z4@|k5OsBsMt*U9 z2_)UnzXJqYj$(>92H1g=tB@#&%*twdm3ssYD3E}n=?*S_h5^emzmBACaSm5&k;X&r|zetxH z9i1g{BfJ?z>Cezg14kU|?uKV8eGY*y|IbQi-+_Xraq_A7$>9bz4(`y<;aZQ!_OLmW z7a(MB|N8Y~%>@cX5ZJ)kH(K}@hvxxEb7C4$XoCoI@-Xaw7i)KSBAyB+!e#F6?SZ{e z+;bn)KT(%oFNWoSErE;&02}e)1E;scS--D9DtUu!EBFCxgkr!Hb_aAQZDbEl2>zE= z*z=5rknb@i&E^ycbU}9+{3O?Q*Npun>4^hj5MRZEh={4FJ@ zt3VR}nS%p}j-cuSy~4>S|GV`U(8Z(|Dw-E9!N)3)rT&7&IfTH02Kii?C<9 z;`wd~3+s6AfyK!CU~~e^yAueuYT(G=F$UXDz>`uOode!m4uchV5R{b_;QW1fFcZeH z9<@z0n+kmaV5UzHc3OnBPen;N;$^@FGoBv^BzJ!MU3K_|?!e_;U?ONd5h3?p3GB&yU_rbD2 z=#GHOI>~G4#}DO)4;w>Z-P%8WY6wGzO8AK_0wYvF+S+j zl^b9nx99?9V6-4B%-T-EHUz77^DAU6C|kdNJ@t7BtUpM5k2OTNxKtP;hDSy!tEyIq zkW${QP{>0|9z3I~qN=JuyV!qEmB|-6_5f9l3=eOujJX3r2&CCOo{pv_D2cya+!XI( zW0|Amz=IAP0~Gn2O#H$@MDO0bfv1(tACQ2kg|x-k!XS&W1v>?$Lv$yP)8ONgBi;g4(F9Z!&yj$cD)M54V!|CE29 zuA&~@&eMQo4FviZExS-c=4kN`pB5fUK{y{Xf&_b)K_#N&e#U(P(7&K_-HMm8RHp_W zaOUmpeRLL<=s)Wi=A--}SV{k|qT1X)YD(%+35}4>=m9mBL#r?q8XBO+0`?gC8}^Ud zLLVW(%0ctL1lV3CS;ctXoG2Yk5u{>bViFOdEs9DQ#cu4y8{n_8eC>1_@d)$GEEpB6 zLkDBATepIb{gl#_uYhG_V^%?Kwc)II%Ie~xuxV=~1dS^Y7yq^@QaLwL(wOpU(~5iC zo8WreHbeOT#HhL8@RF4l4QqOHbJMygXPh#Lvt#*%k?X+IjnGx!V?t(HKMA3Uu+9WeEtN9%bOP zCTiIY=!2FA6VeDOrLL~-@m7JinCCu7OWd%@AcH^<0@DePcm8ZvRHI1hka3NT+W=tH zkCiJ0*MP_X%wL_FY6vs|q{Q;^ArHV@(Aqr&I}!33RCWnY-o}AXruLvltqaw{NhrEaN8Mkeug8d<|wS^=C%(HOMt$CBFHX)9)s^PSd(EjRPrqj7tcY4-#;0x@{UHO zabisoPzXDMf4Uo=g7nsD)=hlEC_=XDnYM&_G&Fi+XV$3Zv!8Miaixw?tGfAK6UNVa z>Wk5PSzQ9^*~TTlyW=g}EN>*7QdN`m@NkI#G-f+kgaE_8OvWXD`U(6suRA~H=Plsj zfI#E|FS@qYvvWk@YHN4y@C+JD`{Z2nGgv!tGq-nkAmR+7P>M=Q2S>*Y;d76#@Kc6@ z9>3<|0nC@DXH8jI^T%_XQ@bQbcNim{ltS_HK+e_6s}_l*_r-seI&4iA+$b%0%IC|E z#YL8|Ddr&EK~Soy%geu+a3@lIuGX66-o6O^T~%YX)zu;C7GOEVe>FBX2E2HOS>2GK zm$S3EWqu^Vt5p4hgWA=~m4H>W@v86M$8r)}6HiKjm0vkS(wXlQ)8DPpCzph0UFot5 z{GToVzi~HxOR_U_%g zZ{NGhd-awvDRb8}uQ@;SVZn`;B}=CKt&6XpzHDXg?Q_=Ka-*k(YKWX!{ORYO$o1QG zUT^>2ygbwD=ikE*FXVi$vNdkYUaP)anupE)?TOEOfNjpLm2=iiE}ihTHDOb>TE^zw zV_BbrKNp5fj{JSS-Tzt{aDi}&>HQcMpHI2#cyeyfdnue(Idk&E_#NxKfkD8?ut%1Y y;e-`K1F$y)r6SoGCIAPw5Y#3~%geuf`O@9por>yIp6X0_DldQf^5vCinY%``;K+!G&#Q`b4fS2kBh%Wbs9#+^cR6jDedyr!8;FL!1jdZ zJasw;4D5~TPV0D7C^Tj?^6Nx8rDMumAbKMXo{&N|s=M@OK z3s*g3Xf#$P=OP)5HDq-ECL6-w&XBia%ZLU(Tu>DHhaoKcot~^M%A1TPLRwdjgSjwO z?S7mkk}e`pSo>9?Pyh|hht*s^O+UXu^-6jkAE5aDK_r@uxby2avQ0=*n0}Y_ceaMUsyHB-`f+P@k+SNCu={?jHZrtE|*%b2?WFoxPM_e=z%dZs;kxSpbHr2w% zoq;&C+x;j3*6^I~s@=r~@rMYD=vjKKb0Zmt_D7vlpK`s&M!+I8fq<(0;poV;#o&LO z{@Zm?N?GG?XA3pIyoT|_JWSGm;Tk{k?R};92N(1IG2zm$PUds|)-a$CR9SzXu`@BD zOqDjsnt|ZS5np%gZG8}37cF|bWhhwR&#QG}>22W(+&{aM3!D{4`xmI|e$F1QLKi)p~J z=wy}7XoWJ6G3=Jprt`D^h^MAyBrqX@Yu39m`#S=HPinuaHMaTHho|Xd`_mB>^@jeK z{)8QtcD%&4IbJE))z^FDL@D&UZ|0s3abAslAT`oR4>t+~I(<_65w#x#9D4_su+Bl( z>P-i00^4v>A5Di+UPXVNey#mB42Zxjd*Lmh_JMvD8z_|b4pI|uiZpr+>yt$A`3Mb7 zv@kRL=784)RomeWksx~#TN(Frmr-lZa^DgRS2@g0BDK&@dT6Z0^4U)X_)g$vR%5mZ z#-}YJf`DbR?aJO!_U0#zt|~cYzFWA1x4T25Enwd^AY3Y_TJuS@v9s1$ zD5*Y~lcpp9*ZeQ+dI_v2058g4lZoR=!c(v=F51pq`Kl5s*D1Cdr{ssmCyU{fS1U6= z02t)y?otJ#tw5AzzA8+&x9zxln>teCbf5j&Ec)aq8hvoW-g`o>K){LLgUB=Df*!ao zEb>%VFzRsc#Ny`B_w?iLB@iFvBy{It<7$TnB*(3Ncn5j99(DU7F{;No;woK-`vz_B z&X~s{mA)zN8e|@cV;chbfU{>fxRrC-jxaIk1A?Y|$kdi-< zuO^`Eap28Yn}{OS4kb(N@GL-~GgS~c@+1Lf_cXf}mQsRbCiN2mPs5@8(-hs(6on7+ zLD8x?K?#P9+K|h=$V9bu~p5+lYzp0tVZiqEL!$ScemDv zNVDoCamk!#Nbca$=}I55iy7S@3s)hWQXdU?FX&NEw8@Jqe>dm_N{>zK#gY`QVI3$~ z_Wq~XrD9|C=%xx|*2M>Ly!5Kf>kp#TGg9)qTJ5gt>1`C!y6DwE{ubxkwzRp%Io+P; z{aXIT5dTnq9&cHi`*GV`O*<}e5i3@`NIjhdn<;m&HC+#$VsG@7}OGM2b^_bziAm0t6$E5=SH`WL& zeWOrp$4MvQbbH8UE_^>^PNV(m5@n0GmV2_}aBr=9C&ggvXMYoXOHYv!1?^DmUsG#) zc*t1Pbu6|5X=hqj222J*Q~%0vCf`aM=R3*!>HXoPtuN2nq@d2?-qPQlgd)nXu|rMB zt=k~O+rp>c!m5UTl+HD>@BrtV6#KY*T+={3_HJpKJ~zqBRfdq9dyQ00(lsX z7x>YVF>x_JMF;J>(i17w@|kZ;?tPG-%U8$P$o?X?>^&wykun@>V(Zb0+iiQ5Bv)WPtc)eBON;(l*30SpT_j_II^QrF8?UE9}b8* z=b|O!Hv3tF6l)NDh!p@HL;9-;{Ed@!1WvqBZ8vGqQ;-8kbSc;v}w4dub;$?S73bsJ1 zzkU0BomTCYMXZ(K^}#1G4?;U>#z+ENm2$qY4i)!l&zi^$Pat#;mxy}v%SNV*?(CHE zAPcLWR}q5(FRmC+nk6XC(yi4{Sb_WXjZr7!#&|Sy1Ut8wlZBP*IqQd`GN}=ezRN}4 zp%DE%aqoGONvI6W@2atQ4@gs1EoP`NHk>On<-oA~yy(HS%&rZK-K*+PSr039CsI&< zKYB!S+rpej>6Zl^9lhA_3tpB-A2*pE ztFCu`hP+Tw0f&iVe{mua51|$=20@>9?3buV%-)X(ugE+fK+++ezEQg5juatAH%Ue} z=~enIlE3J-Ct?5ie=UQSP_XAIG8LU(1v4WJx<}HE$qEzOJtdT)SXqF3!bl6Tgub2h z5Y*>&T7#fC=7{t0@-Z<;wasn0X&ehJ=^a7xMU0RDE&B6*#c;(1!g(i;nTp#kQR*oe z-}}$X&%6I9x2Q<~fY``tP9%#Bx%ULbSK-IxDS?)EHE&hAezF!fy5C$G4;;fG8Bxi^ z-DJnQYXggwj-GqLP+{Ue-$^7_aHn zAnGIjN}Y#4XVhj;bGww)mVbgGUO`xCPJPA>zqH*iL!z%@vE|HK?#-M1wd1lOT{dx( zgwel~Hr@&wT)iRD9Jxn*SH7{*7t5 z?km{dnp5(rxTc)W{9o8*b~=nw3+>YW_fgd5Syv|>555(e^O`kK#md^n<8KA>utPdy zCH+sO>^iv~>Kk6!4SsS6l64wO=eC_caZE0%)GiX0+<#E<$tfZ*;8Lr8+8^8IFVBXu zlIs6-PXE(VVzAXnGH0q!GYahx`c%B2eZ;1|b9wX2NR1Z6Hinh=c`H+9+oSrJL(o~F zK5pt=$VX`|Tr5D5!)ZVPqb6Kow@{~SmD;npi*^oN#kPd$vv9pCb^poSS@M14x|ab)YwoQl!AwP|_8%HP#oqbBCaz1zuIuTc&8wPDSXZBaJ!$D1SlgUJnE@ zy1%r+AMuT?#Ic#SOw^$$@I9B;PT>2WhU}jBb1g@PAVZhCBzq5}!>XX~fKZOZDjQH$ z7g#k~QeTw_HZ3voaTI7tH3X>~?eZ6Fab}1++2GUCjY-8wBk0UGPqQvYq-wIuVOo?i_?>%f!S&NB9>(aE%OR#5e{dGf-guGk4Ev#5qY*yS? z^(pF_VTdIjCsczT%^q%qVb`ky-RjAYC@PY(D~*9A+dJU$QbSu)JW!zK{b=^r#sQ4a zyTFnLvL&Te+zIa6_5$T>m@}@p)0l-Lhw;sY5{Nk4)SsYx~+Cen9CwLyaU60 zxV+acht23NW(o_t$|aUZyX6Oje~G0L4xGE8(&YVpQxC+`xVuA)i zw_8w&NBrNK-xm9mEX-eAkx9n%^x`WrATW%*GW75PMNI6b+L{+sHaQoZiDJG0Ml$Nz z&&j3szNWcb_mEf`tgOt{37oZtxea{pFQTv*rsG*6w0`y>!h%fY)A<6=l~icgy5 zr?u2uui9=7Vd&``-e^tE(n@O!oVrAPTlgv3fz#3R{4-hu61TBR*`i|+2XA>qKt5gJ zvg>nD{F{dXUp>E9M8`x~LVpHdFLf$3^y5?P#k6N+}bt;U>5qo!tnE-if^RDi<-3&6h^F|`G4PFX;g z^flfUtfa<`6k?38dnr8M!2l_eokli=i}Nw^+&&FMLqA+7Jp z0_-ktXd6>#*ylA7LL>v_2BHp?bmvl^XQhwi@3YHOtZi878u^HK&IhqAG5ts>UU$^$ zOAs|vDAueUY5Y);r@|P#8Y1)5`|hSsYr?13JaLg~E90*@cx?r?wv`5Q7d3yf{_>_J zF77>*s7Q`)nAPH2(bn|SwW@a3S8P?_;Flb znO?~`<##a63)vODqC&2@&f%Lg>N!Ww0UEM!3313ZxZZ#eZII2I?yir-*WaR>miUh8 zp>vdih%5krJ%iDbC=m?!uvUsW5Akp{V_Q3=^rw$xrfa>G?CeSp29tQ>(DPSiI1rdS z3y&rY+|V|Rj~l)t>BwE`AP%oSGWcB`M{SA=N2(rCNgb4JT?+ffpW$^CzQ1x$iW#k# znCGM$`H3{129{Dv64cmtdt)sa1*I6~kgJbfT)#ZlsqNpNH9IDdK>v3#^RLm;KU13j z*i+71B@CQF)xlS$9&NKu9jwIe<=$F%d|O-O{qDB5*{^wuZ)UIQn;#RG@-5R|(;UP}d>Q7ClKGQM?@XbCqeIWZ$EeUfhku+!M zZsbD^@A(Y5!D!8lnRH(6bv3%PSySGjhZx}sFS9$YH29pd;(u#*v$KB>wd>1iM)-jX zbAgNpLU+Npr*Gw{l|zL!j9rIe?uU;(yXG#O<^4FK6R!noP>vViN%;zLm;rRSvR4l$eFH@wN?Q*UZpG>X)EdE07BdwP#jdZw#G0se`ACq8+eMT35wj2M= zM5~9_rxKVJ-SHPpjY;ncU5lCYuUbk|?2W5$_89j&{|q?-Vr4q+nrG^oe<;+BF2mN5sYOe>*O9HC`pgv8zLULY3h|ws zB{G+GBx$PHeW2WLJB`**Z7RZuX`QSC!EC13$!B0$LFg>X>|deTePJ0o=UC%6Z4WKv zc^vi?C^(_y;lO~Mn*Zt5FoRJ9c*+6T8&VP*mU;-z8qgjkM0hR8W}rR=3I6Fl{OH5+ zS45r^3Wiy#lM4{e^kdiO)t0lUvC)DyDhmzRf_TTx$_t{)ukAK1HQG8g$yUNRQ)QID0X*AJ$9z diff --git a/docs/images/DecoratorEnterRoom.png b/docs/images/DecoratorEnterRoom.png index 4f330ed3375654649d3b683167f611b3a01638a9..f5bad1580ed0dcda8099e389fc370d70f1aa3fa6 100644 GIT binary patch literal 10346 zcmcI~WmJ^W+BOn`G)Q+ycPbzu3@Osx-6bF?AW96~UDDkp4bn1zfYL|^(%t=SJmbZ_7PeEr#(Q5USz529tozP7X{7wLx@2lIRZv8i z@`q5QI15|DDc|Q0atR75RUc-rLN)a`zsitNNRo2$y?TVOe)qODI5{91&OdJTTKgtu z^%=vU2!r9-ua3BD5I5>Y4xDR58aAH*O zf4^=QzwuF#QjxSUku5&yv+6dKH8ly)(wa_J8AnkFe;XQ_t1%y19gG{}{y;(V zB|SVme06noxjWd~%j;}^@xHwA*SFD8%fw6(A3;{u@X>W-L`1uVX7$P`p0M`2tL+aT z;3%R9@$lkfW5xX>`cAyLgBt4^`7wiCPBz944xB`?M4gs8dwP1Bn+3b2C8eZ}E^o3W zf(r@?+%CR$(k;y)8DZ#l6tC>>8>*?9xhWeP8_USZfL93#32p6}AH}MT_H$Akf_`_c z5Sqc!(J7mHPft%@U*8jUo90~ZMlCH;YO@|F4r-uy=}!$!&Cx7TQEF;`1J|>inOC14 zX9&1RmHtdjNT8#q*D**qT~zDR^dcjH$JxP!rlh2ZXFKi9H(j6Yws;)o7*tvk^!D`V zH8}@1>1b;c6A{T6X7XB(Z%!0qXpS3G>42$LuTHmNIoId=*H>5LN&S)JX_=W0bqZ*u z;#AEjn7&EGWy|~fj@yLqwzsyNot-Q6npD)(^2V$p$%W3gN-J^2ug>@H50)jm!(Cil zY^|-S11_$v?yeW_&(6*YrVhY2l$4aAIWNe5lP5Iwew}?mrttc8SXx@zX71I=rmDL7 z+V9_{U%-4dv2yvbgJu^}JfX~ReeZpI2-)?%I4z5d4^*4>C$eg*=;_I$jBUCmBqV%# zjKMABZ#tZ+tE-zbL@+6Z!X+;u0q@^=A~jSBkEagTEUl-f_vQ_Tj{pq~jgZjX&Vp0~ ziMod$FuqRz#T;%2F7yq=$P+&+JDpbr;-~dm%KTM#Gi;MebG|Nz5 zzkFiT_vWx4hgOQSr6RCiJJ}O9G(`H+!%0CQ(pb6oYYAsCGzV2|9YHx;36{!NYS`fm z?@z_ZX!W}<0s{jBHhy#SK1F`A(b3Rfj4Ez$)mfl+<9oIQZb(meH!UY8r+`38Bxk)& zMso6Who2v?RT2`f)d8IDDqBZ;0{EDmqBsV{prD{5kC!2k*wob7Wi$z@oFe$|mpO8c zoNR?v#G%Z|693_tUg!m`|J_&rvlo^wpBNh9C&-z5QTTDv#mIa|*`WRyXF8X3P_MI_ z%4ds0U8-5h&ctLqiq=h-f&+yUmad#C%*#VWLK5~kF#1uX47QOwMV>w`S~-_ z1Qdu9{>;owcQBTy@6AP%%X<6m*&N;LL=R6-bq$RQoqA?AHv55S>g}mY4mLJPiC61O zCx%NzsAy=<9p;NBHr@8-iAhOcFKVf);}Z~^ZC7?UH|dE(P%U*fKbcKaN@JWr_Ht#>C(d5;EYSPL=ES zmk>)C381I=x7pa*F8bZy0^5ru<|!yEvm48ibXENRJzc;hl2X*c11)LD=Xm(}Xoisc z+Bbamq%dNs&S+w?G=;*sTFcS9+iOBrt%IbFo4`wB6;-KR3stW+5h0;#aFCjn2KucY zhp}|8^Hi90h+yJaIMablG)YNGhRv=_OiY8~B)H-|Ce>=p=Dt~@c!J>|jJ?R)+1Yuw zJsHxwl9!kF{kswiWxeBK`^w4+N5{?hw@%4m9BgQ(jYZgi#+K6$I|8|JqsLovoquR* z669@%HN<5}l*}J%R24w&=q7Y(6F9q3h`1#{AYo$t=Is8xz}!!Kfag@qSGhbyZYI&fCOm-`H(i2IWd zm*nb`r}Xjh@!(dwe1)l0u7_DZwQ)+W_J$EU&ej#{exq*_vFSt4Wf8-|X%?W}psA6| zZ+2e$R-xbG#fl+&{xfyV7=nfKxfFZ@p_!?-)odh;DL0FHSQE%Cq+qCp7I($WmraC* zvRF~6!{EUrES!|r*4An*hUMht^_pEbBS@cnJ;(6&{b82~#;7($_T5DCM`7=&gTi77 zE%yIDK9rj0OTaH?8lmq+Gk6w6V-kp#6D^Wv$RvEZ-B7UI0{nO}H8rN<0v!t0O(LcxC`8o#1 zbuRnYa$QN+8EIN}{<+)$1z+d%0_aXnE?D81M1aH6dr31Efj8yEtKxVv4_TcF{}wdRbnwAjnUgiJKLgG|6C!1{tiY7aFo8{?lkmkiB`j>D;Z$e3gs{`^x`yhun$`>n?#?LOB9Z_*}z{OH*tA4{3` zDk>49s&dM+a&vRDvMMSpT(2_jZm^p<0twqbMwQ) z!`tig^+S*4zn8x|T0V`pY% zMSt>yiIvsP%8HSNB~9?%R)hWAhUEHaR+7xK%galha()0CMn@~V#p(C}m?|c`Ywr*UG$((sQQMy`h|#rbZtJPNcHU zvaF)w?C2Ccrh$i0qSAm2E zMP+5YK6c)uU+t*)d3jL~;fEB>jKh*0v=L3*AJa%G+tgnjEO(b`lmkF;e16{X{*v3L zMTybX{qN=Cl3RGZFh9Q`DIy{ggkXO~Yb=1xRu+LhK0a=8rVQ`@xuRmkDuX~{jZFAo z$52;XJSdKcMfTzV(9OhM6QSH96WG+0`|{U7zw5ch3d4?e`?&@HaK1Ng zyEcFOCf8=LI6f}EzsJVLCU4l6%GcP?z?}rv_{$$w@rnvN`InWa`iRrBfHZaQ;x)IW zLk|n@&miett|b{hMkk7njUA8ZFRr?;O8ETwGka#d6F}{#fizT9ORy9kTIoo6Ik~MK z%wjd>Pai)vA92e!vX;Qka0v-DRaGSnBcafNkr96HM&(>7d^|i(%@m#}5J^Nl4mzFY zc)%)#KSoDKx3<2_B^7F9X6RgV#t^m6utgThy8p&fX=ZM|JJ+aK`V&_?2#fM=LQ$01 zVHhCY?@4T|&MzE0ZqF>Ud@P2A*;=>3D5u*~g@uKNEpGN8Vl_BG6B83V?oKP8Jb99s zRV1B8E@2^|tgOtSkX}??ZtvjG?y{~RF8(z~GHgTAxoN(?pMj0-O}WOlt6-BJh=i_Q zW9N&0jtxbz(b1fKcQ;#G0ED0ajuIW$t?sVZCbC*zTf?Au`GSF=zpBW@Sbc=c%wazf zMA-~czf58!_X=5Jmp?FB1%-mbqMMtWqobqba%(L$u9g8S`^3r`vw<5>G=kvvZZMXv z(Q(ni!NK?9U>U$u5E?BSicHS*`+IwD54y1gGZadHQoL}Y;^rPd3No6UnV;8FS5JtE z;R0}WdV0FAPwKD9y3%xU23sKnigVdcmI0%Bg7^^}7=S0htT|sFA0L}@YlD&&3Em%| z@(clZigQ>?@UZ+eDuVvtTtk3rO_J=y=`l6HibQp%s?=T>W`CoR$N?6 z-pMdvlSYOQeoN1f3#__XlK_7YDH61Q!TCO`6d@MG_%+ z1@wn9^#AQ`fc@{_ID!A4-m1`oa~N&+zZoxYPvLNE74Hnnf52o^2;fhg_+#HK~#RmjG70E&;lfiu|t51Hp`YU+sUknV^ zaBXH0`}ViY{apaIiW)@ZE_r8Bacf)Fft`twD$8fmZIs7SMj6N2-e;27xcS+M`8Fk* zaJSQdo!fS@10*+sE+O{7>1e^-K5TqqaJ%v;C1oAEt23S{TS&l`U^m0FfM(ye-L2c} z_(~2*Wi>BBK6AObT`n#)DXFn^1jwsaNWnjK3 zpx-u)x}@xxmoT7+%F6?CWL^)s#HkXvu2p}JkW64u9N_4PeuN++7h12|?@BQKz4@Kl z6uUTz!29Gfy%3AX!5I>EqdAhR2g{Z%7hePI8>JycqdmHvYa-{_HJjB&qVGjK*YIN# zB+qtfb?lLK`>kkG`7AMu%bpQ(;0At#Wkx)HT!_}gWeO}TFV8ZGIPH1do3w%D?!1af zUS4c)NAlR7+|3PC@0SKcH5kybI|wHwoJ@GOYm#dgx_i5Ry@XKXL>&@Ar`4*rS&nI)G0&hP;d#%vLs6N`(dVNFwY%N2?+#QIWIR>hPmX-wW{Dz?`eI-q%6fhFzWX9JV(Q$qoLJ~`?Q<8 z>sm?g^Vl};EFs6I4;6p9pk!YJ?W98mpeAK0w>0)9o zobljsrk7#F-0piWJ~R`xif+?}znuoUKABB(u58Kz_AdYR>YU@?YmOKZpMgACa!OwJ z^^sc4A7LD^GqoW)3k}ZQwPdqiM{+ENxWN)CDl$sg%ZD;zaI&wx_ZEmn^gRVq_`=YM z#9j)^LJ$Ssew~$KXQl}wi0S$i5{w)pGZ0C>I-cK<@7N}(kkyyDp`^DgggbKLgRrf+ zx38FxBzi6xgG0+0_;K8(c+1A-?maVg_U}q`9Pu~lG70fYI&7z7((#SY`K(puex~pU zd0Aomc;Z4sx$j*$TE)~g+`3bS^HfSIDt6s6B5_f$p$a5Wf;;1t(Ss;D z|ABQ<}Z|#biwz@CB>UCH*1FihlQL1`E1;$IM9l>B9K4wdu3O&0o@HrJ+YO!m?RJz zo6IcE1_xWx44po!ps|9hot56z{G@>h($!7XqgB~{h9eU#5n&TegIH}LH{foFh|xTj z0|POma>uY|xtm!`SXj7Z@|cwL+S>NdCx1l0`ozf=oP$~=X7-GUxn?V~y?wRoQ$wko zd1G4;i{?PV8?ytWuWPY}zSb=ZC#=D4f}ZBDUd^qc5z06@wQx{93n(*G1R=KG*6jEX zrWf38H`@@Er zD`smkYvr)$yVBM`j9Vcgn<3x3TS0sZg+q_{EXq^S`w2I{iCQwZtJMU83S4pWmoi9* zN_y;T`-=Gm4Q$+A&FN&!%mBbKWk;t9r!{*|%}R|7X6NKG`F}V%%)Yyj-uj;1@ML&g zrNqx~>(CTNEx37!JrmOX_M*|~Y1&Be7gJ;=)@K3&>{p|i-J8RzqOjyw^a{^N`L(?L z(y?MNoEk_i`@*ra*PC|ksS#63a=4&{+t2g)&QmTOa*VXj~yus|OPQ6aK zM(L)cU`Aw9*_ahCNyIY3?d|OoYVqvvLqlQhy$3Zi&u~GB6k~O;)I}2mK6rY2n|337 zC^oo2$^w-D;0uxx6E)P;$DYU-E*)RG8UY|K*Z`ryxy1&g&qKvq)7aQJ15qvg31(@3 ze}8uiVEz?%MmenZ$K)hGKYu8Mrdms0G((FuQ7#{_vNdYVy_j9i$D^$_~`Pz?`Z2fAcMdICCI%4g?7D;zPh@) z&cjurQkNaV-0b`#UnT6%i#ug~lSza+@zOXbGM(zw$VduduR2g$&rgDF1*Ug5(g@n zu?IvGK*h5sp#^?T{(BV_F&38T@bdE;w7*Z;yEJI?;^XG#78LaQ)#{n-38DH}ioCKm zl%%Sv%EQeK_y>!TbOBK0RBP=BmKRKH0^VxX`4Z3uy(WhMaIX)i1wZ10$I)ZK{%Lax z$hnE}@e{9G@C_lG&gysCm5Pb&)25~-Yin!grk5fjzJRkI8ylN01y;K1uVr9xci2xk zw04xjW65sV{vMXhWhIpBhYt!+nb)tu$pR(ApvjpoX-Kk`3cG6tzPh^l?OcO>FebSU zATy5EhPXKE-jQZjDhQ04$U2vsffFf}5-DN<6JM>`BPT$e>^Z z!h^s!+dj)KIouFL?=Q7B?plQ^#lQUS!Rh+!Omm?}+w%d24ip)nL(a&n)|ak@O?b*HBJhiV1Pk(k(iHf!tE zMqv-X93@-i}F^zbjVs7ij?q{ugz^oC-I zTzu|Ec6mWo_nA+>7swqr;?W^+m;_KzroT>NucyZ-@4EB@1P5>%z@zm?Q8xD9-0pYW zw_6OS0^#$>qZPb@y6kK$SK7^{28<9v#3fFJ9Zt+6Rjf7}A2O84)-8g(MD%b120A*; zZo4`xly-0G#_CCdA1f&xj0o-T01uq4vj()$!UY9|s4p2le*T!%s&kVr0s-d9fWANY`!ERo0kF(}{P=Nla-WiD%-D^85yDdzX5ZaUr=zjjO907Yl(Fn9UqV9Wi2Kq zrlXU(T$}!1wdDkgpUyARbETt#f`gAQZveYVPftJj^Cwq19svP8Hp-uo3|)0~b03!{ zfnR}y0(RH0-vPN(C8&Q1=*$Ca&S{Z)rtJTY-y0(*BIGcLSHTv5gG0W0=mj9-v%&MZ z1S+#hwN|#$ORp1|Y$a&#%0!{!1N9a&Xm-B0V5&hxMy98vWOTwRdVBKpm^C089O0k! zb=&$`!2E!kA21qT|BG@h`ai|#E~ne_@^Z(v)5(_ocH0SM1>i9xJQnCeQJpoX2Z9k& z$IHQ#SC^Nb9v&B$m*v{Ee*lrwc+M3I?{5S+VaL|PK2V(NfNu~lZ1o>5&n^n=lqwqKTLKq7fe$PJ51_Ik0{V zWa{wD{ECW5Pl9IB0oHFYSa@it$sO{82(GR64-s7SujsvdzQ1^WddjDFpLKt;J}@Ao zOZzz|N1T;F=+y)97)~L4wcx(k21qGY)d?W;{qo*#tE#F34lu`ry@>`)_5O0y@9r?l z4_G=qKYs(D68urlP$Ah$R^P}~g-7fVW*bK)`9DQm`7@km2}?G1{S6iYDEhCwnn0yDGWr}G+z&{5(9mGp?QLOc85|Vk<>iG* z%5Mj}5!PWW4qQn3>({R@g@uvPiK>jc;Olkl-K4#MCLhnF+Tgf2G9R0sPKJ%Ww7iUi zjeXEdXh`&HW(REauQu;q6Rz7`F+>_7WD{4{lje8Zf`m{!$%R(WKKm; z2MUBr>Xy)}bGk{)Y#w+fn3vZZxy^u*l(Yq$goR#uLW22=WIi(PG<~yX1zRr`DTzO_ zar9$J;9UGb98f?sVX&&#addP9%poEuTCGvhc<_aJ&OeGFn((6Ig!N9k8>72VeEIT) z()Z$3;e>VlECMnnL`sU}S2oBUV1Gd`$<4)Kkg8~*LdMbY@zBta=@m}U{q!(9_pRNA zYcpUr&wqJWmX(3VlO~`H1HLfmSi7Jt!DW49EDXe~s31y!x&;*FFhLa=}PmUMJPEiEpxF_({F2KD({|<08ON{60QNjGS1E3N`@3(p-uA76EL`x* zrcc@+tAlKg8v+5mA?UpjR+t>8XfyBw^DwCvlT3XC;}Ye;NT$WIbdXB>e}B`zWB-PG%1z`w0e-v zK?-LzX!Y2hEPwUt6<{%~?d{81+@H8OI|Ewz3{dJDr&q15t$ugMS&r?O^nC+xnBV?H zv1g5D0k{Y}DqhZ9PVO5xW?EX>-zzH?uw?24IsNQGKoL7QROqpb{_P{uZu5F)VL_iY z+CPH0w9$OUvINlB*FZGO(M(~#yO-3@*x4Qaz)}F)u5jjk=GArwz>F&<0U;qkD4;_K zaGG+@a0@-70IPdJJdQagDiInaPUTisSI5i1uzquS43H6kp5Xu!f>$W?;Oxw;rvP;0 zfS*rQ=nsvKCJn9m`}@Cr`xbPcWP;ubRm@NvC<iV>aCOo-2zI_TXGq`^K{CN_%vSRWV5`*#bRW_5k zObvW5*Or!yl4kL-A69pAvy4L$@ducPTz*YML&MfRz}Nuj@KfQ2fc*0?sPvOSaW8{d z;B&(5iuo#B+dwuwS@S;M8`JLq!Q#*651ab2r%1@i(h$fCA4+V0P+d+UnRst>=6Ktm zm^ZUXbL1-`cAo6ZQ;vl9w6(RRXuod$J%~uTK#Cs%nLe;^L;AF+goySG_sIj0hFe;l o|NhWe_rJH&{kNj16Y~yhye7!3SCN1obPK}CN-97q#Em}wADn2HTL1t6 literal 8321 zcma)ibzGFe_by6;W(k0T}EO7_@ z-Os)Ed*gHGk9T+9nK^UjednC>oabzWnup0^I`I=zAyN;iz2TP3_kN@46T9=Y?h z9b=mcbPe?OX7E{duMXyQML#%cCsn1qgVn;%&CLyg$Z_0bCyP8hbWiW=qzJe=TfqyJ zVj_{1k+HC}bn(jYYTcO*jQ-q=i}7lv(W|SoGqPh5mlTp;P#_>EIO$X{Xx(n+qN}Ux z>FF8EjMaoOjlKEo@VI|xcXzj{iZ4vIprAlqT^(FGIXRP(lH6AMXR2*Tb+mMKSyFlk zuwHkVv2t!P|}||J3C*!dX>Penw*rB+V@A?@AzVYFo-_aWvSDs*>`kSKte)dYimn} zjGFr5U;v7Zf#K{|?|Wpcrbc8AqhFmwoCWpqNwSN1ARV<{_Z#Zx*z(|3$ zy`K^y`fI2+_8ScD|ECo?-zgN|WBXWA(m3FR-|#S{M;$lwP9Qrr)?mD>tnAs}#;#Lt zSZ%HD>RQ#>3bn;DWx;-%I5wu;YvcmZ{13m(c5TMs2ACGdd#{VxzIo?hFxz#CUn``V$#mSnr|Jv0`2Rj*$r zhj|-J&~?_**4Eb5g=b|s@ug~LXgr})WQs3GluqTd2&R|i=QBZ}P$3~57BbhjX~J%W zYT^0J!SJt7vE^e#Q+p=T-pQFuN=iC9I(m43Me#J$!6QMZraqE{i2CA3tn|xCbYHxq7MRp?%OCFsOLYtpU4+);PMthYPLY^S5AS($& z`!*QtS#|5OCE5$BAiTc(Tv;Zvyz%paR*=bbPBt*8XN5$86v5Mi(M#Nf<4GhB^`HtB2u8H%T@; zGbv{bULUR-VK_1LkO9ma<-QTO{~o;2f#Jz3xERIF)-dFW5>{UQzl2dCi$4%gn%^wZ z7ETP0ye}z^1qAU=QwbNd?CkK~h_7gG)Ks6H_&ew!b_Gn<=XtCoP$1f(iIrSn)9(&Y z3)lS{zJ_}9D(~%(mo1^F@DUkS8Kev?F*R~o>$w26ohwlzRoqE9GWwXtgiXgL#&o>uK9 z6_1wR=_5{0PY1CpT5gFwbLPD?Qz0QV|74Ci0qJ66Oxw}^UKfUkSx}VFH>Q5LRzyat z!bmJDqo%FhCBGMnU+vC{i9Ng%D6gFCzM1NG>som3a#)l-Dp83fLZNumx!~#3MlVf! zj))Ha7q>w;GJjZ(PzjgG*B*|caX)n?bQo{OtuHdD(@?-UJ5`g#e3mBT;6Ni#Qf@t zMio(GbmA!6UajwWwvQ;nr>NSR5>@irTpbY-qdJ+?nbjPxHdeIBaILfFz-Z+ zX9y2hw&a9hVoSpiwiRX32+^+igo*e^GzI;W{W!om@5?8{ zGeU7>+&jy;1p!`|+ln&!9iN!!K2&~eXKS12RYA=tVrMerIaOOzgAn!N5*GGB&b-Z# z2smeGELoiY_WE&s$#)-OVgxiO(_ms`WMtXq>C>;yB&6o0rSCdA`O?dVl_K7po%5NP z{8?(lxGmT2@4rokiB(miBYHeMGE({6L%^WwP4t7Va7yBXBM)U*NJwdM@$g-A^qr={ z=9%aDJnhjYKb{IrO^MYJgUdoDYLo({H84dWQpb zL=w?H{ty+oW2*Oh7;Y zM6u>(#DP?!(NC=KLQrjva<=EU&;V*@IGOWs%8ABq zak1f#rq75i8|Rj{zV=w9|2|Xm83fp~6vO4NbWzzGsiKswL{|4h>#pH=lE`=Mq4W35 zc%P-qefd)D@Ia44yc!V&nb&Jbw6$Gr+)=0~dZeuOP5dDl-qt87KuNzQl9oQwbPN|h z>*?#8sdY&2Fk{GN)hwj0X=DSTn{mgOoGWts+j#P8p~R&hKTK7jGnE=eAkuO$ho!=L zZ7oG;(xI&n&uD1-V`we4*+qR5L&Lo6$w}L4?O$+mZjP`DS}GMu!!mpE@I~KR8O6`# zy(!?PR$!>64NHP6N2qw<}cZ1dkccTi5l+%{SL#MaMM+Cb zZzas#jcVBJI~soR-h9#8>E&>thrSIDPg!y_P0z&zT)W4;AttvMcJE%NT(p_eBh;xm zgk(l9=+B*~XiG+7d;-fLltEE5&6BU++fplb5J@vNAJlkq-m{Wz4yz)J1&IK*;wX^#Adgro6$75x9zbFKXx^)BS2GDjuK){&*)@#X<(HI)hv4H{AlF@bG zGPc8uKLDTRC~ak7!9s?YqxM0KMPj)EcnN9xLgQXjD%!xm@ng6QdCf=R~!G-2-K%+!3t?_lWP`t+(`j_hk7~h3JWX{;I6@;*NfI z-H2t(T==}idX$Ynp)Q1u=l1ygHqA})=es!LWwRiq)zE4N=V68B>5wn|*!G-Qc;UGMLO+ZHYfqACif~drR~#ZT{LY zE8}ee-teX~i1;z(<<52d1WZ=e{m8bfY=w>7hJOV0;Nz|K-=oyRQa#BYk;EC#$d(xc ziE&sSzJ{n44(744MaIw-akpfnc8Yk-t&cY|opM~Cj3<4LC~xR({B3W`d7`RFpIyok z8BQM;PKMWwTsz#}B=p*2n>+>86QdeOBYu_YZC?0*P$M*Jdh3?`@n%es zcz^PeeR&D(POKMiO){!Trv3Z(ZP@pYOZyKWe(WunnNP^mRTe_V#yVTBuloHtj0&Yc z1-TbBBQE#xQ3KZ&$|;_uP0k^#WUu{Jgm%NT@}I)C$Mdu3>}=NDlSI;4x@+LuDzR=a z%PCPs+kMGy*r+e%zGMke#WmB=M~t2)Mf&e}Jy(g86`cL+QQPJM0_Z$>QA!>6ABc__ zl=Th}n%$Q$bKTQ>6Ly&gH6w{?j6_bzsF!zG2#LqME-H5s9Dg2b=K4?b5f75`Z2GRS zsZSw_O!hM(wQkIft_9rVoqg$>)56EAc^sS$^c`6j#)@}KPy(uuT^Ki~X5*?pR~#=n(_|LV2qGdoNEyT62=q;GsgaVQ&& z)x-5mbf`tgDh)NHY-@%|!y|LYO^O0gtA{qes4ZFv3B=&om<>r|6`$|vi$fWIcI-{> zP2S1YxiX!8gfe$4Os8B;8K0a&Q-3lTfqr6QFkUgdHe4MT&~^S(ZD>s-)XHeA=~58* z+pTHE=;)ClDPM6;-JdC>r?J=B@g!CHNYiWzllof&_UuHSR1$+!-G%r2H;`BD^NQ<5G0h>52X z4qgzF#B(ja@yJB&D+y_879BpG86mW{)@et<`?=O9m!)4v8<*X@Ay>muXK*pn5Yy9U z%<%(Whgn!bftDJN6qFV7mERfZ945Z?7{}zNZ)^C|sj;|+bPONA4$sSTnXXb*W?>VN z?q>gLAN)y6j!qA8<{plE!akofZy=0@#t3<;Wh6dA`ZoBM43|93Qy8T*LD1VJp&~SC z(EESNL;sUo`v2jZjOQiY0@M5cod0b-Dcm5|r-RfT*-oxkrX4t8FPPqEg(7HcYl{H9 z$teouX1AGApiwNt7^hT_0C^U#1b*<-)1wg(1~a=6T1B*a?=1pOLJP1t1_nK;;RZxe z9T`u4y9yT(7Hf4oEbi>kQB(JF0`B7pe-zT9O22H{6~q-gJNCL>;TWhA@a%SWC0cAr zNQ>zO3%*pP0^j)%Y%Ml&k@jqNz6+{byZpSPvzRQ&M!av=o@)S68i* zlsbG~e1C(R5z%h8_p@nbY-|i{3qZ}cZ?O`PS_TFNKr7IUjLI~M!4h(L>cv`w5~tbJ z*CXh>w|0mU`mERizrf1MOL+%$vXIHi%a@GWCMf~(qe!FpR5H0}aB@=L*!T+YE-tqP z?nhgF)+^AsN!WRLT>wu+>-UF+ZgTg?`dPLi)Fnki6w+c@0Nv9}z9p-k5Fn^AJI(6eTDyDgJG^xVXltMve{+ z;x3CA6u6lp9!hzGOb`f{Negub2dAL{?7N-}Kbjj((yoKB7zS)7H{T zOi0KZUc1MsUu`@3vAtd9kPVOuad0l~NF;A6 zjJx@82oPM{WO(YFM5L4)yfwA8j)37n9dA`MA5S)TZ19-6L=Rf~Z<{Z9D( z+d>Pc9pn7Ao1&v*xgnRy7uV&A)~oK|sa1E88hu23yoR2haAKEikSFOE!x-ar#^>uh%L&JHT zJgp)OCI%)9DF#ThkV#x$900T!c5B9Rt+HZ_w+8{;?W*fx`Z`s?jCDt^bC42*xfSp@_<`qBip zb&)g}UQ~~*-hn+;TMz1(1PD+HPuh)_H}7||zj*P2F^+|UV{=r;#KF;#HlJ(=^s#cIC<*MRJMHd!iye`XkwC&|U-XRnos@3A^gh7Y`K=ch)jCWG z0(}7qe9ND3yuw6PL4hZ|PXqyowsm)r&l4GNxHllrzI~|TZoP0FFE@Jj?Ad_W0Zd;% z4dtRKC)Ww2dh9LAx{IRuG86&^FEKIE7*pn0!=TA~?{sfTK9-h-f}+lA#~7s(DU!vWExS=&Eu^pK&CE4RaI3bDitU&X|N?_1stbdYTu3epK{#oj0*tDSrU+*o4<&O zi5W;D7#SI>K7S6nM$H8s4$5CZ^z`%$i=}dYfP)BCGB!4b!QSa|XtR*5t*uR4E7KEg z&Nhn*3TkuQQ-$*|aB`MaR>oBnz~PioXe-cUbZo4_#E2xq;!khtjm*I?>L@KmzFpUiZp0m#JX7N#NP? z&!0cl^W;L`zHI@A1iY;Wn|`Gi7Z+er+MtU)KrBzU1U#t252oEVC&3G?bDUXEhi^CT zw4|lor{JEqv9Z}ZI9N(9Qq2ln{mIa>dXrgN^*S5L$h;iLteMNv<#4pO-*ipv?3BA= zG1P6R0JJy@14D?{9x{RXEEh;A&_Fu4{^_L(3;@pA+4+)Q&%G*0>W`9bam% zbo3PzlY*GI5+?rShv~N0|x5_R)MVuo0c*#m;&c*|7hH#tE-EdnYpgE zRtokt3C={Kc=EID8Lz{yPm+vrr3Q75;AsJh)P=K<*SyoYCnO{U98iCCO-)Tx)9ejK zMq4|(jWT$-akFh}3E;!8I8py1*6FG9Lrpq5I>&_LV^4~Bg1dLi%gVMKJc7=aQvm0B zNW|NGc|3)Gk7KpU_1i1Vou-4k*U5lfO;TF^pq>X&&Ad2U$(m~2-(6@M930G(kIfYG z*#~uzwxE3C!E&QUK-TE#X^=R7p=iU zmKAtjd>KV^j~IY*0}DQ?lM;$>q-aMX9DX`!S8?( zacQaj`bhC5v1STQ!{bCZ2&7WC*KWk4blj5Q=+KTfY?^SXo$)EtJ0V8zUWHj167u@wz#V5A9wi{BuNCTc zY*|@Zudhy8%d|^6%+9)?S2@5ZnK&Q(=>ukTi8>j8^R`KpIq%MY14njo(d_E+#Fg~W z3-yyLhZ=og4cZmPMtXWaV0?FX_e!Q;zl6@vWx}<|^*P0Vl?v+Dl%Kn+Yw?PAyZ|6j8{(K z;%(#x?3#9@}_(sah9)Cus*sqAI$3soIEJf zMab+ggwY+ZXO1%5O9&$j!QMefH`{miH@wi7WlP!y<)WonsPSj3XTbj>ExvPmPv?C2 zu$mJ_%XdE-dUd)4kV2$z8QSW2tT#=3Muz|Pv~aPOh-G);xJeKVG{);~pOvWd{MS5S z2;cF!{r8c~AhbVFzplal`aUuu{NnQRrVvRNbOA6_f0}?DC}eC^f}qO(>p9w zLD>h?O#h*8E{ew$2EHepI%<>BQ*2XI^8O|!Pkcl)wKQuI?&9zS0|4HTs0W?$!D1EU2gJ`Cp z7mu#j*Vn%wCIwq1ZRgK-UYyURbWFu}sMpx;%Jpv=4sZ*6LrFyR^<_={({~g^6bQuv zjS2^q3(R7_AIq*lk=tm&#`CY){#C&3^&@d+jdxMgKLr YHTFzQdA=zf=tNVLRgo!|GJW;m0G(d{p0gIj>pV7`|Q2fTJL(_wRXrORfVerGz1U`h-qxJ**OX?!0$KwFy<^h2z1OEytodBOp#giyF*w{j z*ap?nzaAuG2mREBVQ1U=X*;xDAAqC2#;PK`tflv%seXtumT?#NRtBybOX5LW(ZIbZ zQsN6Z=hL5pzb>cE5bszmq$PSM;7apAAb7Zhnh=O0E#&?zm<${O3AqS)(S8BKLJT4D zPH8oiKyQYB2n!XxIq zx5OawUbB4;kC(+qj2oMpDk~~}#$R|*Szu4Bw!b#Y2cMOtT$O6kFfvNhfX;7un3fCQ zz1wBN^N3GB@m)*|Q#=}_XBYpxtFtpok;Q;Zn<+Zs(m*t`Lc8g`c=X=(_Lt7iG7Ccp zbI*?{mGM>Y2r&ndz}BcPb5~c_ITKyo#FiF+U0q#oZ*LWq?tn{#F$hFMsw`!L!*p|J zXJ^mqm#(gB__#{Q?fvy}C8Rnd>D>H$G$J%KRF)}Puh{*7X(~5`q~CaXvruwTbFotQ@r!Ozt)<@60i#3>#W! zDHz$_-v036eqif;hUJx&f`R2c%_SF6ZEfxC%H(8yWo1HNvOkA0!KKmC?x-{1+S4r^ z20u56@Up&H^Csd4@X&-$s=j~q`ZXRdZZ;A*>gO~z@1g(w(u+8=V5;laUBK?AslG>` z=kxRP!^6V|sTmm3V`9i`%4%yzhKJ)%))p7F_4Jg|2eVu+WXz9j^%N`x5(Ith?p|N| zmZev$RXWUmJ@n0+H}-6a6ftpe)iy&=FLe2%I~w^K8aq5gZclV{Ml8_fv92>k1bq>F zK4ig+_$WP2MAzrHH!yQ^EQqe_1adWquLSpK!uc$}W<@p-u7{c=vj_1Bd6OMNpH!j0MmPrQb5cVBfU2L_nu^F*-d-CK-i_|kge&x>(G+(se zfL*zAg`S?iyuAF*4M>QY@zBr^LD2h(3iVlm8GQwLA$X;KC8TYDk>^I zk}U-VHn?#_KOAX`=oSyRFg-mzrH$JJ0_rB}<`V1qP9Blw|_o6DTzih-B@2=%t;CF{_MzO;4108rTO{g z6%H+jvti8H=8!7P$Z1>)aA9Q@GG#v7sm7ytV?PnUlS9QjH$F&T-5xiy%^tFuoSd{v zMD#8i*Et3CE|OqkE<_1mye4XS%z_w|y1Du0_C-cGp3lH~^?|5q7lio2DF*U;pZ^O@ zfJuI#$uDdHM)-{_|G1SpR5%Yuq1BxC@s)j6vJji+&mWU0(thYMaiTf@ZX@+%>>Void6Da%KD~rHx50onj*Y~8a86* zrn;G%cql`b;8qQs#5CU2fJW@^&>)v>rnEmeE^*RGp z3hU46kBRUwozcvucXpVi z;$vfvj*r0=RZ}xOILM(>#wa3^$oM88ARsr*3o0emQe0e|lVdsmC3fxvKoQQ%`}rDE z&A$5i8U(ljU_my9yop66B@wi{2M6cdXztC4x`DAVY>(Kctel+g7<3$+9XDCyU~Fz~ zzKBzN9pD`cS;(M`tG<4+5|WG{Xiz;4+6uF?vx|=($Bm-D9vP%8kU-*i8hg7;hOC(-}A$kCU-^j>l&Z^1C*x1;Chx)C2 zR+l*w{zq$mUTPvXwp^okU+10jdkeKo_xJZp3JO4w*Lojt>Dn@&vkAd+@$nUvl`ETk zKlHOG$3m<{UN`g7golKLI5Z!zictRv#yyq5l!Y1vJs4jfA0;KFyw=%SQ)A<4E^Up+ zkFQZt2|fLYOC0RH+M6ODkynd`lg}#8wQ!?H z{0IG!?+FMAIZ?Fw1-L1inRJ&!1~Bcnwmif$AJuwn&62aJMzIlJ|L-JlN#tyId0-$% z1>;o56nzJTQZpj#lPPg9Gi4YbA0MZtvW10(i3wvont~t*STR>k!WUbWo6DBmog+V{ zW4U-wJ_`<#%5HRAC=>o{UnYn`>%qLoWFagP5~)Q9`XkLO_@x4^Er^|;l6bV3`%-I)9^;Q|q6Gf&z<*x%7Uov(7deg- zCCu{*m}@hTL^46t6&l&$42LI5`TI#rw`Ock!C3kJB3L1OJ`*ke{u>i@0OE30Q|oBWVwS9gz(i?Op4PG1xM2;bbRnEou*7r!?X%)q5v(f(yKCM}JNGE5E=cTQp8d5)ly4WF+NDgt1#B`7#5fT1@xf-`%yf zu~~7#Qw}17=+>tw^izZ9ZadanXI|<0a*=xw$!fTpXmj=kdNBQvEI|KHxx|1v`6tn$TE)Fj8lS zm`(rlW1(rE0rg@KcZo19ZEdTjuRS3TNZSFVGchxZ`CDia+=W8PLS$`F^~J?1NcAg0 zGB)`Y6}1Q(h|5(nsbFEOT&@(a^S4^gu&X2GX2mSO7+(WtCA$3{HIaJ$?(C;9OFo^u=72+KU`cVK!DE~P4pWVx zp#(PSzP?SeOwzNAVE6~O;Rc3=%TNBqAYE4wFz7F9yzq_bmT9|0LsnvG()s!MmoH!9 z1-_K*SGr|yZ_mlex%+TX-A6JVpxUS{Wtg0xOr;J7ON5y;y4-AMd%NCi&&Gl4Mw!>o zA?LaYBZsFT!0+F`ucw!^Zl@W?y1a+QV!Z-eP55b4SjnYH<+HB&U#!)-bkXWlCy>l1A4?10RNRC_OZ`O>9S z32#bc(Gty>BAdRRf{m%BM^XGK{Hq_P8NqA`#4z28Y z1<72ycI{;)vA#U>(!e3RjJ1)Kki`=&#QFC}e#@&DnHLXe#fZdbO_%|cxQqOtzKngU@Nqn% zKB!3gZz1*{bTBy-abEb^9zwnj52DvTjTYvC?P7Wwfdc83Jbt?p32FmCo)8!6}F z;zGx94%nauTf@4{P0Mw5vl9NKCEaGMfAbnsN|-_f?X|E^23*5vG&?hM)_8Hi(@*eC zF4v{-%^;%*XWRVHFJHc#oSve;d>I=be{N$#$)OXKk^&=r)zWefh^FUaPwMyY-`%G? z*`Uxb>W}As{0`k-1OmZKivLb&eto2$5w%=}mtBo}-@sO6C^G z%f&0p5*@W7-oG#;gwukvXD{nKgq;*@(vRoMPz>%6?alM`Jchv zoq|A+Q&P(N0d6K3D~T&Tx3HkDJX)do2dn7VA`AX4##B=8l?p{rgr&uL6tjoHtX8k$ z1%9*UPlVx0Q-{mr1(yGcVTa9vf`W*M2mtXh%*B7xgj0^@T>VSdB6uB?znKAs9SWVD zon?h3e3)_MGORZ@d*)OpE+Bv^FOR0dU@%YA)n%?yQc)dau`%hVCnrkE%FBrQN$7p_ zy`BQv<07Shi7{!?R~k?tK5CRJA(6;pJyhtF6UTJ|O(?~XI1Dv; zosv=y#B-IVa3P2bvW}-@9sN?&|0j=2lg7rz0x$zI{m%7Y5Vzm{|I~JyZiP|8ZC4PE zBQ?5wiNuXtO+S{GLpE~ik>9M%d2c`o)`cMu;;G(y^m7*gCo@Psc!Mnvmyp;xAoxe9 zft33X?O~FK$snK&lFw?Ti>wCPEbrB=Fp>U^tU&rYxAn1icc1tj%~MIHOGTk^dJ0Tf zloSq9TAxN=T;a~@R^;XyLaz8H0^2CY<8`oD|pssR)iD4YtrK5he2{p_udexe8`(< z`|Z74vXDb{M+Hzp(TZI0=R4`=EYoq%7RFG|`K)@1^76`D;th@CF0l~56$UB*@K-8s zqj!odalCTHTK;E8i>D17Z?89bU%5h5#;#pL1Z$i69DZ}S#BkiM?PqSf-&hM8XNvxT z7^x{Qd9+v{TUr-bFa;HN1cTI6341?)3gwPs%+8T^i9x1Rb6>p0)430bl!#kDQr#`P z%)yP4M{|gMeIP&CO3jl`TgvCB)s5qVqAzN9(6v=23rU^MhF#-sDH>i~uYcc6>-D4T z67YeJMhWk?Oy6!gG>0_k0o=NHYqm4mSR_TN#2};qNWhWv@mWX8vw7}w8|y=`b(n%LC@!1rM??N-fM1&dzqXSF{-FfDT_RiaM8-sIN$8cTwAjp#C!YB zETw#E%Gk;x6Yp}+&fyk%d#7f7;#VpGU%qMgymuQ3<7&woauY!@F`Jdj#(bFHh*fO% zq=wC1P!&f!JbT1v+>I8y6U(~o;oUwvo6SOA@@XXI@JUW%T6&A+`WRpwgLp*e?QnW2 zzlG1?#vB_;WJtUp4<75ICt+rSQxm=B;dk-5e_u{-ta7t)pn;5jX)k$o zmBD}IuFnlfn~@Z)3P%*0J3FUZNKoBu!q;a7NF8YvczHwVrvLYjnS{6U*jcs9mka^v zn8t;Wb+DREOs0=l%!{wfSwFpZZ}EF+sb(R=(jLmjb>{We$|>LYlsTsBQ;+T}32lp~ zM`gSTE0lCwQ+3`6+~2>cG@r}eG&tXd(?bW5$Ldl%!zKyD29rDqlvIvi@ju+*71|q44jd|E1abkon8j*47*aZzcwUUn3oM zpB^88e5$Xn@4YgZKVIW7JTzoCR<-=2HE>@iK6X(GJO7OoB$}ekVR8|&%WG%T-gzJo z#Z?Om2n@BgVSdiEH8(dKa2<59r5n^bf=cBrfd}&PuVtBLoa)FzUX7)LGDZkF8_vax zp5jxraEw-o!RW*UjMHhZ^IEwM5WP)}jl8_P9H~Z+lZTH?veB__4O4#*hZ0mDc^#6s z*p?@-6(sV1aF4y&y)s4GGGz0l$4a1nD;|Ag#`sL)`5E0)y}QO-gGq>Ox)+NOf?q}4eZZ05>C2rkCLs9m5Phv zTTR|FNcmwthwC@2giI(UY6;dhHu@azuU{sn?OS#M4|8*Jp4KiJ#$ZObW=uLI#U%MX zy}b0izO;6AEd%Ita&=vIveD7ev9(=`38wQ{Tv+hi?qUNn6vhe)*y_;O7|hL^H+_A5 zy8^=iGiz^eZ#*fhi37OHVOamJNX_e0k|wWjU%yhG*V>l6(v zC%|$*KKzDV%z@eg(l%Ub><^}uF9*cD*E``jEu|jIXHA2_gj8Hb`ZXK--AhaP$~s! z3RD$<0GJz0NJ!XQ9WETQX)-F+DipFE`ML4y4Wq#PU`xWn!t&+nQ&jF;hh8VB9Jlgn zQs>*)*Z^)6g4~m}|FzHuWjEKX`KsY-jOp)`{*iSF2Y4yE2l+~tB`#an}{m|rtJRr^WcVCbe zzaF}|d9mDscJu;KPqu8QgXI_oQve1;zzacTO%Nh_vOjmCuzh)C&Rhv>U<~1gZa~(Mr(5m z^2Bi)W2m{lOpp|BkB%B|jKJ5!xNVK8AY{2}asJrlxyAHFQ8B5r-2uXbwYoFMgX8rC zWX?k3u(7+7tA%r2z>gmkxoY~{Ww|^0(?ml(smc|VK~JA%(R+VYVbYCBHT0ZQtU(5S zYJZ2!exz+z5J5+nd3#y;d`IfNh;waEPuk4Pwd4I*ai6nd_f?$xVyYx>N$@iyBe#BL zr1wMxWMz>kA)grgx|&+&d7Pbeq6FifQ&`^f09#0pB#2}K(SZGJ0a z_pb??J3F}?MiWjLyg+JGKjh5)*VTEA74do50uc8EE_O}wOtu4yJa;5?IPqZ6OK%YO4F}VePVC|#?dS! z6tYd&oAQ>>qk@dV*Oo?IS3?nqo6XqJ)isVJiQ~PE63tQGbHWDq#g^0k;$$He`K&!} zPuAYlV@uTt=&ejf(IlQk+*`Mt>%GLY(Kvzc-#5RFOmDUfAN^WcZ7)H7V^mLjkr)2n zwu88o%6RQty$K^w_pJ60YxtDuIA`k$(vF%levG%At`D7`8e==9Tf}bkYF>zdzs{^q z_rrF0Zx&-uoHZ^160*^8ZQ`Dp(fL{>8!pZu9{8lWC`D-I9r*|O+M8D)uYG29mdi}b zM01vpy}ludAz+Lut_PtsHvkRoP8s!lU6jbTyput5A!NWiVm$9@BxlR`Sb=BN@tGb9 zJ5{WIh`z|8+N-nT`*|(hExxI(oiCAUf9+wSFubEpAw9|eaHbR;zeyt|IQnURuEN6I znp=58d}pY!5mZjeJsZ_nRSLfLR98IwevB%2`asreuD5K|;Z|{Ys9u*MnFHe@iHz(p zre}nE<&3L3Qfqk!A4y7`7jJLB3hpI6*+UJdg-1j@vmWu;Ss*88J;BU8!AZ3`1Et^- z)N>0lcY6@x`uRmjI%$`wZ2M!>GKPDk*lNln3stf)?0*_YdosU0ufMm~+ju5=whf?x zZ_+KGt!zvT);`t5C38!_YIh!;#yfh4jV&z<-8eUw^q$E}WH&JkDE|G;^U3#e23A%= zA+P+79paPCn~aks&jKb*D|Ep8VX8B!fs4MTW@S?u-$}5$5zl6>bqcEP{<~A-njnPsMQJBvFEoN+)#tx zd8yy#uxrPq3%~UBa|9)ZMu{B#xtk`hAI*+zM<%V&<)DeHMhv)odEEDGq!kt0&rW+V zpA(5*%d)X4^EuO}nxk2xPsd=ojU)ShcD5&%>Uw$(>?ddIY9E+4L(O|AVUoZO&>O6p=S%AH_2UnK+N}j{CKsf zC_>EL54(_jQeuQqx-wm!<=FO`fq)RO<@)Ets-=2Er`*r#!1fY^g>$}%Xx{%sb)cue ziK;d_o(&6FTIy3t78Rl`I$9|dF!l|)NJ~Alc5D#4-qgm?)gwtxu@_mapV|>g5*BjT zpk+!u@ef!$V4s~$YChiB%1tMpZk~+eEFUaYVUXCtu5u77pv;2zk2gWF$^XkcDs^?A zIF9AVw=56Hf86Dy{w%L_E^N5}oXkwUO4q%aM{;8LRQV)3T3$6vCe$YI4~7UE) z(v3zZOZtjNb|mvZQ+IO{^jwmj%pITKQv3%c{&I~K;W^tL0=o0`kwW$pwXy8lf&&}8 zDi0q5s-rh{@wH_=2Lh-t5hqy=O6NKQK(XGwC933%|6kQNz<+*-dF@)exbO$Iz6lNG z75ggUzA*vBJGkZ#*~BVYz~T2ig&&9y)>Q$1mz|yc_3KwaWxy5C&65)!Cv_($Cncp& zt-|7h0^UT}s&()5U%a=*e%*nZ{ z@}g+!#>vqRDETl*`Exn z^nlBrpT_EI0{rKXRzS^eqEq;+RAI2MXzmtRgcPW50=n9TT=>n32XYYzKts)WbyZZt zkzQp3C@3ukbnqigDY=b+?6^VnIyrgVxmN=0mI(IB@D3&YYUSLQSavW_CSF@xTg&l= z*tRodeN=*kByvF^ebTIQ6wv=S5fOrJUZX`wUXW78bt^3&W0rS-?So&vaulZh;|vC9 z*?M3;Ujk$)ORWg`JujdInp#c3 znG04#i1=%nSqM>1P7W(d&v*4ZXMy3u_hNm}kjT#uNok#)HXd3omn050v)J6*+5(Cv z6A$oNFo4}OOPxVlQqtJSh_!N}pPwHv%vipDQQo*Vr4j`1u0A6G+oz0eqN?YXfvYK(BUv zeI1;ULAKUf;D%iM*?D(pWvH-QzQm|0Nwl1Rgk&0Yp9~Bpz`a1#FwoQYnDG2&#h^pM z<q zAR=7Tk<>@yS#6FVbSeJo%>CE7gY&1WPl)sKZ$*4CyHkDs4YN5axbGn?M(&>v0p}_H d^)S>q1AStTrlWnH1~}0Lc_^nUTOwl;@ISrM`~?62 literal 3258 zcmYjUc{J4f`yW|j8g~$3m@HW%vVAPc7RE9ZX=suy-3c{gtcmOlX1H`Q8p?9Hvd74p zVVG%QTGZHOOCho(OW`|pe}DYm=RAMBUhn65&g(hneV+4r6P%GYM+Bt=K_Ji(gss&D z5QvMy32q*44zqE!jsrl-&JM2U4h|0d4-Pm;M@Of>zn@Gd`*TizKL?W!4s^(59S$Uu z@kEyrP7;@oy^R$pl~=}=0}f+t-SHrhkm#@A0u@k>aY+6UgyT8>89`n_ErVE(l`Iel zEQzo(ca0cbF6_k5wn#Fx#VU&&rZXMQFFdA3wOU+vnaounJz=9HhoqL8I-`l<=o;w( z!?9siN}+3!E(=Xn%{IJB&71dMcj7%|X7@8&Aoet3JGPJt&WCSH(h?+oMr35!sa2L` z+jUixwRTi~@S})-g|zjY2Lx@VI|N{tjbQobXQ=F5ZNbYu?1r4dC5ITw8404Xf*%Z= z#g5O`x^79h1IS$6`o<;r)2mEU)KB_Kr;wqv-5h~ zdtDh6(PmQyvh(XTk4sP4GiNe^ntz-v327r@r2nL-R_i*~2JWdD$tfh%s%UBjjn zFxfG;vAT}pg^t;U>wDdAY{id-&zG7%?*A?l=^IaaMcO~f4WX6QHBzn31%-{~$QoQM zg45l-HL-_bk7IS&&dFSUAqc$U3qCAatq566XuANG{Zm#0k@_)$a^6T)Dn^lPOv9u(IVyO{A+uf8TS0NQtZ8AQSWL&MJrhY1HL|{_F*4RsTnB$1 zo1l&fu{Qh*UDC&B>GQ~$ALMan<~RfvXdZv89~6^n$=BkUY8h2L6hb*Vd-<}cx$YT7 zFXkI*O}5JeA%4Bf)nirSc~#f~4Ys;^MNLQBYp(`~(l~HLd`XWxN)L(eyFJjt7R-$j zA%t)tUHWb>3Qg;}R*x;!f@gp9#%2N0-FGlMR~H4p3xiuTlOz1||!o1D^At%%|$n0Zj%b10@X} zVo`}rI0dT$XoZ~5gnw%uD}E5%;Qxq62&up+3Itbh`3wNDBiKcW0LI$OWS4f7bcO*y zB{qlF$PdK1G@_ok!y|n9Dlb)&omgouRVe-(;_N#WHjFz@royyg{@9Z*0F^-PUK30E zelo~2-4;LdPLUl{RB<5^y9f=a%~_v%C(rJl8^PZABY?&AGR376g(qDyrM&1Hox0=d z9K~*~b1mb=s);Y@f34!~0N$tRZ9R{`sU2PNTK@tZO{3DxJ~Atj)w~SVv&d^cK>{YP zYA(LzSA$~ADQUfJ8tXB60!Td{jSvwi#f~$QYqComN(kbtO(7DfQ_?wqFEe(^%cp)+ zUtG>Ljs5Rsrp_E&S!^w<_pBr{H3_AJ>ESgCc&N{&N0LrhCrm(NXbRhUf2lU2@{W5# zM@}BCJ7pMtbf)R4jkzf+P=-V#2@7G@k(#mGo{3+_5AXBJw`U4lbsT0Eir&*!O`Lcp zUB8;snGnt6hF9+Gcea;=W#1A3R#)W3tPi%(dx3EIWUaiYU@q9I{I}Op+r;6D?Iprl zp0OV8-{mH4_h7p+U1zw`4KwGokUdjb+pD04SE4PN7q>O;@cc~pufgKEf1wod z+98l+vKy2^2q+xty95~$`Z7=aMKUd z`uwnZQX~C#Nd{v25VO4KZb&0GrL0?S?To{$S+TVZU*JCvTJ<-@%6`mI&>;SO_)b&k z>yu$t#!iAA?*UwbrN)oT$2Fr=k`peTh|9qTb5Xc1#gZ5t0T%yyi{6Lubx6z!Ap3udPLdKN zh|%0=&|w-9->UqnH%=DfnaGuEJsJeb^&o4jq8&=>54+NUSU$ldBX6wj9buh86)|fI zA`=1)G3ftTgzgLEEX?0qh_jM*WM(_+?N=f(n3&S&%rd9tj~Dfq9b$^;xm~n1Ciinp zJR(Z0J!bpnhdeT4IDO}+g|TFc0s&VZ15RnmS$Q#LTGRWOGNt?B>y1sn(0eT&U?4cZ z?_-4=hHwsV_Qd$Fh|iz>O2~a!57}(PZY!P3e0IArmu|p9TE0He#Ib%hywkn?0YIC` zmxe20a?m64&Cs_Jxg&Gkuu6Vm^pKO37UUWu@A{L|lN8`Y@> z22+|>rItU$oS#-?DKJ8O2Y7LtD>e6o9BtwJ3W&RB)c7C26js`}$j>(B3 zZ>dx(0eR)V69wV12}?>^@hw>Y5=Um*#^TbU3T4G1G!S5*Dd{FkDTGTDF3*qP1k3j^ zk+2PAHD0{Qql3tUH#50`vaq1&a5V`x7fO))yZO?9n^(F_?|M?=fkrgyivF`{=Gu#C zeQ?EUYuW|x(2v0K`H}emG31(bwIvywRb7YXjs%i>Qt!8i$ZyF{dm-c>tHVz7yc^u;vXv03}+U+k^MVZB+cgCpT@>f1ah z-~SvOK&eC8<@%lZVBZ%!wW@2yQ!MNG2AI44ZxFp+O2=G@X$2UaFO} zWE2S?Va!nwlIGI5)l)M&cNH}TurezAExbb$HwHEz+?3gP(JAM?j%lsk{JamFT*pmJ zO5;BfH#3KXNA8yX_T)Gwt|Eu0eKTM0&Rm4JY zI)M@<*W=Vjg!7bIaoMe$6uRW4w8ZxaO3gvE{o^;v-3#X~)c;r`%zW!Di#32q=k;k1 zq&xq6Di<(FH(uF*JH8#cnTQRUBwHP?M$Yt~J)3=UkKzJr`IrzTwGz`6tw#`hE#gVh z-$Je0&7j*3ACnb(4)(!edq&C>a#2xNCb;p zK_L*yn}S%6SxWiyMg@l{#SAb#Ox4svkY8L6;@&&;JZ67K0`@##0$%$}N`MXU@SldV z;H)Q4)oF*lv<+7%v2oKq1zDp|i<=mmd>Z1Iq=>S5eFpd7sd@!8Ob+vBKEqI1*uGmn zIq^lf^P%%f)p0S$yQSO@Edx;2O5P=5UO>k;o@SpB(ww9xHw?`le@oJe%h5WmXzJV4 zm=u;c4ZV<@JksDhz1t(tw^gM+lys4HU+Z3i9%Lt%5h}){&_%HUxZQ1db(a9^ZNY0H zyuEP`56Q8v{!I-*2-fF544s#hnxFlqLc3}@ZjMOg4xj)mjhl)ue=byl_zy&`pMUkl z*E7c4#O8}YBM>&elR49Ca_~4gc?bAb!av^?GAk0(=^%sQ2JjT}>59Vkh>J zvgUHb65WeQ&5(a++^VTx1UA4&T78<;i}Q)QU>_M78w(k?@}r`Qu`KceMt8J8P)}1Z z>2_pdS+Sfjq#EbxY_(ie#T) - + - + diff --git a/docs/uml/CrossDoorSubtree.uxf b/docs/uml/CrossDoorSubtree.uxf index c8869274a..8961c8b5b 100644 --- a/docs/uml/CrossDoorSubtree.uxf +++ b/docs/uml/CrossDoorSubtree.uxf @@ -132,7 +132,7 @@ 80 30 - Negation + Inverter diff --git a/docs/uml/EnterRoom.uxf b/docs/uml/EnterRoom.uxf index 4efad25f9..edf09aa9a 100644 --- a/docs/uml/EnterRoom.uxf +++ b/docs/uml/EnterRoom.uxf @@ -52,7 +52,7 @@ 100 30 - Negation + Inverter fg=blue diff --git a/docs/uml/EnterRoom2.uxf b/docs/uml/EnterRoom2.uxf index 4efad25f9..edf09aa9a 100644 --- a/docs/uml/EnterRoom2.uxf +++ b/docs/uml/EnterRoom2.uxf @@ -52,7 +52,7 @@ 100 30 - Negation + Inverter fg=blue diff --git a/docs/uml/Sequence2.uxf b/docs/uml/Sequence2.uxf index 11ec410a7..41e0b3967 100644 --- a/docs/uml/Sequence2.uxf +++ b/docs/uml/Sequence2.uxf @@ -97,7 +97,7 @@ 100 30 - Negation + Inverter fg=blue diff --git a/docs/uml/TypeHierarchy.uxf b/docs/uml/TypeHierarchy.uxf index 63b6afcae..34e0059fe 100644 --- a/docs/uml/TypeHierarchy.uxf +++ b/docs/uml/TypeHierarchy.uxf @@ -16,7 +16,7 @@ UMLClass - 490 + 590 280 100 30 @@ -27,8 +27,8 @@ UMLClass - 380 - 280 + 590 + 320 100 30 @@ -38,8 +38,8 @@ UMLClass - 600 - 280 + 590 + 240 120 30 @@ -49,41 +49,41 @@ Relation - 420 + 500 200 110 - 100 + 160 lt=<<- - 90.0;10.0;10.0;80.0 + 10.0;10.0;10.0;140.0;90.0;140.0 Relation 530 200 - 30 - 100 + 80 + 110 lt=<<- - 10.0;10.0;10.0;80.0 + 10.0;10.0;10.0;90.0;60.0;90.0 Relation 560 200 - 110 - 100 + 50 + 70 lt=<<- - 10.0;10.0;90.0;80.0 + 10.0;10.0;10.0;50.0;30.0;50.0 UMLClass - 340 - 380 + 700 + 420 100 30 @@ -93,7 +93,7 @@ UMLClass - 450 + 700 380 120 30 @@ -104,30 +104,30 @@ Relation - 380 - 300 - 60 - 100 + 620 + 340 + 100 + 120 lt=<<- - 40.0;10.0;10.0;80.0 + 10.0;10.0;10.0;100.0;80.0;100.0 Relation - 430 - 300 + 640 + 340 80 - 100 + 70 lt=<<- - 10.0;10.0;60.0;80.0 + 10.0;10.0;10.0;50.0;60.0;50.0 UMLNote - 590 - 330 + 460 + 360 140 90 diff --git a/examples/crossdoor_example.cpp b/examples/crossdoor_example.cpp index b54f0d277..9708fdd77 100644 --- a/examples/crossdoor_example.cpp +++ b/examples/crossdoor_example.cpp @@ -16,9 +16,9 @@ const std::string xml_text = R"( - + - + diff --git a/gtest/gtest_decorator.cpp b/gtest/gtest_decorator.cpp index 0df213129..ff010db19 100644 --- a/gtest/gtest_decorator.cpp +++ b/gtest/gtest_decorator.cpp @@ -20,7 +20,7 @@ using BT::NodeStatus; struct DeadlineTest : testing::Test { - BT::DeadlineNode root; + BT::TimeoutNode root; BT::AsyncActionTest action; DeadlineTest() diff --git a/gtest/gtest_factory.cpp b/gtest/gtest_factory.cpp index 23c6be48c..58c3a9ab7 100644 --- a/gtest/gtest_factory.cpp +++ b/gtest/gtest_factory.cpp @@ -19,7 +19,7 @@ const std::string xml_text = R"( - + @@ -56,7 +56,7 @@ const std::string xml_text_subtree = R"( - + @@ -123,12 +123,12 @@ TEST(BehaviorTreeFactory, VerifyLargeTree) ASSERT_TRUE(sequence_closed != nullptr); ASSERT_EQ(sequence_closed->children().size(), 4); - ASSERT_EQ(sequence_closed->child(0)->name(), "Negation"); + ASSERT_EQ(sequence_closed->child(0)->name(), "Inverter"); ASSERT_EQ(sequence_closed->child(1)->name(), "OpenDoor"); ASSERT_EQ(sequence_closed->child(2)->name(), "PassThroughDoor"); ASSERT_EQ(sequence_closed->child(3)->name(), "CloseDoor"); - auto decorator = dynamic_cast(sequence_closed->child(0)); + auto decorator = dynamic_cast(sequence_closed->child(0)); ASSERT_TRUE(decorator != nullptr); ASSERT_EQ(decorator->child()->name(), "IsDoorOpen"); @@ -173,12 +173,12 @@ TEST(BehaviorTreeFactory, Subtree) ASSERT_TRUE(sequence != nullptr); ASSERT_EQ(sequence->children().size(), 4); - ASSERT_EQ(sequence->child(0)->name(), "Negation"); + ASSERT_EQ(sequence->child(0)->name(), "Inverter"); ASSERT_EQ(sequence->child(1)->name(), "OpenDoor"); ASSERT_EQ(sequence->child(2)->name(), "PassThroughDoor"); ASSERT_EQ(sequence->child(3)->name(), "CloseDoor"); - auto decorator = dynamic_cast(sequence->child(0)); + auto decorator = dynamic_cast(sequence->child(0)); ASSERT_TRUE(decorator != nullptr); ASSERT_EQ(decorator->child()->name(), "IsDoorLocked"); diff --git a/include/behavior_tree_core/behavior_tree.h b/include/behavior_tree_core/behavior_tree.h index 19503766c..9961fd148 100644 --- a/include/behavior_tree_core/behavior_tree.h +++ b/include/behavior_tree_core/behavior_tree.h @@ -24,7 +24,7 @@ #include "behavior_tree_core/action_node.h" #include "behavior_tree_core/condition_node.h" -#include "behavior_tree_core/decorators/negation_node.h" +#include "behavior_tree_core/decorators/inverter_node.h" #include "behavior_tree_core/decorators/retry_node.h" #include "behavior_tree_core/decorators/repeat_node.h" #include "behavior_tree_core/decorators/subtree_node.h" @@ -35,8 +35,8 @@ #include "behavior_tree_core/decorators/force_success_node.h" #include "behavior_tree_core/decorators/force_failure_node.h" -#include "behavior_tree_core/decorators/blackboard_precondition_node.h" -#include "behavior_tree_core/decorators/deadline_node.h" +#include "behavior_tree_core/decorators/blackboard_precondition.h" +#include "behavior_tree_core/decorators/timeout_node.h" namespace BT { diff --git a/include/behavior_tree_core/decorators/blackboard_precondition_node.h b/include/behavior_tree_core/decorators/blackboard_precondition.h similarity index 100% rename from include/behavior_tree_core/decorators/blackboard_precondition_node.h rename to include/behavior_tree_core/decorators/blackboard_precondition.h diff --git a/include/behavior_tree_core/decorators/negation_node.h b/include/behavior_tree_core/decorators/inverter_node.h similarity index 82% rename from include/behavior_tree_core/decorators/negation_node.h rename to include/behavior_tree_core/decorators/inverter_node.h index 231a5a9a3..999f64ed9 100644 --- a/include/behavior_tree_core/decorators/negation_node.h +++ b/include/behavior_tree_core/decorators/inverter_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved +/* Copyright (C) 2018 Michele Colledanchise - All Rights Reserved * Copyright (C) 2018 Davide Faconti - All Rights Reserved * * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), @@ -11,19 +11,19 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#ifndef DECORATORNEGATIONNODE_H -#define DECORATORNEGATIONNODE_H +#ifndef DECORATOR_INVERTER_NODE_H +#define DECORATOR_INVERTER_NODE_H #include "behavior_tree_core/decorator_node.h" namespace BT { -class NegationNode : public DecoratorNode +class InverterNode : public DecoratorNode { public: - NegationNode(const std::string& name); + InverterNode(const std::string& name); - virtual ~NegationNode() override = default; + virtual ~InverterNode() override = default; private: virtual BT::NodeStatus tick() override; diff --git a/include/behavior_tree_core/decorators/deadline_node.h b/include/behavior_tree_core/decorators/timeout_node.h similarity index 69% rename from include/behavior_tree_core/decorators/deadline_node.h rename to include/behavior_tree_core/decorators/timeout_node.h index e82f4ab42..38f6e56c3 100644 --- a/include/behavior_tree_core/decorators/deadline_node.h +++ b/include/behavior_tree_core/decorators/timeout_node.h @@ -1,5 +1,5 @@ -#ifndef DEADLINE_NODE_H -#define DEADLINE_NODE_H +#ifndef DECORATOR_TIMEOUT_NODE_H +#define DECORATOR_TIMEOUT_NODE_H #include "behavior_tree_core/decorator_node.h" #include @@ -7,13 +7,13 @@ namespace BT { -class DeadlineNode : public DecoratorNode +class TimeoutNode : public DecoratorNode { public: - DeadlineNode(const std::string& name, unsigned milliseconds); + TimeoutNode(const std::string& name, unsigned milliseconds); - DeadlineNode(const std::string& name,const NodeParameters& params); + TimeoutNode(const std::string& name,const NodeParameters& params); static const NodeParameters& requiredNodeParameters() { diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index df6b46bad..e137debd3 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -23,9 +23,10 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("Sequence"); registerNodeType("SequenceStar"); - registerNodeType("Negation"); + registerNodeType("Inverter"); registerNodeType("RetryUntilSuccesful"); registerNodeType("Repeat"); + registerNodeType("Timeout"); registerNodeType("ForceSuccess"); registerNodeType("ForceFailure"); @@ -39,8 +40,6 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType>("BlackboardCheckInt"); registerNodeType>("BlackboardCheckDouble"); registerNodeType>("BlackboardCheckString"); - - registerNodeType("Deadline"); } bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID) @@ -65,27 +64,6 @@ void BehaviorTreeFactory::registerBuilder(const std::string& ID, NodeBuilder bui builders_.insert(std::make_pair(ID, builder)); } -//void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, -// const std::function &tick_functor) -//{ -// auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; -// registerSimpleCondition(ID, wrapper); -//} - -//void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, -// const std::function &tick_functor) -//{ -// auto wrapper = [tick_functor](const Blackboard::Ptr&){ return tick_functor(); }; -// registerSimpleAction(ID, wrapper); -//} - -//void BehaviorTreeFactory::registerSimpleDecorator(const std::string& ID, -// const std::function &tick_functor) -//{ -// auto wrapper = [tick_functor](NodeStatus status, const Blackboard::Ptr&){ return tick_functor(status); }; -// registerSimpleDecorator(ID, wrapper); -//} - void BehaviorTreeFactory::registerSimpleCondition(const std::string &ID, const SimpleConditionNode::TickFunctor &tick_functor) { diff --git a/src/decorators/negation_node.cpp b/src/decorators/inverter_node.cpp similarity index 92% rename from src/decorators/negation_node.cpp rename to src/decorators/inverter_node.cpp index 8b329e684..dffda154a 100644 --- a/src/decorators/negation_node.cpp +++ b/src/decorators/inverter_node.cpp @@ -11,15 +11,15 @@ * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */ -#include "behavior_tree_core/decorators/negation_node.h" +#include "behavior_tree_core/decorators/inverter_node.h" namespace BT { -NegationNode::NegationNode(const std::string& name) : DecoratorNode(name, NodeParameters()) +InverterNode::InverterNode(const std::string& name) : DecoratorNode(name, NodeParameters()) { } -NodeStatus NegationNode::tick() +NodeStatus InverterNode::tick() { setStatus(NodeStatus::RUNNING); diff --git a/src/decorators/deadline_node.cpp b/src/decorators/timeout_node.cpp similarity index 87% rename from src/decorators/deadline_node.cpp rename to src/decorators/timeout_node.cpp index 8fad201b3..831fd5810 100644 --- a/src/decorators/deadline_node.cpp +++ b/src/decorators/timeout_node.cpp @@ -1,8 +1,8 @@ -#include "behavior_tree_core/decorators/deadline_node.h" +#include "behavior_tree_core/decorators/timeout_node.h" namespace BT { -DeadlineNode::DeadlineNode(const std::string &name, +TimeoutNode::TimeoutNode(const std::string &name, unsigned milliseconds): DecoratorNode(name, {}), child_halted_(false), @@ -11,7 +11,7 @@ DeadlineNode::DeadlineNode(const std::string &name, } -DeadlineNode::DeadlineNode(const std::string &name, +TimeoutNode::TimeoutNode(const std::string &name, const BT::NodeParameters ¶ms) : DecoratorNode(name, params), child_halted_(false), @@ -24,7 +24,7 @@ DeadlineNode::DeadlineNode(const std::string &name, } } -NodeStatus DeadlineNode::tick() +NodeStatus TimeoutNode::tick() { if( status() == NodeStatus::IDLE ) { From 86c283680515ee6637665a003bac95e1cbd803e1 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 16 Oct 2018 12:14:55 +0200 Subject: [PATCH 124/125] cleanups --- BTppUserManual.pdf | Bin 340260 -> 0 bytes conf/BTppConfig.cmake.in | 10 ------- conf/BTppConfigVersion.cmake.in | 11 ------- contributors.txt | 1 + templates/action_node_template.cpp | 41 -------------------------- templates/condition_node_template.cpp | 25 ---------------- 6 files changed, 1 insertion(+), 87 deletions(-) delete mode 100644 BTppUserManual.pdf delete mode 100644 conf/BTppConfig.cmake.in delete mode 100644 conf/BTppConfigVersion.cmake.in delete mode 100644 templates/action_node_template.cpp delete mode 100644 templates/condition_node_template.cpp diff --git a/BTppUserManual.pdf b/BTppUserManual.pdf deleted file mode 100644 index 9ed17596785f49c08c8bea978dce857105879cd7..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 340260 zcmb@tV~{3am-bt(F59}xwr$(CZFbqVZQFKr*64 z6g%c6eAZ7YZj-7u2q6$k)Tc`f^#CQe6UoLG-ac~eNCLujmb%>*r^IJ28eBO8F*CiV9Sdd$#W>2cxUgRW+ft zQDLRWjz1$Y^qY4!9@JEXP90O(h=plX?gDTUPZCeI(`twI5O@w<=%7vQO#V}uzt%sh zGBWLds#@kkF4O&a~l_ zqS;niU_WK@8yNuv!C)`$NOt8Srb5ySFcAz+K~Vf#A5$Hh53g!;4JqN}yrc%LCBSXav6!95bJ3;G*@PkWDY2II?r?X z*FTA{o~UZuWVUM5MN#ymT`fG0TF!_rA}z$J=N1M8o9U^GYLBSVvE?j1u=OO^eFk4c zy!TuP6%$y)=ob})S%?5}cuXt-5J*X*O9)}7YXJ;tNZIhbn{a>ko-4`92DT6avb`q} z8=|{z>2-{R340Ej7yj%!{s&2pyQi)R?2l-)-F0b0=GE_pumShi1Dy8xwC(>U!yNyf zVI~$%mjCSs6r(Ab^ye2^@45QTk5pC$YzvzXOVl{2idDIkU$+C}1z{(IU4bEDpxBIk zeD>Dyn1YqrtDjy!-{0}mFJik)o_A%5`kv$LeZ9vjbu))W6OOt@k8`A4bx2QZ$5g75 zyq;GtzQVWiraT+>zv!s%B`&`|U)cFd_Zz9u@TJ|{J7cL+ZUf>z`IP5b;2lInr@hlR z=I%SJ)JI(t(4DB%Z*&IAe7Ds#P5uncX>zC^&j%l$6J^Q?wfh}NKU~tPVjW9DrOlJ_ zf80EBOO0|>e;-LAwqFcgV86Thm8C?&^1Il}o8_s^o3oFViXT`ur>=NE{DPU) zo$cDPuP>>DZGO{jP1K;r+55yh@ty|GUfnElMIyKC=u)Ptz0Y=sY~|_BJ2}yp%-!Jk zdQp@ZE5hg=icK|-`INbL7hejG8B29g~ic%L5&wcZl;Relf3~fpJxKO zL6a45&Udr-nmc46$Z3s4l0Jv6iH=7IA^3*jp(tuG3Jbdo=NxA*({1j7{>GwNYTUe# zn56FvWXNrPLi(dj>s%dP@=BQ`AB{^{K!!E%*%O$mlzMueDMK$PW~YuvAdH##m4rrl z3KXqog810fbe@UI)P%@W8=SHfJQHi)#I*UOiDHf0aDU(dS6+LA-%-PWZZ4rM9~|>g z!0eqkWe+rBR`?Hm`;AaQfc3E>M{MbNaJ+cUX&kd;^kgafr9-#Dm{GDi+L5@HAR!~D zsb@PuF1g>f!-OSEkGlm9(s*>C^B)2cIKij^2xSJC%}$C1x2;xObiR{{v?BaQke>iZ zzWChHf_>{yz3LZRI!M$az3PyCU_D&VRS2A|;H2Y{TsbvG^De{gv2pX#o@|PY+mTdD zb)OrML!SLZWN0}O;`?&r90Qr1OaeCN#ertp(SiG%mzNgnDVtIf zAyjSp8_H3va4?UHJh#4}P_y}af1-i~QiUZcm!bB_%uOv1bdNc7O_7r{skXp^azXvo z!^ruYQ+sw(j*{i}&!~>V^a=bznB!43Om)d$-D|RuiC8orKH0i$$?$32evQh`imXVc z;*mQ~+foHiF-hX7n(CmBtRE#uJ5gwPpA2qjGPh#rX@syL3t2dC_%n}=YJ@&t^Z9ra z+_ObHeDsL_Q7oMljtL3)bPladHbzU1rsnp~gPT1t04)Z#0(>|oLHhsl%n$vL>(GN; zQ>Fv58Z&A~^Vwj|z=O0XN|{hH-W`nIoKdSy9Ufa)DVMt*>bcj<-L5Twd;c*IMbi(1 z=s$oOpQ;pnCS5r;!nSos7?=Sgm#H_0r3}ljav4Id9|l0Q7oM{p0SvPWY+A!wQ3N6f z^%Hytde;!7H^MU-UYQrv|#7k znR3Bw@XdY_CR-vAFoS$F;}jkp+F}yjSHdEJ!!qP5gj3AcaK;B1lI>P1(UA)<+Ooe; zMr)6gnPQhk_|kTvk~~y5Q>_GmRdzxk@3vz5chID;5AKTHYU=ni0fyCAQnGK@9pZ)E zSVcGpSHQJ^N3gGd99co+Hd_av_>+EFXN-jg4k(!_24U+UT4x)}OmIsmdIS?g+l3CZ zz^`bn+;Hu*n!z!;-qr|UUt-5HMUU;ykD@4<$%(28sO*UA%Uwl)i3bN))EulM&7~Fc z46Xv(jQPwaEjp@3^_Jq8#}<%j^)8z@zg%35Tn z-RekREDG77J4t8~BAW40RM$sjSCOY-rGLeZfcntzkF{%$$iay<_csNADcoiq>bY8J>br2CaXP9sw486^{eqM_&G z7@uVETf+}?6XZNWWIiDkDkI)L1x=y#nTBaIP>s2*p>z?J+YS%TJLnSbH_#UE6fpwg zp?-Ie!3Klk4)Qsva|9YHhXA7skuP{up3M!n#`nu?o01!8NV^zS&+g`cY>ZC3iEf5+ z^&tINY!0M>{?#HP6pfJmlAY4FCdat-Kv6k&w8?~#fDc&`9c}i#A-Au_&isOZwMGcI z|9tXD~|$F<$+laK;=Pd_RFX zBwv1mo&1`uUIK#`-d*W|36(_eG1~STv3KD$t*^NX)UIsBs_6PnX^jBc<0?LJAP-{L z5%-(YIqpg1K4tDE=`|HC8Kw*iiU+VY+JdGo;c!Qd2Om@BusCK9yNJH>X*)8BqDb(& zlG>buUUPrP;kR?YH!YnKhxEXFKRB|sb*^V{WLJusI_H7%MB!a4>&jWr)+{PhWt5F>NFk;!3%igZRP-boh}4p{0-l*zO#0C^QfNF5sNx|gBEafdYn zt~CBWS&c;6SR(KepQ6bCdjKyi;5jbbD8WBJ$z)`fW4k5cdlJG9%s@*OX3S?b?GOYt z?*}XX*S#zL43HDXTO>wbZ)-HLdnjBU&DO)Q%}&@PDg5qz^( zRN(V%cBqy@)y$gdm)Mu}F9rCL76}YuJE;o9V0zj6_X7KkCta?h*>QH=xaE0y^)Dpk z>PE9t;r+Z258a3{?a*Uz!7-o($06=7EThuE(rszOE=^4Ij3R${n$+{;2-Uh&o1nE-lAp zqwL?H2UpoZ|6UC;vHmyJAOj1-|F#-z(U6YYXG89NuA5U7TgOc()ax*9%rF2US(Amm zFf>Q7im-z*mWC%aFa7p8D@oIC0!D|zwn!W?YRJ`Bj14>nK==BEn|S~9@VKW#fL1Lg zgM%Lxz^S?$1Jg{VvW?tPfc%Eq#&>(?h#e~3{(Qa}%5sm;%Vx-sYJ@FDI-gS^*rb~` zoUWE$18~tUBq(1#EwA4=fK-s+#a_wa`(|GS&Ib>Tx5#w7U9ENXy0g}u!>{qTpyY+$ z%9)v}y7tA>SUbLu*Cf1j3BE6vOP)ZJ<)GpM6 zJJwg?VJ2GOd~K-3zDk(^elj&es^!X=?~XspP-MJbOzh_fY`q|o&a*GgxzO6X=bmo6 z*=_=`FdvBL7Un%xNwBac1gr~N@L2VChPQp(3B_0I&*)bEC=||#-?BQo`E2v#=nrQR z5aDqvgnxGMZ5J9Fz=UbLC*eq#uGVGs-r2?1KR6_vZ(pcWl~(Uvb3a7ePn0pgQ|5K^ zuf06ojB%T4%WKol?xbef9~N614A~b~(a$ZcqV{*9a8PC`aC zTb}jCE=>@bTg^=N>0%m*C8x;vDWIx=2*Zv!#ryPPA(@N~JM}L(V|I#ut`t4&g$^tf%oV<2PJ1DZ-*8x?1cQh<1$5nog~`yQ9uz?UqvA z05K9oJiI6wk8ysk_o=?eXK}7@=m@_I%rH;2FMhA3* zgY7OJGK3+~yv+NII(yR1a2@XcoTG@QK*=)rB+(~nKGq}RT#FxvJY2vIAywkSjDbwl z`C6r7GL-4g)ET#rU@tD{!P#Alh2xrn3|F>BgvpwHXUezKCE*+?b$~Ot8A>-39U2}e zV3vr9D3jq*BGIk}i2`t6l{%k14Yb1%ShF27&i=?OnvCgd$C&s_k9{$UfZ_sU=o35b zf)pM}q34Xs@=iFX*l1C7ljqNVm8isYV-EXRGbn(M&e875H=FqYKkU+glT zw&+UgiZQ>M17pVjFxb;!{N7xGD=)-?FP9wLBDdh=q1GG@u4bq!J(7{8QrNk$S0%MQ z?%k*l$lRDJH*u1112H3UuSptDXv-`xA6#(sHOb2)ru(J+`r(3rTTnHpy#qCfo;(G@ z2n)1s;xvha`AQp)e~&91+z{j&ybx zbH#B(DMgFv1G>(WS5Bp1NNW(j!8>XStH2r`vyT#CEW`dxbH0|gqO2?^)oru3j|XJI zZ%mwW9qh^&!~+Y<1}2o3A*p0!_Ii2b1+2f?oBUP8(kU1|4ocy7AInWp{@ub7=-~)2#kPVn=En~KG^5ev z=0W+@n0?k@YCZ^L7)rqnPmfH|4UU0TpY;5CW>VplP{ER$IVX>^F8E-}VhOpXqwpon zS|iLD>)sAy8Be9{f4wJ!^-{Q3RvL67>|{S+SKz|aCmDi-mtMESM#mJYyFO< z0cEgjgMz2)eI-MSYvx8QdP5p9-&_J5Zghjb+6i*`}53oymC8?*VrE zAVYAPJBnp%NN5rDC%Dy;E62P!Wc+}e|87Ph>e)u0Nr<-Y)^(*zmIhCHydU(HSMx3x zV?)kxa1(`WWoz>wqmu<&|8RqL_Jc3+xCp#=$m3}SI+=g#4SG6Y`3Fh?XP|3=cs&GF zz+)Qzwf|zT;KmGAn=MJ4Mw1kBkKI^(u{b#c?Lg*8PoOz~@75i7dNQFo&>SVkGMJ_& zdh4F}*6|$X(J!F+RXLsw2qNLrPhkCnQ-VI&KES1rC39`Sqv3x`9kXF5^CF zGfaM}y+pn@a1}65%5-EOMwMWy9C#IL)GIk(yflL3(Tui7jcRony~~U~ML<<{e~RV@ zzVKv2tk)4Kkl(MxQgP*Q5VNl-7A&D{)nwdLM(xM5!|5ha$&CBC(<- z&*#N0A(NYQG;ry=Sm#@El&aY@5gUy3C0Gg%hBT0DBE=y60l4^V6qF1t;I`EeJT;(4 z+0r&cv2(7;RI&Loe*@hezO#u&o@}yL=wYtFj8)xD$$(*Wp?viV=~rqHqY_@8a$E!-J0vn4+Vx9H9;^6LMON#QVZM`{#LX-_V1w0=a%4ShK*n zI)VZ9Dt28xtDd@3{-V%`B?werIZIfB22U7sOhP;uL zsj&+*y|Sy3%fDL0?44}?657AVe|a!M(<`WmYS8^fwx)81wx$3II(jopb5|!*XL?CH z7bkmVQyW@iCwm7v2NN^O|8!O`G&hxVwKe+7c>k-vq@9_)h^4U$fcYPIsRT_gBxLUa z(EcYPMovZmJEJZ%y^^W3y{nV4sWadoZv3C2{mYiLWdtxY{i`D%AH9N;y|J>X3qTt{ z{}($0bpK(;|Am>EIsRw7Ontzl!T=;B46aKI3a;zSEFE&7L+3NABMhGAT`NEbWR?RF z{_pDj>-ql$wf}!m?;q;@|7iHXmhT_5{(t5BYcl{?Ia%qL*x3LaER1v@BH|Kt3RuA&|;;>s?6 zIsJb%h}qk@{Oe9)8~|pP|A(AGUaJ>)Y&)(V3Q1p9M1^4!n&JMF3h`j{kKaLg1+>~9G-8}a_)us@GIJqpYQH`q_e}_k0?MFe90l~8 zV`OG2@lUz)chIRKe4cnDV_LpM*0C9L`jxJ$=`b*483tgt?fi&LGk1hGb$fRAuDH$j z%^y|;$nt+2i}`*NF4#_r7EwdP^`SG!KTs^d<6#*oFp&q~iq}IGH8Gtq_e;Q}+LR}d zWH-fQg%OUKj9|_^$i;@M$|j*2T;u!lY}qHbJVmBnpucf;Vn1NsQ}1+yCnP?b*E`E? z46igulS~5mrfaR_8knWsU_P^T;oc4}%Hy7oOtGa-qTLMx??ZmBU_Pjo4v?GR&2Dtl z6-Z_~icJ}_XCIVywN+-81AP{<+MC&91G~jF!yqV+lg@Pn`xUVNUN} zdcsOBJofhLH8VuUfu-c_Val>FwS;CHkXs}M6yhrF^_27B1?awL`PXpLuGq>6!80}w zj|Z3(B~A{R*w6t;6I)(>Y#t|;Exhs>j#C-8t_xF-=AymlF3@hEnLQ)V$WyGSzWR;* z8n$U{>s28^yC(JMkT-rfG%`x;@}H|Gmo%uPWaj%&uPIn7M%acJ>%Aq#orsHr+kv2OT{a9J(FMj%C!1AQ29iV_mwyK z_kn`t-)FxV0gNo1e@CYOmgGd02)fV3lz|KxU&dyHnA0UVk>EQoi3&C(A ztfN!lkUr)IHr6g65Du9|^Wzq=3?d9TWfRw*$6Ekj5DA|U$<7Wy&)#;!AK-w2lut8; zX9cIS4@Na)h^P(}1iLXl32tQ_=COK|M;ebc1#*Cdj&Agw1fT2_+%7Nxz*K+>t`Fki zyZ8aY3FNwCKmoS%1(*wLcfTvHC?4kbV z{hH~!)8B9GyTK|j-;dympNeY0W=CMRkAp{Ni=SuXI~DwXn|KK1;~MYxE`nAlP{uc{ zkFp)G-OUij?Dsv;hve(`;^#HhH~Z=Lb-=+UF78)*#`nuNzg;}>?}77ce@MzMLi}Gs za9<3#_1|!;{vWIpR*2T+S^M8!DTw)DxAB2%Tp#Dy1+{ky^5HFHsKBl7(!$>^y9M2# zs1WnPT|$2RYyz=ip`UTrhCBWA1o)^cVS1mAg7`0lUk6ka6k)h(DYhfjxoo zwZ8qq{P}ngP^{o?KZtDs804_A9umNObN8U@{klMX+*A}`2Z^t?Z$Z9!{*!O~0RH&N zEB<_-c$hbW8_xL2UHy1{%(2Itmrod&JKzp{m!r3^Km5NSv2}hRybyfo^Yq*OeR)B@ z#4Qm>z6bpDP<{-ffIv*i4h<9*JP`4@9{;YhtA6`mQbEMzPjt;fHpEd2j##p#DKd4)gi7zDs z4X-;+yRB`m|Cyggkr&TT&3wSw#XCCh{eH1fq&?77T4rNN;q9etU8SV}eqMS(Enck` zZK-feBHXJwg9=5<6&QpZg!Vm#;(mAG4e~vG!rS5mg41tLpISFI>Jjq%xRm^?6hc>L z%}vQ$!3ae}<<}<4M`CKz6rfjw4ARh4X_($Aa}oRTgbw9wFaNPq4yO^O^*GOZK_@>S~$d6pUX@ z2c(=4&e|meo7>ArrK=t`=EY(A4|(fOTnkK{>l<-RrklLiSp^FO4b0NBTZo8TnMgEJoVttFPz$ zY9NGP5qKVXd~UB12Y82Hiz6K?Y(92;3yYsbKYBv${ zO8j&=Wfgu}27%5IJr@Z2y2Z<2>4?2L)aJTIE3VC`8#-sv|Fv@JgG(hF_1c9KPzb_^ zMF9^L&BA;hkWn^CpKe@uWmAaVcj_szG^6Z2mU$6EbNz@=AhpPAceqc6NU)|1hMvk~ z>ZeR=MBJVyH_@VhKa(L<1Ktj!)sY2WKb zbznX4HZjgzB*C7)1iLui!NR-`q^d`6xWhxc{hHz80-}8-ETao-GP%dsQ9bqNF?k0i=v1pusE7R*y!R8Nhl8E11KM6 zf#4k5dOIgmEt^Q5E9Qs_Z#W^Z;W0l2Ln8K`V>zPuxuzE(&^jWzjfltNw~AV!ataOBt^3eL>O`qok2e(Qbwo>D;`6bvyqT*@i-N}U*OMiecP0F(yrVi-DziZ5RR%h)nx zLk$S6WCes-E*V8S8|w|?2@D_DSkKLWRi~wRw<qk4cr)bvVo+;R381dwZW2xIKHsGke=`ba%L<;PRB&vimA;&g$X*^I)F1R4QpF zj7nleKMje#7`>WooXs|X3X4=~ML*8%`vY8fW%JQOcHOFAwn>dW#d3-YH)Dk(4?l&5 zY3H$c%kxU6$m+AjDhIdsylhqVj5o zQe23|VzbNbm#PBZVE|AN^F!G?1uBHMfFN*MpsJ~RX0G(sJ#ha*| zu;fk|sREQYy)8IGETH=Sd84^4kK+1-QBZpN7|ORF30r>=i4hU4nZ9fAp)jq<j*p01qK9NM98_{n-J0gyGgFZNZN^v z-WD*X+Q9RfU}7NFM4fuTNa7d?@-dB=%ErI9vsY{}6pXyH4}takI^lQtDj7fjLe7U6z-D{OkD9ZEpqSbb5&&c^PbR(MK1o}DbK5PIqy9J1N& zX7FhslBDi)sv+{L$g+Q=<}HxrKWPDN3bIudpXpv&nOG&w{FT#K@wDsB zx_{o=IIQMJsp4#@kFay1vABfE)e4NI+o|bH|A zG`IHC3xruu%y8PmSJ8{{#LEqAmZ(1QLGmW^*I<4^LP6{kA%w95HW=p0HJ*~KBg#;{ zT6OlIjV|kA%_-+E+1V;_vL;N`k!-%AJ@!2=o}YW~_%>h+AG)4urGs@_UkQkZUu{5qxska%M%GFo{5*&GC@uP`Q8=(}~2ddQHvqKp5yi z+fEo`OM0EAzY>J?cqS`)9s;H1e(5CyOXg(m%MJOoEFzNT;eMD{zP{zF*kPFNPGdoS>VAIaIb(y61#T9Qx5&e3}+i8DP7fSjcb zn#%2U3r$Qfw3WHm>QF!`KDJKrOY=gttU4m@k*QkGh9#lu{KO6tDQ`IqnFfQxB(B5j zsnp1KEmph&-M-|Wg_9~&?P@8Rrfew@gwJ#5wWhfgDyu?FQT)@qd~+K_Bdd<;g$5Nb@mVm73Mzi`izMJP6X&6a$Uy|7wh}q#crfIEkDb`O_}^qhxRbeaiof za)y&Q(s*1G)38JOOgSp=XZ=XN9P9;KOqOeKG8c9j6&npJmn_Ki9!^4s=xQLXpizz= zouYlVMK$Ttd&4I(+G)7Gcwqe1Tde5WS+JPD$6f4@Ic-_6L*rc=Fbd7(?jxtVt0=in zLt&h&L`H799~a7+Kt7dUecFfMj;0<8(dbkS0|nQDNPGU_$BC<@{++aLsl0fHyr}cY zUe35-6ONtW4@gz4T#_NX{C);a?0!ze(m$`(it)o@59#c2(eT>bq5)*`Y5Zs=I|=aD z4CwkDPL=B)1{RT^_qQT=yb!7=CIZ$;lk<|g0-`_GcF>UzCl^{6-r-P7(zQB_J}e6} zw`tX8ubt(e-BxCiT|jtuIHuE7ijsQ>B-B}w#-uQl#Ii_H>?Kq&-TFnHmSTRY^fl^9 z%)(J-BtV|!-|GOK%8_T@TsVZvG!Lp?PDFFC1%0~eTy+b82(Zc$hb&YuDpDE#)_`XI zz2Im>Oj3BlAQ{j7RaF{r!Fz%UtQ=k{HN@^HkdAWAUCSQpLRy>_O;>k z?CfJc%~JIqezP#TV#&qm&wa+VJm8jwZ6D`uOEVSD2M*bOC8b{?kt;H~!syw8HUhF7 z(H(Q)-dvFLZUD9P{EcAZ#Y;{wMTtdEkM^8s6vYOt!ypr6mbm%1L6u@l*Qt7y4x6v{ zWQAsz{?=p7B2{wfo~j-5T6sq-e{L}w%UsuE7iXQd14R`di zLiZ>prmw86qbdPyC(5nk0SUlRwqu@`;Mh2RjR?=*_sS9L3M45yMl#>TY&pWL$JxM3!7e%#u*#F zaXE*sE>DHe{a&lsol{bmOV$x|^(7#uYZZ*E`@_;MZK~9%cAWmtv%|wGb;2J+Pa16n zq>-d<=dVHSO z+(@V{7_VKO6I19H8uVZT&N{7Q9=+)$Dq-E#NwjdGl2Pa*ILKav=qU=$nIjXUZUxzj z2;1m!S~%UCX6!aIK;CgVZ!^cX|tHL4Y|E0&J*!X zn8$@%s3$e=>+(=lW<+_DtelXbEYN~B(FiUZSPZu0HW0&=8rbjfS>!+z@D z#^~hwmL>CYV?;#dw3T{Q>jpQ1$s`Kx@U9(FM46KtXj+4$puw}O)x`=~Hv*x3h@a<1IXZ@N)c1e!=t|j1}DE1;bt2kU~CG6M;ltXBQZ{|frdrk7b zrag(EqDaQvp7p)?eDXi23oMuI%LS6(s1XkGY97VPs{gUFa=O8whD(rb1qrpUbiH_z zEcjt@`|I-f{kI%$<$m-hc%K5iD$PhhY6~fBPHKfcLMk6Zd#WT$ho9vYD|?UUNTvjb zPZevsR-v6K%CFYBg(q4T47n&QZuRQ0wLM;6tM?%{%;sCJtr|5xdmiEH^Nih=6(wWM zk<}vWz^l= z^sVO3*RY3Ak;-{b&R-fOmIUX8rmA{#NQ0Jn?1h!T@>d19oAvukO+L8DTZ%q{YrLuN z?#s+zKRiD$%qz}bvmOGk2wcZpVs7;2Y2#HYN;mK0Pzh|LO$cL{a;|kF8o9t9pb@q!N+j-RKJ3FgI;olut`V z{%H!wTGg~GZxM;yp6$kKf7TDFzBr$xl7B5_WyRWii@}&|7kNZ^K6{dWyf#>i-{6y? zmylV0KoN~9%&}19%*)4-oSU}pPv~oB+a&AiVaSsaDj*RaK%VZmdHyVbOJ==<|E1=V zh1$Jx)`2H&J~6*{-iG{GZ0#*O?JiZrOrm6FAJW#>KNqeb=P^afmtN=S7cYBS_)S}$ z^n3B*ll%eQF|}og9naM)0G?Bw0_3K(jO@>=@m-<(+7gy@daj^!kqm#iwJSvqg&h1h zZjoKu9NJo1b_zeqmRjGaSGDnK!|=_IVakYjmi$sq5@xd#S{-nCHz$cB-_tlJrYClt~ z#@05`WD_wPm?-@Ud*(PpLoGd#iXgJO{aZyoaw?^(*vZpg$4ktZfA2`0IOv}8b+Bei z`)4@WnT(~685AS@>%&pc&p5~pwu2^Hh0r7Dp&6DmX$Z}OJ>tB5i0uk&`(U+EXTA3H z>H_-@-sUx}G|rJ)2?Q_Z3Ct9M=4k*U{s~$dH%+i2qvW~a5!e|EU5c*QmZ*{FZuBsn zWuelt6w^VfPJ*B>5d2R-V}9EyMi|OQ!Jl#)G+(CWT>u*VLI!CNQI72N$u3m|6L@L7 zUE$S;^3_caw2srV!rnlFGXn4g@GJ!67%3jJl~xEptzBZE8ZQ>xByFw5=5S z8$WJ{x{?`eC)#h>zSQYA!E@($yS#`33s($JeFz;*nyMB3>8*+{LQ;p+sPtf*Ct5Ml z3sU-WmiwRLc(a>|FqKY(Bt5ZOP%x&|ca9OtYCL%o4O(1xEnP=OwK2=LI0m)By@2J< z!X!x)oO&NsrD|JehusefW{*bHR!_N_p`YVR%Vv_qbHH}pY+iZXDQVhE=+&uum+FEw88v8 z6UgCspGGfpiKxyK-OU7y5JO2uEnAm(%vB$DNDq%o8rJXk;rUchO;%Rla{&;c#5`S3J@~e2 zEKL8mZ`dbJ&o3^{Sr@UAWEwq>+SI1LmQ_b{D%h-(A5T{Em()W9) z2d}vn%T4?w*H(!?U_4N57$V-G+w3=a;tze$W^)=Z4?8jhOPO~Eo(bfw-D0GeK@zoO zoECf%aq58&Dk3#=Nm;03BZ_H}j@<$(Ve~*Y!pKBc*k(>Y4IyGT0Rxxnlha-%);WZA zfgP_BnR>DDjxz(bqoHm*Rmv=7^!X?A75oHnOqf+>H^08$}v<>}({ngPt zc`kf(-CXaG2Gy&y_|oGzJ`H>zxy!<{*LnK+gA8-B^L(L2-rvf5<|D$cFk)ufPUVxl z$h2D>;~7|1;$bP4ngUtgz)Qwf%%E_2f$iN+YyK`;dQuxp_g#P9TaXnmz9{#5JKVNz zuv3yb{RnUwOXGO~97NQ=7RAV4n<|xVNhX!VCHcBGOXPd?9+k@u>mD%je^E1oipIu3 z@NMv9h(!h>mu6nw`heywT&2~b`@AMve}l^>z9UF&$EXL4(_Sb3VdQDm0{k2>H<7-p zhu&i)u~l5|IdwA@2%kQ%>+_LZI%ba&HwJC6+-43Iu&#)@Pya$%-KY5kWEm3q>1}J& zOzSfDRrdZ=E?_=*)h^oHW%%9nzCWfAMBb$FXz$cyB_z|Si>tEpSchxvE$qdCE+i9Q z#qlKd+$)NozZGz4dS)$P%DmQ7Cb|G1_zGC|;fd`OL1MT5`GwR_vR_NRUkB_se*k<>X9|BmLz}qbF>|sY5;` zFvEjW^Wm*?^mY>6)3V{L4Xv|_r>3%NdW7qVcno;aqWRuz=py|g4Ricl%X+D#G5Ed+ z>mydegZvYR;VWyuorbLkgoDUTp>e2=^$)IV#fNG+A2U&d1iZ`9Qb-d5Mc8#hR?q0q zthT&IDs!um4bHNge00KoXiN8?uq1X@>o&2K@nz3Ar=B$=jJBVdqJzT>{5q!^CbDsx z)g;$0!hvt9R;sRbV;|Dbz09teU{B9!PTuC*ILMxrFfIL?Q8ZYh`y-QN?c$XSKAuoe zx9;m;IKJuCbLLZtjgWa;vh$Em-AyV|=aLT#rYb$Naix*=b9Nl4`|aa_Rd zzYMU>ml-DcvoTsXx{$76xW!3s_f0o=kfx)D$7r35N?;Mk3VPm9u^lIbv9QZ=JdnfR zt74Q5)DJYE%OVvuKqH`fMj=mrt))HbA~hA$p~TL)Ouq;cwG=f@AHwoeQ)nY0UD9^$ zARJ|drNt)E1A*3f%WM1eH}3((tBLPuViQmWxVNz7+r7Im+~jak#^DZO^=W>PX|a|- zWUlJ9_+NQHq-C`z{%#3Du9sQtKBWfUH$dLSSUdW4Tn$I-o5%8S58_w_lB~=D$#0U7 zU7O?$z2?#elXZ}TV~;@rJ3Zu8y1s_|p%^M8UpLZxLbvI=8Hn(0P08%!O2?U?{U?Iw zyleJ%KtRHf{CV2%Yci2G%IzQE%-}O?S(BBI&3V%>BguSggYBo+8Gi`Q$svuW7+#Hr zxQkq0%dW@E;q}rd4_@X2vj(C6++&GxcgV!<>rEG~RFjon>X+{8P$x9WAXSd}7Q&dQ zG+Mc>%wMWb(>yEs?H^dj1<8}eFhV-cT|a7aBaI|O^{1mW;IgP0UrGI(rTO7S{!CY{ zyc&90Sfnbts8FzT0~*02#p~nPOnXB7{%eD<>kooG)p}zhF;d6a(6X{;AjPCt=EN?V zjZUQMMwtY`iHB<7j6PW%GV)uo47pFtNp(^Myr@+A3~Et)Y|*ep0kL6b!rFM{sEA@6 z`r8#w^ddG#f^*vWEN3M{#qd2|Wd|`GT1`&Y0!EHuuQb)?!Oo*JlF2f0_T(O3-C*Vt zjhp^F6agE9lHS;p2j9@Xex%7;bF)#NFpT{G31gz&X>`|wxml+KLYy^r@*sjSv*8$1SKLdCyG&IX}H5J#$ zF$Y9voYS*J*&PW)nPN;bY?LDMN&}YKiQZV(DS_~=$ASdupF2Ow!%2AD!!Whg)+m8H z?{UMd@8nNGHZ1&%Fj;*mYAb!V%{nDtU4Z*T29#>!cX?FYPz!K^1SoBpTN=U>7cs4# zT`x_JVEaoU!LSOIMLKiKW)>hU(X`4|39Kexy;n9+%8H zb1jpPj{REBtf`7LMw-xflz1d@9|{luOn}6^^|9(W8h=N!U2vnlsVWqO8BL|TY`KM9 zjaobtE!hz5hxHZ6RgLz$=a50ab5?ImSoeUjlcO_7oyrl@tN}Fs$Q^m49yW)CvPmTF zt0f&MX|0niBE{92R|6I2!Apq0(npZCIP&__Wg|oy+tH#B{9`C?%`%3Aj zS0xLMrO(fr-`HwBa(?zC$a>}6{^B_QUJkfT+@V5_XGgZog?-s!1>6|N-E5M3eb4Wa z71=Lb*t<8Fl_(hn*%sCFA!NudWuB%d4Gq#|K@kc0 zLJQHtlXhbcb@6yte-Pc6duTZP@W+jjcsrHvC<0gflp_4S!eNUh)i2K#ii%XbPjKNydXuP!YP3h#)MDP9GJH{E2l=8?F*MtTO6~X>2&{-_SR*gk%r~m!L%oCOx%16AI){w4lDhVlDC%dAd7lAEQqX4otv>rs{r`5uRoR zHig?h->*B1m?88^_j)Piqx4ois#$9%X{abLe~@6qa^AtMQzSt>`W){r7!JsW8zB96 zD6i~#b}RNg$^5GGM5#hu9QvibHk($b8(0z-+HPLxWuq+g&x5yEjd!}Uj=Tp(snAnQ zr;7gl)mcGRLsZBJ6$0|*1>J)Y3i6VZ^~RjTVBt1M3?8Vac@x7_vH+3AqO_zW5_M5q zVA@lX)yYJWHlxX$Tv%uOj>NOMGvnX(TuGu#)T3HFM<-mYP$PlW$s?0oAJ)!GrawvW zjWu%Sn%6BJ(EreybfLl_^SI0R!_HgyUL>WL=E9Tk%mvJ$`;+5pibDda=!>?W*}~Xq z1sbvM^OW+gWTg%ZwfDa@98JNRIdY9U8hst2{Rp_95222Pp*3--%MF)^ZAzvZy53BBdye@g9%iRSg{Lnv`2p%*^LGXyAy?87(>b?M~ zvJ`=sVqRT1YFmD8&%K~h_5N8MObN$PIfqUK!#UfBEVCRvdv>&T`aYiq1@m7wn;4IsgI|5 zn`5V&^;jyn>4`DM3^`){Kg_)YlP~|9rdhUa+qPYG%C>FWwr$%!WgDk#*C|`ya_#Rw z-96hIJrUazF|o0)ATvIZk(u$_*K=RGc)0ynX`+cE$$|8y2P&TIgFnCl^_67*3jpw6 zRP29{!vBW+{R;qO{-2y5%RkI66UTp0fBzW(y2z%*TB=|n_8P-y5NAmUP7+;aO^U{?;j z&=uG-`0$d%Wj~-rhX|l1jT~xB5U|VQ#J~VPB%nkpATkE{K3upr zOwCiqK%o8k10W%h!ho_5)Gu0OyfG!B9*=y1}37tMj&x)9(CnQ$Pc^aDbF%ShgB_z(<{VdQ=;m>-!Cesgv*Rq($T zFrvnP$ogL@U_2s(8~*`0J}Z7RNTp&f-rlBx;z7H;ii2JpP}oL?3O)r|RecW{%8~uF za}O~AF&CzGc49#R`9KAFiROj|pflY&g?zbxbC__0z5XuR213xpX$0y7h5HacjDYYN z0>bh@)C}AU;Q9Vd0vrUS$OQ)47{NW1MD{Zm&pwRzt!?sgivWPo1a5i&1rF>N_~~jH zqk)SSA@Ti&|JgA%Lbp>9h2{SiO#S(*sxILL`Uxgp3KXn-CWIe+s_T7t0%44(KN1NQRtO>y`piOm-<7LIv0593W$n{Nb^A29s`tOy4+ zs4w($O8kod@U!&YK=)Jg`QsybK>#)4AUJOj_%n{^9!Bc>P1NZ9GGJ&SiW!!NbQ~Z$ zYZL(A$^ZugaQt#;z<`L&LnbdJRX+_b>=qg54%j%bbnE1Vvj!R$%Kctk+?yR(6&grl z0!735zWf~$2Lkdl9f8ju3H!1UJl1~I0UMrI8?dS-Dx&zufRu`a0s*MIJH$__5oVx% z1jwK0s#e5kx1SsV2}7iqX&nhD-2`X=_^gh^X@-&ADZ7lUe(>cm*sp2)1?co%C1b4mEDL{m zp3p2DRK&FFLbZa zEPP4w#bS*r0ZN=^#dWO%9Vf~h1%vQku2J@V>r_1#LJqqbo8X-w(F)WX%2`Ybsm{Fa zPJ}wmPIM*^^n{9IO5HkTKADzT@%je>;p2JK9iuG1k6LZf(^#Lc_jc|E4%uf)LGB)H zo@!w5!*Y8*w!cNCzu;PL_g7>X{R$XQZ4@st-fUbK zRbYF60-ov@N)X67=rgw3JV$K1)6E{_GOyHClv`7TQb)Reu=t3r79uztN#sVlVE_1Z8wix2#>cG`Of6SFlrky2OQVHcv86hRdaim@5B4;J$>vy-1U zqM>bEaa%R>x;(<%w#iy4ue1BQ{W>XB(xdAevWfto^%1SyVsdqFUX1oep~_0Zlf!lH zJ(9k7AS0ZTdd$WEX-3C*LOZ(0p8{)@{3{6#L_iyhx2N2?6H`H}+k3e2a?33T%m*N9 zgiL~a-4p*I?@sQ$4Pf#>-H+>r&d`}kM;(knS&H$R5|jnCvyvg?pK$Sf;J>*%ksdzf zgDvZ-{D?fO$U_aPX`kO~YTdhyF_918Z(rM)%WFQb+i-M>4v;bttR&udK#I>_tfn2rXwIXr8^*;UM`4ER@>PF$>LBBq0UL$-ERs5^-B4;M?43ZEfRUdmvAt0$!zwE=)lSvre;Xr4pWjl_tkK(!Tp;<^HN zs@&3}sNBc+HgH{ak%zN!kiKF1E_=F^I@}uG^1bU$XiiMDx1X|c3=ZrT8!;Qla)tZV zDj^lV1bbK-F`T|;>j4l3;M*HX(EiIAP+(@ac(6RLu|4|-E>5aEU5{-)z8m0cN&JV^ zNv1HNB!6eJRZQcc)Lz4gdn3+)M|LR1H(cL-5GWKubEQy9oo@LTN((odToi{^LyD_q z6cE!p7KUUv$K_-AN{Si?IRz&L*W_^2Fq;%CV{)u-!4e)JukD9;{Dxu`j~`c(9_`)q zgr<@__GT7Br{@l5Mhu42zB>1dmTpzkbpZ35$O6s~O_pwqX{zT0{#2ur9Ph*D<)|6H278)c4|A;|@U?y&behIt-x8-zt#Gy>r zdwm~EGKDG%-z<`LT8SRblLV7RRz0ek<;nSrkwWE- zkkw*nvOzCRc!1P?A}DO-eNsWi|F5aH88KHu9@oO&R0pC9FxM>Ww0D>*vCU}H%}FqNg#awpg>O17WRD( zSb2-N$9+pXCyTfnK&6A{W0lWBt4vqQuk!E=hb_f-+Z0O;(p(*Qat`jJ@QV3dw1nw$ zDnaX|4~GWkDwp`XF+p74R;R6M_)sA{Iu@>-i$kCN*N<($JntWZ3U>?l8mK9~jo#f! zvh{7LcXcqy%qq-*H*y9d=lT?C_ZLw9s!K)B=dWL5`5^etlM8EE(@#<+RD(GChGdCQ2e#vQ?kK_i)e6?5X4pMZ7djeVA z6Knt*>DRk~QW-=E9JpPn`2Wn}lnit`xwKN z8<+W-PD&F~a&ySQHqS|2&FAR18YkkhmSk&qsB@GJ?p+}50;fBGSnz$GH*9QvHI6t$ zz+=pKo6xB}%_h=^E?)HH`bcTInJ2~*O5Y$Hd`90fhq;rtzOdXolAG+)|CuB4I#aM9 zOqrn^+<`Z*|H8GJhC}?d%Uun}LPkL8pYOMm>?Jn^@V@MlPMtC?bVNK+`ep3kJ@Sl# z2D|53Me5_%Vl>P)tIsUmnD6RpV2GK9Nt9d$;*2yXS`ctB2r!`?Fp$V zGETxcAMd?DNcvkq{+=4GG*4q+S?Qi(?9Ieb92glDUF>O}#@*+SsIa{Zl*HHXq zb8XypYT@xEeFmir;#HDp4KgoGliHANH81jRGhXf+pi|DacUO!M1A23Zx@liU#^9LT z0w)+lXh+MGoate!Pd(YxEs^6uxh~QT>oHiHwB>R0ea}mt?xk;hJa~Q<*F~MuUZJ{! z4Gqgf`s*0rE=Xv%RXOylp*9+^Y@wN(Fk7r^y>DBWEw1Noen`4k^iFPu&UVdco6Y>R zNZ4^;<8NsH_WZi+)lU`!vtK}neK5Ui`EmxzYG+{Ev#9_IhQB0d8Bq{U5U2C^96E`y zDh((xik3lzREj`_I%nxDiwXpc9c)bo3o|?$A~38nv&6xqGNnYgymLsQ zMPr+lMn_4APg14#X!d5>@_s>k1g{KgP%$}ec0vAHrGK}^aO734N0v%c) zns(>Uo_dWf<;bXf^eRFwdH2G9=Gvq% zXcNdnObCRIT~rMMSXo@aNmM~?yPk#riN2#SZ0Sd-&$9!kGdOXzx55m;VWK z82WWA4EQl;!nP;iNsam|Vgcd#Ahsegdvj(4>9>xW1K#>s!_En=H6tbo((V(&(5&c_Rj>GCAI$fv zk;`U*(+zI|)BTE2Uh%T)UXfA10w-qgXK{WdsHBWkIR+W+)uf)Mu2Zz2xG`{CL3)+b zMEF=@1t=(%!-`IsH`_zachujE#L--6v>gn;_2FNq8RDKW%JbYB<5_Rk6o0m}Xio!R zh#O$6Q)dH?hp)RL(r1}=5YnAZTCNA^nQe1^y2kWsGs={HyxzRK__*yI&hKn2F1@Xf zn<~RTdwmVUxL3Z2xO*S(Y_4CVSkfu|5znvby^c3d$==!tJmBEEQ{N-=OVo|$oCJV^ z<4f2zx+f0RdeyV%>tI8qwz5$E`7fFOTu!!xjOilu0iS24vrvR~`jbuXz{70Ztl+1| zrK`(TdwZk4bVw+Im;Jz4O|7GLH>-l45FXzjbCO&Bdq)CGUGNvj_C(}ZhXF$wx;t;* zs^e$u2HBfY#Cs=M-*o~td3CA$F+<#e&rkt){ic(@ZXZjtO5SgOQN4Wr6 zi()z>8&=a<3<&3 z7+ytjB`C(SHcM_3nzuQ$M>GV=0{cJ;7fzEgccuDRn5Q@A_h(>_4)<`JKXRuvd~P%n zQ*%^OT-o3$%?*Qo?Zpp7ZKH9R{n3EbeaZIgYuRd$-A(HJlbG7#aNMpgdNO!7BU8i= zzTY@Ckn^hPtK!d&IBqv3mp!s@e4i-if9&W>*iRvTC%l2XR8Kv~5mu~J2e9*V8ak{H zL`Cj5Smrcd1xo*+0;2U)mXF$3q$roo^Tw9M6sh7|=1bQOhHirD#xy`Qy(+ilf}NTOi&^Kkcqi~P#a^3^pOJ@d@;cT0L?fgFSF zUIb!Vn+3+pmLg0Es0g>=kE@SoMfs`?qe#l}7`?IocBc$VO#nXXF+pie5+JE2eqRT^ zU1RXl(^Pad{@hI2xnWk)kux8FQK3s<;N$4bk;6GqiyGUFo9&P|Lmo7!xS#KB`8s9E zyPGFS5HLjZI2DrN*DZf?7~&*joni6u=iskKnxq>{9zaAVEM<9PR4&Xq@F54Rlk$_W z6`pc95bi1@1^vjmd(hy|R?J7yZl%xaH0xj6+a89|XF(WnzB%}zD+KUpC47v`I=Hlz zdktmu-s)O!zey5g6^m$uNnd8Y)zg;W0_!QVmdThkB<@uQH=V{Ze?+NY;zzfHBfP5K zxj#>cvXk&~XY=i6(wh62S)K50 zZk|ua4`dy&8$i~v#I4V`5e5b&vw#BwK&!i49Sn9xH{W~ur|M{#P1mGs+eLf0C7!xn z@QSQ&(|)I_aR)gGUyxA#`e?jjdzi^1ZA~-Id`*IRd-_MIyg_rKDyI^?xl=Bj+CKA{ z3@R?udtjZ;wx4I$uhgboo)-%3gL~+f&4ZRNAU$lh}(U4$&(~H%C`1(Bl%XB zKxzAWUSGN2$vKfpE_qGRP@K04^(Zw0*FsuOXPh?%CB?Bw?>)&kf;CZ*^&B`}s0?c?XUS9L7$=y%_wbHG&(5_2R!7JLGzI-0zfxY;@MS99T@ z(&%~_{N=!3fe=fT5r4w9hN;7%3Hx}_jvu2AI@V~#7%hwG z_%nskXoT<)0FM!_za_rrEEf%rl4HTE!Us9vg326P!$EtdYfk(nlHXR2Udx|rs9$Le zp`bWp`H}bZ?fT6cwZ?CPE$I0a3CkX?TOymf|8D-Ex7-(i7!6ap`l0T10lCCB5BWT=17$X?B~+c{U|=1Yo>VYISc6#Ra%8|H@mcwNcmV z6DW~Z!Fy#={2M%-s)@5KWi=mP!Ku5zD16hE@Z0y)XgT{+-1xaX;ZWjs-hAmVZ1G+L zS{J+7JF$ONM6rNt-X&u>+|6`{caVUaKFa;{Veh+2KMe(n9nIxem*s6CCsq}mu`=NCx`O^7(`09#E?sGSOyB_RWWm*UOx#H9T(E}`XBr!z$*99~6 z&<0G#tuagbWbL43kvD(eKhFidTcA@_Xu)tCj5EbQUy_3L4&4l(+O+t!{NEXbULt}Q zUMAkFp1EMEm@dus?i=auc3#PFAHGKATJjx7d-<#yLIBt3kPfNC*P9%g}v=%{qhdJJFZLL{J{>@Zq{@f z<8UrYa+jo)em}Tj-gk;0Fj&Cyt<-!SIQX$47?gn6a0a36F3=@cy4u-HI}Z(BrsvEv zx;-y!G@aot4UKGq`3a6iV%^D*;!<-)Bc>H=diKv^y+76L*~#kEdHG{MCK-@<_;?N^ z=P8?B1e$iZW&O@CI%FFbI!knSvvL^;)^VZ--dyCw{#8(Lkq zVw!k_hGEeNixE)5(ccp+ZH?tmj8-1i2pH6{%unCCnJwFXC6oqM{{CNNX#chI@PA}z z?EjIPu@G@EGyN}1G&q?!{u?DgaUPJWDO-yii_kP`U{*@N)FLR^Qn$TOp%m<)Kt*K4 z(7jT(M7^BnG`%5E|Ac6%Bs9upQcA+!$gjoYF1P%EpSAbCw6^44i~OvO`FxAr=kSkr zeo9HD9LCg7tJx9vV19ETg*ShIhyLFG6Y7}>33m?C zLJs6lh!3Hv_6KqZ3hw7_c(6$dj({>$wCnQ_>OC#oah8UPm%O!x79?yO*gsDJJ4$>2 z8gK*uzNBk`wu$=p129Jr)!gzUK0JpH$|6F%vyF^16~F}cuO1CZFaj!w^iEO|VhFKL zU}Swq$v+JsiVkpx9jFh}vitkDF~TN+FJL%O0j2!Gcc6EpgM3Ire5?2ew;u)Z0XINM zP=64h$3g9o5v0)e_cox-L%$4sM1Gp27z?>Gi3FjLJ}(~|(#VC4+$~dM0R0F3I&h1u zT^07#RCf^%{khT6mW+iBg^^5(ikfh6p@HJ$fgVt>KLICiYw(}5-yP2caBrusKS@fU zW(g4AH1{#!2k+nJhxd{=Jpm`-h_CY~U6#Rx$U?gTmwO;|5aFnOL_eq0{|eDifBqGs zegAxjRo^f$^ndjP0Dlt-&Y+(kenAQ&wesdO;qh1wMHYVJS_i+{6uTk0OL?sQyjbrW zg%T?XaU+E?Kp~@p#C)4c9;znkLv{N|@onETGJoyBi@;-&!8jqtiGF+EAr%ko|2!a@ zBi_h*cJ4#*e@uf9BSRqnbochZKn+!XJ>t<&ac$nL$-=}$ff{Mj&EN_pf*DalJcS{J zuOS>f>pTi2BEiH_h5|w7eg(Z)((P-M+)4onclFB#29$<%n>2-X^*;+$z5%`g+oVYP zP+a>*WH=1y7pj<>{+cBN7u216By#OpPL?!uT*|iMQMYQ?E&5U{GqYKX-o@`tkj2)2 zm#b>d+%q{p{Kq}2@>>RVTn!Rc+*X2?IE)^Ae}=@GZ-KYsq_Z)KB`K_;@siEf^^1M3 zm|OK!o!t?7!?)S|J1)8e$$TD|(rb1X;B3~e&#I~C7tD>jZ9bn{fcsY5fx770r+sOE zS}unZM>S(AU3Y46wHNUv1IgyCH{ZSogRHs;UND)3vk3;Lb#xCrdC;qXIn0!zt&h%! zrUf6T`8b--{One+jybQq3+C?2@K?|6c^T{+H1$vA&by8*Q;Z2=-!5E6W#k38B+o6^2sw= zql+3p5;vz#1TP08b{*D>XX&b7na;1PU)Q2AADz0+6#%bc3fa(Eau&R;qUN$C578|U zxpOfw1}`Gk>R5&loc<@3)XeLTf2IQHH?FQ!53;}2#tRS6O#DtRE54ee3Gp37gc@-6 zv)Yd#PqWD49hnj9W)&ks!&l7;4a#xL_0ikxOd?36fZ1nFPI zZk$w+DA$qGE;0D{cj1k_cOvX5QGh*DAx8-uUUTh{EP&mBGa(3@DFO9T*a>btkpRpW zWz=c^9=~tVc6vQVMU`bWU_M`KqD8iisd=vbEn>xq<#w@v40~d@^S)0BN;7GN{ILat z!~;}^&oV=aub{-X(uk&On8)tAH)h|Xwp!FZhW3nUFeR8BzfW=t6OECe=S}(e88i7u z1e-aREtl5kGRYh2*E(7#KMgOcGRO79M?2Jy?b0|f*w6kP50f>z+6d9vD|-dcKM zez9xr>Pis2k9k+CPEcE6qxf3}Nhu7}U5UZQ6q2(Mj*>Yr68JFfhT8BS7v!g++J-dQ(&zvfyr(9P7% ztNUW3R5)$(6pK%zQbc%u+z=^IIPdheNqbLAUs`-}Ww^vlf75k5*VAT@+nwx)59TKZ z|E-y0x-NoTD^Fl4bhr`r-GgA(H4#G>8||M~$$MxE6CkwjphW!ntSemPl<~0*p=_>! zWwOln@o;K%{eIo|Im)foMH*gK25sFR272!fvRHi$CL;wu==`}Qe z5O`a4-Vkgh0_kTl)5cnKKa$^X#}#nh{a){n@i$`&YoO2#UjAda&9?GE)9Z>*FT75z zHec;WTpE|&eR(KavfbY3Wv~&&r6?@^Y(lQ_w9Vof+CB7xe6pn0&Da+&Tim?xw1B3b zKUJpl0QIHUJ>obmjfx!4%L_y{zUB7O!pBTZ$p|CraNoV>& zfe1N(?y3PDqVS)d{R7t#pCp% zVm=S;wZ#r^jO3|cc~$8?-9HHjrh1{@bOgIPv`Np8p3!Z+PRtdvX{^M04i}W_6Wcx2 zQI&>s2rq&>`a6AL*SuE;T|$`Cyg|~6l7WG5mo(^QQj_Y&l?KIg^Viqe%0U*JN4O{QUEULWj2 ztP@XkWdlOd#A0`YAF8CU@3Ekh34HN9*U~i;>NK)|oU(C~#l!w+uf>f>20%gpA?#dbD@@1a`fu2iPtDyKV5|qR`v_ z=18HvYHo5xaMrqaLEj-Kx4N&w2Ym%wV4kSy&i+_bFU@9}RUdxU*7$&n1alwH&@DU+ zJ(KlK7IDjB8Dg=bzhiB`fVsmWiFmch0tNf@$o}WPGn!-LT3RiIfKjU=Z2#-Bi4M;T zH+u)jO@O2J+h2sVyKmip0hFqxu3b>dU2G=noAxm%w$GwycLSfIsUV3{i(F-IkAbb( ze6f!*V|`uFQ%$4FdQ{Qk2jBT|r;K`IdD_*_0f8igk>LmFAmG+@sgzg4OV5}++{S0y zf%n$C#rkP`-_dn?qpgkl+LZbd5{UPUO%A@kyuH=F1$Y;6Mz$Wpz6K6bJo{uu8u%rp zmCVDTf*-x%$9DzCS(lAqAG*}P{XTQ{jw1{2xJVa@{CTc)NbEMZ1J>cL_$6$W^VI@8 zmn=sD`f0DfUfHdQ&n=Dc$bv^YkY!iywRBNN*SPqUh%1fbjU>HX!VkV>$QQd@e$FXm zaj4?;iJacjHkVX&bTV^>6BDHk6dNIEwH(K$AU?_~$MWqBEdH9V+~G}*{eU_;5AAw& zDAugnS0Gx}O_-7$bW>yIk_TsgH)=iC8!gvJaUH27hG&dIp&1a?$CL?usKLs*YE5$) z>gT-oB?U)M91SFe8+}9^$H33ZF>l+VUL5tX70JetDX~%a=6q{$BdbYjsm6eN$e4yT zINH~zuAP_wEdhvLc=55K?Y~i-h_v^1+^o@=`d$r0slzcHMXR(li~5woFsrt)5z!a-{|SXQzJfj<+pz#>4;0T z2ndd;6~BgR=U}1b-HA7gCs`qKaew4fD#o!p*n%B0AheHcfB`4Ft9&(YCVSari9Mc9 zd9JmiUCM)>=WZ3WojjLuXV6{c^DP}#I>%)t6|^y^ceXwBUHWf%V)FmBV*mw9y9{mS zmNwJXz@spfqhywdK*GFo2 z@gX8ceUPICRF}HpUtqJ5yD2=Yeb}^TsIA$|Eg3a?-W|S!igGwy9Ptf5RP56AQ;dRa zeTaUZA7A4@p)F4``c|XsdgJ51zO2gXxu$>$Hs`ROmwVG1=nVl1U*qwt9wt*$p`yT) zbU;bj9Lls04-Sp?*w;B&P2tpnhj&#Q1FOTX_jKcRy3Si<)d)n>t79HG;$Z)5a6~SA z2{U2=tt~Qdx{=ee(LAZ$1e*b60rz-o2SQC1m;7DrlpZuRCJCqpuHhDsK1J8nAcFF5NDuW}XJs;=LUr!EJn2pbg! zZ9Us!UB6BYw2r3NXEN zc}1x$?@({beDFpPS@=9($%gIe6m+ zX0}k_Cd^0n4SI%CDY&4{!^iIRzWfH(dc`Z*$B`X8M?h@|<@ef^V0v#86^g^Dhh|>- zwIX5AGKV;MzihI6{)?g0Xdj|x{h3nQ%Wi-9Y+mKTXl*GQBt5li%t1y<&-c!<`@k1c zaw^}UO`r6ruvIN{9f^(9qqXaPH$sGFZjCLVdx`wx}CA2?u_on=j>sW&p2qjW_Ir-v1)E4Ow~%!bdU)}ugG6_U`T5V z!?f5iWSZhbEw2e>73o~eW{S<%sIAeFgY=6E>a^CBOh$y!E=;~&`cn#e=W?eZ`})24 zj=Pz+O*sJXqJv73B|>EkE#oZH zC~%RKu204`zcnaN7 zv#DRThUv`zs?puRf=G713)!S$F!^9PLg&fx0S-USWzl9mb*7P|)vn#x;Clw)RT9^P zWiX;)cmy;NHAu%wK`xA0u$D-o+Y_6{eU5N|YwjO`f?rITl1BA?>$`#oLU<%ypC!vo z_Qkkl)$z#~7+Ppf5iw(=WuTE?eNpseQ$Lxc2#&X?)wLmNkNru^Q6R6UA2}&ARwd)* zgLHY6$Wq;ZTAqB{LEmA)@v%`d%l_ifX;7AZgX`h2NLfXZ^6se|kq9ftn|4rcr><$K zJq-XuL>k5g)o*37O4rqebJ&2RNpdAMyTEmPTFtiNQb|kZ;GGY^ePJ!!a`>=%#9INw zA7(%cz2>9;Tf3`z)}-ff%V^D|m7*ZEo(p!avp&0G^c+VrlV*wvc3uCn&gOMEnO=`HxFjW|_%&i+jFsd_ za4dvTpZsf!pzP$hLm!ClgjEv8QEF0mibCz>6K`E}XI_o_5O1;k@mW#LUD> z0#25a>A`GMZ7e6m4XQsSR&VQK9xrPd^L`T`)bjK)6Je8K{#xo3J{Xdz6Xpc{mvy-hO({bwrOWT;$#!s8e6#Z@ z3G&0{`Q^>H&>?Sw?~e1}VQel%nYbjNFb{mRyASjK?9>n-LL{X`AbXS*34b8om#kIx zR;qZsfQ4th-m=+M_csYFXY87Vd+tAh=!h0#UI=pcqyFk(9mTJx8ea=v=gu*_q3ia- zjg3m5fB1(S_uXsAgcZl%P+AWL_pWKJB zUPZ!HrkAHc7Q;MiG<_~GJXqGxB<93PR*dr2Psmnrg-yL!HkGl-2g(dSMyn(5?{g>C zu`oweONskN?Tmuq63a1oyH~PW`pu%?WMMnf4wqzqiOKKb?z0iTa5Q)l{~d(AfD;_V z>ExidISAPqPLAbca8no7kKd^RAg`Q@weGhZK6` z%YgAkN_A#2bL_31C%-EPKgyt5=-obINY195EMkJ&hV{rhowiSZ%Ch*sYOZeGHJLK` zF|L<+wUi&Q%Wrnhrc@RavZOoTMWz%y7Sa5gaPKno0#v+{c0meQHYElnpI1D)qm#AL zASNq7cy(ci2qps3&EyDsDs@Sr`HsT_&(fIFq_oo)jTzp#&9<1Z zdsar}%W-Y3r&lKCV`gY1uVHo(-ba+v(}AOlBA{qn$FA-TKCgvPEOZN$Q4s44i%L!U zJEyn@*)6)(y}!&Aq$n!SGbT9MBmap;7&mmfT7GYLXGtiH(sEVsF(+|cIFNQKY0tB@ zRRwFp5Pu-frJa ztlkM=%V>baMzxNdqV>j9bHi|ei#YcTG*p)iYF zA~hGuGxAQv=8isE7q!>w&2cu{2E0peuL>WnC#Spf(4k2JIl5M#V><&XffBD)&-QH9 zY9CFwE3gpQw;vtJi+ex!jdjoe7VM1!vC-vh59cw{V(NbI#s-jT^O0zNCa=@K$61>V zvYfh{O8zUx>?&ro?K^@N%XBhoi{Eg(6!eX|x_LhCY|D6k_Le|SN->x-lA?-TK%9o#Y+abb1hOTLw71q;Gp39?bcSkkj5%-h*YEo+b$etN5cZMp&Ou-K5&| zC$XIW0@f9~bmt1U4a$%isdMP>LY%w`!(^^AR6z;fBLa^$qh^?sg#Kr7ZOl;pg9E~? z#v7U{H$k{B9~iC3Jhub?{SfpF2~W%nRI zxg|k&CS@jZ;+_m+Xu3tt)M9)C0kmSgDek!M@FVqcg`G+#C;Q21>?CSTdq|2{dVG@chF)Ke|Skf4CG^n#?u8)%3!;c+j8BT-Xf2zu&A0sJQ z`_#UebqL54Uc48eu=-JsXXa(yi!$iYC{eq``GlV!o>pWnDocL}i~;+{s0<&uKyu#Z zmp3r|aGR91F~|JV2{2W__@IU2A?DP#L`!GMQJom6okaHbA!klqatOl(kF51D<>;E$ zFwqoZ6Fjx@t}z!j>5`iCS$Qr=dZLHu>!F1a{mfgY8zm;HH5GpB_t~c{9QClH?S-o_ z_*=;}f3qgo`NG?^)C9`+xxDCyT&YYin~BHObG- z*T%@TKY5b(a9tR7oM&niTr-i=kY(L_$Kl$Z2F7Gz|zMlZ=2}xFIg24 zuFxZWxy&SjNqiHsQsMwSP82o=ha+~KJ@OcOhXsrJxjI@yfV8r0*xb5c)}b?#pbG8Y zGNq)7db2d=Nb2Gb&|PJ%&3_F8S^l%|`2T=<;K0(;{Sou`+tZ_oc_Dw61IOSjsJflF8Rk+!p8k?xATw0g#BLYH#=D#B@;o$y%7d7mp%Q>L_BQCl9pbgh?x!b>ATVErJ908^#=~z?&MYBxYAKJ6H z(z~_KmBTITkdeMxzm2sZ2>6$|gd@*hCfNWUYy>L~90A&oq*Kr}fJe5>g{ssF&1TFL zT4X?~JyMv@{$J*jO*H<`knJA&{C65ri z9Jj0zOtNd|NbDlB@9FagD4rz0HxX%2BRG1U==|uk_ge3l5CU1YA;?vqu$tO}Jz@u^ zgZjUjOT?;`qH3<$R0%J!F4`$d7SO}O4d7>4`J-D!CBspuvQmW@nAan(Y9Hs3N$GW) zizFUSc+AI)pjdQffaPvWiDFodL&{}f8a)sN2>`Tab-hLDdL@DqoM8N;pCF#`Nz~o} z;Jl|J@cprRWUcuH=A4#uO|10Y5_@#r0%y}3N`$v3Eb!v4W8F-{UI!=a5WQ(ucgQJy z?trdHit^YL=7ioJA4oNH^g@Hy^0eXs6Z)q%cNNaDao3f^(bSRWU#yzImMK|9t`H?1 zn*t%qPt=43j9QtgaN$@5`dMnNjcnjKh81tf15^>Io{ZHBl!mwl@ax1C?mH)B$4H{T zsCg1?Rb9O@V`srjrJ6Aai#~K8RCx@jq?@NQ>s}P6t1JflDqLYb!Z!4W-k|^X(flB8 zWGb_4=on1Fi%t4K>ocgDTQRX9SdrezJ&-}qu$zsI|5S6R;%hUYc68qV8s zXggYdVgHx6go~%|qDD(@{^WX+R~H`9iQOlvpszGp(plHNaJ5NL?!%_~Jw@eNkj!17 z_`kko+5f9_{9nigE9-wkE|}Q41@evg71HA_ah`4QYdg z9RsmZ;6jSOev*QJ;%RZNsVON=E-z_e9)zMudUesjLxKC4T4@K+qJzEPgopzT5`n{s z5YGrLi%a={Tr{vQ7(=iZv9DntfrKrEUy`{CkYA6rX~wSL^mY(s%XfVNr^)q9XuFdg!YjJv1JYqCI)|g04!dpRN6mR zf$-0%HTeNBKUj4=z!ou)UptQBM1^t#1_M2PqP2(&0lh^$7XiMFG>ZY3x`md3Xo~9E z+A?@Ry@-MDL3*S9=u7}W=r_l=x(PEFq&Epa@SG;rAHz&mv=3pNNRT%nU`s{^OUL~H zoNwx+=onBUCMKMHFt;FLsh>RjnsA;Ua+A|r@JG;fkftY8NT7h;?`P8pGc2&Ez>lA; zFF@od8@pRvtZV4E(07KC8u~dT6k1Xuc;ti(DDdIo;UW+=Hnq^5;NxcvXh6wN9XrI} zckYcK%LP$x63|A!kYP7~6RALOX8)&!10*m&ok`624G#S7C+8aws4T?vBKP^z1J*D4 z9kBhA_BWvHC!j!T2^ZnV?(}E+;HN2s&(QHlkU&$wr=+RdC~(9c>abt0t}uYU6&MZV z@#WQ_1_38@2N^vSHvN?3utO}U<9l&fF`G${Y6L4BqWgQatUn^C4mg6ia7+sAYOVL* zmX^cy_#1g&?1haaU$($T?N_ihLCsF8; zuIbT#kwm9QF$iU_I#87rLiFoRVyf0jqdk!4mCWzQRgDaOIro=( z^u`ovue+5%4#V$al`hAM=&v0T*9>dNzj-h};Korm)eo^_Z&&lJAmyeE&M>Yd-+kKq zLbwAFm-~HB8Nz63yIYqed=wGqp9zPSex2UqTEr)`q>PeZEu!srd=92x6z3?xgoF zwd8$jOI{q~x0Mx!vvsN8@;46)6EQP7(TuPOBJOpT>HYeyZ@#+X(kLz?GYjH=_Hp@w z&y^KL!TlXUQ>3Db)_U{t*OpOGRT@!H1r6+wF+8s{MoukfvJo^ZYt(n80D~Bz)eQ0GFR$Qt(w*H= z=l8F^HW-Q%2EG^Ranp(F;YXwP_HIAu+AN1LkM6D4MUKzb%Xx)6M9Vygw&VBTBrykR z@KMUM*06q0O&INdL|>~%62=YnMyKINx2A{f6%QS&Lwwhqm+<|b-<6#W)d+<}$2opf zw7=hnh*C8;kP7I=Sj6%^x9o77|9JX!j=+hajj#L;a)qxi1q2m2j;DVpnc%UX=uSWG zm*%(ywf|06lkE@$@{QKOtM~edNN749S1?|cSakSOOT=&cKy>H0s=aBcjKF0>9$Vkm zrs0paE@fzy&Lv=I3;3xU$6Ul zWo6Gf#`x45(^memxL)5uZxfcJ*+Nf|2fE?BEVUI??^3Qa++}qnbfbYGg$Ku$X0HB; zhaa@QhvKSuXBNi6@lWe9+Ce!yaMJe_+7YPK?HEHXzk|HP&6iC&A!5szD_rUp#kwI2 z{l-9LvoG&zN_D>0+wZ25KTCi-CM0<)4BsqGds-R4rl6Yk?a8i}og+=#{rM|)d(wdd ziC38>_T9~|MO(h_D%8RvN#`gwR4I+M=v0pwv+$`=M|=}2ncx?M)CuX)9(kwTJ18Zz z)5vfiWF0L~LU^blL|>{>R9klrD!z8&Q>NMUJ4E*kDpFZAqjM|@ZX_m!>58rhvsY#q zlO@(pWd`oo$1r>H3miSK8AG0P)sr=4h&A{6q17(SbzI=)6M__}lGhj5)F7&ej zo<%1_qu1m#Wu8#8!jtdv-Db+^Y-nPjb(RXHl<0p-#W(Q8OGh&6jBL5s z!~oNOWF!lTGNVBVug0tV8I|(LJjihqg)I|MbIQ`exXXAr9e1IkaofsN-G1D?&1&fB zsjNg;Y|On#-@j${v~eW|Gvsc@{Txb03w}?QrA)Z!ziyT_L7Jw0dLc^Z)}9S%Z9A|i z=x=|jm2(>aij#eUq3JM)Sa4|=eO-{NK^r+{*1QA-j>X!iRKA>!(oI6^S($2qK89zS zq3yh|o75FiD~6~oR6s931o4KwQ$PM?2CIiR8&qq-5a>M=KmOIO37yVF;Z&RTnFb7swDyev@ zqF+Ru{3jc(V_A|*gU0P%VY25y?v|xgDb9~63ej?DLKFoTtMsC*6EOO5X5C{JhaQrP z8N-g7$0RCATe1@StAI&mA5Z& zXbGiYjcrKmhSWU(xpj~O3r;xH4^4P~Cb&a!Rrh-IZz-0`+Ie12-ESG(&&z#bB-p~V zP}7R)biQjf?v5T5gmU>$*$Tfr1n2VK$GFr@fCleIFV)?d`NnO%QJ8Yh;+-E%SoTXNE28`1Efb)XlYi!$qGB!DK?BOT9jIY0iUz@b`yhl#wIyJ5Ja z7-wwlN9Y;$mC42d@XukRFvi-^!!6yxHh=3zo`FlsPO4-*9A@Uae^JbqPmci3NMt+} zo8Qy*n8D6VD(+7nQ)1#Qnrr_tAD=94!5WcgK#zYPd-Nn8&hOH z$^>b98Ufbc84GL8Q#rtes!cO8e1p)|WA=`pb`)6*rDMw=|0w$5+Vgbw#a z{SufFBFJO=OMT4UY`e@B5`nU@n)Y=xA+H`OwXVF-r70NkrxhY20nfZ_jbOqTSuUxB zKlGV<^uCiZ(=1AW);1U75T1b-(FhS;d{`T@*NeA|HX5$iDOBXvl45Yw?C=OT&dp{8 z$x>UikNx-S<>7QtHXIx#N!wAu7U~J5gR~`uo4ds$<|yW1_vy!JFm^on<$)+{1JADoQo= zmugq~#nZ@?ITT}Lynr@cVeYU~Y79cP=|)TH*J^LU`d%gt8GB>-+-Wq|V|uR^YY2Ms zAt~K3n)n`2G$|s+Z+_z8qD~Q6JC141S_qfjMn5{e+nc$1$W0Icq~WjeHK*xj_Y0(p zo9bfs-*cpp+u5`s8ZQ_1jS`!Q0PM@zrMMU*oou}eG@8P>AV>Q}J0#z<#^`N_-1_jX zUOQ|wZ%>9l#rCLqF+V&@Bqk`v+cNDDlc_(Nleq}pt+|xqlcdLo6-boYMB5bz$Ep+r zA~mcCv`J4knbapzo-RJ4)Kn_r=c(zYf1s!Mmk{ddacnZXwz0#gCPyxzNt{efFZ1c) ze86UM z%D25S&!yyV_$f#{G^;!A7*_&1UX)p^oM_C{N~#l0J8u3~H3Shz#+I-}A-7#d9Ih8d zC62z0=wWj0xr-^f5OW)?X3_a{Z%X!mPFIyLvw9RPjXfZ1Soz$JWzfAlp^zq zU6{-9%|KwFddO^-k?#Yf<;S=Os{SX;@njVA?kXUkORA_x-NrZ;TNfwh za6)lQp{;=bV)mzQdEmjukd=)rgk$Siz}uf3>vz-uit)0z^(lI^&E;h7mHKmsF1FaG&JUE=6cyG_dg9$*k3g1-AM-D2qJ&TTL-RY-u z&7TD()u-jJn@r@k2OMA7D)};Jd{=XsT|^yJ&vO!xN3ij|jN5S{m?w7amXHaUIELk$ zW8U9MvT=KlJ5ujbPdXcqlKbgj(qGFKqPehs zD6~q&Sykj$Z3cWg%Za*+bq}Ey#d6Eds|EC!61vv&2zXji&+0gtT&FyzKE-^azbJos z)hw_IsUgww8;&M5SbxXO>azRHz{Y6)PlJ6W{ENGAFYil5zCyqrq_y1 zOE1F#`Ggw^mR_6RW!08%OW3@i_WKan3BEI~`V(Yy$mO|a_MCH-wEcGa^D~-pktKZl z=EB+vJnxllEOZtT$^?FCp^mI9t2mfuy@-h)pG7Oyp_=|S1Sk9T+l1vl(c7= zmVmAM3E=U->P!K2B<%@AED;(fJSqFnD6XA7OgNk2w z=6E%9w zB3()tAgvvwl!6S!WuT{^73GEKE3VUZ@`jo{)Qi3-3SBr5_b9l)B}AaO3?7n7C3J#O zKzVt%rb4%?T|Y5wKrMf;L1#Ak_06^l?xh$p{dBbQ@9$K%wkkD*S9x)02XYb9p+}G< z(iPWXI9@T0xk~lS?(Eb$DP1`!^Sy@Np_`F#nrJmG;CNpwDq-*K$$HG@OXfbD){eV5 zbJjHWkpKbaFZaO+U_^xt*O5Ev;(hGa%-k^F#~_=h=7`?>tYUWp{AoV7yZapeF@<}m zo-JCYdX@7dy=BU)?JA9H4@R2#_v7wNVeKQVq~^)H_ERO9zXk6+B)VLlZhTRM?tR%{ zTUFTZr9wwV1ImC{cR?CYn~4aWnWPqLcDj%9fFJ=Tj-aG5up$XVxBZ6E6{*pPL+}(s zMC@s3wj%oHgf&t@M#utrd)%Om;LK3#yHZI)v|)PJN{5$&fd|%YybFuoaFtIhQmD4% zXDt_6N!>2i?B1%F;P$D)9R+bkA?iexJn7FdSs2}7(yKdF6q8iZ*n35EDbnMp zdR!Jm$@Sy`bZxe5n(|6}*+Wr})94rE*kk1@X@uxWMdBV8h)SK5Az?Qnjr(?8n)4@l zYuzJGG(-U(&R&9}v16ZxBMdxRLJ1q<6@@NaKflmZvMJXWcq^IJWnF{PO=s=F#z+b~ zj&r=WZHu)Ur?u2}20NC-9r9q=rbv^k%JO>b$?7Qm1==??n-Zr6F+Vb2d zf~c^}o{=q*lV;92FLV8JF&>DdP7GAXRkf7*1SMw~cv>Hrd`#X8GqzM=5f)`#CiFIC zp=4)JyW|xw-W}OY{OKF~`l8&$SjXuR>H7S<5r}DmBIE6|6rYmaV=#inzYaBG?IRW} zr>IKN_iJR!)2;cXLS3!M98&akN2;z}Cl!zH5kYL&{b6ubM)-qos}#& z>f|c#CuS|*i2pvSW5c$YsG`)URYLC$+))E&Kf7#?$i(^s0qxgI#2xLM-z1P#4$J5J z2~P)#FC1skUesy3Rl#fNN~r6g>XCSKuiuVC@gHK^7wHKYYi-J<1XE?HwJzl$`1J!k`#l1>sR-RMEXU(TY#G*Hkvb71_{&q-m5$Q zw@K{56wQZi3G<>Q@=04X-J7=vxy?6wmCer-OqH-s+%Cj_3k1zhaD7pYbvaHECadyk zH?HGBIqnWKcUsr4$&`t_D#Sljq8z+QE7h<_Yu@AHz_V*JSm<+M{!Y-&vTSmWwHv1( z?{Ov4PDer`Ri`^;C5-r`lwGmkJ@6^ONhlECH7HzghN~!ZNmXp$DSU6bEE?2#$iIK3 z3beF(@vzf5FdHC>0sMMryllR3W!E5X&Hlx4lz8uc z2Jk&)M?5C*`a8#>cWUNt%Jg_U2LP;TXiCCFmX+ z>MEz)A0@9!HcX^+;nu#O++&vpB>cUVY)WH)pLt^5Kyrk(8gg|_Zo!P}QXo^h^1JPF zB}z>OyTFYWOw01T+}8(RL0Ct)WxnRn&UTgUcjC+6NN1M)OT}{_U#3^`CGT(_8IYG& zSW|qbzMBtFj2~g!;4Y#ks+5r-?V%w6SIt4)05K8m9Y`xJbqbIq8f*WD?c=X7f#wD zjS?M8Lok*#7Nez* zr&KyIVy84o+kgv%uV6sgbTinD0FWCc)QDgup-!)prt{iac~SwcRcP08Jyfti`O#p0 z=6S5XYX>i*)g*r~S3F{255>Y7Qlbd0MEGze>}b$^Y`fC`xe zwdZJIHW@u^Sz9G~S;_*yr?p_x`3S2De?&A7Q$euFuu zeIVZ>mx8M=CBvAxW$;vc?Fx7gE^7IsmF>^6# z$idU+2&HD^JNXz$#;9#`IJoa^P``pw@uIVV@9P=IYiEu>B6PDzo8Lhb{W27F@6Urm zXA?Z{L7{*`D=@X{$k==m2sHlu5kQ&F-NVl4X+h5bn+=$e85q=cK2bw3{G6U@&aBz# z^zxX{nA}4qy(X=>IPNVGQsKcbQ-t25kBD^mqG&s{UTN|Es#sr}WWx}c-XVEbFcfiC zjCc{aqEv}yevG4M`tmtS_u{!u`~}{uF0}oBxZL}n_ucfl$ZIM` zMj(%mj}6X_kHO{_F8mMR^7~c*IC&7JL1985e#3&8VT>XDmM7E)@qUyG5b_hNfa9aU z$4BU10boF0SyuCMoF{}TT|e`+%P zwFL!%s{IB75@Yc();E!Wlv{$gg0S)Inp>R#EQM+Y@Y~P)O7u}$!iI8!IoP*%b~b2m zbk+;#xfn=Q^SLl=;g^9r{Pk_|vG(oy`B|jI=Jm$c0iF4Ayy~a)JZ;Kpws(-gfOsjf z`&aS9r;LKBhQUC9d3E8IRh0oNxdQP0II6x+`k}tN*!XE(YyV9VbA7rI(jUv!m$a}f zFH9gELWZsb+6=(q=XYj9acu+7LNy1kf4eq2+XwKDYISM^;!xM%;`~*%g-lLb2GQgN z`o_wQVu85^aWilO$En9nV z2Kr%e{88m2ynk^Gj?Dj`CYo-L-LP;HV1AE1+L+D z)ra`krN&#q-|9OaI~eN6D$fWUzZxu5E>NfC*+{P z<9FZwD+?{!uMP(JzRylRh}ZECi19buiwye*dkr3+_U|0@J=yVZ+*@DM_g?vLALv8} zC;K-8)8B?)zvfp|g;zirKe(q$P=gqMcz^$q@~ut> zzJ>cC`c<1)t)*W-qWvXUA2RCyT6RvOh6$Cn zv#?crq%zt~jcyXT5X}TZkzG8|G?7JADjM7vU&wHXssLh~}^;f+F*H#KS^rEBCd z+B=c01F;g}$K>SefSqk|usJ0L3c?Wgx@SG&LuK2~8Y*9bq|BNjy5G-p*9{tX+p;c6 z)uesy-RzYl%|gel^8k=F#M-?3VDo+Xt8&%7%r`&e`X_PQd1a5j{$WL}Prh3#dwMn} zN@I1G-P=KcJ%{^G2?%fSaxJ{#u-_=>T`IYIl;I!h%b!>E%Tv%bPhPUJ1bj)dL;MXu zz1X=2uf4}kqL$W`i8Cg++xF4`_<(OqcvZc`xY$RDYY$@@MnMdxC6m71DV>wInmqWE&xCi?d|M3p4)!m)jE|_%O~&dil00?2iefT3}h< zqwRRUd4O;ZhMuDU`|7zkFE*g%g2h?Wsvu}E=QRv+B=|q<(Kh>v--JlSKGAb&ZytE@oCONYEt~(#_6i5sie^E${7;) zQpPungaY@j90H)5itT4CZ}yETETOPrl@wsb$tO13|IJ z)T;vO>hiE2cpXScGx+?D{woL>k9^GU6<1hfspYK2OtSBMD>hsRtr*Ch&@fI0}}|wihsd6*4}=`IgpI z3qJx+?xq?niYh*8)Br#^&Vi1W9ZbRyLR z_S52cA$&4wHxurrlx6dq&j^3p96QeZ3r}I`%F^j}Klm13U894jn9cRD_;!V`j)~3) zcQWw!x$FKIdI}fv=WPW!s?BFej+k~E2BCDmnI=ia5jDzPmJF9QW#uVnJLthW73i)t z^VNybdHq~;PWDB=Ah*}i)H!4cN^z?Bqn^4QM!xRZYr8p>V8b8FM+9HB=N8V9ZseoC zc|7X%+T`hhB~BTjgCbV(zcd)Zio~lv=C; zfD(pbipAgt#0Me}pVzQJ$9Vm1kqQfUSknH5n2>zjmD>QXjI@Yl<4LIg^*+g^ZbjX4 zQgV3<*z03HOVYS1A>ocf(h6Sx3z_ zvU+vE{oyw-%RIE97h}f2CCRkyr7~qCTUH4nHIOXn$1N^#d+608Kobe?Mr6UrjysTc zqxI9soW!F`nw8kz&mRin25ijxQMh($G*F!lIUNl+*3)u3*%9Gb^`Gv4Q@ZB>^QV(3 z|6V8FS(LQ4xw0>D`G0#0-}GoV zi1;o8;gReZWiHs?aPr1~)mSIJ)rTuGL+y{IE!5Lg`-R-NjtHzBcL8^jaoQWa5aFxi zqJ|O^n!uM{zj{5Jo4Z1y`DnaUDu2sn*P1vU_~#;;2#XTjqXUbMWrR$`O}0o!L?{vC z`gQWM{@t*dD?R8c5|rz=4(aSSQf7I{{7o=Jlk|iuI?yGjr_LiZE_ValC0WNSyu*Ln z5uk6^RnQtd$2JO8e$%5^7>jqtsY5I}hwtVG8b}o%kVMsd1Hw!VLCUcm#)#EI?$|9> zrC{Cl4F5K1gD=zOCb4Q=49IyS@=J4 zvN+nAbabYK5H+n`s7~R;eld<*4U~sx{@K<-2>pn%^gajkQ0`GY`+h2G*H*WRB3(`<8KY3w zo*1g+r}_)T3_{6r z0V?D1Xen%m-BXo5;7WXO=d-WxvVEQ|QvPBwk&$REvC;Xx@l3%em&qudLVKo6Q~kr( z_^%I1)>0-|o`nLcDwLZ& z*g@pS2@Qs?kJ7bMsPPz56GEV(`XbX)lh3#zKRBmr*5?hFwjykZ3@BD2N&rZ7@pc2X;eL#Ch=roq2;q#LZkBeBO+gU)!!>Z6BBD9erkiYgQ$Py?eVBZcwc1c z8-kaNH5X7aYz0E|O=1{z)4aJ5wgb6j-k!wwfI9_EWb&zT3O;hs^mw~-5ypNF*U~AEZhU@kCd1_@Db1{s9BR3s zswY^`ay*GFFNmZvWeN!wUwra~fCu-&ShSo%$mP0@k%RN%(K2fPazAjWH-k&+1(&E3H<=ScdnM)C+XRmVLF)TvL*HSPWt-HMop*vohkANyHFeg!E zq9WwMxxxtpdh4~`)Jo$Xsya>o%R7q_Vr zRlY6Vt+HGDc&H{WzV-TC@8qY_$$IMc4(V52GKR8BSmf7voq2gFtj(LRtDu{NUhr`U zy;+v0NfzAD3+fyI_V}Iilzh1O1drRAzuZUYU3V%LY27Ye0xXGO0^DG0Le2sOHTSp! z=vA7>vp(Q>Jk8mu=*5v7PDL;=EK*Nd{%qVUk^EE-3H5UEzaUzv{E;hEFo1v!VTMLy zDnbytQ-en1=7kftJw`>7fr*6UaPzIoD{r;5bDAS#<^+4~LFUb$R4v8s#ddAnW*LG> zZ`o7wi?L4Fu#fLOaCQk&p*_Fs5QpZH(BzbH23`NuOz{x%TPa@x_kF-$^-)8e{)gqntu zRikGth+6%*VBL!458%0MF%a$kl%bqVn$?pr>uJb6BXI~B*sXMrBI;G#MkUw+k((#s za5oYaFk~R@cO|~Rbtyvo(*69%!3y%LBjTbRihmUilYZLI4mzVDY2fER0H+>$vbe~6 zv>m&1F?~sSto1&9yf9aDani=~JLu;iBxAT!D*{`K1E}i0<8??88l3i<2>;+LXtdr+ zU5DIQO58(nAhjFH<4h0*E_ble&pkyD8Z8PmT+eeC?v)|0)&{yycuDeehJ zt5ri1r}NHDzEMJwrVG7UEqzI!c}l{yH};7AX{_g-9Qj!f!?D%o!2UaJ*li=vN>w-X zGoqI4BL$^ctzBnx9}#JSfLME16;PSu8=>cMpw+wMi_5+h_W43?UZE8)pY}$Pjc{7F zD@TPh9240iON0b&Pc)3_2I8m4*-#O^@OJVe$gA9n0Ia!;w&0>p?8C19xp=2YxO@Cs z(=j%E{EFj*J@A}!+OPTV4BUo(N>FOcQ64QBlgP4G9=&M9>U#M$Y$yKY^b2E6vm?7f zc|n#t2y3onG_g^k80!?Rn71nmT-O2Eb}1HPmoTKc0RDoB%)(SpEJuZZ{xTY6C$G$| zo)-G>P!x3dHN*2!P6-vCK|@?dTWa5*?X&sDYCMR_=t>PTEy>TPIUylqji>e-uSx#Qg1} z05qB5!ZWI7pL60jf5V3@b1=SQV#$o;P+;jjH}Nc4(M!JlIA!H25864#zC@iFt|37C zB`gTWF@4vOA3P$=V#RD3jiK~q=(^6O^em&x22>tNRTP!Nmw0Mm|s=hMjL-ixl5(1MXG^p~~3WJBk@DigfPZyX9|LEYR3gCAjSL2X>~?l8 z(2Ta*8I-Zt_k(?i>~c_bo85&J@7f*W2&QqT+ff?v3x_}>reD;E;PRrW=;6Ehv~LU8 zup*nZ9UDNHIqn_rAbl@0SBe>xE2GeK2(N848IINz*YU?3(Yd^fqsO294@M;tH~^g62JZa@T%dF-Jk4u)D93R@G!Wj^M6%vhoYOst$6D<;SZ7mC_eM z;SP#e+==CF*vLtM;vF(;FqJI2+Gs03miW@I$2Z@B{~{)!JC|h9d6qL#ikseo1Zn|# zRtQCsjpbZrU5u93t}eZ8)HazKs8?=9MYQy)OiMsSI|@^^t{D)6L`Q6aGxsay`X@P| zx}b%i1kb|t#)uMFA{L6!vGo9Y09#b}gnelfY+=aR16}tpCcEg9M?sBY+f7AKm_T|FloY<0wwG^BDpNi)=U$5Y6pSHUbD?gl z(wC0x{01Tne;1Zl%dzQa)tBlS!ge^n{$@D3#uz`U)%?8+76%59)GNAJmQ#Xmci*!^xafvO;Q5#MI5WJuy3wWsF%+)k5&Tcs=r~M6(iS0>Zryb4&|ghKkU)CAWON%-vQT zc_>EzFDR_fY|6hQX9im_1=1{O0Aes%41#M{sSK|9V$coNHpI@}07h-ipmUJ&h2_C* z;%W11F=0<;V(Y>1i1otAxc*NN3(pPKf*CLMV^yMNY~VQ*YP#Y2Ry>5-kBY`+Sm^t? zl80CZHz(CrXe@IMv(&J@>)4P{nM&xJts{hxq8!wU^x2-Pzz`ZWy0Kf7V|e2T2yQOo zeBn<*#lQhWtv1hMnoO9{EoP+83YNdd4_mf#(d~}SK#VtFTB2N}G3(#nmBAEJsTO># zKZ&f7FSr|s2AA1rxsMDx%p;a9*OxWz-%)~0OtrEkSCS9@sfqhbPIlf8&1o?o36GHQ zLZxi1HD}=LP7}!{tHRe^6vB&xk{cVu^i*$o!&Z#;vNvaKCz{c??P+y_M5a!<>`_B& zqBnWkHgBmOH1*!r^lD~IuRdO_W`U%iiYo%39w z@Nt_wbMY}$M0ilbZw6My5WVa84zbhg7t%5@OSu20Yn$RPmzL%IeTev_(*80DVhCk9jaU`^Ia)T9V>@6A*L*Lv)g47GAVo9qdW z1aCK}@A>NWO;A4wYl!q4IkY3B$JAYi#U|pjHumLP6w`EKaU)zPpTVAzPeTh9)Q=N+ zm)>LW)gqnPK2bDLs;mTqMPzaC_^Te=Sh&8#^pYI-A`$2!(qHoWnc_0>;TaAMxwxqw zdEHEJ{GFvQIV=`YQND8kFnk0P2@j<)f4*kc8@rqh_*U z)ibh&AZ6`Hs-R4^%=01GmAuN!d=N93xY{PD<&`QJClD@bZ*0Y*ey(UTDHD$5RK{ zm+G!qZUIaHDQS7lk;8fU`F4PQD&LX}r8_cR#k(z~Hi(%uVg#*j(b96|Mk~A!*bzoLh%F9KK}g;wo0!NfBtFEiG+j=vqjdp$hy*39FxEqhwga=5XQs5%E1}T)Iial^f^^%w)%f13| z;C@`q^_!IsQ?m%RJS|9xpJ`8@ZoqUFU==j2g9Z$H^pM(jA`T~`orckSzIn-9v?iz- zdN?%sZHPo;km)Yw%*-S2${=szTQ zW;$iG0zXGm%Egw?QjMbtjQ|20Ko&-3=#jX|vAj-m6}cqrvtf8uICD)Tv-3o%)A96w zW;yoGm-9}*#c)lPbROXzKog!uJQF9ESCu_tWl^{8t6_l%o1wM#8D?;X!Sitl*Ki*4Bl{ zD}y}i?gGe6e>$Eo-o7Eocp^|$3}m5~_jse@z;R0E=k)%xYGX^>GlYGHVA}DZBi`J? zXnM6r7CfZL1Jef+CO&CXaV;jDgKe118f%?1GzhDJmTpEEy=5lRUKiRXFj6!I*!}+5 zKi#56Y+3Gd7(T8o9c4USeZo~R5+q*l2+1d2^d3B$pt1+srzc@R36ZI9$#BUaR1QC! zj^E%73@^_Z6sl>$Yt?CS&tlDpQR35bpKn$=odL#8uiO=b!M|*;L2F?jw2|B`ZhcVl z*>9qk-cs4`q$B(pY1fh9$(rKOo&3|7m3+kfraOWBWG!~C22S@FOy}$L! z;2yK8S0iN8Srl6QHVpLj94w$v5o|DYza+4W2j?tu+-g0TH^Th*(QAu+@yEkMz5ZzMY{S>>XlI3@y`0czk`S;FZz4rZ zH-mf!arhf)h6ZQfBpisM@;iEBw{v4tl&DY{FK$Z1&aT!eu4b~xxs;qisuB|CHQ}5{ zPr1B$RI>{y#_5izG?CB@_wgpGsh#nyx6#Y3zy={w!|*(0Ns;&SQ$4!g;8g5RJsiuy z&=|cT2%h)aBr745{i?ng3~w z*8W>+mQMoR%7PoQIc%~f^neyB&=7ZUZqKq;Yu!4Py2POxdDiMCk7(ZIMPAze&4zrw z*iSdIi^+-S`p>}C&qhrWlDaJ@(xLcx_jb7m(pcuvYEQBFrPSj z0zv|4?aE*-W4U_dzvk1F&BjLf4LPZdQ)3)!Hq_;R?B+TR2@yR0pCmf z7if^)*UO}VP8)~08oQLV!uzh9zSu{NZ7*g)-q-yEry&MA;Z-fOj*>~XO^U6;I$e_O zS)l3*YIx=$?vKzgWWsC~XaJpEj)rB8S|4Bb1n;ps=0KZ226g=7T@D9>lp*EkUR zvanB)OF@1ZZ{Z0;k}?e`NhASSrqTO$dFg}J%HP*qr)W#rfBpe&TlrhmXdi7997(8O zK$rwdD&@jOw;t~Mr3^`YuTFd1OReK_O{dEDw8e%1e#nvL_3eYB@-yfvtqSz)OG$j| zzmJry(M#4!VblxrEpI*8gO?lb7S_f<>i8rmhgZmuFUB>eJA+tZCN5Zo?4Z;!pyorBKaq9`_nJ}ztPkHja0WM3 zQD(?b0ty=llfBLSMSNNFZsvp}`!&nN3^qwq=pB?u0qJnE$NWX%%Ih=+VAQ=${GRWS zJ8V9zynBp-r`)X7{iP3YWU9!Y+G|&fGYHYkN+y53jkj4Q|QMj z=R%>P3lz7+Ye*XIZdBe(7TkdJq|dP{=2JaC?|%ZI{abz`nGRHIrF(lNcvbKGWM)0l z_Zoyp)-wxha00m=2r`nhcgFX<3gDo0X2|?kR&4IUL|oVNpX+8c0p+x|Y8#6mJ(z!d z)4#BPKk2T?<%JZ3Cm6Ez zr+*7iLMQl9S82Vwb2Hh|pDciUQ2dy1$8mb?PkTQA7&Y5nlurcy`}s1J9N#dWl1;AO6KC59i1J9V zBCS#ChWt_@)}-gR?P`86R#ja{KES}CSCs5jd?z}WNVjEF38m3G4D0w9yuT1 zraY>Lo?#5klj6&9KcAAMSaRL*7VjzZyxyOM7$l?Gdl4&_*#VpOC#ej@7yr2i z{Exg6ce^WoB&>!LNnGtN5VtojPWer_-06k}^^y`TVRzq3nP}S!EaKryFd%KicCK0n zq#bFluzl6rSYL{FkMgG9>l-PV3bO{DJ{AN^R z@$XVz_=hddY>aS@50a2b;3WtHIq<7+TT@`d-NtmM0Q`8X9Qs|D-@}g=W^Z|rER!v1 zxy6w>`6j^^3RwEQj(XmMCHFGf(r%IF{02&hV0sd5*sKe7=<=PgVQ_M2_YN_ASWB|WpWRWQ0w^?tmC+pu*`!bfd9{DYPAEl(*h0Xa1PgS~qUlI(l; z1z)ypyUVt1S9RIyvhAua+qP}nwr$(I{rms#xpOA&iI_7HH)7^Rzst2FGxmxnbLGz1 z&&uzo`LM|POkd;Hw|`nAQ!aoKdbNy+Qm z|G&bdSXur|;(uvK|Lk62;9wwNW6*}8Q#5w4ak4iwb|B#9hN4rKGq5l=bo|$22`dHy z)_*HhyuAM(VN(A(|9|YX`9Dy-|Aa~Xso{SYlVbfhsr5fCu0PeICt%@Vp=D%aC17V} zpk?Ry-|8r2V`*crWUFsz{I62lnwr?!n;H;k(#h*PIvU$s(+L|pn;RM{iV12%{Y!uP z_u+q@{LfIt)lp2zQQz@jum0zNsEzf%-xN^>HUifFXhxUpZnP&RHVVMiWgIkc;O!b@K1QS3H;mkycLN&Jdsj#z@V3Hmz}xowzw)5fMCpHFs8V2+KTOb$YX2kCg4s zz>WOU>6R8k%)F(gw(X+#i4?Fg#`GL0c%1-oMwF4pBsa|Rkko6I-YK)lOY2FaMFq{W z(64xu*o5URD7QdyKsdIU)C0|tG4Y$jjM%bxhmo8u_Vn*EF;ry4Fz|FYWt|;cLb3GE zOcDdg$5AxsEaAoXyR>xD`z8I^H7PJc7@VZ&NHAM+a>tCB4lN#QM915AQ#erS*rgOF zoXDVgnVaY^J@yhi2fKl0;<7g-N1>+r+C3dWNg7`nSx8jsN;fs0Id*YhX@vZ5Tndny z#dxszyNsoQ!NNEujatrON|t%r`36AE7Am0vTr(aX|2USo-4TFF{$`MBSUuv%z*-mc zlZ;`Jy&tO(IY#4tY=$kg#AHIFFLR=K$&UMp=3lrJd)He3&q=!D$yp_>#pV_b?xAR1 z#Zh7oTFeqB9J%@1G>fMLPNSK-?vq zh=vfzKjBV4!(r?G>sw>HIjix=?W(i7^V#dt>vC6b9vqTF5MfE41q6qNfEpqJ?8Fzv zDbNpqKwcRE0)_Bshu%LoGskB&l;cV$mI4Ea_7fk%m;@!FtFF{{md_7@oqv83l7Jct zp^KP?nh+KQNZ6OZwA&Y=fSDik0xkf+5d<&|f*nO7Yfje1ZEDjbMRL#nfL@CeckU|Z!Ufa%?5A`NKh@z3_VtP z_A{yhSU5i-K($4{9FH{s9(0NiHuZNlU;LY54gh_D-R}9%(63Youy0hDrdk2^cHdnc z`WDutl{cuH^D{l)v^+on&%qmbz64mL zBY#oIJUv-H4yaFQheZ<=c45rj3z(pMg#o_nVjv+wtE#sv(g)L)DBD2rjpOQg8W_0R zPYK|?BO)W1->q!|*QFo5TB#x5wW|WN0CqVgH3hd`f)AI4pK zJIDL}wty=-v%YV=mbq$l2KXo|xKRAWn>pUR-={Cnq3Y@w0Dh}~0%PR4Ffv}UFVsv* zF0bzwKVs?Sd^v6;z54)mrjM`b#(x9}AlQ;u`|Na!Qaf%7ONfXBT*DuBXG%&!$oWQ- z@bh0xC2EO?1OfJ`wSm2S{t3y3eF^`dE9b>{I=26gy}{c+1B`i@+%0qSxwZW!hPmR? z><4~v0o5Kz%*X|}@>#F}L;+vZ`h@t-cG*!I`IdX*tN*Az`@Y65ZROzjymR;l`{47g zVVW2{XA@kUgbe$z@r8VNMmy&xq-Q(+e%cZWs74b)v_5`tdDo+0Ng+qcgBMy~`Cgi$ z<9e_l{lYDWY8K%4zKRNY!3Dqw1@S-xt_C3@qJ_Ib?9yO_Sh!DS1r+qR1$mEmq6S6qSLf0OCF1seejAhds77M77C%^g`$*eU`RtzRc1DGI3|vE)mLaw@ z^2aF)(2%1-P2~nz3O*!bUy{zcg?O1DT;G@)fsAvdV$Aa7$NNF{*jeP+oHyp>=#ur= zKJBbTBVgv>FEHME9i)=6yP^SodqJT+JrZs;n8wByngSYeRrT)e^4N)g60#n+nL8SL zc}6Btl`ZA4H(Po2^S;PcpWeuQQm=C_3T;&6wuL{zu0TX@mqaY;@t!hR^To_BJ+Naz zmz$C-I*PocUX=DH%l=Eqr*oe0z1KvNaGqT8pQzMGVfoC6iwF}KHoNE&@L_hZ1lD+# zQ&Z2dyY0sbch)={4TYtE$vdN4Su4rpp@?M=s@x?u};8+WhC8!O?AAfS7 z&fz)Cf2&|*vOFk`Y{iv$k2Wz!jz$aVT+S$2ng{2erh|FI7QEB*exuzBpjNR1%hK+# zx!zU_pa*sd;94EJ2mEHcOUA9?RZD$-w(?0pvBU69DJ8F3*&Yu21peWVvW`iW%rWpJ`RRS${fVvea>4WVs<86i; z@1K;ayLhF?dOLFH0l0qWNsQ?A@KYGECeh7ciy6{vJg_b{LT*Li-xEX-Vg^Mya*@L0 z)yMOolXA2lHppq8fSH=;4J6TBmbjCnOPo4@f#p3D_-jym2A*^&-w%sAk7%nTiVOn1 z$puY(mhx;6P-RL14k4d?HasquM=)8v0oxUAAE-RCZ{O-M!10j`rX%U`R0-oq*h*P$ z7u7IiUk{QTW~(;Z>#X6*YLGmG)-588E}o0jXQXm?CQS$@xh^-;#;XSAgx_VAL9(4v zaWkzN=hzq9hAO3-4khY|cv6`D2+bvagOelI!NJCHby=q{HbSOymbrUx^k=unv8p`; zt3BvN74{*+=KX=X4F(-pMNwLwdgP4L#@i45Q|Jg6FH3+@H`y1h&3!_|T`>>CN{_kvok|R0Kp0f8T(1t3H}~$bsF~bWkR!8@arj`)7Fu-ot8M)Xd14=X zqth?!r}lcu2-}v!(cL=3$N4t@Ia_v&-z1y^+T+93M!G;9J9S)(DkAC_Je!{G+7O$; z0$&~9AR6Ukn0Ll6`PPEN?isTdlAF??zQ}jw9ayR1vIjdFhI7s)t`PAVu$hgT=2Mk; zem*e>s2;h=p*(DBdmqwK_Ty$#9k;X<0S*sg{aFjamo&GZpaI57XZu!Q92hKSeQ6G5 zw4%XpZ}%`@yvS1NRestwLk(Su=yH%M*)cM39(vgo#yX|u`HCV&e&iWnRv9ufH`rNj zB`8&^^wm(YRDly&Gx>~s%#-YGO85%u{d>p8Nnju+>DL${#H7R_9>V6FhRjYCsQlc4 zvenOH9m`0<{wi@^CCZ7XI`MF9PK}-Y%}v-ss{SD~Tl2+wBl`nYY>T(ma7Z)Gp057* z2fJtnV%JOd?Wz`_$(qoTO<1zNbdkrWQ2VJF>UYzris!{1B@6rrE_psDkf;RVLqYG# z8Db@r)$0@7ZTdh^NOT{!s6PgBe!O~o%ygzBNu9AEVk!x7zv`^C+)9>H!k&Q;wc#-w z4FFykAY-o8#8X2L^*|FX(I(9ocGOgy>~ZidtajpcT@3F0$pzdt_eb8RRd}VN>!V;6 z>SdDsP;|qi5ssTfJ#A?Gnaul!@|>E0rHiuYBu%b$EJl`Lw>9v@hwf=+l}NJvI3j&i zE)b$Wa0@3zjKhc{-Wp z4h$#yL1+;ESDmq|cGIHiyc}=S0M0>=lF|=*;n&wi4)mw4C|$LFsxbYlEM4lp^~)Qg zx;dsoL?()A6K*R3kIsFqQPdbQ+!S!Uv}h_?xBB)1?CU|4isZC2X2_deMlG!#asmku zHi5>Fv6{F`nak+u3T7-#b|4bi;0mkDC*TSrXQngPkbHgDI z(iJ#bB#Vs@pKvfm#4jX{h5Lb1gn?NKPDai_2GG|RB(N3Xxu5106^W*A(cQXSn!7`G zbc|Bw%IA<=*CPfPI|ob*_Fos3MU1KYc%7$o#5aoEvgbTneJ)ukH5=7@YAi+cal_Fp z6>>IxPnmGE_vkitFrpimDs>*M+pgD)FDa7{0W{iJNG{bpO8OgKUUzq$S_4jH$G28P zHa0?J)F@f@I1K?Za7Oj{c<$#|mO~?5{_$`0FhBSDSsQ*XwWO}mb7k{{19Nf4^u#XW zzxc*o;Qsh^p_dS!-8J<3%v^k(EfIgOjvjD!p{0XGDY>X7q3C4Pd?E7UIn&EkfAwPZjE;@yEDG#L~>g7P#JSYAY zpv(ZfL(f21{Cgob*??TTBBLWyPw92}`tBq|P{%KMHhAdLsox;;9P23syO<>^)lyw} zQOLb_c_Y=F<;65vR8HN)_D(Cs9XM}9=DZBbD)Q$kUqgmr5>Z(&bR^5fa20d%DwzMcV~F3QC=&6(Ci+(J}HS_^lZ0?e-5S z+7ML@G?Ym&uuQKtXK(du557Dy&D4hzSGX-6i!P}|< zt;#OVNM!@f>_>2b=pVLqx6?qkSb-5s!X3gI&#UWX1{wIAN(r6c{$cflp&aV0>I4p_ z!~WvGwjv#P1P7hCSTn@8c(c}R?y2dMB=%95s7c@3kiq8Z042qf4K5Kn^bRK;rCjDW z$Cf88=GA4h5|4mm%ML0qsOAnau!-0U(P*O_Mrau}1+dMAC4Uz1eXW|#pYCf8GQeJq z>2{8_t1OWSK2EAw%NtgUB_Kz;H2x8DrM@wQU1{$` zL?{PX=k4RlbFeRkXH>Dr>?wGNI+y~wiSP{|l(Cv`z2*}eKmDIyM9zAD`a80SY}52D zD>3R@B%0!f4$U|9orh9_%?I_-51iXXY_;C(tvl~1+q49}oni6ng}BO

NLZhY{9& z5cxBBDpd~o{$gg=XzJ=#7@B%Mh>2{Rh;>R1W~M6WG9gyw@>ZWZ56sf-5dblr>w=B$ zF)p))aTr$TloO;eI{%SuKxM>rTB2`n#BmA(X0q~Ylr>#q&|>cMBpC>&$vgWlc4>q7 z-s|@BV-pSbVfh9tTs~|%2?xu3RbNwEGkSB4G0Xnvt9Wtultn}_)QVz~L_@kQ%#{gn z&BSz}6#G!GI!tr_Qk9o&1Z|v}FCtCct++jXh8<=X;|}62Eqd-O5iys?t{#MY*I7n4 zio94-al;u^4MWC?Wbij}|5D&pZ1BXhTb{WN)8#02!(hKhl(VSR0~u#7>{a0B1gD@I z7lR=*Oqd55i(Rkx+3`+1d7raKE@v5;SUdew=}iLUT!%FAOP*sP|1Zs500)9GAtiUy zJO9)+{Q^;DE^Fi@s$S~=j#PVho2vvE*cjZ%ElAC8UYp}{<>x>#@(^Jw$?q#^Qiq)k zBRB08siQRxnSdhqZ|mF;6dBPzRER-z`=BxY_(G(pz_4b94#}atcq*N&27Jl!%;5BB zGCA(js14WCtw(zyAw_v3l(_b>J!Mo2=Q$EDT9r*lJ{0DxBoy;uJgbnfLZ6aZF4vrm zS6XzhNF7p3qmr~=X}mM?UT&RF8r+ZJ$F3{(b4`{yMf~ci98m`7c=tQWoa3PyY6#B8 zu#gn6S6;sTgDY}`L@t!VH8$cz9?|bClr+s_E@fv8AN&C6lC&Ohu zpvQw(!$rmH$8#g$0#oJrGB&9NV-ZK|s@m#Iu4Ii^PewQ6Lj8?*)fhXH&fH%1VLGbh zm^va+X4V z`#Ojp_qXCYp{?HdaWcAQ2Z(m}w$ko5>5oz8X$p1%H**KSad0H=81*0RZmY-DE5<}> zV4Cte$cZ*L0>XEoByHSX-D-5h%+Naq@ZYVMNY~)nMUXEg^{hdUQmD|rG?G6*S`W3R zRFSX|)ELv~=$PgO_ksYuX3@9O0~Lj9wO4+O?`_FA`IC@|F}G!nIK+D>?kS<-qPw2V zOR@c=P9rJ0mF4>dhu(S}Z3uQ_DxBuOwcYspLBi%wx^{L_9obG%)9>y1n4L>km4%>u z17RAHoL06B@7KFlJ-eq0fj+F3htN~)y^l+>Nov}(A7^l0?ayh|9(|j))S*CVI;VIih zjzsP$EWX&&sy;iDCE}n0a9fVg?Wyx~CplgYQgzOc7sA3yA)7QG7U>Cn&+QT~$&@`x zCopEuZ9NFKc|}}554Op(!5bq8!pjx<-WVa9Y(te_5`J~6!(2MlZA1l1g3p(7+Q3*W zz)^p;)M$vbdBC(Gt`4P9OlB8oCdA(^?$-b*!USrtQ^Bb&oN&G2S54_;;Rq+ z;3D)p$Q7m-@nt1?uu=D2gW?UWnI+)YeuIrlQEiVQ_8JF^hUBr{wbzI-`J>|>yg19M zqcWv!WIva?GDaGz~r_pKo=Cr$`?W(W!<81gg_PA=Jsh1`@Dg%XwiO!c|P zyu6Ttz8sieX&Qnvb3Q)kx8GPlTqCeNoxUg>0l&Wfy;wctjVDW1pt>p8UOr4tl~gVd zTf#*~wk7H*Ic|(v;be=?pjo=F?Mfkt9s2y%)4hekH-7^ zBW9hI{EgUTaZ7NK=i<{SHY6@b>MdEHuBhOuvr2emy+&ul?#8P+G*#@00ryH2O@!-8 zNL$^t+%FEV^il(Ot|cYzmHKD7Y75EKMX_R-U9CB47)^VfBS+Isg@2Uvm=ZeJd}C@q zuBRAVtZev{v*sv&9azONw);g94TxbUEWmU@^J^|G^TukaQcKE_QjtJn)_`F8<#P%d z)(@4acwjDebJN=V^2h{O!?Qg!|R_MXC0?K>Rw5fN^UXtMg zw<8?@s9ISuEQKD0FU&+IL6K~U=1zXJ8mYBc!0Rd0Tt~_b4X>nDnQV$1@uU`1$Xx5m zGg-=w^_>0e_Rx0k5b-;g5??s!3_3NssPoSOY6nx+pUpE%R11|P-$});k@^x}6@YR9 zLEE?kr-QG;sYYaxdH?Ht|e3jBLJ|`Q0hSCMll0)4Akqj?2c2K73Yr0GRv9hy)-r3%n1{ zM(v;Z_V%!H{!ZoJcvtmPH;b)-K{_5y@8vO~U8$ro!%2uDZqyWa5Zf?r1&tI+Zqwdc z=X{fakcfaRY8SFo=N0g0+3yWI+lxw+j49TFo(XhhZMGG!Hsn%dYkb0N=phuVQAxYR zP4~yb4oRoHY)(w!BQ-IPYp#x0e)IGj#A+sa7?((fy5e-&$qOrJA6IX?-{;6-?86GR z5Vyvb0ZZD>Z!`)4TUwtBuhMWCv2ln9QuUt6v7nqFkm;7%mflP=mk<3WPxb6;U8G*j zmMzE$N>;>eH^ovs|Cd-v=GZsiL zzqt6e<1|~S>JAR*4*DcbU7ExCt|ylYeUxrJN?)Q#^MaTc9r8}44Up+H{I)IlTI4DG ztu*@0??n0GMQair(C_bpoh{c9LQWX5Ha#m#D@*kTX?#bF!N`(+{JdS=&|bw%tKz}% z=DTfOnrEc4P$i!6{1ppmz`0DIXEe?%bj@^jsRd3d4u}~#@)VD(=S}2lqWOZ*&QG`3 z7r^Cwyx$@s!xtZXZ=c9M=ZKVe{badXK&H~Gw+95bJ*61k9d&v52!T+%%WzdAa}!+t9i;Js z9rs?3E6Ds+^vh(Ml^b30@V>IE47S?3YSJAGPaZbRE+qnA@B_Eq#v$(hNnGR;{u_!a z<-cf}{nIr5k7oN{wCOL}^cQXVi#Gj5oBpCrf6=DDXwzS`=`Y&!7j62BHvL7L{-RBP z(Wbv>(_ggdFWU4MZTgEg{Y9JpqD_C%roU*@U$p5j+VmG~`inOGMVtPjO@Gm*zi886 zwCOL}^cQXVi#Gj5oBpCr|Gz++*#C17&;PZ%je#DD?%$(-A|dEm|6}xjkAz@l`)@=- zxPmMH`Hw6s&|CpA!J_X&n(xDwfIE0BQXGI^3;`r=fm$q8C*)kXFUl!}3V)j;=qWBD z0)jyI$?b;6^yhbDmyK~{=I0bQ(>?DscYS;#$0|$&Xkre9M+zrYC?W_XU?Ct?+fWh# z0RRLFDiDx}I6H^T4hG1D4HslF<^(RR7-8WzaPA%)uwf0W3OyL~f(RktGdBW23ckQ09fS$Z`~5eN)GdQpKL`iN;h#hVdMeR}J;zCIlt9YH;{286Lq zg)B9I9nfKRzz99Fly-6$s235;9B}8L&s;L$K1g~y|NL)zjC>q=9X%HefM5JQg!Cj> z*n56~eH(x)X8?vYxV~N3Ft6z9$8^4b!Vz`>_yu!(3g3}Ge<0$#a$&&u$(1JEb!;(MEgaBaW_ zpb7RPcC$l$O9t?mu#hN&9-cu78O)G$KNUl{{1&J=z9Rl8Zlx7ZK%cw5P6Wn*bb1j1 zKHDX;3=8CY@HH>}>eZ7W`EKIqqX%HfNoZ-ofB^7-@O2Z)2=qavzqJeabpB#B>WerZZ4MAL<}DoL>EVlP?^O(w+h-^k z{bm}UH7p4rIJ3fMNkvFd zenyv=f`|+bpuIi7OS}fEr)mJeo8Y2CP=BkN6b=DRFpqu(0U*f`pa<|!_O85^z_$jw z36p}txubTWRxHdZ{v#h`pnnth{G$@o^0RxnTMQ5EK3G8fs7L`JmHs$c-|Cn}Qd-CV zydOkr9CsEnsZ+rKqbk+ZTb4606$=?Y@iIrHId~4nWSnTI_%rndZc3~Jzhe|mM|yFh zf2ZWJiV7d<2;P&+dmq9uC=UZyjC3wft(2D>t4@C9=dPw5dAgi#u#{t{b=L|-#~HuP zR`MEX3s9IG<*H&Tym%rGtD z7PQ+760~kPw1-Brr*L;>_Onuu?HQkks@Z%vQdXMe^+wkL%l0JWJDHRVRVBrSczzkI z-;Aa#D94WUpAL-_MAg{YQKoEbZABC1szQM8aL;TQk(UWegh9^5hI3Zu7)Lo5xAT!T|AVU~qL5 zS+tDcVcR}8XY==zN97{s({f#sq?l#6J z4QypDiO)0Q;Cjb%b$%q#f6NVC*jDl$a#Ea$>{s42y%-Huyg8LwcUrk> zYZvAtZpc?cxH*ld8dzc$f&NS3bwv!@%3=|G$(+la$o|^>c*gZE62-`g%)y0bWzwWv z;JSYO`R?~v8Gr@U)v7J!>>|}B0WBq;=Nv^nze-(o+=9_gZ7@Qtc>zLHyb$pymY{$~ zR+Zjz*uI?-jLK$E@cOPf+r3y?l7`8y$7fdzQ%4?x)97^;SROtvq~=L@_oITK(-I!{ z+GYc*&qx7Q-nuk`v71Zj0efC(Sr4Q4nYLe$-&*ce;z(Jg_S8{_k~`BEJa3h(b$)|&&-Mv zsWg4ltjbPA`UKg^4X7iR#n@v-W-hr!9tPLGE6Q`6Y&E?!)#Ep5;{}w#7O-Y-Z8!W= z!a|+hDQ?E68H5rNXtiZn7nZquK4Kay%NtFe>eI=ib1@51@~iiR3ASK?PZ1rO{I15Q}m7kPt4-+0FKJU|kLzpXf0 zg?O5x)rp+2mf_`Z3|^VA?br*`=Hsm^iW4pvsO}VGa|jCRM3hzkS-U%F#PstT5-1*b zpH>ZTB65*t9<&*|{&;-Arcld$Wd}nno+1?2IONB;0u72Q5jvx^YG@hb-Y>EBmHy%B zF|&#w$Y4-l;E%kacQBNDGNo61CeyyrYVAaU9%Abezo5mpQ8^{=LnC)%LiX%T_Sx;R zW_Slc_DQC3_aH~YU+0M?_rHigb2E49q|f7Nf+ztMH$I6yqljBit0^VZtI)a7)6|(m6|!uZpL1egftxJ(qWV{FEBX z0>ZT)on0n(kRuQphRrWYcW6mu_{o_ja;@3Gmx04}bXVj<>X|amR}WD8AaROoO*1y$ zCMsxH{!aTeCM#bXg&=MvYCAaK7008&<*X6RK#NOJ;7jFM(U>z>ybIX~1AEQkFw109 zQOB`15G)tz1<0bBD}l>bHWRKHjfsrA9FEjrU{+SBW;ScBVd+Vrs|slvUdf zDH(N>feb&%&!*z7Ub6OJR{--{yj4Jbohm0_3f)lNU8f5r@9#;htVWaiQaULHtinWy zPy{P*vitO|@GG~bcl&LYmCu&(Yd8`06QD3RP8+A<1yN6v8`LlPW%gsP+<7m)iEa*! zN337l+5%xVM>H#r(+G4R^X6RH-{WhqrU`NQlUDJ2A5k|= zpl)O>&dj#=Wk$PnzNd)XPUKAS<0r^_H(^bxKC#WmVc?~r*DDfGFO&kt*FDUIm$py@7f$DJOnzgd*Ay-`c+DZM_+WT=!Ax& zYG`B|9{2nFXE6gY^r+ZziwO=hEIx4t^KT}azQ0it7mI&5tq8_+dLnbFjH>Ayft z;f%B#J-s!sMLEU9AY=yqI3hMe#EKr~X87=b9tU&qllbD5y`@Ac$W+@=RJf%bdNtG& z0YpSbI+4i0uf8r$>ovhTztj>G*b!pIcZ0hnUaRQ+T}0W>W@l~A2#J}vn6Yq-eM zN3)1|`z8-A9Qf)6dCj_%gw{5$9)>R*-|7c_T#AdO4&`WVyJ)%%`HEmWv`cSA?7GX< z*DV)mlADgfLGS5FWE*9CQ?c?UCL}Z`vDCq{GatUydP$#DbwwC_;cOiTewuLGO4o)K zb7aTObe}}0(2dLlwdJz@2D8a=u7GXN>S18_#`KEx#dj(#gO^W$wLgtx(LyrPQj2fn zqY*C>nztBRA%P#3ADjKx6e^K{G8Hf((ofxD@p#^1RkngjMkO#PE9mlMMg~}BctB`H z2GP}V8ip3ZiwPZiMRL(#S^Iz-)0#$ewdVW)kJu9T!L+r+g`MoC-&~T&etD!nf*aN| z$0|(7quJpK7oapwkTMR%@icz`P&L_qbX2LWD~5z-p_bya%Q`P@PAW{TXpFBZQB~&X zSo^%#KiG!sJI!XNn4v3Kxoxe zvB6n6sop%owxB~NLfCpBItgWsv)on4NcYG%l>#%jP`g;#pR<=4|9sKf^1rP71$8l= zvj^cHwedmz9+(<-wB#0b;DP>DI&facd%Wt7XS7os$R$#E*(o^am2Jo1{wTtu01=y< zAVVvuu@u|!&~}XC7dZrq%}1kj90MCcC(Q4DTD4~9 zt<}X?rKX+PunhiM+Q{x2q@Ni;C~+~kgQIULr+A1^y_)jw2pR_?(YwQ*6L!R!E-$6a zfVS2svyQ?m@`AD3+Gt2%o%D_1-?>|{%E70Vla@ptZLyrL^3OY@VYok#PG_uW@>!0- zTBBb<9m>Y;Wblg@%Y0aP*z{}`@j^p(s?E}CE_@|sC;)!AD$0iL$deUGXS!pGp$nF> zEpR7k_(Rr0w4>|78(kEcv9To#g)kSM>vC&0Eg02;ld@GbSUkP6xCK37uc}9xGR8p1 zaPQ00d1aTCa=I7|mFzeRpD<-DdCu#_Drr}-6qI+%am4L7UNP$mc`WsmUd8HksvvhQ z`4ce;aSV)~ z0H#oR657I!;v21i_e>(}07U6>7R{aP!YK#Th(7UI=R}S!f@-ptop6fx(EaX>Yz-Jh3{QDNDKJ~egiCdzc0*1Ks@TceS5F&%zF5H?pBG%(m2zh<#h+` z;3FRtDEAa>-vu0Km;x?ZN+nF<;;ot@YG+x6yVocYqLOJC+^8pm_R?{EEAL9Yv{@W_ zIgxYe?p2F{@Yq#*eSrNN3mH!gUeJI!D1D28`CZ0Ww?hJp}I@$Dk~~Y5(4=c z=~jxbDD;D{yvD~D^H0r83ve&WH_neELM%jF9BJG;DL+oi#1th@EZPd3=Cfv%F#GUJ zmPV`jISEv827_WaYt2|=@P#6j9cy4C7Tfks1MS zPtk2bK}~4fhx@7Q@Vkp!kFsdIDCaVcg~p8|znP#kz@L*Y$8587gTLO33 zRl|s7ovPiLyT(O zB#W+>`*Qsf4O)sDo`1WU#=6Mbsy44^M2+3J2sArVQ^QB&Y zdsLI{2lxx=1!gV7!VL$F{`x4&CcX=jt~Kk;(wa@gSX@4Q*~|Um;*EZKm&9fDNRwqz zhK=!Wg`#Tpk<#=M)Vda#U`p$hM-qt06!)GLYRhiUEw6%KMY3EFDDND7*LjV!2DGHt zF68 zg(Jn==4!vidj4jLk!LyujN&hR4*7;`!@BI$ElB-QUM17mhQ{IH<+@#ZAo?dPs#bHC zy$UFNUv|j<=(%)%^j7q0bI)7Fft5n7?WtGFhNl=Vf+9KUh#%boNV}!On>mV!2UB19ZYw9RQX8;3Jy8ztXr`MqR$zH z38b2h#zfnc$WsW9r3}qaZ}z@F(OGcWdC3d+T*t4MuNKJVUL(wYkH-iY)-dg&X_Wc* z@r6+S^w}vw5yj654d4s(u~Yk9(U+6SWb#i3cgIg3={66<6{d)bTiGpxol&ZTG&*JS z&Se($XUL2lp^hVacFGTR&J?WU7-w~Bke&_L(2CzplNLg`BxgS*HoEh&4>=SjHz@2U z;}Zs+4K@qRZw(;WpKpskGv_OQss8NZ&6iNZd7+m-^dC=9$663KpN=YK)0(9dxN3`T z^*q*JNc#{mcr1$E6TO}`nLmWi+pb1wV=;as^e+8f$2<0fWDLPdd;OBse;#HWd(Bsj z04aEXi@wIQ8sQrktWz*~&YAuHOgp}z@$rVLf)u4^3+jwMBJDosWcL6WwWt{eFzR|M? zuVhlohp7Si@<`__PwGuFmcJHy=-} zNjv~tq792$;v%ElvVRZRHF8xU%m=048?pFljg4a-D7e83SeCDpc~d0b|l=MXy<|J5Sf2&jpQ>uU%0r+(2-+2;N2 zEG9MnT_IzCDjj+@`@_ACO8K$bvnGe!G9EsGH&-`P2AsgBrckFRZpthaPrj&}-tybg z*H~`>cWY^{%-yf%%Ys*LkUf>FWzCvMth4-#c?pHqJ16wp7Li?AQ)uqR^3PoxFJ?I1 ze4t-!ekfbB)Nv(_R=>vW`+Col(x>U19%ol;Pq63v2G&5l_=Z9-ZX}7ZDcQo{6Z6zv zyC*T;9?G|^q%|wuyfN=%bxB-2Tzld&6^+h(jhdZOTeEWanEUxpVw|1K9R~b0?Pvhk z=GZW$va`>!p7l17^=8f`;~|_67Dfe)V)jwcOlzRgeDYblJNzXqFuVy-ib89ido|6n zlGd*#3pZZyB>)w_{)>c&KV7l^A|Zl-LI~L@eofH%Ck3}N0OC&*ErEziu~1w= zz#Z`=Z`k3Q=lOg2tt+uHuG2Itb#*$+bn7wr{f$RR0F=09O?psMPLh20p17q63!@(eiZg1Bm>a{8^}py=feRr`{XKzfd)u|p%r5b0wo4v zC$>sh!!PKRlN-z`4`;4v zHDYZ9ejXJo!VdH=R)pZXchJDrotZ$_6mXbRpn6gOZ+u)ZWtAE5J_wlaoBrNfaTq-E zK%useJ&3o&VB1M53NF%y@*hA!!+_qIa+skaJ&?~=uy6BPrYLL3hwsl*c%gOm-y;1} zxWJ5pgqs_PSYtl)Ajmu0tl%Jc6ktg$#6*N(!YzP^I<{gn)j;w#Fni6&cjMAKJJ;a? zhQ3cASP(u1JpMPpH-o+02>jejxVzWy*-<`M00aFD~mR)}!oC_CG$kS2kjx*mex zwc>O+94Q2R5C|XV_tlA{0{YHo3E|J(yWN^Fb4+c;)@2kozwf#;!otkxa;kGe=;h_r zVPFD%MM!;JAfUf}j$W5xKPJDLAMs#bj~%~b6@ZPS!M><&!$Ei7zD)LR#jrYjj)LJ| zrjgpr{Bscbw|vgGfvCZPk-G@Kk179Yq9K3((?t9FeitsgqNVNr?C=5n!snYnJ>B~R z7eHv>%A&{NH0uk=`NFpFfBBW?gy1ahvi$vIv7;YIsKC#G5J(Gwhzb<`Wh}O*9IFG- z?jg>-aZAVWxd|%>i%tS%2OlZ)<$i;Z*R%6|hiC$SCGFa>1Htn?4%&|hhWOpy+5H63 zSMqs}Lq);9cC{=G6&?z#uTDLI%^w4zPY(7Fgb=(8xBIAh&mV&T6-gcl0GaXW_hd%B zqn3Xy4j|ChE$!=55Y%p18`#$U$Y1jM{Pny+jGzO-zOzq)MT>f-jK1crp5Jpu*}_dE z)0ApwMn%o8XeknUt%6yvBhEN6nL6j5_f`v@XK}btT7Kf3!uIYx>{6Ol->d1U8>8g3 z=r_-*f9Lt#CtP<8xE?8yhL$HrW*&wUXS|}5=W)T%psj504A&XF!R+09*2YKTaYvt2 zzBLQ;Yx(k|jBD|b6Fq1smBQ;@W8pg_=2yuwygisMrbLUn zQ>xx3E=v&*^LJTkCwQ6Pr&Wnn`d>wK3C~TkaT7lW=hVJMua52To^}VUnl0u|l9WMG z>|d5XFNL7qTeR$ppWXV&qyr~O8FAKg>k8*xgw}y%PKAYO-3XYB z+!a8*a&)A)lWtWR&e=OL^g22({;Uhb$F&jUug2O*ZLF2#&8mWa_g>V2PFnk{IzjrD z%yw3*wYk4O-7}nxS=@-*j@VoXB>b|}5 zmBDkru>yIUwkdfWL;-5k>x0zPP;J2PaZNUA!dUhm?$?yVx>^{$A^T*A8J= zkySi)#+qP|6eQw>ll}cA7T}gM+|K|KL zvsS)jjf|}Mj`vZ3c5K&2-B<8S??g7*n9C@5135Nd*uzja`v|xRDbXAy+sp#LOsZEk zmvR~Tm<8;O+Z#1n#Zem-e(uf1b0*_xw&S-1{go}F1?;7%E8-iq;-;nu#{H0ex$Fq> zcJAe8gx}LRsDfOm@UUgr{rWv=GvqMv%9%Bq83vyXZKpl7PG)NR2GgX}UmDggQiVE( zzJfV=S|a~07DJc`RG{o~fNs&9!LkeqZ#2s}PR=P`Ai>pX0)Dkqv4WrJtR=31qS` zkB@5tMKY(Y?j}jE3CRodPmWaQ-xJ?7El<_dsid~YTcUkAaY08F(+pR6;48(kOn>aJ z1$}nF7S3omZWO%zf*1CMZ?s^|& zRq7xNEGhvv?hXLFcLbU*zXp*I1QBD;wL=2fDvLH%)i-n*nBDWeEjz98HxdB#Fqvv$ z%)1@P?KWfcxom&0_WbrUWeKSv(+OIfHP~cX`k?A^fvXl=rBt0M_a!WhPU*PV7cSUr zuJzPki{MZY6n!!#Re#)M^7z%!|ATnEpxQy-9V3%pKleC?qLwpWq=3_gA1+bd@^>$8i(^;WrzA`? zZ5_ST=7G7V+T{rFyYnb~sLMfbg-T~kLEzbqB}%NgvamsC}-`VxDs zIcmid+czuu3D)LL>FFzVB`Z?f%PG4o)kX7JlzL=LG?vNzuQyV3wqsffz>oNFvTaPTatqc6?;EU7-{5p%G|bD zmo}=HAiG(OxFyp^ibow!&*m2dk8>Qx35-jbok({uz+I1#p%aElKRtvF~Nb)DG$aQYwa3AAVgj2dYm7mh# zkSF$XK1!V;+(0pW0j)t2x|^$^uFYfU)v``N*PQRBzVq`xUVhgH^37$_V@v!~R$X&? z_L*7b-6h_rOPG8!1a-G|hr+ta))UNnu*)_^dmKdQyEq1}p&_Vg%x^OA8|I5(^Cdkk zE4#UjE#~or%X#KVm?sBzKXY-?ANs)=~?nk6B-Ul(;WIG)%UTL7+nY?a@BLc|^2 ztA2C96b)6){1R>=lj+~o4}nqL=6Ty|xMX#?@$8zU$~!xBEcIsd-Q=mOtNb3S>Sb0# z3g$n!P7hl}lxvF-0GgXMy#RM-kbK^H(m`^kDI#=E)#1_ zO_WzAlo#Lt++QrRu+_!Qjdl%y+whYz)nIlNFyNvY$CHwP&xwsB?)D|Ts5L)6OIS`i zEO@(+g?`O#DaB&Gf2|20%woA|$Kd(?lGjI4S__*jVwIt> zv`Kb!q$XfYxWMINEbH8u2+vH5w>OZOE1F{aH(Ay_%E)Y#tL6SE({dlaNEuf_a#rAV z^~nn^teNeI)hsWREJKA=go58(!({UHFCpCwX^{Ks%*@MHR2RQ|op!z?U}y;=0VJ>^ z4+x{_c$wK|Y#P+^BkniCS=iFV)~eo|Zp^P`G>9!!>9F_dlQH^+y1Ui1;$k7iULxn7 zy)CJGu2n|E?Ytb;E40VImjjSWaUW<$x@W9KHPYE>Jup-i*jdvbAUSbg4yR5JG&YN_ zW3LVUw>(3VxVN- ziq?z9Tf%d2e&moVM6=r4fb7%3H4mnr!cA*?{(7XQrIE5KN(D}I-8o(ve3^Wc z1Z<+{{=MKvIf*OtxUov(${`t48c~C^RpXE0;b*2YKIKm{ZFOf@BI#&K=t-sM<>33K zM}rX#=wqic&)pcJ&1ya23iUt_qR}~6L0zS6 z1Bd5m5(F>~J<)3(tkNwZGP6GkOpg&-k3XS6LGsv;DT$MD10I_FH(_AXwe2LpCUUU(ZxfSQcynBYZBk4I+1nq2r?A z46*Gfi#~ZS=SX7E!E+ix{8snsT-Fo3M-S|#)TTWne+=^VN-~uh|?V`S= z4_Ae~?t#Cf0SPKyDU+8iCk^HojMax{v9e8Bd)vc_^Ij6%T8VyB=cY)z^s&C?!Ne+c z!wS;&dvr$UNel=&>_lZL$+&t;5ri$2_LT93G|7YK+L9?XLWS~6sQEd0VL3eCV~;<| z`HfXV1KDeVqPd{qAh>yO!;}2z?=O$_XzO_MM!Dgp;P8b9G*x15Vavw^6+J##_cuJ| z3yVB6V{b$JVM4{MrO6@g4qgLOl75A&lqH6`mbTUc5x0Z0HgR*AiJS#YT*WLMvG2Rb zIG_)YhsZPqPPzJl`dn2h-Bzkg&+IH|b79=9c)zo#Q@ydiYgZ7{xe`}F9+Ge1Q>;?{ zIW;aGR?qjvH;~3lZt-rmjG$>eN&^Vr*Y;SGJL`yFSnRqeW`$o%V)_l!@MCw2#*1gt zbghQFU=^!R44Ky?n%{2)kJiPEjjJrsDG_b*p(J z@xQPqb=E$o_9MJUfMYZ=x-JM+vcjRtmhvV7jmf%%j@$sjt;`LQqe2j=^7l18N0pQ% zv(W3w)?Xtwh6eXi&Pynh8xzy$;fC7LdAev%$Y`C49sBL7cV-UnfAJ+*u;SiGzg=Jb zt+x)g9O$^$=c8Gm-OT!vO@8CBopw`~`QnwgS4y;iuY{&)lx`9MDwNp%N#EqV0>Sr| zLd!FtPuHHwLO^_OC1qwO#bdW)2v;Y9khj4p_E^|BRIYtC1N&Kd?- zg4=EIIu)Jq2h#y6SEe^$=t&ln7W0V{l{mFl<=Pt06A-tes0K8hAr;-jOC3RtWRwK> z+^{)wfjFuip-J@TARDO0?g239`M3#jMEAFz3lKk;d;HaDg49^|Z|C$X9w~hTbB%EV zMzrKq6w=Etvd#?3N8?2Pkp|VOCU~vk*|EsMkdP? z9UU0^H5jUR7h=TGj4p;w}O(Av*v!>#?!*$v+7y&cNNx)O&y;t?_L(owIxw=%~uw;pBK6$$cU|` zgPf|YPA};_Mi5LT86tvQR==z=xb2T8R>So#h>6Lh2lb6G;vMh~1<~_H_m5p(ihS1))A2knsy)iBzo8nE^xhYe4Op;3e{uJwshgtZ}H9iOa!}jZAG26hbOq6hm?uy&EY$a@ggo1#W*PC zXr)F&#zOow)yTZj#FIwN@Omz)vhM2=`;5W)frN2F!Ab>#-q&-}>Gi zWrlvB(8T^*uzYA@1&S##J#fhLuZ*`b2CEfnXEL z(s{X+GF$jgAz`IsI#3T3WPFLp?O^Y+;6Jm~cn}`-L7&6$_hGfN(ORC`0VgHV{dCCp z0^s60PIFc~-!l6anF$g;R%;$O=o1=SvgC1 zR|pp%zenCk{)$yH}HHZc_(fM=d-Ab3rsjGd2&M~X{3TrkO%W@#|-9=dr3yc z=bN=dO#o(}gy`1JVro=umq76ufd!nRGNVdtrp+5RxOJUsFlO~AjmVMZ*jP;|jmtq# zRZmz!Z^yq2E2gCZMHPla(z1$L-syW<2_~EC;42~{)E*F)81r*VbPKedcd2@Rp3Y5F zP@18Sb+kjAjf5L9aJ*c6Z+2sfEsW4~k@q$ua+uqbbS!Ajwy{wGsY4TeCVfMWcSqZS zbtNUmLuK4@BG9GIE?`N>Jkri!s6E2tO&1zr12?N27yGTRb$JHAJMm{;8i>bt)Bc?D z8Oz1kqHl(?Aq%~)AJiyk$!9%JY>O#(a<1ovC>FM|A*}l>95bZa@x_K-AAyBpH<@-1 zpR*W?`iF~v2JLLMyM67rgplO;yI<@_Z?4aTA$KZvXXf>23Ey&oPNq3Jf{oWO(RNw#AQu>3b8<9I-G0poq)v+b*L(0 zr_qb;bgBt(o7PSRHd0qsXY0O2g9vEY{bci{_6BCmXw&RFS9?zz0;$oIl`#4;##utp#d`9E4=Px zFVv>!W&eV<>1m)Z^D|6VYe#7Znq^{w=od)Ito$&3bq-~nO5JQ+G4DCF3ufWgC3X{p z0V6_d|Iu8uoHE^5mJ>v70nY;*mlnN7h@+U^XMW}H{_1;sxEu916ctXqP#+!^_nK<#WF1(MsCR*eZcactnh_L2(=%Mdtx0YbU{g##|wtQckqD#(tMUd0EmrJ2B zgwIoP@o7hISpfcZyuOQyC*~%uD%nfhNknEko|ERr`V?}!ud9!>p-WG~82A3FAoK{= z_&TUY9J>M2s@InNy9;j&MR%R(bI$O@7ni<;w`2Au!NUxUyQkB>P~}{13ow zX{GgleHqC1pX=iPFKl)}VPP{%b7y*Edpi?L7fXA)|0&DP!SYY=Tu8{?gFyS=RC`8F z0!Ajb|H85V@2ous>%Tqu|DLrMMh-dDq4S;55e7~5sTQCEFarYf`>&(>x6l7q)BgX( z=otSoGbTf07w7-+%-H_(%>G{gf28a=2sqgP`EA7h^7S15Qtg?T2{``A+Vk;2(JMIF z8!MZ-5NOjYh=|dvn0mPA{)49f_czQ0987;tZ2lkldUaX*MFxbf6LlDN4v*W{4e~{z z(!nYtdsTVuKR{>^daoZm+z|(tVqZbZMQqdS2Pf?I!^YwZ?DH;+rv+-aizFoRiFGJL zjxItU1GnD0I^ZQ>x>FcxTv$lRobM`Cka6fLj^I;lqO6d)V7ZOb5VckbZ*U+#h4^YgUrmSIEbM+5x^JY;pKVKi;0@mBGLXEYD0#s|0 z>!@)LTer`~L~)R0v)9y9Y>8vnq1Adl-p*YgEIzBWQdQ9b&TTZzh_*cR+;wPF{mcE> z7FJt{opYDcad$fXTUC63?3>N+3;QTQ;EtjdXS94=3W6LWAgkoh$DV)~`-jvxbWikz;>oRu$WsofD3bHNuw2 z*CpHyJEj|rKtOLl9cgxW2gc0@i7?f5>THx*;^8j*uGT&-Ws*6(VWE?m3(`nBNn>%# zCM+&CjQRY+m;6krf^-k#Wq8e2)*w&ACOh+IKZrh#hXuA;bGu+CFJ z09rxC!nP`$Go%X=hbEmV9&!_9mI)kxPfDQEG-XS}HTE^FTJW3Advi_~LY4uaBU$dR zD}KR$%#x-gZAo2?*ol}+@xHQODVbq^0k4~0)+DK~XJ=cm6WUs{EAht5MdKAGtl5x~ ztFt4*6&vs%K?^?2olEdrzVcXN28}3!Wu8uu8dz@h-W|?;P`6iWZ3axcmzzs``BEs8 zm>*c$sdBRNI^k$jju6EP4uY^ENhWpmc5D}eHGHW#kMM}w$|%9MRkg*XrC*(;OrPl$ z@em;?BJ9#q2~)Y3lBp{8tK=z_*A}I7u^)FqB>$DXn>{dytaUbq%d>Etm{YVeCc5ZE zG$$Ifl_o}qKT~N^`)n0c7o3Ev!`OF+FH;H7zWo&S7ZyKp^V{L$ClckcS$#K3uMdt7 z+2Flsj!*y+mMtsmj3ct|6s&%LMyR4}{_DcU`H$t}UkleiLmrF-j4TX)qaFXeVT) z#K8lgpa4Qe+};9sczXQ$addG*1{@9IA!Gw!r3KUEFD1Ast0JUl}EJ^;1U0GGD5Ghf_Y z)v?g8v52qQU*QD3Gec{j1|JYWH~@8^{NIM}ZNWT!0Iiwe9KARG*x$e*%6AmOuo*?XLYzRf5*IfPek; z-+Fld?B0H6qE-6Wz+mt4QR|me;uc!oT4)oyoYEgxR^U{H* zOv8QDUx9E;4f6=LWg&F1{^;R&oI$}`5GG`(EpFgGd@%;z^}$*7U&BM6Ucb8&bo9?! z!bg5}%>8aC#F<=QJAT=}gMt7Ou(Kn;pB$OvmjVLd-#rLj59s<)!0w#_bq?hZ1;E<_ z1+dB9V(^zw(#PoidNuh{`;G^F1K5ncbog1Avp@1zX?S*U_SPBT_wlef!hf5Y4({7F zu%2wQG`F5(2s^Jmo{(2k(aXvlpeIXXgWYa$e4lD-^3XZp^PEsizjGS8(mA*F2mju0 z$GJ#9ZD%#au&~0bHVC*V;Do|1Yy=ZpHVph9pvXq!3QLa`!M&abe z%1Xrg!rZH4-#%P>12KFa1+H=e;x_B`qtVaHy`#Fxtf1T}V$#)nVS^HbGIp{$WbW@{ zG~++JLNTq!?Ah-h%F(<5s}owc!HIGIo%O1-(Rr4PaD}0vYo2_vt3&NTd_qeQ6;d8% zL0nc|7_-_RtruKaKSmS^p*M5_QM_%}l&ojPw_@Mo>ha>D=h1l#$Pi&{(u1zEbM5}H z=33_eC+vY}U-!V&f2-HaJ3ugAq-9W(>w8W2sGa1+`Y8umavcwxE6_#Z=~~N z*Dt}Q8WuP@E56|$7A~zyyHnzf}VHfb~~3O1Mm|O3$!l;s)~Q@ z`}_54Ye0XF{4^7B5G%WG^_S|k6VC4x3)WUQrpBZXkEX07>E^*OHC9JigJ*MkW5S*U zp_5}7QUAs>Y5XwiJ)dgfFQ=|zk3b*V_UJE+>Ab7;IKH#lTe>~x%&Vq{Sp1?XNw=)0 znwW{M{KAhNpA}T73E!o1+^ntR>iBX3)ZoWGBj0l5fyg}p_4UN*GCH^!ftR7DcZH2G zZTc7`Qcbdye$FPlWZXK5AI=8NwSKus`M!k0n(6Z(&kAi8I!(k{=G)Y52GdUs0kc|* zvzmn;PkBn&q5|*qk=>5SSx#oYM!6STo9sDwEjz8j9aVS)RFCXP7+HhjOig$>Ze7p5 zcdqwswst?w8R_$f&xP{GF}&Mxza4@|mVrbxK0KqlJzr4)K}hN0dMiTiy8#!alz|NU z;zL$jov+_e?hEIp`^vGg(V5g;KwZR|8a- zWXa9vrlJhX?}_46(@lyHKegy#j0(JMvF%=ww!AV4z;F$9Z6ZTjYq;o+O4#Dba&_o* zF-jy*0ipZOzy9*@OnRi~=Q`?5QTGf%Or0o!Z42@cw0gBriG(8ljn0j>_EuVskyK|a zp&cdw>VCu1zxDJ8IHxa4z5%YXOp{U9i4Bs) z#`eFpzV)6@FVxndU_JKbDlh9KJ$p066&`C4`nnU5eUqZy2rsc=m|l=~2;uQuf2>Ci zI83=(&lQ^yzuO1mPMOz ztLS6S`>7UEkW7q6^lEU{Rhvl{X||dd>t=_$U^Z+S$@0(mU9Q69;pN0s~H%gM$&zw8Y^73IouJW>(0d6 zFddjkCzV>>iE{aB56nBe_G}{gvM`&hQ)Evrlc&eXS>edVi>G1PeJbAayOt`kV%DpZ zJL*Jl1zbGw+amuGsy|qU!>QJn1xIsPWTRIiBXHZsuTdDIys=1li@tn$%=2izl zMRP}zdfvI^X?8BkhC7-Y6|o9zJ#C<5J0P{W%?>MA?*Fa*|0Kdsdw!2!Y;g|ogwLk!J*a41L<*h2ol29OQ!e3AOI9+;n z&u%BVfGH*#AA=sxMypEmINmPc>u8qQ@Sac3Y)lxm^n>?7{@KB_^IrtcXC z@L37q-&10D6u-HAp%I{BHVfj8@`-JQ=Dp_oQ^?*{^$zFJrevzG&{UJ^3~r>8;1AKr z214HzK}@xPr+I{(s~P%$aU$qm9+L9x1fL~Wo+R-K`40y4wCjbxDCX#U zwa^#t{z8Z*K|V>5)ENXbjQUVrgh;>T*MtXohw%ehW~A7?j3KEH7FWHibb^RQzEY&X z8HL81UL{(doW^(Q&Qdo&V(2KIdZhXdr-S7 znme8}PiZp*34WWK`g=5oCkFwwmlsqLiyZ`*iTygzFj;hsF!-&rWkOx5&Vecu9&sV; zVvuB{!_XEIF6o|vernJy9&3+jZ)PR^sOetHtOcxB8VYWyFX`}E-W0qdwYL3C`OE@{ zoiDN;x-AXO!&4antBTSfgC25J6^7Q1JRX5>s#(KELb0^#)vptIQi?bPwu%^w8$^qa z?`4Rjjni^HkjLX zXgw?9F$cv@9K%ILUMD88BV?oLUlx8F*Ct3TBHtOPu-4B_@0O3?B6CYOA#5+Exa{EJ z5l62r)H4|cLtcD`-MTkqP{dTCZuTDpG-?$HVZ_AdnAJUr<~{54J3}J*$t*PbrANaSc4i^J3{=!BP)NSj6B4h_Ba=GI1!^pZF+LS4L5A|4y5@xI;}e=e2&YRI^xt3 zX4sM0hH|#GDASV@H=-IqPebp09AnlFA}Uu+DBBG+gf>rcJ(4wdgqaowqkkUKdGgkf zUcjYu=U22;F%-YXinZ*yOAm9C>4aP){fF%`D}bkMY3`S3grSLC(p;<;u~mQVQ_Zb4 zDVMy+ZbB{Ce?(2UN5Dnt^Z`z(HptgO8`GIZ6S3C#8^TQxpN}0~R7az>S~v_P4U?|4XzSuj(YA)g!BbxqabhngCxD_&yM$Cg=+S06H!+jCm7{56iXPX*&q2}%MQ@gsFpk{$Jgj;apviS+^eVmzTscC!fQ0lJTfO~m=NAV7w_iHIld9K0;pNx4O zqTb_Ni;4+t^j`O2Lte8ChZryMmSa@i{gqyiAZd5PD*gh3{H0`}j5i=LFFrzZYwp3O zWc7x+sOjZZLIWAhM!Jv~b7Iv&r^WY1`aD1WWEimtHA-?`bX8Q$?q6%<0T=OejU2o& zlMfBWvM~56Ci3Vr-ve?iXYa4$r_NH8`)U#71}TFn$6Jf0(1Swfig<#mWS7v*UFCWr z#uxQ%H1b|Cm?`ob7@f{esqWc_Lb9)`gHPm_TBhQvOk5i0`TAH%5Ui3k;?-Ku!K|a5 z0#3nt5v{FU6)kL#-_}EQ-Do=FI7%6s0(H5F=9^=yfDg*ouTxoNPCZ&xg*(_5VZm3c zm%kgH-g?vfy&Rf`zJ=ZH`Djbp0WdL^q2zqpPQg|sK~H8eg&mZYtht5Uga(F$SUbvB zw4P_f--NiQ9938?7Y>xJDsrkg8d8(okSf1Tm7IUyf^zQQJ_sR1!e%V!7Qn=PZZ3Jt=$#h8a^O#ZyFozP5kEp{dJC*=QCQAJ zZi+f(iQe_AlC>j8cLhWx6ba^bXyn&E>Az&6&|)m|S!y-RPuL+=qu;f5Ur{@$F=8>| z?Zwz?K`ChY=zvgnNeq`dO%%%qLYw{hmHIqxwQU z`Q9}*XuRmu$0uV&)K9J!*<5qs$Q!?)xU&&Uu_M>-DSLx0z@C)U_hut(+tn*10VU|3 z7EPP=rH(wYF%-e1ERB}QfN7eSa!A`CzAhC4Q34fufv~5*j_dWg?5o5?iPMuz46F3g znStD~TqVxcWe{$04dAW;>p~JI16xQJaUkeul45dn#;`A820!vpQrB>8G#_ND4O*)z zf8*09)0-`Cjj{G7H7krv{q6g7s218{1BcpV*-w4|agC|rn!$JL=pL)%vn_0fs9-~K zeEv)uUSy@Rx&Y|^@XqS;r6H^ymD%>!-&K0JJ1Qm#VGV+F`M1XP3A zBuq=M=V{v&C0eC((%8G{x3VC~`Ns_1&TQqai>R@3F-I5h%o-aAR+i$9tMmPm{d^st zOy7CC^^^XqUYt6{b(ItgHzGB;UV@X{ZHTUd@Ul4yDf)r1jkwSa&P7w(^Zd*;k7kf} zb}NKtsLL|9Nha9IAHJ5xLm|mR&s8z=1t!*`EjjL{V|^-A9uOLo`COglX+ZwX-M%(` zd84hGVYq5sT8GAz+=^RsYqLb;u27C4F>v;tWZ=GF{E-j97Mx(yZT5 zJ|fh&=Udi7YYI-zya`mt4ar_@Mj`-r6wuci>!*MJI^|x+CueaQ*vU)b znXen(2_lgYglur*m@@2)&``x1BnADBeYGO?OP1_658kY6^Js`F5@kO`yNjxnKxh=U zp4*qCK8uj-a$KizsgAesgRer8hB96T?k%XwZ>i+`3YH*ov!rZOC| zUWA{}tI1%GOXqS*GTY<3s)BN>n|H2obHEOEQ^?5Rpd#&CuBuSm4=+V zc^wn8`0e=6f3w)`?XTNr?+4NCh@!^ynQW1%pTHQ}`OM(tJ|M^P(x+h8Ljl?oYyHBl zyJ128#e4*cOSswWNt_||Sh7(n4hPM#ICm!v-tXI2>$O zad9G-^zAJ2v9jf1s;)lFV%lw3PwF6P(+$mFsO9zCyk1$@3Y?i1*mV@D<(%|7Afxvq zyz72@9@t%ZpY+o)EGFC;P)CH>a>`eax5Zc1ZA+tl&t3TP7BQ9qm|r^gh&)Agf($bN z+0N7ypFMvL6Pd)NfrvxHur!d2oa68t{?LjC$4sH)j6Tdo!6VbxO28V;T$_8`u7(vl z)J%^Mnxkbu)8;5<{P(_dDKmNlf}m8sY{g>Jda@h}d6-}He6!?fB#y-NIDWis8NUJV z9HWi?ei;(Av30#ZYnm9eHr%VKSfJ^>z(zbmH$XB?${dUWV zdCy3wPblsEu8!bq`mxj)k5lrb+j1K7e&`L2uAK}`$t$0%;=3$_Isr;iY^6` zjW*ZOqRt}WkUI*yZ)Nb%##0cH;dIUj?GMgj?uK|Pw3 z19lZk5SiQU6FungC`ze$>n{e9s(YM%-+Bo^RTa)#A7jF;aG=Y#`%iZC66qreicEo4 zw%i)!R1iO~SH?ANbRh3le>o_Xsn;7Zj$L{uIrJFoBg$l1?Q%D+Zgu#ICYeijTM9-H zo+f0KV5&XnpfUodF6yU>@#p^7oCphwxy1UO!WkO%v&nY64H|@)t5d-j!e#h5DO64s zUE{)+VyPTg7V?V6J(H)grR#0h!c^lXYf(Q7LL!Oe@lPx_)|ZarM8}k!O`4d(V?DF% zZpUSDo~~hgx$zvCXfcPiWs_=?Ouc6ZFNZG)upC%!;oSHV8lI$!afT7Q`nKG{?!FfF zk!(|UZo57hG|Qv*dYg7kI5P*cs3#0$>waeN79=eGDKtx*eDND|%m~(vg|qWk z?_SF44)`-v_$h>Cz@#R76kX#Hof0AfMj{$a-Qc$HhjXB83^o?T>ns&I#+m`ab&_{% z8MC{ND`9R4V^U7>nSNn#V$x&pR@Vg^cMx>QW8*vR^_AqP2wb2@Y!Ar2_m#lPeS=Ab zo&IlG@#DDSXL{vUdR5MviBvl3@JgAwYx@FJVmnafoeiwi$@prU?(%C7&R3(UD-fM! z3tEhJT?R0Wv<7Iu%sM-Kx0l%b{Qb(Oz|2_$2jZo>*8(wds=C zQOV;W8TM^aE1=tb3RXKFg*r3x&wxH_7VPT>%lbt-Io&5#x5>$B;y5ML@|E};syYH7h93kYk{T#X~OF^@{#+8(1qH2G3e3S1%n0}CtE#V5(ej1z7MsH zOMEdl=|rSHNKqeH87Ef|di>ZovsJ(9Iy-as zsF?u-iF{Ox*JGy*!Q3W|7rrDW(1gIlm|i?^;BvTWtQ_*_C!FSMp`hFeURCnUPtmpz zJ*#OQYIJsvBurHR88ju&(=5zt-N0Zu7%M)@3Y&yxUHmy_fiJApbJ9gG)KeE zaxxYc?WFCD-WTXCm?PWG3*KO=9gQVz8T%c&yDQdMfZ%uY9QH8=z!cPb{jHNKOd(#; zH(1vW@FVyd_$Zi#eYw2ztRt#s5XT))I>N1X^~8vKJ;U8Gd&&&2$TlJ_&G9}lha{fJ zt`vs90#^wBwgM`gep$&bN2l=&F2iI84y3i7j>hmjCC2x>MR!|&@H_~dTn(tjYTKaU zgIRwZA8pMemyp&++eEAZrAWNSKb9$H7a!$hrXmTa+u)POSIhnG)*YmVhs}DR1>rZO z!EDqjk(Vg6IADc*MI{4{Dp*!mKj4F#Ym`m?zBB0}pDX}?@ow6su>E;k#`8!PaNvXX zz0kc|wF__|uPdii-K`c{dUVljV?az%l=hNdI$!NRSnasWl#{WN&TMM&gCOD2ZfSn! z1kYf#0k@-u9~9xIapw24hJbVvMyGSPC>l&4R4v&mb69nl4z$rTAx+71FU5IX%JGl=E>~T#>xY2UCIeq8 zadCQAT8t?2v!dmyw0}8|aJZJORYwWvh;j9(}7yyc!&NIu?5rp^BhUcAZ8}qABwk zJA!muR4@ZYidoyz-vKT$OXa%@$Z)CD`@I^{YEW?ITc*YU#%`G*owZ+u75@QEfeGs11V7JMl^7Z=YtjJ(YD*rjRtQ?&07C3&daFvp4FELBw%nXwv6$fzgQ#MQ$% z_2#&V#oIaN@HMW>QG}ssMB!o>jp*W+p{)6@R@gd49%nc(xsIGqBdary4thC^2NT1C zLSjhXNi~%}^<`3Y{@yZ?A~m_^o|22DMobA1dzYbk?l@m1Yo};bqaEB^$Bs|Ln;`;U z>3psuaS>|F%8#tbn-8L!GquADH}oaLx5a+P>U3hPk9$yiRs4#(SGoB|cs)E1GE)jD z*sg++oVD|hii#-VF=>-(q{keNuV|S-#B|PfkpoXS$}t&}xWTlG{)w?(MT`QL57ket zscenfm!z_;2If)VWvM(*!DO0aT9lY> zj6*V0ZigNakgXg@<0MxRTwv!EQ)6l_H3bM?Dr8DXh{&8QBU7(-L*+qO18^rk?Zz^V zyxaSn^wYbls!A=x2IG^P*JJ{O1ti?;H{%6UyhGQAkw-Api9Iiy8scnSP?n$^wJ>4W ziO>Y2pc(b~H}U>NR4Du(G4KVnL({#8MnterK*2zeQM&6qy;1MCn4vivtOo`2--{+k%je>AuJ!$RO-{O@8sY@95A#f1M; z;x78%ErfYNuS7WkFIj>1N4hR{NauVnzVe zyJ+mmw)gc<&66*+_0^^OaeDfT=Sg~Y<xqBO0v?@YHDgIR)J|F@0}D; z5Wrsh8LI)1DX`9ufL*~p^I;eOyaj#~kV%gK)7tvy{5fS58KUS{p`m)Q5F8*-B8Edf zh_mzb0Bl?X%3|<(XOSa6p(|g|1u$+;8~_LuXaBv%CFTKy!7X%js8dwVk z9Izq3c(D9FJ_Uf`32ZE!*S|F`)e?dP0n9i-fE@@l!ajc*f2b#ZsD6I7VAMg(+z z{=-60ApYMh1nz%X2$BD=5S9dl6sCK`6m*oJ0G{uGJ`#;k19T;UfCN`HT|?i$QaA); zP$K#bgaI^S`T#J-e?O`llac@!tx_c2=wJ1}OZ>#+?_V8-;P&kZ^`iZFe|c}`DezPL za&g21jgNKlMq6`Ltm)sUzBkNraIGR|Tk~QNLmK!vcKlO;rx>$5$*U@UqBUG6E(V>f zxbPrI6O>Cw_Ices3avf1NH@4^0b^H+7l{(>!|S;RWct6@yQdh-!gj&qW!tuG+paF# z>auOyw!7@=vTfV8?VA41vUal8#q&PDzpEHyyNncn#Ae=C zmf?ih>CZ^p@l;bz-&cV)dBgWp)ln6Ak99E@{2f3F?!vtZ<6e?dl!uFbzQ&^i-To-e z?P95-+xp2nwt2?fjy`V)c^UtF1G8E%~A; z@7UYWgm*0?%{lQ23i@0^*$*}nl7o`ipc4ipWd8UHFHb@Y*mQ(3ZFO?z1{N5f5VkA| zH0wESI^uOvQhyjv6m|&MHjO0I*BJEHmhNo9yO`5t2&(kn?_54an1|oNlP$-oR5^FfUtm z%psVUD?@X_F75khDtGx3vq9+GJ#}z7|Aa8kPwJ~}+8|Od`Hy<rsba<=E)yKmP_|#v7eh>nCm`kliO1_@aEZKzYjuMiKG!1X(bbIEv`dOj3%u^ zdpvYXtOszCPPSB&efT$cJpRk{@-|NPv1NpoFS8hYN0Jfyy@Ny{H@QApP$m*J^m zWm05c>Pp(ROR(kB+0=37Tub^>hT>FD1K>M-}?uTmI#;`oj=oxUP zuqZ??8Rq@NGdu@Y;54FCB|>j9Mz#F!Cqgn-Ef*C$g-qp|-NX1cl@Ma)@GP$7{oF~u z_pZs8!JxNLVACZZ*n6Nrwk|J5I526inM#2jlZUL4 zm)+%Bgyac*#ox3lRBsl`huD8M`&EDW#8o&)&55e#Vd2xhJE3^VsGM2K9LLE|TmHcC ztf0W*Y*f(QbWE*yvy>K_iZ)LK2EzX{t_oKC;4yMmQzVPfFah5UFbJvR8MAT43IQR< zFw_z~?i;~tE@xbKWejba&@dC>?#ae?phMh!=1u3dA-O0#Ep3gLBc}P`THt^)`Qdjl z-{P#JHtWA4o{KJ-*d%(njlQz};066SZF6V6^D6FJYo=D?wa zZgq{*T1!o1$`K_8KINtG?NLZyJt72dN4{wKFKxp(Dsx|octp#md@~JFmr?zoM}H?sZJ1;WvusGjB5QBKlgU+^TMI{wi3|b(ACiHOra+%Eh2k}y^jFeu zFAwq~=ZPmC$CholJ_f27fu-uV=WD;q>sGzQLj$l|+pfe+VhFPJDXmjq%fg5`0aZI% z$-bhPgiPGU!{IiFKrq*+R#v3shc)tg!x@8=bXR#D)|34X)kTYcLaR^R z<1nNN1js2I*f|;0O?e4!W*^}h!dqC?W`ajKR~V7u4hY?Rh> zJ?Y}*HK#-vc@uJ~5jdG-8d&2uvg>GQWO&A+tP1?9c%c?YJQO1$hz8w7h2A#bGVWi{ zARTHnEDD;_IMoS6<>jOG4RRg`^mlXx9ydKd2G4+Qc2y3{ywf(yV=(XG?T2$i{ zc`114?uyg3}kB37k)h|ftn=zW1525a~OMit*{dpsbMy4_t)uq7w^DdOh z5ubcmq&Tu_i2z4ZnMYr^W3YPK4+zWhtL7g8&vP>aU|CkVb@%_WuXYLNLv_=1M$D7V3L2DbrN3GDcs;`qsVNX)>O3*{)SzB}d#AT4%sgAjaz z&N~xGfB0B5#uq#n23;=QNUjt~tc6Eb7x&bibaIILl41z-?AXZB+>>=%g87E9PT#k? zMYhE_xbzRRehp&3PeOMRJA$11u7!QSZC9Z zvYuHq%Q}r&K)Ka)W{Kw7mCm*|m8|vlxHCgTG!lj#vE(JCCe|3wx+=-{9VzL3ogBXr zjUn#oHS|iUw8(c72ClCj{~Ypymj-qtaO-)Slv>f!?FBd7oU>Dn5=wQQ+hPOK@#BWn z-O76qMJ)HuAP+EjGHgQi;k#L>E9vQ`Jv+6Steuw#JZuL7< zC^Ez}O+`uP)0$<}4d{ls%YL1vpS#fNjhybqeN7|+0Uu6m?w$5imDJg7{M_yuwuZ@j zQ(wpXI-bsMgUQyb`8aPbU+ZkQd{e}2sP`wff~_3s?2z43nj%;Izb5yet}uf^bM>Y` zC_kd6d%to|6Io!G&d4_ek4Ny58_28UW_1`Rq0my|pBVM+$%aU5tBB#$k|Gz;rH;lX7NiYO-Z0uYuXo)) zPUTq2C0n};c$qIs`ge22WWq#V+ZaD>YN*-=Pra{%HKO<6LX6o#=R#ei{LZpJ1oQ&9 zz@;R^?-eKI=^8qto9|Q_T-hA?%axVqE1kDJ+1xqAM(f_ZOx{$P6>vPAB<~i;XOxIB z_AL`KkaykZdxgs8qv?Q_hIL5~n<%e!UpTtR&n;|Ta_sgS*$1w*Bj3#krHxOwihkND zybnC8omQc;Z^=FVj4>+_KErlU>_f${)a&7})!s+IIj=?{MOl9$#R+4LKiyH&)%Hq5 z7JxH9SG{82S-f>qzPSo7Ks}a@g*llmy#opG@4F*kjtb6rniB1ruzbdLqy%aHq`!md z80|e3@hnE&3@k7a{?kDKlPv~jgt#?Rw!Wg`a+w8Uf1sxj)|82C_R%z>Bg#zgM}~lG zNIY_*2DwCD4N-cbBOK#MI*&^2s3I0@RwD;-Lm1o9ZnE%+&szj0s{jm_zv_aQ) zJ$-zO=*_+E#V)gyIG+#RywPHLI!>mSE?BKPf6N*{BMPhfyJ+SRf< z2JagI$ddX^ReZ55#5TRmi^t_ohv@qvo*cZd<;p(eR@H^3YhDwyGwpcv_fg_-rK$O| z2TO^`4X)2b*^iPZqG$7HJ>*ZCrx{t81K7B3-eoNTj3fIF1L#yA*3p^9+~M#vTw0$;%P;FRA?1Wvs6aU z9E>>h&a-77sCCsUwDR8KO*ZtcEl$V^;(gGl* z7bN9r%#=?@>c@6&Adi8+HQv)3T&1B87PE3IO%S8p++CO#15Y-pp;*h(%RGz-;AgDT zqJU|;?wxdqWcR3U zdK2seC=s0o+dQ!}J-|)t^Se4rtL$c=a-$$g(9_Z|{<={JJVL*RCa#v-3@@d~KdZ(( z$17#2LaNQ+-;ct$n&?X?Tqe2RlOuT#2-(&YC*j1~eR&uscOT|_yQEE~G_-F0RT8^g z`Fk}>z}hG9QwF84D7KZATGz~?f*wzcf!ZAp`Bk3ZqJ&v{6Q8qrz>XGHP0*} zuB%K8^1d#jLZ`BdLd9Qon`)fWWbRxR_%R3I${HZ5=XW6SXU#h4`)P@VxM8})^Wx?%a_v*Bc#9h`+psJ{Tk)viQDD$oXhSK#xoxN+UVyB6 zcJ<6W__LPy;c84U2>&c*b1jox?SK_n=dW!?xt7gGtO(|j}QpNQYLtM zA-DimCHq9{vWb!U^JA>eAk}8a2^T&~{ruJ$yx2ei7`t1d>7N#&BsrR<^{hgWZ zpa1dU$CS=imn!DeL%k5z9Be39X3)Uu)Gd>Lpv&+r-sP*| ztjuy~OeqxCHpyHn7xOyg!dNx_ zvcqAQoupFqcx*0)Hp^R*8&!>kZI-cmI@#@SwI7ddB1S>%^~ka9&MIbMhSz5KfrNw) zq5GDKF*H}l6*0TLMD-6thQP)657_znpivP_XPGs1O5RSJ0}YYXj$9X{t!tMX z6)r2t-Mrq6Ih-Ux@{fr9YicUC-08~*{Z1t(;>Gz6kg+}yaxY_aoWCmFdqWwBEUxGr z+tcQUoWAS2g2_H9e%u`g#kEg?+e>SRs+-!GQ2SY&8Ri`-10ioJel`@2R8f^z@`qJ) zn4do=-SL?3-h|P9R_bP165157!g?3>07)sXW&1peugT^h5M3^`bM&$LAPbh9a5ZiV zmbvs=%j%p(Po97V+yXD(onNvkDn-HD@dT;;(vcOVvHqDraYJ^+aQAyDHa%s&9w-Vl)Vi|MP}A=U1uE^VWMB?v$fhj=q7sH>gl3S>baM?BcGpc zaYxHKE}l}Tkhxe1yUzXEx#?U>Xt$Pp#zlbJd}+U{ys&}kx(XfJ+*3R!+1Pu0nVe&= z@uA8!Tyhh=4y+39X5)Qt{2lb`f&9CR4X+I*e(g0UwORWfR`upy9$9XO`F1OwET`ay zfSBTKJ*hb-REyZ%y^%WOAW^7^b$?|E((GyfiDF%Lwz{I1*y6ZGQd1vfO~23oMBpvi zs~>RHSL%!YswRJOl%K~0J*pQ4(t=G~JBK~)4p&N7eqdF2>)co+KMG^SBjI~gaZZ=g zxNc+WJfj&o^iT>OapvNIjyCrHmicJD-$MyRHh+BwlOR2u({CgcGSq_9>60&(qROU62e_@EW#n=^+7T?8muMHZ zH24MPcfc1cN)r}_x8B@zc;+3XkCkCl=60en?~gF~1;6_Owo)B$RPn+d zOBeGy{K#}@scr~(Ts=YKYgV`urV@E8BKQ*XIkAIVG|L=J#5F=1;GfwUVu9Toj?LL?lOeI6P8eI zP$K|3+lv-de0YNZ;JO3!&CMlz{0Wke>_VV};`#XTqntu91iT0!_#lw?(6<11*ODKwGYAUF`Gr$2 z9LKIdl|?ffB@)V>sJ;-Gu#C9d~uwA+3$dVII{v62=4mM zeWLy;lA}CvV_cj-JU;;S1LZTI`!O#712N3Zpo)MIyaMW{&C`q5hQj0E!ao5E^Y*~~ z4Bd_n1jHKqlO)I5);saSLHt2q6q^UXu#Ya3uV+4!S_$W<80_gGq%VQrr}tSVh=?Hm zPz4V4iC4i5a|I9m<>(U9mzCu!Xm|IB#1t&p=}o9<;p?8K67)UWDi8-?j{reJNekrX z2221LQ!Uh;kO|@;=z|^XTQ>Xor$OG^2{82&BJM{iGsven#s%_0Prwq6tS1wi=V6mudz`%JV00gwP5+-maQ6@&vG3Qr zP^YDqnd+yvpI{%clA@q^01#*h$zTv+VSxaB1PYLTByR|Bf0p5QzOmnJFL@arYPJNv zM@#?gpaU0u3kYm)ZZmv*?Sb6XIPU^}v{Dw zsik~_Uw*ga!|K7uZmaIl-+vo`dJ6FZeb*OiTttf42I1j!qSt=Au!eqU81jZ8FD&18 zS7}NxcrYg!(BXY+6D^1XV*%K=fs1mrefJ@Ar6{?PZk41d}WftBkWn~`8yMqLvBUpFwOWZQK zSvU}@B5o%!gSC&QvMu;i6pJq9_P$TTy2Wl6V>W4rXs;Gy$XYcaOvTQ3;Zv`w`D_l$ z^pNNmG@{9hZdT#!!}!xIE7VHk%J=1 zB4353$~vNP9!$=S{e-MUl80+0Ms*#1QUJ!GT)Tj>Qt7#>MfI7QsgM6)2&}s|u~1Ci%e2XWhE?Y^Tr?x>@37p(;vr z&Y$&_olS~tmm?QpH*oSfN|cwHd$@Eze2uWJx*jk~Fial3Ygs~RQHYDd4OCEfq2*kw;7<%dMHEmZ1A zQf%AmMkdqs#_xW<0Nw_sRS6t46XKFT!Dmicsk$4*qJTbcJw2!5!4}H!Z1bqSp4K@( z(=^*jY%Xw(Nf8%x^=;kI#0~qH1lXKz3_|wh( zaJE;hprml@UZtB{!NgWIF&Pj4*E zE_X>aTzhLUVRBj0%|3KA$LV77-{KLs27TEG!FgsCc}t%wW?V<{8Pwgz2hXYLo+#6Q zJNqpSYwH3NK269KhzS+dUf{-t`R`)OCGZI-&R!Iwi^oH4-_NuThSH`Uvus?SpXp&> zuA`;Q$!%hL+{1jR1OL{F1h?{yQJS^uN$+MYNOAml-7duBmVVhp=VAd9i4teMX>EitPp9sKA4Hh8F{sNx_EN`m~d z+bMo!Rh;)eNeAWL8_1<-7*3$W@LYXpS%pyb(#m^pT<$F`Kv&$F{uGas$FX4XmPlf1 zbD)q|A)e56Gvw0Yb#+5Lc<3lO`rIdF;I&zSPT_P=DR$!kH7)48Z|*lwv2X3Fo~Au& zI-0@^hSm`lTrVL?Ch#MOBQEyG}1QU1wxz?bcj(5qkC|f!U?(wg(Jyv?^ z!&oU}vN|&mDvZ>UKy`J}5yiVdu4)QJD-63uRb%D$NV?gdE_&zuJivjQbO#K4cN1EBj#?;e=<( zohr)s7CrnYFL>g5vRugLg;$41jXykh>hTU%_N=$BHGcpjagFV7^2{FaSv`O&CJ|A_ z@L$HBaDGE;Z}Lpk#OGzA8gROnXV6}u3j`5r7-KPVXv-Mx^o~wtS(i>zPFr|*lixCP zXahGAGBCVnaK?HMl~=|M`|32%c4;41q}8_Gla?qaiOD`@dP9OIH@}g3?$YnTv+-Ay zd#4VeE8ugaRORb@$Xj~!)J6_Z%K@g0V36mPu%8eIT-Kx**e%PWIu8|!U8lUS5!X-W zNceR-JgIk&&$nvJ=Ujt6b#au>f@7Z&x4NXKf*ghNmocr$6lGpEeLk|Zdy(!hG%udL zP-S?-$n|<0gt`x|(Y(&KOKG1o*tQ) zOmD*yLE9H)-|A>r+jZAi?YvGP(wsARGLa((gQ*w3t%6i3>!c(@)A6a+!4=j{9Ta^I zsW12;%T>=AebC(6Wkc58hDP9`A!wbQ)*5T3=swbCL)D$y+VkdzC_M;6y|%F*wsO*_ zg$C6HmK?4S_UKg7AO^FFv26|9*oj@O+h=jxi@xm+I2AP{$fV6rccM^8bY&2ias}P4 zf!QLSf}hik+$>T(e9-V7_Mc&nPKdCMrjfyV_wTQ|esYnhHAQJ>`TA*`k;z!4>CqBk zz0nk=IgbX#t*xl_gy3a9r_J%Deam9ZTwJ=1yAYnAL4S#Mhs5MisIqmPYEWmQoAn60 zK(846WH*yF_DDDRF6-*h)Nd&5q|2ta$vU}gJ<6{bL{r{yiQeysavR8lB>0%0Kt!+2 z{E6|Cl0qc3{)_=SJoY$IIVTJPwPL{YJ?_TAxjEgfimmo{`q_Tb2`KvXN5~6LyMLLQ z%ShhwInkwu)BAf&$Z0u#_Cb;LFof0C%!jr|K(kOY5i2s6d!uXM=bfiyrmJLPje&Nr zaUYP-h^*^H5v!m;tIJ_>f#Sl?re})sr;W-g_!elf%{@0t)D}}0Ex8N2SW3s(rC8;% z<||m?(N1Eq)KY}ihFJpbu6E9TgW{#ArB?v96IaA!gV8u4ADVVEc}(cDekDP4WS{^K z$Xd{D6dj)ro-vIW|A{&Sqs|}TXV=V)^bhn8R0>M{JLOH|oY|N1#%a6gD;4x|u*pkx zTU!*mKi)QhH@mUB=Aa6_e>i~%q4JcX?{8&jUoBXjIgxd!NYOtbQ+?Kt^`U;%)4o5Y zt#p>X<(X6O-hxIJM$a1c5YP0#34X7A;eCn>rWORG3D3jnxavLL8r+@RuEt;SBf;fg z#CRSk>7m~ulKf<9nd_#5EN)$Pd1B=xoA<`H*U5s$T^mauYx|X%IOx%;Ut=N73507W z)asf50f7NRwi0o~gmNOj(zl4+K0-$gGir?vOrlVLXdS^uq%gK$#mVFbhcDGpVS;|= z>mlNMd3tkh#v194^UV2bCj80;DZBPGf^M&NRz`Wz$DMKz`5roCxtrmb77u{GKMvl! zSSnQ!OvKrUor?7E2ITPi*0PjNl`Vq@g;v~h)G6;k57{Q$ak0HVq4pCj_5RsYdFiBI60Ukg&G5w#G#X`C?o0Bo-zn@j>|!z z)%Lb=G?`{~ixZbb*;DF!>Hf1Tfp$1Zuxz2-XBR0J*T75QzUI+HU^z?3KdO_?)w4M( zkx{I=<5|L<(EzU}Cp3Y~wy;2Gw#^te!8h>5$aE;jRz5zH^rM0ny2-L-O%3B+ zdSen{#OLhs z0bF4!$^H}zoL2Tv!v~K=Jh{p+a&HCPKQGIUs`wMSDj~sAYVA+&ZxsTZpAt3c4&V<~ z)k|UzsKa<<-TqI|WpUu=;uny5LopdrJ6m10?AI*j8xXRWDPqQJ& z+SXZtK5V@1iKW_dT6H{m?A$UA>S@O{7Rq7C*vy6GR*n>5YK{nwj^8 z`35sOt!rjm6%dUXV$1T5i7(&3*GeG9FDzRy)qZ{D{KIw{vsJ0VPT{JL_?5(VwTZ#+)?}CRjrbpWW}>{Og%l9 zlJj&jXx?r%%VAgMa|x0u&)#ps-?Yhc4wyN5+^PwsXUXivkbRe=^eai# zKl)h1&)Md7te#_8?3nf58;(@bE`1!ivVuEluh3QdmT1`6OoJCc15EiQi06Er#bftS zrpL03G08qPqI^E|p-F&*klJ>@#WR=3_YIdZEALZQ@tFer*@%pP5W^bzkzl4gI6IQ@ zJz~@$)Z^W0E$p6YT%})WoQ8R?ic4X(aZ##-RdCpLb@_b~pXv z-LNS*u_GbI<1=^=pmD-SLo3M}je9T;rX_b)&0YqLZRR}Jo3|eO&rw=4blFH5$~|B$ zpIJjQ^4gdx2J2_^`HLLSEJz$3y=h-wJ>giSey0Rx+x`$Xx79t7NIgOAPI^h;6OfG0 z@QM)2lpeETGpLrZ!4vHAu|Wq_yD7CT3`GlK3%-(UIiK&SzAt%Glbm4KQFu-HWb*0~ zcerWcMn3SPln_=^W~y04K3|8ziS#tsfL6g9{O)9FBo(7Z!U__Ts8q8h&YbE-s6z#R z8wU^{*MX&@HCMgo?9F?~c9(SaVU4aTn@NiSnd4YdO72M|q33>)eg{@BmU`%eae0vv z>_D@G-%LqPaSz$8p_9UW(3UW6Ujq`E(ljphR*nz$aacF)C<8c;#_YnKqX2Q?o+~g; zEfw_MEowq#&Xx}}3Im=$=s9zF#WI)9x%ba3$5c=39Gb7R{T{j);znqxIC`FPkoYXF z#vh6X>mwQI=XZ4?C$8Z(5vp6Dpf2W=)Tp@w?yVXUGgf12I*KCiM@%T*t{?(RN zU?%VUsYrm-*s75@u|s6(n{)CS0>Sh_Vk|5e44+gfK8E7zz|ROMz9Bf-?=jdB-a)!- zttRL>{|u65)u`OXmb3WWB7S{Gp~g0+T@8-*rDUG-8azk}&s9Xr&fL7HN;{}DNkeehQY+}N>&`b5{AcQjiVo?N}`P~JHe)l z<>Yf`<%>UKFz@duPNfGU?n}GAM{-rXDw_gJu0uH@T*HPvZnWY%s$6n9 zPm3}_jrKA0P>K7lmaIW9cLBh(UVXk$ky~NvqJ%Q{;d=@1rFSprvFGE^?W~oCK zY7TeFeJW=0rIbq9s#A&pDpSCB>WHAIm4~Fnc$B6&CjU67r1*3^p@5!KxL~cl=hUyo zxOLELT~a(CPS8uxZf{aSmtTl$^SLlVg9q1MmJ%V5wrxNo`hv*#gktWN@SOVSIk{zO zFcyq8=mn>r?Vqq-?vL-&lAE@m97Bh^?TpkpR|(Z^>zA}D)J*D3VuT)dUJvKXt+nY{ z4ae~TyF;rjUcgRL+Q!!Ql+T{zR$TWu6KatwIp;M=9<(!lo-qPtQ=?UQqvN$HltRwG zMfSkxJ8)HkCL}K@nFo&^{0TXmyl#)RD7hDML+&TG84PEoKpTqO$}^_e$JnrlYB1UF zDl7IYRjDZ{H@3{!gVYT%BkJI+%Eo5Z1&5AePj+(IeM@o0MoA9=J< zq9-N=WgC%XE;060p5dD<0s_P(D`y~k#ntn7esWkoU=4XZOK&JsquPpHJt}8q#>2hg z@f59<^@3SR0@@s3v>|Y;30e<_VzFD9Qznj2Ci+_-?|ish*g97M@(|CthV|`?B?DOl z-8w!QDF-4%L-z9qO~{jqC}3RJL+ZNk;^ z4^`iB7?F=%Gm0k77upqiLs^XzA;+Mkr{cI2GonsibEd3%;=Nr`@8poB!iSj+b1YV?|}7s%<%vKv(Sd7QCT z<80Ewvty}w=gO0&V^NHAMF-AX%+pScTCZg-!*TLr?9RV|NLYqOZE`3q;kKDHoeM2! z(962iNjBZUpEKBDNv>r`Xw!TzEF;p#A&xB?x6Tva2=9hGK zSTP$fj`r1Ev2h7O_i>`U;o#Io4E(tssBR)yZC?7C=EF|1*|@kL8KE$8z_yuQtG036 zGPPi~xe-{@)~3n-VIh`z00KwUgk0Q#(KUuRuauV&lh}|;t=2&~fohO}zV|)b==AQA z_Rh_1If(j>7PZ%ZKYcJ4PcrVa5TLtl+6}_zc9KD0%D1$soNy*n6W5>3jVGnrGSEIy zEbKs%2LhSy*qsxvuDh4Pq5O_dZTTbbpGU5Y4F4RmCtze?V<-5x&%fSpOjeb4EMi0G zny%TQpb`{20UTq5FUcyGRk1iunFM6Ug8vP30hDO}<=wUj1igN~NeidQzc5`xdUrrL znz-%iuI{^aZDUg`OVj*|Ve~64Oz4)1K7ol{8-;BZKcRayS2$xd0CywFR0`9@`WX3g ztM#7YEA^}4d;h2@ViIC783_OD}#7a_WbL}Y?a_!Xhh4-OFe60Wpt@F?0*A)Z=?3RclWJRQgM+n~`^FR08y z$IyKS-B~x@Ujevr^Z_p14@GP^=EeH!R}5_guW{!chcPATbS#IU8yP91-d!zSkX?JF z{#JpLdNX*7%3-CYuWVmWCacobMH=ONIvHRI_M!OsYJG|kRP=_;5+PhNBHp8|44kR; z>QUW$H~@)}qF=x*45-M)D1gk`rbMO2Q}p=jU;Zs=ADLgpM{8^BAGQg$!d&wkF1Q8) zQ2o|jemx+(7xL!bzWTSUnZE=k9xw8;fjl)JT{2Z8V2L5~GZG6gPtMFw)SfU_uIjRn zlBF~89zezs-oj`@GuzVFed{m;OEBqzT-bfehu!aH`OkTKYc_Tue--o7TuiYxz%PpQ z`@5GWY(5U;%Bz!ZIA4CM_v3i>32)DKm9^U_xR{l<#;hx1oL-0jczUK=40uhm+ux!M zWfM@)9!I6bc#v+l+fLd@vtDX8hZKec^gq4A!(EshR@3>}ucAOl=e3ov*#wU~Yz2d? zJwKFM88j|yC!BT4qW@SkUm#H7Svj4{B@U9jEzqXy6VC}Uun&*aTKtIqhderp` z(XSup_mbA@>)X0d=;9c1Jc@o#7}cz%Bc!^`RQoiyt_E%8a#)jYV-|E&W_yF253Y-E zZ?n3da{ZtS8s;;6kg6nTGAor2L1WNYQa=4<|6rl6dF6$Cel8Q&FI03c4|st1CB6#1 z9C25~h;?@&Hk2{3W*R#?8wC>#c$-JfM!|jyoi*_zGK+0NbEkRFti9q3ij1Z(tzb z?|v*G|GLVOS6TY;Ndyx_8be7ZNxpm*d4pb@sMM~K7eS_-XlHBkXEv~Iz(gojP}y%E znT#4ECZ;bF87XRa(hIaCO)8u#H9-w~>vCACWCf0PFtcU&(nnw^pjhz@tJ@P%15q9z z0fYnm#4AHYU+{!?<{$#B0U%l3 z&|qj71#es=6apA%eTn?dCM8 zU`MT`0Aykb(w%hxVW0T?5<`do{OsZUN89Azk9+(dv|s)`o8$1OFK1`+U+upzGW>Hi zhm(PTo%LTfa~K)^Uqy46mHzi=jsaNEKi|0jegXd%?wq5E{eS&-{eRTU`4h=uWcc@D z&YwySBg20rb6Ed;`R~mfdNB?HM#g`1eH8z#lk+e7IqYnIjv4){ZT?L)X?Yw*m_Khj zJKIABn?KuN)QW=T9vXG*1NoYH#b*Ih@o&%Xr1!>{TfBsqa;ApEvC}cx7;kbRaM%sZ zP&pw%B=$`)iZEFPC6i6Bo3*Nj{Q4HgF7b(KQhj7YV={4W5-L_kE9P(ysbdf2eBf

h(D#88SdE zK(KC_##I(f7d@(xsr!Uf#N;f$;k{`S6(7!H^cTgn%F)~>7ja}boJbo6*}giEKvD86 zG~ALTyk#RmdB*2UGKmV1obZ3Q%88l5-@KVIrt=3W*U2)w>H8MIIC?)=#I5}jPO_0; zJE=wO(@uk32t*XtrTqos82fX8$i4p$}#PIs4Gz(l69;AL+$=6@* zuC$^a?vON5|Lw?pQ{72SfUtIlhv%=Q=sA;O$$gSZSp;o%yt_qt3j0Ee8>BrUizj zPux^L@l*D09}L`J=e=?1l4MGf^S1Fy$5TU|CxR^0tSEb}pcVLk_4w1kuZb@O!3$fZHwI)pU_X4i@!%N=sTk zPy;I~3ug?Ul0Tv&5o6;W5ODApq!_9jowJVq5m)q|AvIAOCyRaE@2WgHuqyBv?7m|Y zyIawyfR*b<=1@X#f0hF-+#B@HW-iOc9m&9Vs>j7NL?Dao;^&7^G1L$KHtG7cS6-H3&>4cCj>E;11bxM z5}qMowOX-9)112S?ebv10JXdbJ72#X8SF~o`cL?!aQZAEwsX+QEa{k@wL+*bS({$x z(>#k#crOBaH2^RI4A);n6b6zIs^}Qs*#SyuM`?SlrN?x-DYM3^g0N6p2E#}NlAg6q z;)(RJE}6S%{?$`TjVpFhbQ=1QWM&jBs3T=ZoZ3|Z<_OsuiH>6J1WC;v0FLV4j=ko< zMwy3o2K8p1WfdECn3F$<`NMSBVe)=vD;_k6+{)k9U8$MZ^#Lu8w|nY{BBDtw=5~6n z)E@3jPk0jwiB!4y2<~U}w-+8&&{r^#+TXYaGb?bq3`+fQYrmzk6`J#P?Yy6Nwgbwl z4d6^MsHKMU2*B5d#MJo8e%>w(aN4WszMPz_MEAuo9_>O2Y>Vr$FXFKs;e!w+zk-e1 z<>Bq}JDRo$_Xl3`%#~$%4f}$ORR9Y=b3;8!%t%Lg284imW9nC&&6 zWLcUM$O;*cZ*zf`Uhe=kDxyFmgbz3Flq}Ua_aXf4*LA)2&j21pCX8XUXJcLhjg^U* z6OLAyFohb3i6lDJ-^R6D6~ItyJyh?42df}xl}~Dzq=6Dw7Xhm{5_k5Q0(ZqI=9JB) zfL>}f@T%TJB<$;ZJ%oZPBo(U?HO6@{(!FSBt0F3MRc_)^J!P|E>666yI)4;BVwh3Ogvv~og?h**fpTD7G2QEK6#)6GvHG zY#ls-|Lv5RhGTC4@qF$+;3E4*dbg|p5w)E?!JPBN64&BOhVY&dPAIz-4(;Q)^;u;P zg15Cd5>gy&X)Rs(<7yfgSt>cBybkx5E!&6L>bXZ~YwbRv*G2zL&itgUs0=c1npvj+ zk6^TU7GRT|QQ_i5d=sP>k?_g!8m8qG_`;$*oTSG-`aG5-Tl|(%f7f5Uv6KYH05}NX zSNjGkMvyVz&5OxS$6*RCNv`I!>99>n#`@zK4;@;DC#W4DGLyV0GWvr9AnlT4WSMqn zPMp|pW?dTt1BaqiHUYedggN*1PYWTE7fAMw-^2WED#tgIb|T=%uhWF9vCM+G0)(+5439QiZ%CsO8aI z&NyJeNC=@j2GSXj$NLsrkZyGYq*Rb3Ry>9#!wtFhlJ2?nNJjL1O;n_n% zi~e$xTIiZS7Z-XHjd)W&ysuN<0>NW5vh_R?!1?jk#4s0) zXxIn>CtSqwhT$_RsvinE-}#IF!RVlI*EUaaHLy$KKFq$(!$OH~%#+2zB%xNx*x~xa z`Tz#%r!J)$ zN?xKtO-W%!Sh!uo)l0+{E__lVg7rBgCPf{o3Cc5CAk|`B@I!~$dwzNt%-cuMaR)(- zSsk1|nQ1SdL#Aqp{dI==Z3C!&t@HQtFJDmC?lg*11~FJI!&bR!%(Du7>NA`M@CT!`?MRz1r=1Bwm*@CAGYyq@FkukZ2iqRq$%hs_jb8 z7AgYK7pnPGYe2K{#6!Y9@vv=oVt22HnI=4@(%uLI0ID;JO*_QMOkENE`^K`yqg4sl zc;sE|bG8eAQzWUjS}Ld3Tw%`~MyIQO@RIk2V`i%EBfpN0@I6jm0b4)&XJxwir6yAK zkC?gP!nNELGhtfIB?DMKJ&!M*2;!X6)V^5Rc4^W_MR`EtWo`aWn z2D?w<`oHywF_Q0@`;eXypeG|Yk;Rw9bTjD4oT1b{)ZV5?UJoW*a9Ah}`#~YUa=glJ z4}(V6kx3LXRODFZS3OVQPD9dt@{YQynv;6@Xt%qhD}Xei+^uqA<(6a?gJ&eHXsZak zcE*4kbMxzAjMS}FTtaWD264&ctWU6bI=_R+*jyynTMWFnONK2hR_mO&S=e+R_DYWy z=iYA_70EPC=UDN^i%a|hfEGL9=v7why&P*?0?`$qu8Lohh)+V9h9~Iw=^?`s25$k+ zvwWxG5Sf}mW>oHj9BUfd7pl9Ak!#ipsr`*oG5ZL2Jp*L+#1qPW$-i04D9t>e+X>q7 zyVw>)H=2DDl_|LEvi!&PeG#`uqx*^R-m7wBXfC2u+lz^Uf;8L71K%S;)$`YXZdQQCU`cS)mPLYUip9^4?>{ZL2?+Za(S29_5nMlEkE}Rv&{Qo zcVHXsPOVo0T^(_jZBoUz{nwpdH@M;j*^vG<$g0Rs7x95S@eApJN#hUjWq@*fyq!s} zUCa5kq4n>NFAM=XF`nkFTk^<3oJl8ewL{ysM6o zhyem8kAlITN{zr4$Ezv99(RG@Dso>m`*OtiGHpPoe@YLYe;h1aL0HS%RDMHhfVfyG zv*)*^_VDY$VV*}HcPa)R;p}&pO|Q?yI0}?fH((@shK7m(b#ZnhZ+Kk2k@!dx)#VgVU`M5mMm&{%~%BxS%Z^^)Kxr zm`t~D3wO^-#KiUTJBIZTx?O`6GW3p|>iGH#2C=a=N8JCy{Bn}&|KE6Qq3JC_RK;1B%Uz|AOG%&*<6 z;K_x$KqMERatEiXfUXj1 zh3zWQN!?qWR@0s8&$q2wbv*)Ui#|@C*7#m7LN5*PO3| zD2LGy(PL4$kx>d}%Y15wvGibpA^kw|XeUx++PZna=E7x-Vj!wy@gRVga!#xaMl^N_ zbH|HIh|I)V!bsf)fJB|K7|NPApGvx&Ct{OwV~YtEO{*xj^D!r3oNAEN3~x@GoWBX^_f1 zbW1O{FaAzL)BSh-UHFmr4bJ6!LPfRmrlJ_d_i3YFR%s2+lF5Y#7B_%}4ZH84aK_Rh zL`vPUmMlrmnx-|*`g<;<)ZXG5uG6E}lMiy~G_0KYJ920_{8+A^+_-xc06;J_MoOT5 z-tVaaK8&zHl`blJv13LheZ9XhiAX3Q#k+5~esUgP2-%3IVm8z>3Ag^t!|t(3_<)}z ze*vEp_Uc=%#{BkGcN%Cn%MXbcUVQdgw8N-xSymWL=yH7?!~*}wDPj6@C#WImYfTu) zWThrDy8vrqqLikLId-y*$b*=@de&Ud{Z5V^S1Z=83oZtovmR+DOj}Kb_D(=bP9|^0 zN5|Lngm=?2H*7;4UT^)6SDdu5VNs_8v4;lX<+)6+UC*f;^fqq$*x%Tkmwqf5({@I> zSoTrv_^Xlk+x2LcvaomhhTHbIA7BHP5rJ1sYWrP^7+^2Fx9=i3@P@&r@Wa{^Uiz)| z%BE<*{cC>r-^i`OvLJ)ACc~Wr1<}s=YL5p6J7>6a3n5>vTA!c46QRna7UQjOI|2Bd zQYW^Z8Kby#nvx_Kbf)!&e7DdM@-b;Z>MF+hv?sn3@8vQ_4>tXD9o|vJ-gt~-WnTD5>rXq+2%A}z38DwDC%DBB$1|**9>Y8cnSK8mu2dR77h#Wa))Y(%S9F22vm6nM zBOK7WG)3S|q~F5#{U8L{7G4O~1#4*w{D%`toZ#eLDEXZc3QE4uG%+wY&SF&BUiC1* zz>Y>A#X*vVlRx*emJ?@NN$}G#$hW8oHBG8fgSm4%ag=LfS>n2@G$(mPlc*$O3phxO z(l4aIuofIi(d*pC-sL0*p2s91NHt-SYtZs=UG>I(%;*qHe%ZAB?I4n6!JLo5UEML? z@U0=i2-oryK5?F{D`~dSiib_hMNG-tHCbxBxc}@liw!wrc5J9bTOu9DMCM?|fPKZ{ z_^4?`zd1*eSHeL7tUGOU4l$Z_2uk1a8Z@+Xw8akmF#tuQ4Cny`Wn}%dSR$c} zov8@fmul}d$c)!6)RjVq{v0>KsN_XMgs^l>`0{tb# zRx52buVk5L=|$rQU--9@GnC(8`z?@6El({8xFpK9bkS;%PwEVv8IcjbQttu`a)oq2 z^!~*=-IU~L$SS$t2edW2yL}1uGPI-934}|X+BfHIJh&V;ZW_%vOE+5)qS?F3<^v>Sm^2&r9UU-}bK8oH`WVB_hC`n(EWIE& zam=9adWKeJQqeemx_YGJFRGSR9cJt!Y#4X(m`2uqYpVItY`y|C6aoG0iHoQ2A?}_= zp~kYigKBw-yjTQX8$ua3w;cb4iuc?R%y9q96Fv$rajx z^HQZN=gIM~nJrgA4KXD5A`I!vZ>;!aXGcQimm30vST|3x9mr|4b%f_^t&5{0?&wFH z#i*D#a|2*yN+|lDsuekniYzKc`@U$sB>^b|4g^J5CdSF=JO>L}N-%VhZr4U$Gu`2% zSltt8j|?NK$0TYxSlh+zmFY$H)gL0)-gixrVicvi9Qzm1Z>y z?JMj2G_LpUHbV(BCyzhpjqi>wFGrBUQgB!|!P0>{n4LyFo?d z1o~p$Vw0+t{Lq&FO-QI@{~EGv&Fq%MS;S@R-p8jA5G=TV2V)Lpe<6PeD47 z*n)VlceIi@s=p{Ef4#9SrKpcO3!61x*Nnts5&xAdyzrhJUwzH1ZJ{5L9=W<7&=^YVzuMHkPORS*eZT#)a#a>>=nI$7VXj^5-?fkFqdyS%p2 zVxJh}lDn}Eu2G_Gg%>L`=(R>k%)%hv1}clq*m@p_&6eI3QaPtFwZE47On;n#d{w*Q z#+vZKb>EUY2^~_@5E=I;*hjY0nKzaqdD3W<#=QR$(MA?=ecHFF6mvYy-$~14ttfLE z2D`RjqX9poyWa>v*jHdd(~2PqJMDF^Cweo2R-?6Rt?2e#XNdi6{eE>_bC}!PHh^+& z$`kGL!u8%1dgZ%Q$G&OfNQwqxAR?BazAJjHs8$~tn@2#{o0lv8BbaT~N&80_+PMwJ zwI&X(<5#=L3)JVq{HWzB|5S8fW6@>ma@E6ru`$DWt4z!A7j+~{2v=r!qZnt_O%+w5 zc!%-C=x>M-8ES5>Q2PVA5I$97arzcebOi0i%cI5ITumoCL#clC^e35y`Yo=T2az;$ zoyj-#eeKE&|6XNMYCtd0c(65eQUL!(eV8FdROS6gDFp zuvbjk)CCVYzO!)^Jh|zaH%4zI-I?7+vT%=SJ;%P({Zd`zRF^j*#ilAlOq37lgt8+T zJ}?uO>Tu@t9Y3M9<|u8AHBIH-a{8VRQZg%Acj1dLVu z*nlT;dP-rXSw{D}P+NCudJu$!o2*Mtifl|{Gt6QGl9sLyh9Y5?;9J~J40TfGHmjaC4YC9Mfo8e$!kAc^0!l{Mme-xL zJO|4kt`k-lox|v&tQXh{hE-EUI@u!fj;qgEvek#PN3Lr$BIYxwBON`vz2B^_&tGOi zbFfrYJAz8btTU$pXb6{OFn2W1^cL7!lSMiGkR!d~r=DwO5mDZ|e@Uh|%vLKm6)W;qt6l$+ zLl;-&Z~)C>=ANJxI9LJ0V^+`BYIU+9Z$_IeRFZkIwp1&n!JJ(rvE_KoJCQtue8ZT; ztC7FG{utkAkD@#75LNOOgmZws;l8$ba6<$3D=#@UNT-i!Wn4Oqakf`|@y1n|xAylw=mQE`28;{0D23KiSg|II3MBEz>vi7J(OflqlLS%_2 z`IifJCGZM)Sty6YA*JSXuP_bGXej)|>nPV(C}dmef{q7Zn&T*q3mjqki6qx#jaxbY z(*=!P@Nn!rFRX1OoY~T6^q(vb)G^rz21Ephkx|v0H`tv)8jm|;>v{{GZ(xaq-QPvW zU&+Qfr)ad&D&HMYgw+uB261S>-Ii}~z1&ku6&>n=#o34P$OB)fCai+(lK87yS09vW$75LzGr8>DLLJ{QV`pGVcIw7Mn6V$;@j%bWPlb1;2&ZgeYHT!umaQ0}KTu9aKyu`I0Y( z$szg&D;1c2MDV#irIPqgoX|vn#+#G^4-!dqGs}>mxsWNY=>_nV)LUeMr26-UOGMp5 z#dbupUquAD+N7h))xL1b#-ct2er}#CS<8#sQ}yV@RqWX(ec#{(X68}JH8SnZ{l779 zyG5Ybj;^^3p#RK?m085|624S6a2kdux@m|b1EkR0@L~B9D$eg3U?+P={d{WJMq1T` z(1`o}%M6qB_WR9`GIJb@$nandt`$h=gxHjMi47iv%n58%Qs68Po2EDSAV)SP&?^(Z zarimx%nW|kq#Vq+JnCH6v^Ik@;@F#PRWg}K|LT@7ndM%6R=6hBg(Lb|K_(kiZ#H-xSJLJC; z6R>lP>sEQV_xRbg9q19Xw@6)QCwYbNJ9K-pEcgZOL@6}~`YNQTbGb%924~FVwr?1~ zb)r>m(l|VjYqprAIc8z}CEKj*q>=aii0P?IRK-IUW02kUiFb1_Lb1nf22(aj_V zlb0O~%pe>uqW>@I~H8r0hDLbalwyDI9m;?!HMs4vAe=*8l!HcdIE9101D1Tw^QRF#1 zV*zzo?L!)ezG{`0i1znoyVNXc>o3eoAYG|tTP((6q=o~k8^E*?+_fqnaGg76Y_LFO zdX68DBPt5imD+k)OoVj9bj4%oU9AkTYmLwJ5ha|s5#ZZJQf}Mrp|DFK`|Gz0skQ^W zsS^;lcqySjQwkwvo8$iT+ zGQQbIy%WN#j-lprlaq77scsuIT|`{P4$J(YC-2X%(pz3|A~9hZMW$G4fi`m*BA6l~ z3q(=Z>lF;;gKBfI_1z+U`ZW~&Y?pNl%GL)oH^>*JNF?a;!-q*(QWzT1#>h0PB@XCY z)e-qslmLaZe5(-uK8Q9RaDujj@?M1HpmgZO)@Y&imoiIp)d};6V}j_s^N+)-zSrq- zHL~LnRjC1K!;Z%E`JxZ<-SFp@thlREJ!C>dSI(o0%lEA9|ThtEyvAY^WskUBgAEnLq z&fRp1749e1Ke4yzrR9&m#MUm?r1SwPkoQfx3ScG(Cos&=n(ns#u%2HgurKkk`gU) z3Bg2Lo-ea6q3iqYr8>zRT?{l6$_477T)BT9a#^-`g*@pk1pAKHJ2Lm&#_cP3GQi`J zLb6J-i@ZnLsm;+xbt&qb<^`IRw41Ok%qA0ll2mi`>=0g1Td%K~+7I0F?M$5ryS}+7 zu1+vNVN(xlc4@u6vq%*K201KPBW%72@hb{Q@7~k=9lWJ1oCj?27l0?Hv{C=`s&B$MF;?WniX)7vm-fwW8&kc=)CrvOS>vj$+N3 zHNPI_KbIwq61{=qya|hjA14dLDGT>$OTCp!g*L3mXvurmpq&bTjr(h6#V^aHe| zR4TtlZi}wj$DSMeOJ%>Iwm1Qioy+(7Cm0f)Txf1YCoHyW8S*3DEz`1KpG zkR8f>6G8b8b7j{Q?5pIadycgr_s+k9#<|PB4R~E`w>EIUIF{wMG=(^fpq5ICwDD$3 zLt;;9d4n3%oD%4ymJ&T(z@be>fMEckF|6X0Mgb~uJNBPLnY|=wwh+JVQ63o0?^jMR zGh&a$TIY3P)vKL3%xZ+14X9g~ov9Wmt)KR}<7o(PM_a?* z#c!aie&60HkDTb*t={|9G{-qjVZGrZ+XEmYYge!^q}eyD>r{ezdp$LxVKdHu%>e>VzQKIcZ2k!1c?^=#Fy3qAoDh8e7MI$Imyf z8-%D*Dc1@YHgGZiLoYIPSklX7paLFpW>`-bqa-_mYE-5?EI#Rc4eb#S7}f%;Qq|#j z)BM0cGb(bc%;6+Igjl3^lGLjlv3E=t>v)g$eA5R|bO~%4#-Hr|5ysRT93A$yc6j7{ z+(y;)M(cfYCh|Bk%hViexl8zxcx<2ihMiMUs7s)A?GcY&J+%B9i>!w_9XHT~iTPm0 zI4oJy+6|?1(uxV`m^pbJz&K0=vOell9i+$XX2f?KPKHTvXra}~MOS{|#A}PlmbAQv zwI5^PP-ag5e#GMUD*DT9IY|K`XTa(pJ|I5S<~6h>l-nYJ4cIhh@m?$Aqsc+Z94aTo zCAd2oXN()0Jf5YM0S{*C5tYz# zFetiF_b@xhYMH0~?F9P#vps0sY;F!4qy!I680Z7L&{i{Zcd3YJ=JhMys|4?P9p7u~ z?K{_sg?2>Vh8X!^$bcMmu4a5gU~{tHl_y)bY?zvRj?Hol-wxp-!b4iU6DkyOHG>(2 zbNx1Yt|W^k0!UBPRf6rAz`F36CH=G>H7INE?ra?9j}G|RGFVQW1+vyUD zxCxKrYML}J{WNA97c?l6ifEHw0n#|bzfy!QyC4Hy@$hrVL3=cK zwh1z1qzx9U?e@#Ji~WjsX}+a1Ov9bwi+#iNdpYcSk52W#?6!NCUCc@<`SDgrq`|a6 zDIn8^yX0=#f!Knm(i}Hcr;rlba>_^ zw&ZfJrI5&3uxI^Ttnx+F$^%~ujL+koZFT7hbk1!JJiLzVQEkN4D1{TpI2>H9X+^0~ zQJ4d!tO#5|CkrxEAGjXp1|mV8KWF9qNoPA3vn3P7C9DmXh51YxPVJdCCMoCkMuahqhOEBU~iFKlQrlITPc#*Aj|IhU~VL1ECzy%F6?N$jpCi?Xp~en+zB z2%Hb$wV`rpAVP5nuu6Q)V^2DG+e}Li%p)qLkd}IxzapjtOj#ot-X0PAMJoCmkVDDs zfGdbLyB6_Zx`v*#mhdykjY?+o7^&d3GQq)QuX5hEMaASP@y1BnIhM1(tv2(yHL}V@ z6L-$ltD$3BelKE- zix|H}sqc(G_&0qf$PSB$Z!89U4bi81LoJNtnCbDNO(roQW@%fDx@!%)oZpZpT;KiF zWw?c!YYxWcr^#+*-Uh0Jj}L(=8-~W@-17MDnp)Pk!oCw&q;zfdNRWqN#^UDKql;)eC^W-!Wx4I>5L%G-O~cOUfmeFx_Ulq5wVNC`W6caP zgTN`#EIf_R+2v2U^|6`ln_iVi0s?899aC%*1wFE7R-dIaqm=6X2bJYG<*UwS&- zfRK{?HvP7lRI)6Rz_C$OzqO^NIoKp(mJO)w!8-b~bJ}>NA`~)`6ijPyzokmS72LkB z7F+3-3ws3eu9$>VLnJs#H;I16;x+EU)T-BO-K!Buh1?jI8szjnYFtcolPFq%bYG?P zv;wUAj0#UVxq#!CK%b`I7!5IH67n>KYoRW-5cL=I@7BygYk_qBV!g)-7u}ujnHd+H zS3r5Ek-8=2D71zf$@*pGN+CrZjtT=k#UEJ(h=vA)$=7(j6YcDPQu#NN*;;KG*OZ73 z)sdRAAxwn!_QbW8@Gnjfc5lN%Vu9>PZ$0Q0p*FiLpdt1am3ms5?$hvE{H*sxC{~>g zo^VonNa}~34}|q!A?*bxMavB3&Nc0mCwF6kYVu2Ze9IipyG!ze$hSKD$-aFF80sQK z#}!*0mbMoxHede^QHyOz;PXtX30HsEb4pZ7?GX>Z_e?OeI#|=euw+MZ|7~&W7q`(! z723C}nvgM~+JF*n6faMTYf06&cGX@F-I#5rM7m1E2qM)Eutz5$@z{ zKSI=zfT(rc(<~CIsLgXv@fy0{6$fi|Z(4xQ3kj8lAgB8JTHG-tgu%jK%*1fGdaH!8 z4U_o{e9#+~_;tjfYDM#9Emi@qM6UA`gUTCZS3Zhja*wJmJ~nt}@SBY==Lbl`UTvUI z9*wa0m+G0mtoFqy z$XzturRjH!i7Fjc!BB5%##4)in}8&2FoE^n9^Vze4DHM3crp1usp)MNQpP< zaZ+>0w4QCri!z@m(xJiXBzlsIC&Z^hho@z`a3lh(?v6YqxSuHNrLhl+)TaN>n_=BXb7@GxiDhjj0|g2$kbLvA0MTZrwEH#Tlqu=c0kc#Avix zgJZti93Rud2|FKtd6*c)p$4n&7Lk5hhh$M{C*Gk^yfCI!-9aB;>b|LT`1T&&yrocy zXShxO%uT3n_Wd+8nKeyZ8v*ZgU z=tMG6fWtsaGjPRLGe)gAgVeUpk6Ul=&*cy!2Bn7ru7XIoF=DGNrtI*I#j5=Ea;P1% zz8iv-6uBGofb+8`_x3qwNk9h3%GD1Ikugdb0`~j*Zf`Gmx=&Tq&K$8xo*E7m6?Y)( z;C^5tZ3ZIgZ0KTcuTIUp7Dz0~h)QkRj5H+>R>K-$YqgT!f;6G|LLLf`?#-mx3s2BKF4~q>8SEAf0r{H2X@)RRtCb z0$(XyZMCF^Dw0#SJRpr}{c<1)_4dcpU*tGAa)2+hzgB{-+U}7ohw{f@hv7zv_6OtA z_HRTe6u3~X^5Kp?y?G(#(!q6ujqnd6aIMp2cdgoAMV^4VLxR{w{$4sAwVmLB2$|}V zGabHc4c|DMDW>JVGzt41!m`SYq#{yd(qY4I-Hj3gaR#J#x^WPvZA)_|puepH0jxDJ z*Y!DcBwChi@9brwo0Nf~ta)1v&&Ex@I*A|5(A`e9lp=C3`i;m08T+1JILpY)@{T%= z-p#JYt34qgVLuf&eXOUtix{p=M&DQuIQ^7K4h7`Z>B3drToi-&_PL?7p_bd88ai0) zrzc|@I}rqQK(9vKH_Q*`C^wUxLiv%yJ>~|jo;{jKX>6Fz-cj>RXfte(7IE+U`YYx8 zKyS#Fcmpv|*Dtm2UdmV!@et`_K^-v-w+XGU9=igdx@2LtnAUbLKP5dhhwaswrxUed zX=LIZ*foXU%xd_34$srS!YaP2&-FedupDL0w6T+!ZBNN{=nArgGK??5O^xzg)$m{~ zC6R1GOa3t5>O4J4*3t#K;p;Ju%_Y3?SUqJ1R&fv1+35PwYL^gC+fMoW zcR_T}IeWNJ(Z)d5Ph1!hn{WA^+;BcYZ4m0(SoYVLNkDvgLySlMeBsOIg z1%H7TR9A$p%)Z^#IC(Q=1NkZUQ;YS;is2$|fxmTaqg?_(4YW zth$*fjp|AuRgr0s7#+S9@ zA{=)y!)oL&dlfpy{wgjebYIic_Rihqqj{88=rlQZdTG6-zmy+>$3o2dW1$jfzK+5O z8|=n=&p_k}xpjE8hudg%92ff7PeBY5drnSC3*Sh5AspdjLQVg1D%6znV(ybDv4MrH zaQDhiYG+pakbjz@Dscq*Vl9%O6l1)AbvVKf;5Aw_#1W3`C! zwQ8GJ>?~rjMN3d%)dx%%4E;{W8#^~q94*2 z`!dJW`Mc}_mvjEJvXf_}AINmf1J>KjIRWxjCS|AGkE2K^vQG3+1gFXl$nMy)psZaE zCdJI$Ayo?%=1+K+QAo3WP?re3`SJl=63eeizE z$`i*U-R2{$I7u$AuEo_w=(IGy=Uq+P^AE_Bf`0zcpHlxORX9z-zvW@AXS<`a((>Hq z_T4=S{>v{fvO7VgYi=*39|wT)i7p)yT9Q^8W~uX9Zm}IIBH1ZBAuNqsc(Qi=&g5#NB%nHdxILw(`7iCRxp>Esj zHU#0A^G=tACMY}FOrd_RrQs9q1~$8thzoRqCT`zP(u2kY~Z@}9(SF?%V zxKTdg;ozu%Ouu_RH=$(I%Yrl|)EGA(z~o zzyMkrj;F0$A`^m3p&&zfN@^)n^+y|OW%bEd;n9%119(dCN?sJ>J z0GcH?fnLg&VsY09am%?PF1xx-a}vO6iS><#k$nycKu{J4lvJ4Pz9bfFSJ+%(+iN?q zP{E(j`x%mFjoU6*8KUGpk51#PN9>6pxyl%@x{AI1`;NwW3XJC-Sa}T*k5Z$rMwBmw z1BEkb2b!&nJK+Tt)65OLwM;dp3|e;y9_cuWCGe$47H}Xumco0)lAS=-B8p3_3AyVL z4~XMIbsARQY_6KA3g+&B{$v8kJoi?mLXIz?MgBFND?;QZQwNU|$?lx!9d5ut19#I` zQIRE*1U!U&5!c#t;5}cC`!0)VSr@)(Sd&M%@iZ`*O$3~m&|)k*T@1a{ z3XV2jHF%WG79!g*#&Q~QEc3_EP3F{&wMc@t?xR;>k>_EoQ4|{cnX5c z-2`D|G{}}qeigg}cN`=lOe|vh;kbx>IClizE@;H3)l|eC$Quz)nmAnZp3iY4jM~bu z){M*3{BIO2yE#?aZ<+2L@Bnf?7ietqegEAP1hr>XiKs&&2sy1OVJ3cKUPlZ|EB*X4 zKehLgE4&^$wS+|Xg9_8X@?w#-h0^~?CogkCeE#zH{S{v{{n@)tl7NFL5Y;EIu&1GE zsj~iTRR4C8jzyMN`49S9%5APmvH0D5DQVRqxRep1-deyIjjzU_TV1(0aW7d`(AfD_ zkfU6aJV{ZnVR%8MNf>9Tt!fvL_g_ifL1=n=@nYlmzYnh`VFsQaaHHg-;^V0LTN5Fk zQmdwaYcsUWvv7ddg{yooBmGSO=;=%z67`tCanbkaY@kfz?wWu<4`;s?`LxSJZu#~8 zDStTW6eCj~qI1bxAS+Qbv0g<)0QzTg{!ODEC4}q|56S>XDJ;ZIcG7O0E_*xGULAAH z_YIMgpm}SS0Qy!Qsb=u@6#H7O(xmtn2d`k@DUl8p+W_zFsvlk#T+ZH9!nS;?uMRjC z06Vau*3wuK1+>1!_{!`x&sZ?c;w@uXy3-0W9m^6j<9*NPrm@4WC3u&SE3piGZPzn_r{Z4mFvF{M*Y=9E8esyHpLn9U?Y2a9cW zohN!`9OJX;e3rR^l&=?~zYMSVTWvreeiE)Zc=u}g5~mRb*xtaJln_!!683%ChXb!? z>4JBjHj9wJ8YMi*414&ypi;D{4n>Vy0t1A2VlBw|`~rJ;I?Ihq~Q0C0GE$%+}ARq4V;qLD4?(XjH&J6DE zKDav!4g(DC?(XpT?|tXht-7b`yi}4(ce>L%T}f)CSMR<4)HT+<;(Hst(fnkw%P~Sf zUf?nE`@XbH4$H}!p@ce-bCQx)m_vONAF{iCU_sEBYp+7QkU+F&ITh<4b*XU%JSFKY zm9_n``UJ9-H^$?i=zH2CwTT7nMis)gS=jfN3KoGBE_UCJO}Oz;B9v$zZ}`0z8^3T( zJI2&km`Udscx&k-oGvYPG_7+`&k$> z)wKgDkQ5x%t!Es1`5K#^y7E4_hhYW^jDqhOji_h2?%Hq5cU&}dI%4_)*uPNhG!$FQ z4ts1ANEASrBogF}%7W!ztvxc^4gr4a!6E0u3^Z6L&Ca|>>Z~zy`_6H8)PMX-{Zgns zXI&yhy1lqA>qLMt6ZCTsOPr*SSue*y+NRizRZy(nYu-dRB|0qI5`bcz@3x^&NR_$! zdRw;?{@2s{2A%jdu5`Pd_~5yN0c2$j#~z_WQ)Vy)yEQMOz$H!Q+xP22ZH=l!I9UZ< z#2sFL(&V}l0%OHfh+UUF;`vIS#@&lH#-rV$BD(#erG2GL^_X*9X+G1N^6vpLgv-}A z!wEk(r55aD9FnPp0zT6o-!DK{M>`y;nW`XvKPCr57wDnH<0Tkk4&?K7=w9^5+ZDp( zs6}NIz2VRHQgUH-_ZYmR`jI*QvJgFmC2vR}GC?uq?EJl7z(hSW9Nk*=-T%A?*@)Fa zi1LJtevj5dc+1n8QchSPF~-&ZG4X7bvihw>MfY=*W92WI#=FmQ%F3*AS&p$QMBGXP zw;gI(q0GksT=yUUKYV%sb7Nb5xnbOZp*|t*QC1OjCD+tTP@D)U#8+gO>8}sJGZve( zIR8ZfaYOWs&7wx7)J;u$`M3LFJr!on=JRk-HjA~v=s-5t04C9V+zRSsOX3`jKEIr z4@p#vPE^ai)=USodtStWRUdh|)#;;{%ME8Kx~d8)2NF#s)}qeeYr=)|(OF(#NSZ0D z#c*&4*?mV`y&h}!>&3|}8oQkh{CrhM$_}#nV{x;<0BJ#7e3UElW2&^cB`s8@-YW=H z*0e8LS5|qm&z)8HbC;NOfhKlo3j8gR5xNRdTBNbK>G-iL=4={&w!iJpwxdVWNMwJ= zXKR8>ByON4e}rOfiCg6ol;WTPi)jY|v?Qx#+7eH#eg7_A7yG}7*Tu-p&iJnYT}%L0 zPT>EG-t|Ajb+K`<{Qs*_xj<_C@LlC2W0b-zA`fD*aglU~7nU-z0T;6YiXo8}krt6* zD3FRm2udB>6@BfMek$N@3lru(`sO}<^2c3ryWu@vY`SKve@xvTwAtBESAmIh16XD$ ztAH91q|hqN0Rp`M01PQT7+55zhX+8S>idp8cfcVM*lwsu;ob*$ewd&@eJYzP3a$^(A2cd-`p0!aEE|`4K4_PQmA6?e{Ud0IDujj9Y}zw`s7!-qT(>FCvYk# z=&VUJkhH(`0dfx|%avS;P zV?$icZH0vpDd?pVZBTN6fp=CRu`J9&<9Y%V`~&Yl!C*i?X`x{-K|g8MbC2{R6UsLG z6tEG_FF-|~NfhM-#EZUzSrnBs1l_F#!Hd!u#SN-v<(}=OLvAY*q^gW>B{T z&Wyu;P8>oG0C?;4i1j2|^qHeRq@3H#5YcrI&oANx47)&jUX;a+Q0m6JUZX$SbkxyT zutHy7_aa34@cm;!A0JRyg^75(P`OV0fvM!ZJ+^W%vW3IE7KBz|TQlI`P0!LtI33K0qDx6bK90Tcc+iF?3vPGeY2G8pZ){>`t@ZgHTC&XC0n_P zpZhARqOYKi{b&M)jE;_ZMXf9fQfhG6chj`P3VXTqA0$f9`w>vTKNimRQ$Fne9wLK3 zeT)VZK27U{9Z7Ex2l#xJJnJTq!ni$yeCCdQaPNJNThJAZHzQ3~mY22m(IionN%|9mlN2f{DsSfRILg+(i=cow3)I!A6xm>4 z0fF6yUQbnkze$*Nm_t8Sjk`t*=&&f&k){WXDEgtchRjt7yaQJM)y z*Al`9+wcsR{;A-m{YQ3;EOtRB?$bQ;m0TH(A+KK}y?jn-3qta>ay!W;5?#+yb}=C| zF@?Hat(wGfVs3IbRvdeD$9FB3sUMeD9zp5R*fbMz)B+v5;=JAdK(S12pT6=;QW%(( zC@lZDMlBR?4<1zDBN*|)LVy3H(a?lkt2{T*>sx92heWC+oVpG+yTA1bY=l09yWun}Wnp08bUEu=BBUlwwW`g4S`m)ufVy>b1 z&6T{0CgHQ#f~|q_V3GO!cCL;Y7MnNY-5aU3ssoFlzKe0vCIMt&%UTPZ_qmEWf_G4Z zHvDR)T43-x4brVNj_33P+62aam3}3c?Y~*NJ(WQv;O3ahYv(Xbx)KkLWmjs8ezZ!f z5v?8th`Y5UZ?>nJip`%DMjT$8v<)u3fmR~mbj^e4>o?>2xBS@_!k2_z(UQZ`m{X?- z!-7yrXB48EYlHmJRqU1QB+mZRmA_w~I-bqSZW|d_q#D0@CHWw?-_ni)RxR77O|_%u zi7d=w?ZgqCrL~4_J&SJGA(u}~drry4OtY_|qSBxXz+b@(nVYC;eAVXqIWyVmfq%mm zc^^3d{=0R0Fup83n^yt8w1bJ^!>CpDSFwPIV=c}{L*kMNnx@V{L-*Jc{% zH2I{<@#nR&N>c@C=6fd|ZAXBYw?IfyrB?6T@uajYqgPuvA>k3Aa#AxX621I+m9o#8 z;T<{eb$cjzwt-PT(_xP*d^nzxcb|;2c3w3-i?5u|)HEk&@*euedVg^Y6yr-(GYgTZ zoWRY(#ZexL82t(t9y5ROO+-vfg)b4gLW<8zsOMzP(z3pmabI`%`61oJy>MhiL^Zo5 zH2RsbL}0iviN`X2^>T+y0O)f*aSa=ZZ+}WBr9bX|9^a5t#e?Z>9gFX|x%y~vpsC{; zmvkFHk;WCCHRK#<=>~Rz0@8Wf=8M2S!x2PG{2Hipq*_zgxsLV`P8MiZxT;I0zk`<^ z5kG$P#~Q9qTzzEw*jCiDMbG3=0?E(+JMHL8$yR2x3(YiE(TynAE}AYfB0v0xg$ut3 zy8R&YOUCk9#DUnpp%E_!MkOQOL$}*SIn(~pJPJ8b`n8c-R{LAAcz^sn!DSPM7gN}e zzXv+}u_P!U+|L9xkxhHj5ts-2i;?U!sdVeUWcXL8xOJRxW~*EN3N#G~ZMVEEUs6mH zNiF%McMi%-THi2z;P>Z9oA2y`JkZ2?a*p6jBKWy+HL#E!M;GcNe@9y0*H$KZb6lm* zIWqN_xG}StnmV^!{rWp=8C|+e@~HyaHf}lCHxf-FnO1gEdPB#}uFEQFa{IeX|Lh^Y zfxZj#JAsuZ;tt0jT4cp+O0oDMc2eKsMzZ$JjE~6*U~1ai_#LFZmXRkZMmMUR3iGZY zw+rKHC&k^Jg@&FJeQEDsUDHl+;N_Hxey`3KYh;5>VvgR})k+rvmtcJc-s*Y2P`ST2 zi6zMvPENjDY&E?QVM9ae|9j&p|Hf5Op2_;%rH~G#-u!5{`)j{nGV;Bdc(SaT7g~>1 zU+Wp0q2Budmb;CBp=o0do2=G|UN&wxs6Ia-tB;F*SVc#AB1B5_#O@*}>1ry3u27W6 zestvi-9T0hRsJyMfhIhqs?EF9&TwYVXfx1qAk~Z@SoC3kpFgDm!GtD~e|7ehtIPeW ztNW)MDRZM(i#f} zCOJbTY{@Us>g#v=^I+ZJW@BLBfyaBLEqH8yCMF@coD*Qr7%qOtgRx0hz$ESPej>OW z%+q)aZ03mqI)V67L;4|xz<3w$u+sn&2n>XV>mowzbC5vrzgyrX!j5|sW z={yc=Oshi5CzOxclD13gM0!VZ&Jl|Lg)9;vMpe6L%7rzCfT$R*hOgzVF2U0U&1uy^ zLxHFSo8kA1E88w+Kok~ML}Et&64s^DTcqRfjL7;@Ox`2MNiAqVk1Aw-x$xap^AmyX zu1Za;2M%rHDh;S5WzL^F=z1N*qV@6op+dT5Uw-95cP?gK-BH>2{ z(}Cw>Xq=>HmRkfidDr(TcYDGevz`_8+0wgSUu8}3(tfHY7X~m9Yv;u#&&;aU0YaHw zQ$HX!bwVVAhDX|rsjDmCg~$)IJm`+6Mrd>Qo9yd0z8?YC%8=_)x90Whwsty-OJ6!J zwS-Xp;tAONE!pjN#rY&uDSD_T!acqsw=gAmI6b1a?afkzT&pZJ=D4k*yRuRbF-~ML@z2bJcoU?+ z-G)WDNq*Pl>>udz`fKUMlw-gXDQ;(3bLlCB@d-ciY8kpJNa-l=;TlN{^c<1Z+eH5T zNMRnkGXPgQD$+U^6Jf_^uzpZ>R&EiBj9y$BD2eqskjfoNa9#^v?95Nu+gX=j21`%a zj{F($)+8_ck|k-L|ve}$k?6n6Q|(LW-|*y$+wUZZC5SEzY8 zlB3K?#?`j8CcH32x0KFwB;kF_VB;Zc+4GpVgr1z%b<=b}&4k9jSgNrSOvrd5U0k#T ztYey=ouUi#@|V6*;VXQbY<-&FsF?|L4m#>kO%ij@#3U$`qUw?A$SZWbQVla}K!LSe zow_w5I+rmloxl_5W$*2p(i%dOU}^pV+^s<>#$M8|KP&PVzlMkbA)A{ZX!2}5@=ON)M3O}bOD&w>F@0+hK5zzbJg=1{f zEH>{K&lZ_8w%Bt^v#U#4k5J%>o$e`3`Q>1FHQW>?@d-{iGm~Jm-pg3u_U6|fbf2MY z;Xo>^6S2uLdG)tPEEz>)a-q9xNLzaAB$Pib_Nhr8pu}In3en`>j|?-EJz^}G`?&x# zSd0-^s1RqF?g#Sxikk%h7gWAT0OI9eCb-m_W#lV*2^F_idCXPGu)E4I*U4pLzPXLT zUsd&rO2;;~X!GQCq!WKuspb;Gl!9d0Ww+J+wis(QocyEf4jC+HHVMxSa*{gG2A--p zV~4}uMne|OM3fK71{drpR)@y6Bi-P#R6^vDX4-%0rVNmyu?r%0gjGCqYC zoQnnI&LB*&d7_vFkLe`|^;E@Hm2Xa8KHq^=W`m`xzH;(F$}lGpUhBX$C2}5=Jl0mK z#)_R9Qwlq@;AwAkZXG~c5x7FZo^2j-Vn!4f@KW*i^>^hknN@Cohw9y6F~i6XleAj@ zj_@&~_6PyGh8}H77@k@`yE8(&%HaWd#r8N_jUYU!S|QDhL6!yy$`1=i)^%uq>?H6Y z_gnc_Az(haLjbGQawI`e6-8EUg?<3eN1|t zuMWCld-Q4JV@^k%S%les71c{$qawowZngs^(Yl*ESTI~P%b)$KWuAEajq$hiQq7B( zf~dFqJPWP4b-x^c& ze2tqWJ4k<*)K%oGv1n$VORr5e8zaCRB3nU&e1acf44&}&8CUgu3B@6AQS5psPT?Nk zUplOXR4GfCN_%^tXN=fe|Ht34%##nwnbi%@wS*D%2nzDM*2bEj8V|uhcM*rChd>Ut zO&`lz={GO=T^31|hct`5E=H|^HPu~-7*xH?>FLA;GdPoe<3JW&$4Z=AoO?XK96ZaC`m}Lrua+Nx@L$8HcFoxWL9m}?}~9UEk2lI8I^YPGyInq?;K7N zCoH2D!J@(tI||04%!>XD(Zg~)2UGJW_OzaZ3sq?3-*sTmVjxvXSTnh!RaAbG9Z9U; zg&$P2XX2cIPgXz04X}&&XR(tK|oirxNm-ME^Xxx{P-|I~CknrJv zXhlGWir{2=V=qb3F+p^_&>K5SigC|LE5z*1M00-A%pEYy%2zGxAA=d98JO{2RMz^q z;hJZSy_V4Pe7J=Hk^rqZnMxVbQun$4RKOoK53BJ!>il2j5!I!{J~vG`0;a%>mB zoxV$O1Z+WE1OfJf@pyPEm}xx2JkeF9)CJ0q323qOr|;b>l<6vHsLc8BD@%nCBh}IK z^M9qapea**`%OD?RWf(C_=hzYPV!|5A`_7_2__85Rs36@)?Yef(!NmjW$|cIoQK=0 zYgG5gzX?_GH@N#4FPZpkoGXF*B~-Sx)P+`o><``QIbAH$*cr`A2m} zYYm2A;$dfwrEC4e*SGl5LfnEj)ExRT`ld;6?D{^xx)3_}@2MHet2lZ!w%q(B+mC;a z!RZ7zPflLZ%!fljbER&Sp?QIQx%;_gi-t_tkc4(aE8f;I?{CsQsr#*uIvWeIq&vU>lp9bwmnud7! z!!0T5QnPm@8CSE2zsM~5pvd|*h<=*idEI3^X(C-F0Z746DZBg`mM$gK8mT;!S{WeI z#4ZuB|4vDW(*NMv1vNpeXQ4eCLv1jO-H`ZOv9x8rj-n4TL474l^NwNHL~yEzWHNzn zbjbJYT_fB%UlCeD|7^VzNG%DP5uJhteLzYmv;6Co$ptGq$L4CYBkypG%Bjw-gi*1>M(yPyWvWlf;QgQv8BoM;r#S9Ui${Fkt1#ED)n3U zk_&r1DJDEJPQuQHBl)i#hy)w?G172>IB$KqBn-AeIqf1%Je43~A!p`V-lZ07_9QKC zjIQ6(1`H#dJl(HxdF^dn5H@_KRMpy=~0VdE-O;t!BavN~o?XUnlMt*An^O z3oW<9cYKk%yBd)oU&lv~g28QIp^u(WZ(>N*HD@iE>0GcOsO;2%1KD!Ohnu|+xT=;{kkR8fW~`HnR}#T_hTo(wWuT4w zSL&Q{t60;LvVR0t7Gbo5^NN3_S93hxzklg5C5Akv9rRc=QN`u@mOV3J)BW^jy%Zg8 z_+ed(7#N12Ta9KYb^+~e@hiWq3)&I&er0AZEDbxU?g?U5ewe~)J--u=vQ~{F-W+^L zf=*uJOgSub2^O_eH9EF$fZ2%0!@>JBu-NxHqpK#{Y6vXcdA9ZN0xBC}$n{w-v1{9I z(JU~|%r|%dYkk#v8ELXS6v~VCSRo5si$U8QgVhQ%uEzL2+ren_o4j3i1hNd1<&BAY z!7|k@FIB$Y5Ib+W$f?Xm+p6HrEEFfK<4I&}OLJyRMg6K%q>1N>&~8(C_Te=QVrfj zu}UX!LJ`3rO^1Y{rX+>Z-lb_eT$(7Y{;(-3>8$$Tn$qG1+Zj3TV{b68hw)&tZxZmX z`txzO-{9a7jnMg01DO^kil-^s;VCWh+%oFr@+-Y+;_^q2e5;rDK9QOc=QicZaWxbo>Ud65I?A+& zo@6fr;l$PL>c{<-U(i5H<}ly6JWYX9wIoKl?fe4K63?PBauu#A`?7aaUlq&9v0_s+Ybzb_dtuVK~hkwN%FmZQ|%>h>AHF@_td&1O}bY?3EWw6#%u2E$|A z-mw5ocB8+BLv;8)om!Maq7A#%37(l(g@gH>rEYBlfgI(IR3EJA2`w!oW-)wtBNTtg zYb%h@Tq%`&7G$&BFAwnLKvtcxW?zwz$C9LSJC6W-?Z^i5>r%VWPE)TuuEV@@mA4xb zA8ndb41Bf=y2h0|dwkS?GCZ=(iXnSFLGgebR!S6fy zOaC2X#`zx^Ge$-h_J8qb|C2Fe0x|&s|F!&Qfty$rc$IJJxN03W*u{$l7WIp#;4s)p z=@2T!S_32zH{>wHi%37dGohLFPwbJEuu9R;sQpnJY8kTfE+bZpZY^l7s?&8r6;+&l z0TEIB2_^_xc|i(6cahWR?KEX_@#+70>$lk|9}{<*NL7wbSt_vzjX|u0f}XFCXA}TH zBMOS}ytsf1TIl8Dp7sST!U-ZS_Wue5k7CTJ4IFmrg^7Z=b-@jg0^yR4l1n9qK_Q9o zCrl_P24K&BlR_baxTQp6;&}u}SraIAfITsxE)*1Z-m9Km6|L}Ly_TuQK(y{gcThT8xs_%S^P4+a4cym8Pn6yNMA zR9k70ga-qJk#ZM0u?!d{j4~KR2*n!*B5M;!5RzmzK#3tGJ;A(j2$b|T$ipHdAaw{N zCUb_7FnB&B#WVyVzkZUkp?G@{Pl!6W?9N4^0bzPkA1ElCwb~)M*Sf}%#FUWkOMxLs zt=i1^ldGCChm^?$Nc%T%Tc(q}S!EQAA41Sff)vCI#A0xPSQ|7{68>E7kJ*74(AaHVyTFD>SRyst(<9rsZF#L>S1_ngI8Ud*r%odJh&IfVy+uyU6A{Owz^8q~s_@76 z5nIg&U8036TW0EMv&|IGB$Dgy;B3B)t4?HvxjUWCy&{ z%CSCU$RJg*tcg*NB}k#=#Go(-dF1<>0Qv87Mc7z3H1NcPA`N;7hxzotr~=Psn)_ss zM72U=8#TS2iPpFhPS0hAT$)w)W@{WFl0na<6G|Vm#kt%Dsa%Y)VH}?ewP@dL8tz4n zY_tp^zM0KvO&s)@b*kk|XH~ZsC1<(E^GCuce-Bq$x>*d#*S*D?YEGpkYjJ7lN+n## zaqErTh1&$!rO3>~)MPSWYNF)w8e6jZ9_%V-tFB=frj<**jaf9@Ek&iLyS#SW2y@3u zho`)gTBop>Y(`-wAB9E9<+vZAf#If2sdAyRhFk|K{4ZXeoyFePLz?ya!lu4~1^`F% z(^hEYtft#)Zi0!a4t>5!+mBM#yv43^9+R`%`?uu9Ia+xBP)@8azuekPsaeOfZ9d&U zMYQm`H%Fx47`%u^?n*Iu8@IRBMrp~O(SH!X6C=S zZIyJUQITc$c=4BVS!WBw>wGwQt;z*ohMk_LPV#FVH%j}_J>UEQZ@M6Z&W>m3s2_Wo zLVa*ioqEsTYo}n$g*D5r(E!eBk>lxIx;;I0LN7kbnYMH>Gy0e~PEUmuoJWQaSM%{d zyv)QbWG;*|C8bPt-f^kr?6wjw5`&q6|p>cyB{mwx_{{rHo5lGO0KoB4Ltk= z{bsy5elOv>pw#ECr6{Bp%a2D1WB0lm23pg&({GRL>}~gQj^cAdREA52)9Cmvo|JQp zy7B0Q#FA>KeKql%B5q>j*u9dL#8PFjWv04TQ7O;G4Nd*K$1}Z=rmX?jm$B+-jz73` zkFCqw*(K@Ybi^N*TVJo;BiTEy5OzOsro{5b2Y zbxO7Cg1%NfI(nE=s`yX;90g1-kC>Y?b#Qmr1H8MRim+2X>^AhZ@z-DUj^z)%!9A(F zw(5piy89MAzEdR`UbxDf-^(R8bl(b7UBYc!&&ug!KN_rivsn|J9;ZS~8M6K|+cnu8 z927qW-C2^e-|mEk$x5d@WW713yM|Te`G%ohI%RZXCqLI}v6Ff{?2W>zYwcLm`uneJ zv^qXaUz^9pRCrxz+CB%qUv0|z!rT2DY{B`376A4}R&YE#a107g_9m{zrcMA#2NN?D zQw=&sdKMr(BRdrwgRqmSp^N?3nXl}BB`xjkL=0U_0hA(KOh86wm+O#i}I z0LCvx!T(=iRjsM*JkN#VH(fik%jq0;E2x3 z32n8nm_D1R!KC_O-mhaN8Gb1T*pEo@o5llfhm((NTS?=nS3n98U$|B2X&BW`Fh^Sq zLYV_iM1nl8Fk(gs(I5wg#^E>W7%!!Bj07a2dyvHLRV?uw_Y53ASy6Z#iIngFFUfB& z1xiD80uhK=ozXy`2s~n4jzuJPoW-O-D)CA$NJ+ICgcwqu!D|?!EGbFYR}Ds?U^dwp z7bg(pNuEGcC`6SkZ1{|}@HlV_ByQkTS)Vy0rn(BM8`N}-g+(JO*q(Ub2zsHoCF%g z8e|&Y-5K2J@GWgj0?M73!F?o1<4qh!gb71JvMjJ=n2A1j!NJ-GBXE7k!;(dN?P4O3 zLZwO0099YZdSQBNFm!R*H$eL?=rElG(E_siI%yMB_ZSu7D$RH{0c>k%IY$IF>`KGK zESw@5IF8~O=i&T{8TUDodN6}57$hY@q(DxB=fAPlj&4oXgXN8iEfSTzIFt)02-{=A zF~TYYcBZM`T@Fb(jD{Q-=BmFa=E&~#Rs zAAq)P?_iZ7w(feg=|~;VAt4sS8z4~$@jjD;WCYt4qY1eVY$M9@mM)>%SaEl2!yFwD zsY&ZtjOxj8c)}{L%Nl#_tXjNGOfptm;~oM+!36Lm$&Ju z*)MNLAfu$6R6)VugPWf?AAd01H9|DP$cj1ZD^s5KzA0DcfS!O8MVoK38T&5hVi>3> zc9!?Bc1{p+8fPsgRVdf6MyQ|DYvw_vq34pCN7S$rg{!t1bgNQ{l%ppng0^9<5GWKZw*C zyhw=ef=@$5eS7`eqv!dC?>2YaG73UNu~Gk~{oNzOE{Y|+6jFm%a=gJXd*8Q;+w=YM zc>B~qH{5=EMFYqDUKyv9E7p7Um*_*issHQQdBNZo7~~5_GXNf3aCwtB-=xu zG{)tuH_%hX1^2_%4g0edzqHXyZF0+}ib+(ds8Q03H@=IQvIc4T+(a=}hlWCub7O+-F76|b|9JY>XeQEma_VLm&-w}%0@As}xPvo{qEW$f#T1k-}%JViFL^X#M+!8v-K&s#R`r~9P>@#lHs!yb=t zaWyx{CF1Tgg{IjAYNh6xaTz6dQVqFr@$zDQKjUag)iotDD6a2#Ibj&+JI?FaL7ic!<)Ute@yluH4!{3y308aOPMan2D zG>7j;?|PE2z*pUs2z(jh!bu>392mx>*yB;k#lgZegNDr(phN zVYTA4SBM_KXcCI}AVa57oKMkvzJ4=#-CL(znN#HFSOL>F0ps_-&s{C>{yUcl5M0_Z zA_#jz`)NaA8pWKM>w!2wu*s-Mwmu!@6gMLxI~wnSj}D+9TM)y6ftH_uww@UGLX6V&wp{ZZOvSwl>y1Tf0@Ewz}|0 zADqquwEcS3>ehF|@R4Fnw}P;Xm%^5sK-;^?GG$#sdjdh9)071v_wS14CyIwEh&uPs z_8ZYFf4>uzY8*QHLwLNV%!X}7w3+peam9UA|%4XDayji#s~P% zMZVgRF|{*yu>i2Lu>3bD0sQCT9}#9vu-eMyp4z#C__#A>@J+tv&N(y|GubOp(?oPN;?rL+l$(gx z&oC3_W$DGU2q8~{zct{a4G67+$ryU8dE_k+ly}Z7y{*F3rFD8sFTu13C96YE>2tCO z#;8M6i_GFVtkfCzzUaB{^s^dt%brp4Hi#WH(F?a0-FRF0g|sNlZ4(fi5H4GX!({+( z6KXp{b>sJk{pH71EH$5}*1c5QxlzZZ)e5NY3?jE7)>#Qc%iv>Q-d_r2mvPX)3=cyX_yj@0Mw{!4+b9UaphyF#9B?BBA-}~6N^)0% zFG-qvu~5Q|dSXt6NCmUIpIRk?K8naG`qIZU(9m>pwdhi|W@%)}&`Ky+lBLq*t)-+m ze$M|)x*9Gj`4tj>A2@^)X(FJUF4C0Bk_^5?YnM=VUCD1LZSesPM`Hfxf4>OME{0An X9!_6RJ~J~X3mXuQj7(Hs4DSB`QB~@> diff --git a/conf/BTppConfig.cmake.in b/conf/BTppConfig.cmake.in deleted file mode 100644 index 691826d8b..000000000 --- a/conf/BTppConfig.cmake.in +++ /dev/null @@ -1,10 +0,0 @@ -get_filename_component(BTpp_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) -set(BTpp_INCLUDE_DIRS "@CONF_INCLUDE_DIRS@") - -# Our library dependencies (contains definitions for IMPORTED targets) -if(NOT TARGET BTpp AND NOT BTpp_BINARY_DIR) - include("${BTpp_CMAKE_DIR}/BTppTargets.cmake") -endif() - -# These are IMPORTED targets created by YARPBTCoreargets.cmake -set(BTpp_LIBRARIES BTppLib) diff --git a/conf/BTppConfigVersion.cmake.in b/conf/BTppConfigVersion.cmake.in deleted file mode 100644 index eae7d397a..000000000 --- a/conf/BTppConfigVersion.cmake.in +++ /dev/null @@ -1,11 +0,0 @@ -set(PACKAGE_VERSION "@BTpp_VERSION@") - -# Check whether the requested PACKAGE_FIND_VERSION is compatible -if("${PACKAGE_VERSION}" VERSION_LESS "${PACKAGE_FIND_VERSION}") - set(PACKAGE_VERSION_COMPATIBLE FALSE) -else() - set(PACKAGE_VERSION_COMPATIBLE TRUE) - if ("${PACKAGE_VERSION}" VERSION_EQUAL "${PACKAGE_FIND_VERSION}") - set(PACKAGE_VERSION_EXACT TRUE) - endif() -endif() diff --git a/contributors.txt b/contributors.txt index dd0a3a854..578b30da4 100644 --- a/contributors.txt +++ b/contributors.txt @@ -1,3 +1,4 @@ +Davide Faconti Michele Colledanchise Rocco Santomo diff --git a/templates/action_node_template.cpp b/templates/action_node_template.cpp deleted file mode 100644 index 4c7f3d069..000000000 --- a/templates/action_node_template.cpp +++ /dev/null @@ -1,41 +0,0 @@ -#include -#include - -BT::CLASSNAME::CONSTRUCTOR(const std::string& name) : ActionNode::ActionNode(name) -{ - thread_ = std::thread(&ActionTestNode::WaitForTick, this); -} - -BT::CLASSNAME::~CONSTRUCTOR() -{ -} - -void BT::CLASSNAME::WaitForTick() -{ - while (true) - { - // Waiting for the first tick to come - DEBUG_STDOUT(name() << " WAIT FOR TICK"); - - tick_engine.Wait(); - DEBUG_STDOUT(name() << " TICK RECEIVED"); - - // Running state - SetStatus(NodeStatus::RUNNING); - // Perform action... - - while (Status() != NodeStatus::IDLE) - { - /*HERE THE CODE TO EXECUTE FOR THE ACTION. - wHEN THE ACTION HAS FINISHED CORRECLTY, CALL set_status(NodeStatus::SUCCESS) - IF THE ACTION FAILS, CALL set_status(NodeStatus::FAILURE)*/ - } - } -} - -void BT::CLASSNAME::Halt() -{ - /*HERE THE CODE TO PERFORM WHEN THE ACTION IS HALTED*/ - SetStatus(NodeStatus::IDLE); - DEBUG_STDOUT("HALTED state set!"); -} diff --git a/templates/condition_node_template.cpp b/templates/condition_node_template.cpp deleted file mode 100644 index eedc19959..000000000 --- a/templates/condition_node_template.cpp +++ /dev/null @@ -1,25 +0,0 @@ -#include - -BT::CLASSNAME::CONSTRUCTOR(const std::string& name) : ConditionNode::ConditionNode(name) -{ -} - -BT::CLASSNAME::~CONSTRUCTOR() -{ -} - -BT::ReturnStatus BT::CLASSNAME::Tick() -{ - // Condition checking and state update - - if (/*CONDITION TO CHECK*/) - { - SetStatus(NodeStatus::SUCCESS); - return NodeStatus::SUCCESS; - } - else - { - SetStatus(NodeStatus::FAILURE); - return NodeStatus::FAILURE; - } -} From 1b5981e640cb0b0b6a18c92e9da2158adedd276f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 16 Oct 2018 12:34:29 +0200 Subject: [PATCH 125/125] more docs --- docs/BT_basics.md | 18 +-- docs/images/LeafToComponentCommunication.png | Bin 0 -> 7077 bytes docs/uml/LeafToComponentCommunication.uxf | 109 +++++++++++++++++++ 3 files changed, 120 insertions(+), 7 deletions(-) create mode 100644 docs/images/LeafToComponentCommunication.png create mode 100644 docs/uml/LeafToComponentCommunication.uxf diff --git a/docs/BT_basics.md b/docs/BT_basics.md index c1cc2e39d..f802bdaf9 100644 --- a/docs/BT_basics.md +++ b/docs/BT_basics.md @@ -4,25 +4,29 @@ Unlike a Finite State Machine, a Behaviour Tree is a __tree of hierarchical node that controls the flow of decision and the execution of "tasks" or, as we will call them further, "__Actions__". -The __leaves__ of the tree are the actual commands, ie.e the place where +The __leaves__ of the tree are the actual commands, i.e. the place where our coordinating component interacts with the rest of the system. For instance, in a service-oriented architecture, the leaves would contain -the "client" code that triggers an action. +the "client" code that communicate with the "server" that performs the +operation. + +![Leaf To Component Communication](images/LeafToComponentCommunication.png) + The other nodes of the tree, those which are not leaves, control the "flow of execution". To better understand how this flow takes place , imagine a signal, that we will further -call "__tick__" that is executed at the __root__ of the tree and propagates through +call "__tick__"; it is executed at the __root__ of the tree and propagates through the branches until it reaches one or multiple leaves. -The result of a tick can be either: +The `tick()` callback returns a `NodeStatus` that will be either: - __SUCCESS__ - __FAILURE__ - __RUNNING__ - +- __IDLE__ The first two, as their names suggest, inform their parent that their operation was a success or a failure. @@ -62,7 +66,7 @@ when an action returns RUNNING. We will assume that each Action is executed atomically and synchronously. -### Sequence +### First ControlNode: Sequence Let's illustrate how a BT works using the most basic and frequently used ControlNode: the [SequenceNode](SequenceNode.md). @@ -119,7 +123,7 @@ __But__ there is an error. Can you find it? is interrupted. -### Fallback +### Second ControlNode: Fallback [FallbackNodes](FallbackNode.md), known also as __"Selector"__, are nodes that can express, as the name suggests, fallback strategies, diff --git a/docs/images/LeafToComponentCommunication.png b/docs/images/LeafToComponentCommunication.png new file mode 100644 index 0000000000000000000000000000000000000000..67a3a4aeece8126d04d630a7a8aaa88cb3be86f3 GIT binary patch literal 7077 zcmZu$1zc3$vtJPrK|(>05D@80Cg%L%Kw1SXNkA zSn^%`{r>O$e($~g+`V(pz4x3mGiT;IGxtQQsmK%HQR0C>AcB_)vKk=J4MpJk6c-CP zE1=U70CLk^=A{-cF7Et_>JOkv?D0a^L(|#H18nAI3DUIj^zg8BGY=WP0|HS=zm%2M z@}5IvK@3U2r#;Nn!F2llX6iiHcfHheq<4L^QcPjDb-O|vX>{4`Y8H(fE7ZzxIbIlO zRU0JXDS)HrUX(_#Oqoha)#ZiM39`{eu;|dOyrP3kjxX~QSYW?bu#!NM2fkYOKFC7y zK?lJSd?RfdC0f{^pxB4G_@JQX8=!b05a<90B(($r^-_UAkek=X-G?L|!N#VQx|?q+ z+J5avMMaGg3HwsbsFz`>-s}kbpKkx`$rqcPoLpR7{Naf_dS`lMZfdbNlT+h8HkCF_O<)gc%qA+eYK@bha`XE%*eU)|;4`n?RIB)+{tS9bY2p-a6DD%;fb*H| zZaHyrr-k~}RSQ@uX)YbI^$xzX;v~L`iprvYPGe)Eh`6}8q@*M_w<=o_jhMH~U@8x` z^vvw+;v zE-5L=s#xFK%T7pm9xymO%oNC)Ee4Sp=H}pFC}Pc1|FN?2m@K-+3e7Y8e|U0>i=4(Q9rI*PpUQQ*$A= z@X5FgPkygFZ!ip4A4~%lE}>l!VGcYe;XCv7c z2Ls&h!qnvCDe>{~VPQCKw%XdsadE2ffD2*j*tobj1qOQZuCA_qZ!s8^`RmuOfwlJX z@^TO~pd)5rWVBV((c#~ow`FBz#R?7@vO;+`pPZZ&3En*jtHH5X9`WFxJmvi|<$@si z+woem)IG2OAN+sau+2t|xRf?3I(pv(y9q0<=Q;C_T}RWy8hxyHGWRGbZ0+nC?WZgD zTJIqmLT(Q~cK-d!u-V&nq23j6D@Mk(nM(7Dii+ZiZrj@r#dygujm!fAWc zC@3hLoSbBG)lkZ|L3e)aD${CcY8n|Ct+`=f26bed`m)1N5l=g5>Gq#p(aQm6h_<#i zz#a}C;B2&+vaqvfi2HiExcqJpy?uKr1y#9#=|eJo zqM)5HduP+9f39#KH=lnU^#K_Q>Dssb=BTCtO%qH}K4risxPD#A;F?yn+{ohOuXlJFr7xo(!#W8s#L$~cm$#m`XySCVv}Eh@@n(@!vqC-rh`rDh`lO^J|5EWo z62Y&_MPEnC+Z$jo&f$me-v!V1m~;L!+|VJH-u)~j+&iY*iU%`4`qbUg5z_Mub9P26 z;!(_gJP&QL7L8HU(W$c(^gjrutuX5Jm z_U&*CY6JSry^y>$J?$m3psMav4ywgA)Yqq1Z8J8UC0e8kT>^0HOmtypW)p$nOj3M7 z|G|)pJW>`2jVz=Ql*J8W4xR@9p2f(Mlzn_wl^5EdWYB-aEh9>rtq{+(G zqoLbWA_37dx!yaly4LdpB{vm2yHY8-r+j?wUS6>g5o#=?jdQcE%5JUyh($Z850322 z%*+A;0`w94C{%Pr1f4+>7-=j4b+)tH-ra2uyt-5Y%j)noF5N#0CGbbxAr`lSTJ*#| za$g_Jor$80K+M;P3JZVHX16EpA&R!8^{&4@CM1Z8 zzo}kN&B)Nv(Xk&Yuc%<6dQRL~Y2MTOLOzyyAB~=hDlDT|w7WC0I<(@Fo}OO3=D*he zz({Fldz+e?`uoJi*)caKC!)TgqH~LJOT1S!f6dX%EH}Hhrba;U&ySZ^qv@WUoLrVu zvAr^3_ykX&crw`0k+Y$=u&{e>PM#KzWk%rLjU z-W!k_Sd8t-_c1Y(sL;?*M@Pryz^e-+{HnFN`Ml&WX^+XdkmO$Ge;-|=8KvUd~C~uL=2ic|fQOC!hiVSkP^?_mQaAq0Be| z50YDM31DkwWd)y%LoM*|;6PDX8Bw1e85x;8>KfP>r5D zz?yLzHIkB%$z=(*Ftpr;1n$2?4z)wI{t_ARqv;Ne@p?Mx9ha$GH*7D~^-_OWxVN#U}YU8s)$FNAhp+H>0)9 zot%c(+^mN)AwSw~9LJ^c0!E1E>jmdV1s;?w4qlCMJ?HGc%i;n-6jAc_<(C z|4*Xe?Pk@33#7i#fYTDdNFpQqMsuG_p6ylvdEU^}9^h~@U(A@8n1Jlhf(7>KFI}@h z$^w_`oR|03)+_-?v9s%6b4%ee^4S_^G&*SY!yFW==g&9@rVK3B*poNN09vZ61FRIl zVnpUM_q}DfYL>7+V@neRkf9~*V&kZm3}7$4rA(?si}2yooXSe|IG*U}Xn#My&0~#l z@{j&UiwCXH!=*uq>}SYs&m12=+<1@Y?bxilc-`II-@=LFVq#wC07x#hXj;GJNWAH9 zp%VJZ+=US282tYwIyrr)Mx>FU;ro=^UO*g?hiA#4&lJ$mX}%5rcmNcAAdtl-FwvFm z`{1X1XLl(x!{5D|oSyz{P)FD!a?{KTokoxB=#crKAWJN(t*vck#Y6~}YhTzcOAS_I zS!e=tOA`Y)wz2R19eH@OS3=yhbN1|ei6)Tg0)~MteS*Qn06y@mJ4U#O2V2e>ik39R zdnZFjOfBw{=!cTCv@C$Z9HpgisMz;P3@?Q#1BFIG!CJXqRqwOf+S;+PF?Q{8HMS(- zhR0_>eZ;1$tV~EqxEfeIx?qy4_VCf87!=i4RdX9IB&R{`$=O)~t&sE5D-|V%`vwN{ zd3p4`pxGjJkAU(QY)Osv^_h}^#?$lLKw6ZZl;jCm>)kgW{1=V|pLTR~tPf?#??YLp zDvS)&)juRAV)M|Q)uRO&*x1<-2n4OTk8H~v5ceQr+3RrETfGuE8#q!xhN?sJbnmAf zXtw7^Gtn521Vu40n*$oTYgFSYw*RLBI8-W|!lTOR6h`l|+cTdi$J5wu0W({<8Nl8h8Y}tJL z)63OYWYLVIcmg{3xVXB_-uox}zaHPQfQA)sD%skWBqdGe%g1@Zh{?%?ymocp$>d`7 zN<7NN#9RVZ0#F$P0R(KQrLMlRw-<1FXd5gQH1X)Gs*(+tbBWgW&!6;U(TfWU)nvD@ zv43OEi;G!+HShVcpawu|8jpF{)F1#mD9kwk&)2I>`8*IJBp|Sl@vGD=*C-KmUINY* zylDU;_z+5=T@j8mK&8>u*}1y0Q5KCSak}}W!EkAdkwOa1BP=9_jn$s}JRCPfIPkK$ zrNtizQo{~|!IiVtQO#X%c%UQ9xE(`72mn}we^T5suNq0T9tPwQX&0k$zC6b~{K|{B zZUx`i@E@&P+4mmdueccoHA%>pr?oTj_<8f&_Jokx6`@NoA>dedlfu z>-_Q~pcxn9XnN@?c##Nf{JCwh92sqQp#;#y_%vOq?y3WR=2lI;z!52aE zbb)_Mb17yB4_R<${FG^|wcr5XBm&Ku)Sv!t;C{M3sp_J(C#NA?w6Kw^qLIw_3Qiyo z=HzHb*$nAW_0i0Y?1%gMxl0p-B;mt;k10M?HRqF{sEsM&iFxL` z#=;!!c7NKC(C$gjR9w||y03~<_F=dJcpOH)m`#8g3duH4gT~=a2zOz!L*;NOnY@Rr=sKT@YLp^PE z9&G)V(u-Ms)Vj&5t0P=W$!LeXB6^6Fbz+1MU6hSMotJl-bem;7}f<;Tn5654^yZbf<3d3#wU zaJVd^=}<1wl}I563Q45$`4O*+RPXS_;`SgHjXvq7U66FqOXxwXfj-}xRCK8HlW>CO zvz)N=6Xgi#u}yZtErXNBiDA=a?&B=PLu-_it6%*URkk6%yQajnh{QtR)!4xH@Z5u4 z(Qjw3mGA|j_7_O*4T+kUu&7$V7dYlUEc(4AJYAwr#v&ohetSZ;@7=EgtP;9~k$C&_ z>G41+s&l7d+3#|G&pU42pX6r|W>QjiD1*Oyc05Gf+w|(uPSKU$o-sIFCM%%CI0PP~ zo_EiFf(^>K4=?al@*6IEE%W3FSwlxsB9Z^)ZYK|)f8V&+!LL4whL3w*Ryu^7c*Rtv zIkvo8YsievH3b#lxb<6(B6F@;9inmFTnqBVZ=+6N7O(xONtY^8`MVo#d-bvlChG*A z#)}BQI5#+EZ;?m!#&t{w+M|z}RGHqN`h%I?|Fm;Dnkz%E9!l*5EIvxzI@M^w4t$LL zih|++xOUSF=7S`3$SP{6{$$v=zVkj)i7}~$09*PY6@_OVUz3}Sy3``*rgDPB+7PXs zKWd3K);omGX~DN+Lm$i@+gw?rRqYjT6bQpmqnxU>#bfQ9)QuCw21 zZDD{hJz2Ug(9p9EuuDpQ)DorZz8t0?W6gb;GPj21>hv1{drSCTYST9k9xFb2L?JsO z)ehwx+28qX-V?BkEN1522+Lsd@ApMC{ZeAz4iS9Ra+V{P>(F$TV+Gk9J5ZdRD}Y~- zN5tigS8Gh+6zr*gccP~ZxH&t^tf!TFtH4w%Y0;v##CLy32TUE=hfM`kVLHFNIy4y zMoYk~YzW;K$*j{}Gl@{>*h|Hd5Nmw^L%^ zK3nN(==8xX%(GA+{w4z zUkF5L<>zM(x?9S`Z-09h89i>L@``j?Dx-Fo4*Yestc~$Oe4o5$OGGmXEaeXGh|b^< zUgWcjfVQ1RKwRiW;m$8R%)#jQk8UNuOv|{n@s`P26^T3VB6VmbN{H^hWDTTur#>HN zj_$cMKO0%x=7~xM@U`(i?K)iS(8guZ*4JPF&h4Ln8=lli2y>P>mpI%0WV*B`0zpNX zc~NQmaO(%w8xR1Y>F8X!L}fwxlwnV#SWB1LcK%6u|j`;pAjuqW3I2vH8NZly7Y+1PIdjI)&L)=f}ifu$t&|`h^ zw!pngJK!}z03QGOQ?pa?MNmxHTP16Vgn;+>6a)ZSA>`{; z3tK@;F-fZn4=Q&2Bc`6ty60eMgD2dsx9t*%iNiCN80(ygc*73+YF3!l{lP@e#Ftjg z6+t_|w5hMCZsz;DvxdYMtIYkmA2Z>x(FL?VQK_d@?{IbZbRVl?N>i=TE|fK7r*yG^ zg>Jg$HM#xwExdyP8;BB()>Yrj4NWf62er$N*+EQ2^kJA}{(Z23W4yS2>eAdWyNa#=J zb7O2RyUI5%{b!eUP5bY*cMk?O+Z!6vB8694KHqoS2=MwHpa&QQfU`ICVE>vzTF35M zA@lZ!kv_~;GH1F<{?E-J;O@Wci~rts3gXJ! zX5DO*AdKtL6u-GCMY)>tP8KVu{n`KCmjVX(dyK!+{U3T5Ne}JZ`<8n2N5DoK=;aF) K*$NrckpBYlS?H$# literal 0 HcmV?d00001 diff --git a/docs/uml/LeafToComponentCommunication.uxf b/docs/uml/LeafToComponentCommunication.uxf new file mode 100644 index 000000000..ca5f6103d --- /dev/null +++ b/docs/uml/LeafToComponentCommunication.uxf @@ -0,0 +1,109 @@ + + 10 + + UMLClass + + 620 + 150 + 100 + 30 + + Sequence + + + + + UMLClass + + 540 + 230 + 100 + 30 + + DetectObject + + + + Relation + + 580 + 170 + 110 + 80 + + lt=- + 10.0;60.0;90.0;10.0 + + + UMLClass + + 710 + 230 + 100 + 30 + + GraspObject + + + + Relation + + 660 + 170 + 120 + 80 + + lt=- + 100.0;60.0;10.0;10.0 + + + UMLClass + + 530 + 330 + 140 + 50 + + ObjectRecognition +Component +bg=orange + + + + UMLClass + + 690 + 330 + 140 + 50 + + Manipulation +Component +bg=orange + + + + Relation + + 580 + 250 + 30 + 100 + + lt=<.> + + 10.0;10.0;10.0;80.0 + + + Relation + + 750 + 250 + 30 + 100 + + lt=<.> + + 10.0;10.0;10.0;80.0 + +

{@Ns z&lEzHwU0B|I{HRd@%7y{d^kOLX~@<^kDRdD!1HfOG27ki+#0^-d^O~iE-eHWtYv4> zxYjz80GShrE^=j{)l>ZA#QpgLnA4Pd%$J=z3Rk7L@jaCuRP@X3gx-E@P(1ajtUoeg zj?;GPm0~zsB-k468BclRkuy0!IIx&1py?xVjWO(Ja^hyOhGqy`30aAn5xK}O91D_Y zQQGJnz|og|ZKNLJgtDNvfXEHxihb5Lw6%4vz?#+A=2^v?UCr)}_;)gifF;fJ0Bm&- z^g?aGSjhMSYz*c$@-01_VyD>DQcF;E`)Aur^46)f#G0Rv+;^6k?m<#qDj8#Yy?ods zd8HjtO_BGYq2uVm%zHT%6r01<<}GZfHDI_q1^oQBRn1=GYZcru>9MC-c-1N+-P9;MKsj6d!1y+Q5%)g z9uh6atG3tc)s^E7`oqwuumY063MdWwh$;gh3X07USQ1BpFD*A6vqC?5RX0#$P() zFP-t1&iG4b{G~Jg(iwm0jK6foUpnJ2o$;5>_)BN}r8EB08Gq@FzjVf5I^!>$@t4l{ zOK1G0Gyc*Uf9Z_>Lpp>BD6$ntM`#wOt=0WIvD1bYC>9PHdCl9VK**9qV8h4<7y1bfRR zkK@)WkE`>T&=f`4M3p`uQ?Qg^K^=8}E1UoTN)uQ>0B~@0Y;bULF4`)zfkC*BRFrI0 z@QVW&e?idi{8R^^K;a&>39ui2g1u8GjfxE5^5kL3zsKikzxjYLCNKd700H?@_^$vUJ!_E%a6mvQ0<|l9 zpXAvy0xtkE7#ty12JgFt7$CITTR0%<8`|638~iV_SM}vo3!-QMT*D$+1%NMLTpWP4 z0DR^_OZ_f-eZ%VV=Ybk438#F+Sq)O?t_a8(b|m$|8Nr3Kb8)ou(e%lC<~IRk-AVn* zfid1v>*n;pX#9MW!2pbbzsNVbJAA1A=U^4Ues^KtfZ74vI5;?7KsW&P#Q|3OH!?n5?P%q}Z}3TPnqMe=^=!e@fP3!3fmYBB zA${J2pIyLO{Q>FZs`d4*eW|{%^MU;Vpu<|Bdtj_U{R_VTWSL=_KA`!Xw;=Zb8Ft*T zcnJLVpRf7J3rkk({RA(0zS+L#wOwE}C^5aQkNAVW3loxp+yOc?T0sCRvv_a-2*AZe2y(OG#k}ZqS2E);=>s*1JsucJPArjrtnMV+{tfGVBe*v*f2fq?F4$rpB} z+w%rx3l0dhqBo1MI~NmxIxcYE*GazJ)aLymiG$zyEEejcQR>^f7-j*-^w#s3!`%&# zfSf#z{7q>;7XiKp`=v1pO+S|35mw(Uu{;>Uda0pl{{eku==!FB| zvf7PE@27LhAC?Ql zguUUSLo2v9)y7Q5B->v2o)f?5*?Zb>PKzeRWTaxclQAzJe$Z=^bx4aDB7G|w;d$Mk z;*nGX>yZ9Hgt7WYUZ)QFj zj{@~Decmh1s1v&Td6nJ3-lRu;qLn?HGt4slDPjVV)=r${vYYrt2^HeJOBy<*f6A*B z0!`_}psAFm>A3#N$y`Z*r8r-ji`AA8>bCD@$3&2xdknqnW+ZF5B#lf?rTSf|mPEmm zhDE2%u;JHLaxAqapF<~|rLrg*SkWooPlIo21Z(CN@^wCmJs<~D+no&r`gT_YI`(jP zf(mKFc1siK>W{cP)yHMje7Yyy9#4yG*O$mBid|3WZWYFNqtNZG9o*J3(tRhin$dx<~1pO_gX6SXY& z5hET&bHnHJbVQKwqbvVtVj|?phaY5}NOpDz=-@OG-w56lV8?JKwW>kJGn~s@6w6mEJ6! zF=kqz@R=&5&? zQ{haK$^Sk_+h@zmJy!m&q_kB+c!{I!pMjQbJ0UCznYX7x?BM)unyR$QA96HSRY?;I zhsTNOhmyF%MmNb&F%Knfl*e0i_D;=$Ez};wYV2FkE_W`{oJHmhXdNOj@p-sUbZPX1 zO$=-w@2eluj#KX*a2broi>(KtVj~TEbv=2sC4DedVUq%FP5-hlL#>6Lvk!2BAR6{6YJ8sY~C)k&b*>n0G8d5pMs zX25aEHGC$Rr3UWWSLOCAJ~hakln6LNIi|Fv8kvqn@Z*ncPm7?g2x!O3E==+3YnzilPUM; zF`yS{g>-9NR;AS*>kvh2I^C2VTwRC>=~t!=b4QqR*SH&@#sPJN}nhaE@hEx0?GF zQ=S$fJ;|&=)&WO6dfsn1quQ5%3Z7am_g-S7>N4Oc_XLIsc3M^iB}Tn`&Z&wN^J=%tq(JB<5O?U!w7~pn+4RJ0 zS25+GA4B3S1A*Ag=FT&^@Z%fK8yk~%FW=2SL`E5%CZ)qXpU??g`b7J+xy=VP=-q6r z2DPz_xC)PP^o=mfmsH;TyJfb}Pb*XSO8zbA@Jd`x46P4%;K)=2{{4C6PF5XM{ngy7 zNV1QQz^{Yi<3?lYsuVw!5vAv7*rJHdYZYyhQmIpmhy;%>;f~W))4%e$HRb@&i85M89)?sIb8(IUbvQ+@;>qd^7!s*kp``oEWk?S~>lYTZ2 z71@462#i0muQtTzFYCiPQ_HG-$y@-Jqv__{!1@A&IPlQsKG)mXD?%cEO^Al|^BAqZ zauvmA=82xHgdJ1rZF4F zq+wi0C5$j)Q`y&`Z2sqKkM6a)bg(L4fQ*OMf$OfX-xwH~*UtW#GxmA%%wj|ri#L0C z&~WM%u#Mw`(69M4dzZqZXGrRe&?2kl{Hx+N+f4Lml zy-i8Q@{UiH27NeiZ$vu3AT84IK2xrriU{K*_UX!9>=xvUdX9d< zMTx?R(_87gVb3ifU6zU-5RH2%r4as?7!;l*l66eqe^5R&TN1XfsXiL4?xWnyQG+=W zt9fr)@_K!J-$m0|vr+QkW(1%+?FGFDrKcFdQUf=Y0ehiMeCZ*YVc?l%n9IHXXX0+I z4!9c0+Yv%dDw)Ivwlh->G<-hOAhY?ljKYR+R%MJZjHrHDQ;~+2w_KZ;nt)?y7gB?h z6~j>S7{MF~y4)~g+uF^Ds-RD7p6E&;#J>2wQApM2w}+(EjbFSKt#njj`>L_u(&fw* zMDt%`V#D*OUgW08RekwqH<>b3P&br$etc9P!#7h<=oK<;k?|w% zXJPvh(NP6<^jA3IN1&4J4r$w~?vfxxM+o4{6NIuiCgNd8jG?()qlAhz_I&WZHI}rvm)mGCu9BogtR@Jk8^EQ;b*`cr%MPh)#h0ho)^52w(ePeh| zJ33SDxJb|*fK3}(d_;()`MkRXEfEE>LvDWzQ_-0si$3G2D+2YiNlt$+x`Nx^Blic$ zp$)7qDms{X_rmja6;lli;qy9`27LaEL#bl10X>g&SiiJ^?sTa+1yh9xUCZ8bS4@!v zX}H@qu#Bt*p;`EY?JHK$QS8`7%;EAZK4M&@_|(64zfty1lqhmu>zP5JoDV3v63-$Z zhuibm@kPu8k7iFJ7E#mj^(PTKM)8Fkipe6}UKlURSjQNx0R?a;;V@@%&KxYy;Q}!0 z+J*c>DjS1F$$22fT~@Dkn=zOBkpQodrVMTBPH4$@6M1d=*z&W;al)(8IX#mO7x0ls z>xp>yJhAbtu#JtbHgz|kgle*zzFmSS%U7hy-SWi!aTmdl(l536<~1YY7UVunx@w!g9f-23*rdU~51OL*OEMoDN+O^{(AkI`LbR!{QM+)fV`Sc9ws|C`LlVEN*u4=srN zYh`+_2)>s}UUGyI6PYK5@o9bCgMzI~9|GoLv@sx5?H=KG(cmd&G2>Vy7P{w@!QYxz zampfjt-Uz0gkVyvq}*$VM{AyLIrD1uYQb|9nLzIwUm_YwmTd{WaBhv(0kc+qiJjp= z)Mk@zj@8|C4NIjOs~VT_<~fo$t=fNomHu^UpV=x&`@<>($mFgKwf&fQq)Hq^vf^3Z+)#@&|XW<7} zJ;~rfd5KcgM=E>nIl9H|E5%ctcgK}D)GF>Po)_qdOT$P2L&v>~`0KyGJ+~L|Mc}z< zdQ>Vpk%AAN(*!+tk18q_V2CA~H@DkPJI;obFvi%}8?H~PB5B+AXoH=3h=eb2qY?!? zef_I(?izR@)wH)5C&a2#`O*03h2wJ31@RuH(WEH(G0de7)oEDt8MLq5n%havU+k_? zH_lf_-CsbF)Q1vRkLJB#OwD-b}(ImEs3V~3efPht+Ff9ZcxrEmd*Z_5-e-W z>99eJg&vJ_*S(Vo>@>PqfZVLrGs#6d%-nqGgRfi7pdt6Hc5y%z6z2gS0sOvM4lGK=R26&hSa+)nRoiq9ua@Jl27vlB(9gzH&kX0+CRX-t=0#~c7rh#j5h+wv* z{wAuybPc`Jxop(kNVz*CzDf|6lT*oIL`}GKh4B@3wx8h6r(KvhjpI0}QJhc~#<(EC zW47o9R@FJfQIo+2UI@iqTL$BZHAQ-bT;XfTJLyiIAtbojxPm-p4O{Y5(|tYYVjnW7i{oF1(&Oue2_z#J{T%|cXh5@@ky3m_4Z`Uv>gP_ znomEV&H{m$gH~$020n@3`nlhlK=@w?#?k2wr$5B_?gGB`E?rM36I7OS&+nKpkEMQt z9+(}MomT*dp+)aNXD|bpxja1xO-#xiVNbiKDL<+gIK(Yc5hPeJHvn#k6$j~~R5{x~o zJeyzdrlvs5Qj$CGBZ=3M4q@0^whu_U?CORiA0oL1LAZ*gV#^tXx>JErk%4NM3$&`! z?rW;cGB#5qp`2a4&wP@O3s+1m4_q%#a5FM&-qSLdg&48_bz)`Jj4O%=ya)oqJwO&Q zwxx`>x8w>zh%eHU%1`k}ifx*wZuI7J8j!LtfwE*t<^-X1vX3Lfw>u5t) z(4;8P?0?ZzLe8YP!vUE^$TqJ#S%>ek(7cJPNU5A4SUDr@Ve+V03*d<;u-!xj>PJyU zlNq0`9sK$F$hqc|c$83T!6Yoj$Fsi*=MNldhNyiry~-WNXjP}=!X-b6f03)ej`P}uDr%0x31 zg@V&Nw0X@(r0>-e8jZ+F%;jO8DKfVb=@up@G-UmIBIM#EqWE!R%V=oKUMPE(=M~)! zMVs5%mjM6nuYdAh92NHCSOKsvSvx>h z$F=;WVS5_({5mSNVE^h7q>guQYA+{?7yV;Rzov(Hn5b_Q$^A>E^S@o&i2Yg53fE^!rJOR_=atL7&3uBUM-jtHWT?fIkk{5v=kOSS}p1p4n}@$BhK zc=t$_i*FwV8dFRaFf01h!oCJirM-IM@q)P6NBV1%8G89Ve11a^T6>(Sf6$t^c<*FF z{AMsh1kk!X6TtLGyX%1>1-8Vy>&BW{dJ#M%s|yQC)2kd2x|DsJ|4H^jjf|e1 zp%$U}aZX>7zO|zs__4dZy(TrHW)ymu{aIkG^y+_L73MF87e^oBxA|JC$@spJx%#GS z?j}Qi^~XO)IyBqG{xB0wpeEfmHe4J%==4SLBiyKr?s4Uxlh3O`iOI~KFobV7Ag~z< zkY0vVPa2d)W_Y9r97J6!ama^qA?WI9)si;`jOfMIDu*M6M@f)&OQbyU4BStKGtX=n z-R&rQzgqL3IT-KN?i#?0>DRD0dO8{$pW(9Hhu8qaGr$Y_HG#6;6tC;JXMq%6bc}Hh zxv*gxLg`}bVW9JxNM>dgPtL|o?EXjThRv<$i2LY#*u-K;){JAN z^m)F2wmu;D)9rGs*Wf;VS@Lf{ME{+p)c6Q1;U=p+v<>A7tsZna$E`N$jUx3*&8?VJ zC`}II0G?=z0nNBWF6JL8cmD0%U@{crRS^Kib(cI?Bf~KJ9$I$(4`2@6}1nN^O)%uzA2L04SIwU>ctO=Jkixt*?GI#Ep^ zAv#H7aW^Arf4gHaGaji&y^h89qd3l*)G#5~I`0aU~ z65iiKdS@*g=G^>WG;tx>N|Zfh5tap(Sv_GW1Y~6VQP;*M?F^7Cmz@9N@w_@G($h)- zwPAwvBVH^_aYGLVJu?$g(PKb7bMqxLiyIMDI~R_cQpX~KVC1+jTIik+%FxqSihwIo zF8q$fXvsi)f#_^3gqk%b@hpkJF=RL4^tT;R&v|Q)Bkb8gd@iXbP_mw?{6t)VX_0Oc z&#JqRb_>|EL=$#TjXxWkFQ?z_usrODoZ{<-im=ht@z^9Px9Sb;F6EQAlnH2Q91T{I zl~S8ptyif|9(vfJ_N=yT2^0^)hcD)bb8X%_l^d?4a=>?SHw_~I|Ejm!!jEkgnHiTw z+;td9o^=N*B#uX68bI0l^Wi7UxiXBtv%bvF?}%!J7t(dSG$~}BjLu9x2de-IAIZok zinz#!Y{$b06@i%mBW9OJ*etTnbr9Hzk0G~TkV>{_PgA#h{|4RT7Gqp1FlO!guScBT zz=k$`Fr;*vcY4D_Ac3xu;Zr(micGbr*!TDZHK$Na{;~Yu0nDd>?rf0;1`cUP`l{ab z$+=Q$C>@jJVjFd+ytbe)a(hah%)im2`+ZvDUL$H(2CIu;_(cM6c4C7f6-}$dvw>B_gkH>B;FR^a<=WmS@WTe<8 zkAWzj(0%m*yD`(P8%>V#qCYudpNRxQa)$> zrG27Ov-)5R$b`Q7L?;zH_`Ct)>_|$%id$&rvvyJ!_MZ^jr^E#mh;y<;CEQ<%Fc9OdzKIBl1#e&gC~w_2Vk(NFcc==6F1jI=X_?IC-EQ@mq6 z2p{*VJDRi2AqVQlZ(3DJ#igPe2Z!VtX>Evg*V54lG5EL>VD^$4mACU+Etd&BPQklN zZp&AtJ4;7BHCq^YG-TFqp%1zbIY<@CFGpkxs$&q$!`~Kl=8WB|MfaIu-Fss|cJKD) zD-(m*AGrGGr7Tc=vAbD2amVyFDNRD{m~~^4_`f{x+IcB5-LuCMP7lNV??CRB>*;m2 z1XupScan8$EVS6f4B6dfkEeWAT{35lp;`o;Jwwya-C28sh%hQp_NabhbzPKg1`3AB zd|<5JYPzJhTp;#36oXH@YR)*Zk!%MjD`Yk?UmMPxUY{J)S-8&l_)&`Ot2bb`CF_f8 zrzLsG8VUx@8`TrOvUT%$idAT|8?@5V8}Y`D5uLflMP*xe2*#VwHeR26;*=X_osP9+ z89|`+uujbmA$j&s_v}&!>{gCRz{WcG;W+Mu)3kOLb5%3(J{=QW88_^=k5ZK(TFk(h z8gGMj-d)YJ5CI_e{KTvR0y^MjvUZJZ5uiFa!PczNNUF|T8OSIV=P@xRp<84iMC8Fe z`hBc`jn9$i4j$@W<)!Zx1Pd=)9UkcpFQbE<94@xs%w&259lEsHJ zOg`_QMcsjJXF4!gNtKPZ5^jrgUsE1SFZz~1HhjU0ABG+yyCUg)u8U7uA}|MHXeZC~ z@^wW#j&NITcsf{n9ECbL|!#qg9yy3ZG%-5K(U_ z0TaM7KJbweGCKTi0kG8k9$iy?4z<1>oBn%qHfDC`GSa~-ZqVGF<4C?%`kG{p`s^9Y z87F~&evC%XW09R9epEO{8!@#_D2#=<5G5P@M+5bV$O5Fc?7F*-SzMlvt>J&Y9b)Lp{9 z0OQR%P8Tk}-+kFjRlu6_GVk>wY5w} zpEll(Y#Z)onXIAvSajaN4`1_{WtZq<|4fdDA*~^o?>j=5(rc6aE6}OP-tKQ$&WuRW zs<9Y-Hq2sXbcjRS+A4a1A?dKTspfj&$`tkOXwOR(@BZRG}*+!acKv=NBu< z4q2_nNb{Menh}v12EPgSwP%bDKxY+elCG1Fs0MjT))KeH%Sen;P}1UA5)30pS&cQ# z4$1DN3pX!fo9xKBL-?`@?7WQ>7ekj-vu6!~w)$rmY?Qqk4<8D>rhiS#$x981>|$^u zQ*md{C5k3&bv#M)QG4IPL&!8n7K>2=CXMqDs6p1x5%8J2tQM`kz9Ca4CrPz7MWJvWHsV2i_f#|TR*JC1U9-J9+A@qZ^agR9Deio zklLGtiPC!>$p)vkvK+qz8FIx^q2E}*S-y}zZGq)@Y3Q=5MrXIm1{c&|10b}`#gxYV2TGa=*O3~#&`~5h}bU5 z{NFLRFv_cF{l$qDCfuxi%AcBrhM=NW+ukO7u}f7E?5qbfQ~}^SI-$0^+e2=w?<;{9 zX~4GW^d`dEMW>Zp2>z^Jx_{yRueriPhiX);d5nAwA!jxwcXL$D3av4LehXuOHVzwV zr}FSNO6^$Flno)g_>8>N%A_>9a_H!x9t(ZWk%_qsYEb0M=M%v)MFrP8+@BceX} zkz?nVf;9_?dBaqCCfOzKtv4*ICW}W16JhB1XsBbz>!9(?)dRxf>tllx(mfms4o{RF zyoTau;AYhN8Qs^X_vHXjd(<^=&s@_+hU>G3NzHyL0x1W~$j}@# z3i!CSRb>=lfPkPLfkHq?jxK(bQ^2=lQa!d1f&>K)+3z0GF(Lv2)R8hk0fT4ee}z~x zBY^$%5c~cFv-Cu8AV44i0u6mg2M~?{K;x)Zp!3I|P^+Y`WmEe)cEqu(!3 z`ykGM?<2z^w|`XN<6J@r3Jefn^B@H_gmLMS2LFHs;NilA6!8A61}F`qg*YRh9y&TY z9)fTZx*bAdQPz9|uu)8*JwOD75NZ*q`{nxqX#Wu(voq--xdrsnqI_)Cfwzfu1R@{+ zj2-}h3L8ksghEe41pyd@0Y9s-0&L15tlyc$?m@l*`rm@}&rSWgck!?AV+$JgMF|=( zY%f59JOvEe0IVv2LkMU~2BV+Eb;1J-RQr(y;rw%u;T=Z>aRtycLh{SO0Z~X?0S#aP z`0E!ALR26}NkoTqeTPiAGsm8$r5>z4K8TA$z<`o`eDZ-(00D{VaD(sN%W4T9*fGfU zhq0!Zp8O<-phhR>1IAe104=P%CkH(u`WQ0@76c3lEF=ml6at7~1~`OkJ^9+u+Z%#> zq#plUiWS_yxd3qo(l8bf=q^}An8uGJM>>WA%txR@u%G+Gdv6mRoP)0q3Q`1+j(|lG zdz5#N!8ZEY8l}MpbOlcbVB9_e2k`&>^RQhOQ8gL3D>X~SlHj%m+`zt$H0t}&kzBJ1NrkYF`xn%_=h+&4rdepQBA;z{e=re z$cQEKqjf8f9i+I?H&*}wJXGU1sVMLc2oNF=z$3vB(yuWHAnzArS3_{y2LZo-6gr@o zjsyVK#NLk;NAS^MW~c~|hit~~P?hJG=>G!NMSzfg&_@x7`JMJ7{e}?14I;zD3J1;) z(@YI-!$Fr~>Tslqo7}%A%f*JYk2&op6>_P9!=@j#BrTt%Mz4^0xv%bJwN_1f=9A6H z|1g8BJD_qw=rTT3+-x^wg30XX8o`To=Q%viB&Qgi^1>l_8~4sFLY_K%bALrUyr{;O z<8_Uq=RUPXeze0;{*)}T9E8=JsU`Ka$YOyx0@Id;UvNp|{j46^x3n{(;}!#_5y=26 zyDVj>m}bF680k#i(YwC0#Vozy*u}anKeOWR8h-;CrSxD3UlfF37%#wVRTV^8qGCBb>oaz_Nic1d_ zHly721kWbDW&Y8bHve`NE}GLlegT_^ta4^A06ZsUxzUheHY!ZkxLc zC@M4725)+c?8bfLJj01n*2~d_zh~I9vTS0+_0P5aub!k~S5Yh=?q26%{W}cI5eyB` z*dr$Hnk+KjG=X)%;`hI*)SF;nm&2a#kxR%wW*F{1MvvVy$ImBUV3S4 z{s16Hy_^&DAkq?$6$E*DVOP$JR`MK$8Wl_Y8Z@XhO`AS$p&A1xlaV7gprH$GM)^Q! zj>XqRa^Nr(V!qC*`Qb|dvv*JaWRskPB&DuVCbmIa0-P?=RJH>LEn5z42wJuN(-n5u z5&CpQ_$)<3B`@L$=YVq$S%Q4+Ba^wDHttug24;>6FH08DX`o}`0?V*$d6{uk6Ax6$ zSnf2+4sQ}JJ|T)LG2(s^UXZgn_3F`$qA=J@S2tZMcf1t0xhmEP zl2i58SZgKZWlIdxZ&?ql|76j>j9ze@-phBJ)u;}a#jaDSPDZKs^`T z-E-eOf6YX|pgrKXrzB6LA))B|u=eDN+(1ot;hqEF@KJ0KJjKe>pSP?&8XJJm6G_Kn z8aX#aM@{QwT~K%b7_su3iu4o!#Ke3r5f4Px?$@K1P$Bs$I1C{e-G3UBI1=5D0Ge;T zj@0gCFX`1ObA0o&(CxwnuxHcgy}%1UU9076`5l{RjKjALR-tr5AV%g^Qq}!aFyrU1 z=(#0g(PWZY@VoR`HChiRmpw!w`zaq(*-JX;b3M7eTk4fDaXQ{j$+hJJ|7d!87d7e+ zncLX9o&}SFCYD}2#{@sJk{^4ztG0;ErG(2v$@0MMgx;doX_j=JK3i1tNFug|r9l^N zTahp2N>+XDF)Vx9;i}-3(XL==wTu~zW`6N(uxNAomvz7SL}8;FVlDnU26&T7KGziE z^D^M*PM%cqLv=T=_u_$wu6QQsG~JTA>QMN(XUjd4*fX}}f-6du+e~j>vk_coM+!`! zuuUmX>Q}&5jvv0P@JWzeTW`ss!EN9L zf1prvxW(ABm5zWtxVVuz0^meiE8l&9ydA+#PgIL==q2d8QAPiQlC`bY8#kCI0o_Ji z{Wn1=0lB1w=AFuL#d>Qle(YYtUFBnt* z?yp$a^kBVvU)*nw^ya0YE$v9rT_+wtNQ`KyoC@*m1T7IOK`&-5+^fHs>d@#-8_1p^ zZ>ro_vnyR08H%nS3*Bu@B=ToG6VnEqD9iV%P7>#&FhxmcjL0k?pq}6@7yD$&4p0VD>j_D^IhVT5KvX%ZcP!XhL+oXzVg>GiK&4 zTes(@Pf0i-IwHbFjkd+odxq%^8d@scb=5?D0cKMhRL@^7s7zxh_lLDNC%Wue*tbp~ zx)XS6fr!8#ISHI1@(y>AQ6fw??mn=TKl6=iV_cuNjXxol%KRZ`$`(r0kDIQQJn+6B zm7-V!WHGoBLRIH`*{M#%CS^5gHNAFbizuF#r0R!cm0|amuD{Z5)ao^B13Ss1 zb>?lrkX6?GEKpiR|1ME5GMWzx@I;(!7gE#NxcpOa82XVom#LbYFSGSdf9jME1h9+e%3$36^KSnjeqK-w!l zgVPvrK7EnRL{}RZmY)Kx*z!4~?5D($mJn}i)#h5CdNg6wa0rm$i2El(fj~n-=tE+B zpEYl;cmMOGc+K8M$%e^uiV`c(96x(z-5P&!r*Jy8-03&9iqvEK@cDfIIP(5vp1P;A zKhcjoP-Nt|`&u6Uaah?Qz~3oLA1Y8{DUAnBfA@yV_(bM}gU{#Rt)8VotW)9RO{p}| zx)>-vxR%^rg+}wdy52TH&urneYgW=7WK_IgV~4TIObB6EBDwmr=}G*Ch23_lG_w~d0}JO&9N5YS1TIINsOVfpg20ny4b*UR^EAYuKy z$SG5K%g;BOWHem#-?mTDLCM_&ZaHl-UpREX=z_8IkiAJ}ZD)779FE$m`vlv>(CM3awqy=Xb3u`|coXl{t{S;@PG+l+1# zLmTIJ%@9^bJC18reC?IqVhBBBqyyI73&fXI?boFXbHC$;zYz}Nerw8gKE<{b5wImm z`RN`azibXb159*2p5haM$-0C3hrj25vRIuP@DE%-NhMDaLW!^+&Go&(CzW*eDz8+OBbVHIIcr9@7R>JpE=kb>6Z!EAUxNn%4RGEY) z`I#FDKeAd|#>PsVIhBk?PN6(6EhSGY=WD?C)##tXW4R|Z7?7beoSV31wAt8%|9 zDt6QYXQBv?V)TH74#p(??-l`6w2NwSy4U+4YNy@GZN{&)&lKl?-WUZn!rq(#rJ5@{ z1;J>-Q$aZit;l^|VZNZf6kcC!srd7LndZDqYPq?WZ$in)=kfe=WfS`~$cEmn;bVC! zyAkS;shjX;TcT??wy~VeY&4_DuIV@(GKWTpwam?Y2xi)dZn1@)luCDRuGgqbl~ad=i4;;#`C*a@vsJ* zW?hw>M*(_!gUiqu6iz&lK@^%@T(PmX75Hrhubw8+hjqr`b<^u}mEdt1%TsRWBdZ(W z1!}Kg=T5kHJ?9u2l`&Nbw}{*r@F7xUk!4ql9|xnhY?_|B3%ril^plcs6p9mxlu5Q8 zHtojV{``Xn!D5?J-|&c({)&MG(OZU=!{kna+!TYg_Vb4M_6U=e=LX@GiBY&OD!=R^ zM{4+)*@!*1#6+lxug)h@B=hz(T z+%=zvpMv@OMlNxM)prj5w)skJOYx_SymVAg>>+H4ggy>s*GETcjT$PFLJ}G1a%JRSXF6kg*W0htD*tjPEiQG#~0l3s=^a>oeZP zc>Q@6#?)~ug7QA(9IxJxTd}=3A5gBA5=FYHz{Rhw7kpHDuAuTf5$?`QG1!4j^>~~m z)TZE>%woJCusU2iptK!zv6PpA3J>b=CzIgdPX688k>*k4T%b zwX-9`W+ArR!wV9Yy-C@?v6k5t6MbiQsa;?9&l@qnlh^k4eyK1YL{LmQ`k<1RnH!p) zxw0E_vd|sGI>Cd3=blM)zYP`G2V3-`A)|{(Qq)1Ftu7?N+RCX&B$BuN!Mz6zs1%@a z0{ho!$~%=M(uJ^s3vyCqA4!u*&_hjXj;Fztv@B<&iHUEUcmiVQSgR+B$4~bJn$ZBG zWY>ytP&JlagZ#Z|qKD8TzqM^FwD+I^$2vHA^8CZ@Ni+62#aiWlH{Op`s|ufPP;}A$ zH?}X<6_GpHvs%u-iy0zIudf6ebZfByNZam{t34C5(`;3aMjPraVIA8(~6U?h&RQENaTxG%BH zE0s;2hklbmYA&cx2k)P((k!}O@w8*5-a|=4Pg|DD>nL)OdCrxb`736suZp{}Ww1RM zY<$do_D_egIQ_k=P@b8%_qer1lAV)rtJP_W)vq9@W8rjxx%^_A;K1D~H6O}BYYy7m zRfEi|UDd`B4V;t%1`;Qm3)D_or4i5G6~i#L^`BrvSD zZ=`!k%Dz~HN5($s?t0VfZsp7T^*^73+hlyiH^D$}q>rB@oq`7uqd!mZNk0d*#Ps_H zDuMp9{h2XzH9e1dYauOJQuAheJvo9~YVT5(s5w#6Z;R`*rD2=y>qOz|^67CjQ&g4E1sMSMu9E`49_h-59oAI7CW< zqot$^iB7EA+CIdfA#C!H{8g2GF92@0v8D8Dtie3aujadoU^zgFU4~A+N*ROI1RI+M zW>ySQDPOXvHv6>TJ=|~4rL$iJ7<0deG1C#kI4{bpkFFr}9{45XE$4K}lxAy{v+)wP zx*eQV2d@Smz^?Y06Qcw3dk=UJbQCUP%zjfobhItVR$FdDZM_B30eQ3dWG+k>d^Kc< z<+bumZVJj!@EN)5i15SZlfIi2u0(Tw>zQk&3kRFe$Ne6xp2g*T*c5p(DW_TEVh7{I zu`}}Xp@;ItRmN>xMZddJ?u)f3^;(k3C(zp6qsrEl%KRKf!*?@8dS_Hir?c~Q*`)6p zruENEtDI1=L@ zGr&nMx-4Z& z){}ZBav3S|8`6FPm$t6-JmXadfu#W(m_^<2uQoq39!L{>h@C+erVQ30Ss@mIeW&WS zvtDqPBKF}qTou9F6aYeQ$gFHgAU`e*IYHihLlQu5iv&A#-l&y5>1}$i=g!%s0e3Id zNWKs+R!r;PrYkE`HEKV<3fm}AW{W%Ip0cP?gH|Ob_)QoV0BJ}Qw?+7_M93~`PWz#s&ypivF0XXnWWSY z&5oke`;c>xICXT+bUO{7i5Rh3@5>)$(pkv}j_wUdVFu5KtL^yAkLSVv{a4V0YOyxW zkutEbv^4H&L45jLjU@8C#&X+;9&or*QJ8Ee%uituU_uO=GVNd-No6XbTMi(k;d;Xb>rlZwG4EEo(Y~Zq}F#B_o z>R*;{4E^ogy%%o(Va*s_?&_!SiFag2+2)~M+R|IIeveaJ>olY-jePKLDxR#{YCE+}_uOp?rc5mvKT^D3-dOZ3m4rZDuH zboIrQ`nmipZKV)i4a1Iyg9Ftd982AvIK%T?&T!ja5vCVchsv?nc`Kf8NB;g@7~a*I zVMEL^-xu4en(i_p9C51SlRxW1gWi|7+sHy8faSevUUL9Srp|3a!xJx`8Ev8d$kbOK zpkiI@_muG1+6K>Vy{1t4v<&A~Ps6}qOF8YnD8nu0JnXQd|52nAiWezqarY*w`p-F) zyjyEKPq!lEx#629&>C31RR69B&;mB{+d-}HvI>ac%`Rf8MdkHTwYp4;W*?QaLW#?D zCzIQWkBZBS3$|&;2ufd@=f8a=d5~f0|5f2`-eyZ^8s#*_e;EF;JP7oA03M6mBQ7ap zT!i1GC-trlZWfm4n)lQIp!e#0D#1clsemSJuY>By(6NtFd1=}w%7aPe`&U16SnySH zm!5=^Kw5@Ml5Gq>8$?ydvgHCv~7-Y*FA&|sFm^ZDi6Vr+Z8OX0& z$zO*vU!DrtTkz>8nZaEcBT85hkW#Def!#nFGcJAu`Y=(5y_n~k|Y8MDs(Yp8)|~iH#(LVGI8AtW$P% z??BhtDJZ@5Kk=g9%dbI&QS+2zQtl4_WIVJad3Mvbg`)(ZNeu-797_6Ku|1~}QU;XUA@}vK6Nx;Uz!Ses0n7M$nWZ$f^Ar2BC!3h)}6D&FzFc5%&P5s_PjE)0dGU$ge z=hFk7=PNqcBeY>{G6MuVxDFjoefxsEXTJkRR9838*EtA`0LKY(3@8Nf!CZm8^{cxC z5dtDNBLl_3zKcWgfwI%AD$A)X&&|n$oF32yjkZ%gLIe6iRAW0J-@=Z)59S2s1por4 zgMYI#AtJCFT!!8M*02k98T=Sva0I9mAj&x;v-1stpTLX(ydMTcw&EF_LyG^nt$y7Q zfP7!T0w4x{Q}5)R=S3ov>klxHlQ)Nx!=MHTbO6yokl-+cTt*uFGzbB}oO~}KhCPcN z9U1mAfFPYlxWBtPV*sc!f*E)O`0smi8zSUt*dyA5Jd%qnAnG7cn5X3tWc%`n&L}|8Q?L_Y+E zgZz{oj_&B3h;>-tW87#bt^2DE1Idm{jNKfBW>*Z%h6EK(c~ z@bCJ|tSgV~EU8VY+_xY8Ypkd&{0Ss5gk&I~A%g@X;7^mm@`w2NKcu~LjBic1HQKgq z?zZjj-L`G*w!43A+qU;^+qR9}wryLt-{-yW$+`JX@}1=Vvr<*5TA7(MHB)QNQDc~8 z__A%=U3WK#F%IO8e~63OB*EgueMAFqb#yyCe`>;Z2_)@6eromtMQ@pK_B>rJGy_Wq zWM31Ge5C_*3w`=}ezA;yHNAd$6PF;Oyo^sgjemZn84^JK>LG-Dr+zcIY4|I?H|qat zrw;pUM}5|xjm%H*WwS8UcYUuQ*h=!XAQr@dwu9)(E@Y6s?sN5bOSz|5oJ7H%w1H#y z$QTrA5Aso;op&e8c8?Iv?!Ce%ecO%yqrL!Q4Eo|d(ak792?#FGAKdRce^@%dZS-$P1-?0&tP!Sfy*AeVGQb_tKaq zMkE8!P07%IZ{8N;tgaCjOuYi8s_qn!(CShs^^gEoa_5^f_S^T;%1l>cIM#jMXcC}7}DdUg1kohnYalb ztz91>^o7>brF9;n(sQK-!N$)T{vckjG{#&;mMt-`g#}umdoDHjy_0O-V|RiGuHMD( z%RDjoV~-7=Kb6}hd8{Q(|GlIVLEoyeXdv0oP*sm$dlOr129P{(TJ`9&3}Y?md0lAY z&4J`adG0Hc51R`}$Vd6@G&&#Fmv0@x3cYZl=;YB}C2&{jL{pHZsbd`$UQl-D)_Erm zN$8MS7736_)q+d?lW$tDIO?I| z4I$NJS3{8)&blEnZLbbOWP}?}YwY0%F!Vf#;Dg1LMO>BwyT-vv6Q4Mvs3+1eZa^#SOx+h7h9*%F9)<$Q;S1u;+(P%%2 z`YYNwYH|@8p~y=p4+@p6%7nkaOXI3{1#;3$k&#GqX4K6MrN`bNg&#q&R>Y<*Icpu( zCOm9HR^}J!C9$NQ9W{zq2+fxcyH>rFU4)(tN2zkKdB?Rn@~fQ+a!tT}R=l@3BrH>I zX2K>7VeNqv4;Egcl(SBTfM@dI=74E*F`ACi+++_ z;|^^dGjv8F+k$r#g-WYpIyxhS`my?IuoNs4njFkk2)&-%dx&f4lIehUarc21T|%xD z@FBco081gv%kQh>ZnW>JT-J@G)MN~H0*ad&#dTI)WqMu9m(HWN-A;v)Rn8@;2Zhg2 zY%T)-n)Nq8K-w)S;_%Ab^5YX!)Tr%rDXv3hI{CudAYUyzWsAqKMc`JlwMS?o*IRTb zQh3_^H{cV;<6#P9K!^2@@I%P$+12nF-gW_bIUZmedFfSgOVAU`)oS$ZQ;xfPnk9G8 zdZr~s^Y{Fxisae_Y4WsGOxZ9*QjlO3ieox}b}+r6g!Jd>w(Z^kTn|hkZPc%MVabg1 z=NmNWYJ@K8@p(92+N6&mxBNg33;*i32EDg|$?X=SALhMrI4$pJLIp=>tmlH_Q6*lR zBXhl_-H(&`s;y&2oNYl&-2=vB@wmL7NgCVBJ1eJ!i&^_CzZ6qDQ{aAqHpho(#NcJN z!gPn1aBaZxf6 z9raP89BxUtw_5UhB%34$Ov0<5nRj?lGo+I7~ zbUbIxY_=`U@;*`vzg@cSoij@*=il*dg`JZkbx2c=-dP85fuNqIc1AafYAwoScQR9nYRz4b`b^tAj7%;a43tJ z0&uB;>0zF+_q=z~?|QiN6z3(eG+Pt}J?x(_U=eeQzHUEuEuJ}DEY1jR4AozL$@8=J z9FyTL;1qKM{AWV*#>In<-I1q7$+$marUXOsKHbrHbj`5|1oO&fds}dS+%Wq7E{PZX z{MO)^mDISS#ToIGTY~D4PPMlfaUlqlF<|6U7@o!z4KRwK9_?`pe^pw-=<*^)5jq7& zib3jzD6KstNyNZWE^@Pn9u? zOb!YLX{C1RvHFEMI=JLHX`7jnSCv0pLwY|wDxB+;4+Q{HBl?01VQ(tNf$?y8YjMjy zrGn7J13P#dFq^~v;`1ppucpr`=rWgpQ^==GGYXie)qGTDqsmBz%x&%pxv4ExASyS1 z(X67ep=MTWW+shhmkGRzq`s1IC{;^I3&|R@^5>SMEE`8c4C&ibU$3QCiDvth> zOi}N5mOk7+Amw}K*Etqm{(+s=<2wE+KEdA#+)MWH-K$kbmZqPSrsu;q-=&`_elw&RY+aTk$YrT$aKAVn+L5H z*zftKxx8t75PRsM>QN&e!WAq5+b#(79$8|UlV())b2vY5vo~Jv(6D!NRNFZYh{m?r zr*R2zyP}v1O=Fl@Iqr(bRrAHlj&0(H>R}B^m|eu73Ztl)?m&+}L8dsZR_$ic+JSAz z(fuk~&>aWK5kbvS$)2SR!$&pi?yyHxC((<+@3WP>S8{b59*Wp#)#+VYHwdzQ8Cw}m z)^}P)LZROZ@rsWn!y?=sT=)A0UQ}bhZx7C6y{CVYB|}sQw*4Jj8KrAqvxs4tEU|Mv zUc$d0yS0|2FnlrP3SzSnq^OA2_%R`8@YxToqKh z-KZ|FJCf=JVIeU==ebF{n*(RgND^v%FU}BW>ItY&W{9!vHQGrBB%VNuL1?rh2~@`V z%39n+SAvd9C{I^tT3P?WvYq4Ts?^Nw0D&i1(k&@<`mPsG zcN@o*HrmixG)Wiqiked$-;`R@7b(2on#b+QakXEK%KB_UYf zu(l)d$;Rj-`=AL<-c=3Nqgn&#vmUxAEbT@6c=O3FjiS>b%cIo!#9$Y=$SCbvYns?U z#}Q0a>gV0ne~S7tC8@Tsb0&;c;lhF+C>5!0zG1=YH<6A7aTfzpo+-)lNP-!dMQcCARfhq|qA=mmX+QT(#+51849s_+7J1%w*4QgOb#t?E+kig&SL&H7i5% zA90}Dua^cFs?FmYi$gOWwwyFOgYB*|jAp=$l0Uabr0UIEj#WBxKadF-{ zZ0mc^uIEEm)Zt2Tzk``=xs^43u+yZxB&f5OYOj*mVQDM1lTZp1PaaiV;e1A@&t^kI zk;-Tq#~0XH0fky5s|xKL5&0P*qK%|>e0Q-<(Tk+g*}{LqxEfjqwY=1V^+=M=Q+x#6iB(fr5619%P1r14v&RdIEr_jl9PKcP zhDXWwpkbO)n0P$ZB94#^jFyWk)KP6C44*Vy*bm(__763Vn+lNyUDd3-OG9y0W}mx; zC{`wV6+YVcUsqQs+_{?RdH=YNVDMHu)Cy)hFcPq9h7kKDR%o$Nx6@_Ubjh>7q}Y_SrPW4NOw>QxkH~zB4?+* zg{CRH#`AChZ}o)q=kS6l-A=9gj6fVBtA<62V(v&u<087Glgi@mSyRs&~EN>k=~HG)aHE;j#O=dgXTiv%_|iW;o+U=rB!HrFN9$-eu8bRiAFugY{bS{-CvNo`>fH(gI?Q7A2VfL6FtKslv7$EO3P zbBEDG-2``gagCmUy!a+!o~$mUXwRR#xb_udGFRhQ?_v(Q(#0p^4M?8M#BQ*JV==kt zc79A8&NdNfxyA0x@Cgy81hSZJM$&S`^DXC(!&Ol2mZzR#kc^GovcE#c?s$y4(Vi== zI~u<~g+k9hTZ0k`(`@cQ!-Xo%_*yOUd8W@ZUOVo$k8kgbP0!k0DG^{25?%|?m!1Xo zuZk@H5d6|Bp`%rdKYYh2An;ZeRDts>+gkkm81cMuUyfa?TTR(Y)VYnAeGBi(^5y;@ zmSFi@S2Dg39ZN=tx69?idDG$q2awAaFmT9e)F#K*RUp~5$t%^}!bO!=94kO!FbsB8 zmy#Cd{O+nvHHxbrAv@5v?X$LYeyBc6j4JeypCa?nx2B~jME2U<(C0Ddf(d5k%(Oa< zhJvP_^PKCP=N-?jN3Ep4Ei-RjZk0by`78Etdwh(sHr^xgKvKaR{0yA+s;RXY@tIba z$I~4UoY^1X<6W`)Vs3l%l0ALh>g?p4y|Ycx*qEY1{J}8K=ztGLD8r+|tu~^ICC|V+ zDedtKjYJ-Am`kI&UBIpL>5qlWg2{1j?IiQviT{QIGcpYea;q1$rtx)ireB-vnXVLF zE^(>TUejDxaR>I$E`H4I=TiAqZRAy5CSZJL9lyFt-cjAynLrQa`-I2DyCq>Zm^K~6 z!Sb@!RYqK@zW-I1zMx`(8#2L3k|5IEZq%7I2btVW@~cOAL^_Z%qTb!cV7;I-pKboG zGqzK4RK-@;9j0_R<8hs-y7Eo%@;(k(DZ8eXMy?BcUvWEpo3_T7bi z;G@r4k+M5ZnfP{D8)5+m;B6VSHI6V+If813(oX}L8T!~fa0Y4p({8xt%*;$Jmkj@s z<>%FM@e2o;7*e_k#PFRKxoXp}h$XdhdbCdbEP1n`e6&u^syc7{8Ef;G!yjdb=hg~8 zcFrK5n%NK*^Qahr^13z2b-zpTGzjZPaET|cfaSD#Q%$7)o?r#s!Uk%6z`e1+=PaFi zMoTO}PuS6E>T(Iza;)gsXoKFpF%h$1$uplS*eWUUXPZdI?9&mKbU^f*5k2ir45q&} zkN;+`qO0(&)>fd{A2$55*!?TZM-hUqCh zpEmS3Lg(BnnDO!`vMS@K_&JZO#8)V5vdM%dp00(l?+LbYbBtYm9K9za@rs=2eDUxh z3nD>5U`|c}wz!&x{3K->o90-pP6rQD>Hd$FX}+fn>y6*GQVSwV?5~V@C-8s` z+FVSEs?a6=LyIqw=3t7!O@8IW>#J7MsEm91e$H6a<7L3-2u#YLk5~SdA|ge}OH6Kw zuZ6H&baEYO(PpX#;2&XZQhDO*#AaB{Qx;x3Uqm)0ss-nVKC$o4bIdvaU7FK2F`VH{E|N6|8>?)=qY0-Pag`!T`zm?{p%D~` zS9kcUiIXouq+oX+RB&^L)A~ngh3#x2GK`Bm&zJ@Rkx2liq&@23_kl)3SxFzN`Q0;( zV+?LcK5?h2D;W4G`KFIEd@*rN*>8V(c*#M zK~2N1ZfjDS$XZGIkIpY(#BH6p|DmeJ_}|IpRov}Oh!`~FjVw)!0Wb{8&PITLM#StK zZNBSg-_L($eBVk_P!ZLj|CUrYku$V0A)=&b5EK?RwJ>vHaB?fQvHUNt%hBvJt1toy34`mBf`aQhu_y=c>(F~o>j;CV zdR6_T2QoE;2>Kt~_m2Vp;pYGU;XWZ1F-JRF!2jN5Z2#S5-)%-BHZC@LW{z(@5LPC7 zPOksMcfxkoc8<#ShQ=oUxX<3q)ZWp|h)A13!4Lp2akOO+F>$dlHc=86`nT`?-{F5v z=I4iD5Oo8HD+3Gx|E&JkfY`UW|GY_z^E(dg|29YLJCsb!9RKOCeRnwj>HKTOe}(8@ z5n@m=aRdB+qQt?<^?$F?Zm3J!p$fuvT~%M#@kug^;8~csH@H@kX)?*a;Q|Lr*(Tt&3ZK^MYJ9x!skEJb%$`2V$oF54K@VEEg zct3|ZMrSBN<_$(-SQ8dC>mXFqoBY-i?s5p92GJ2yJ!E31`1Ih2(L%>dnqcjZR0C(w zPPyW`wvh39*CX|E`N`0Qk-4UXRm~V%?kv8EgP<~G=s!<5k<6$4g1s71Wc{yrPJ9lV z*aYVYn{1G)G{9ry{kF`xaX7O?*{I7v# z?2U$!^+OenvH*;0d~5Q*!vP>~{JDwpY{9h@VkX5a z)nDtITNmUlPFy#f2Q9FcQ6~a56VS=>S20Ab2olwMoSwfjb9OkzqmrH+&Jp&%=S@3c z&KaUD4IYA1n`&6(kiH!{h(Z?B1yM5N#_EO&0sjcTh?+3`#Ur;|L?n?1W|Do8qeZ=y zgKK1oTReH$H?Nt4m4jg$=^ga>+O_~sDqfx!IL>a4+`5EL7cQslFs))UW8~aeY%Q=< zrz$SB1Y6eh#HHU<6m8jTEh{Zrg}^I`P(x)RfglXfg7QbJI_~>`&8TM6*}xfaI&2d! zi3#k&Cu7;uuA|>6Q*y10^AXzcIeRLCBS)^R?^<|~LLp726HROEw{VoalQ{m75cr@{ zeCYkm?kz4bGy%sPc+h(Ul_%a5LRjNRu@V7YNs(#Q5Z`$~*Q6A|jy8u!huO61k~9$| zVAv$JOdrBk_vpxme2&1cTa-r-m4CcrXNq!}9oT7LdQHVx*v+%7wX~WkxWX7(-g`Tv z+dn@pwgNk}Hk1$AlqU?cPH+ZbUuV0zjpn9vdzDf+jkOV zW&F->|G6~G$;kOXLLj&pS=s;Z+bbFXt}=hI$UwId-Sd}-s~`yA>I%=;)5AFbmyRl| zfN}!`1%xCTAn6(y1b~`-_;dA^bC>OOrS(*$c_uJ@`QiC!Cm;jJ;LcKFpHee$H^a(8 z9T_AAiBp_|xCL@^dv0-ab7M+R0}$I&KHIU8C-N^(;_t$tzUU(`+ZrIfD^kD)2)veZ z^#hF&C;-JF0->P+!-QX71G%}o1${XHTu^~W0(gnpf!OH%>R8~;V@7}Mo$u~J)YgXz zq`VwK88n)L0tE*LbAASa7G(9`vHNTo4&zGIJx zY-`KFz(60D$dg*1nazm{*#isG3~3&?(QBJyfZJo&1LPcs`poc4Crt)O*E8%*-vi%F zy9ILu9?nhWC-I^|+M96@KM3&b=K>;1o3s;0n%{U~BG`ux_$jCsi{Q%* z3A|s}0Q6hj&$r*H*(I>0XQOqU`0o}{t8cM;hY43&bX0vJDi(z6@cTwC?Et*>hua1J zy07da^5Hr7-J5nzaF4aMZ(z-h{mx>bpblS;RGn`-ZyDoPWj$y=FbFR%uTY;CPz?>x zxsA>A2Tx~JEbMbE^0W3w7*Wsk;0n0G8x#m0P%XH?r{QaBAa5^FOC}^|&y_Fkr*a<{ z2rxU66=x5OHKf1cC(m0xj`dsWJEs>%7)MXgQM~6*py{ivZaLG~`#OgZLGRCtPqVId zoS_h{w%K!E;?GoBt<@FW?cvdB(CvNnZD1hZM496or0ZOZPiNpSzpwlSFu_mTOJ5U} zfE8}gps&7bH}|jY>-S8I3g2ot+-(7x5*`6ZY&e4tjt5zHFt-Xqfu64`@MqLp-@T73 z+AoIFukV97fxd~f)Mtm>&-wzqiPe?Er`;PED3G7FwnT&z!!rU>AV31!dm*cSonH#LJ(J*0 zAp#*l1UukB*4Z13zVb=>SUn%lzdqDH zU#6!5dp8ZNCR#1btY#QPPiqdx<&{+QvNHP_$kW*2H|rfk&eHdJFS57v`j05$qb0RuIX;^)pjVAEWz*{O3;0OEJ(but=CS0toXLEj zw_0D%LODq|hmJ z9WD1+`g)m61x_x|OzN<^cl!o&G_N3Pg;uTcVq7D$o^{qbPLh!>urzedl8?4^XzWRk z=!l|%%Rw4=D36Y_o8ACLRxh#{*7XOA4=v3)n$x zP?-3KJC4?lnoEA$Gj*p56joFDTY>ZP4oxfaAVcO7!0bPNd7&!kc~)$;aZ56SK9I1& zdPAYB_}09>UOu<@_2tMGv1k3@V4c(gbp+Ay-{LyQucCV5I9SEFq*eyzk8SH0#+pIn4|Z$d%!)MbWm>c`Dh$e9!dZ?e>VjTrB(za!)qa*)xb*wps&Qs)$JFZrKrVvIa$& znuu~dy6(NN+^?JLZ9baQ(x-Rtb7l9V1lMCeTSO78{fQX-1V%SI-l9JRp{0lFEQxt; z`Tp43Jb0v>z{ zq#}!!{ZyD`Da>XjqYTS#N#az~e-$FXYcaqX<$K!T+CHOfcw`bm;2Y{%M+CQ2bJHIb zv&WO?>d@ycre>ZmtH-7*F+ccA&V&dEd3>D9m_5{vjYI5pVV zS!y{%P@k}dwEqH9_Zgas)YBv4nmQ|%L(BI)5Du$PS-xJp=Ao@%8t-8+N@x9}?u|b_%uOe16*-bi;%Qm8ABr}7 zE~SbsS@de<4mvPffai~VHYh%X>Q0v)fbr#x+7+wnuh92;7mh{k7?ssumTG-as;|bk z+$Xc7dDMZ>F5e{ZXL@fPVj_aw|kIB6G127rZ4pV{WZ#f4I_sbZ8 zvr!oiQKmY><&!mGx>5)G+V>e=HBdM-Ag?l#Z7&w81?1ms%#lFsw?N}n`6`REBov4n z30KqJju#$Xv)g{0!4;8=jlzy)V^pTO9d73Hw>QbGdCn$hHY5z#crKACeB%XV?{+Mg>LDE_ksAhG zTLFYULn;rd;3tL6Ehax9PRP8o6)#(3x?-^HUOO4;uj0B;v90)}TS0TIpue-_vG@36 zyXXc-lj9d89T%vmUd3DdaE9di%2&lQLBo7^+FN z23OKai2E4i{UNW4V81$xyBi#-9RO^EQ@p}XRgAr$c;WO(S%`baa z>I9IAe56Q0G6{_}K1(z|Jcyb(WrpUF+dDwfu(q()sS)E%PUre&6+v%YML{)>`xw3& zsV3<8JZOo2Dse2G9(oIv`;6dH(#%)o@i}c;cJR7{SNXI9s7+2YPoCOokh(GA&gTq> zw!ca6%6$yIXAFpmW;WJuh^99VWx3&&IR1P~pt*ml`H$QyFVO14)N_Ch7ussf1iKgh z$vLg7WU_=2>Wh*pi}O7EQL4#PcEwoo8_}qMSuCqV>>@l3X6P{IP{Dr)mx}5Zcsi`$ z_kn{s!JXPg;mqNLSxT!RSm4Xdq{3knZw?ZA4lT8}d5{f0A&psWf6H=tX z@Rg)EJYZV%{7>854+a7{x%u7v=$L$mP`4LfyhA}J>ng1Yd(rE|cbgw%y#PY+Kfnr` zp8NKWZyPW@mzz|?O^e!FM-?tP2DFKrQN0{-@4E4kN0K~p zl38i>k1JMY8`;H>a0WDRwuA(RhL^nlQ1Oy>*x{YgWI^Xo8m@f8_L<#piNDTUx{jfJPf|}a*kTri>O>QqHWe!6I(yTbxT&?5NDbj zjQqY!=l!#S@&qZJJG-Q%ilz85TBK#iQ?j3%OfLkG^c}LzEC-#kp}k$86^11Nqyenv zaaDtMsb^Lim5ZNb*J0-D-lC@3!V#i$dVwcZ>*Z@mLNt3eNodLs6O8`U7fBeY*&TS{%J$P%s}?^h$5-oWaZ;q^#cO?Hl!coG)`_FH6lb^qS$oX3L3%un)yf;AD>zjXaNkB2OX`Fk>y2B}=zt zw;y`qicK-i-Hq*x0!&qzQmZM09^4d2tiM8f?x&}lt6N{&mAY!y5T0IN(L6(DeVR*B z9xJiJCSslkX?D0)qGCcCJXgKgQCBR&pvHtJcjx4`f)A(P=9%siM48zx9Mt+zLo3BlpeYm4d~s;`>4o+YbS$gPrAMc# za0A~gEck5s^nKvzsWZ9V$)T<9o!jo3jkcichY({OOwOb05NuHrbY~G$*g{*%nwiT@ zsAo)wwWWH-=zcVeB*s7Hti)+Pv!`-akyFLfkec9uR*5uGa*DhL=h+=t?V+8`;hfQs z&XCWC9HgF&A0H0bu41@|Y)FQFNZTD<`&+F=4~?8eco#svyh_sbOK$-q$9_11f98)t zFS{Kl>WW`Jr8<|yC5oqS1$46Ufg%dqzmB3F%Cnj0CF8U9S-}h$WEfXc;F%lO zQ2xTICVrA3xz7Ke6#2n~GmDdZvEj*b5{eTp?j>i65Xf zzWCQPD=g-sHbxz@MsNF6%Gy$3Is>BG78 zE~y<=8?hSk^CrSdG z|N3D9h0KMEfq1S9qEFg1lfEI8|hoQ~(R7;WA5CY-h3fz3u==>n2+gN+3(VNI3gCN`qh^Q22!ihjU{t&h^ zr>p832(uMeL(ByutDsu)Jls_aO`~HrV4mWm8q_w3uT6zQmOzJ{Bks<(<$iuF{V4vW z#N|#dhEsCx#7N;#rV{527(kd`0lKNjIg`Z8z!lO(?hiPapqv<)HtbE9CXCpZ)HPfg z$pf2gh1IIeTYLA)^ko0D!c=pWniWc}{_=S|SOaUmhDY;j(MP@?d4;+DlF@tP;1;L- zy)|^2B!5kEZ1zMOQDzOuYDvz;-zE2FTRT~O>4a6;c$2pdUyS2`nj69zVp!O&q+Gd} z+Y*RXFt`TkuTU+$?uSihv}l!%31iR3NM*qvr*G5rTYoFA0iwprMVy_W(<|&?I9ZBY z&Q7-rcC)qoGQFp5RuB5mdU5Jlmz7eiJjgT@dI^ql*TK39!i#2TWSD!x*5X1}cxR2R zkF(R4yqW=?*)33-A%I1mUzrd`zxkUR_Jt%1+?U17=9t+IHsp935A~_hdBJGWW^;8G zr+@|4w|iUl<&8F~hY+gpjjL|E%Ro~4^Jr~<4T9?YUG`m0S%qF>QPRhBCC!i|DAm=R z%82ElEXj(5@e-lAKHabqT2XLx;!B`DtWWl6H4*{3p@hBESUu*oz~)&cq+oUI-};ln z$AcLjnce)yJx@2R156?z0M+2iA!W!3slJjeKnnI1_hLybNR~X3m*B5+(@3x?3RNFe z8$ea+XGj#Tp38@%KC6)IVqAxDiH@i6owq`ghB840{x!Htq*U^1g%#-gg~ciss+Y-9 z*u5C{Zf8c6(TeuvSd?f;Y*U*UOdE@zzP#lhL8oo@GCdLLSZT>0Qoc!b-dYJKgC!T! z7JP?y0V<*En*7EbDZlr0`VhT2XULQLXP#5`DgzxgU-0#kE=t~raH!99wg}@;RTZ$X z4gLCiiYt9aGvALV{Vs{@Itaxf^c8XoZ2L$ywmOdd`T8IFD}$u4QlE2%I`E02kgK;m ze14wwm2wZQr}_qZ6&O(=)V%9V%p0aBxVGFkZgr~U&D?1#$F`nal$(YBm~+(v-HKeO zwC-QQ%+OBlugf}NGCGR5XUy;(mb-Ad2>FR?x68*reiT(0;f#W<_eQ&rni5T-D_|vd zTF>LVoyxe+b{2NTpeBPmCY{SA$zn(7tP0MfZq~8H!wEmoMJXeLhmNvkc1Fc1s~R+D zM$CqhDh)kz^*kzO9_et`cQxPU>8smn=L6N{fTqU$o@}0}pTHE-@yO`t+AqiY)T?0I zO$pu|YxTsVyJk-D!EykOPrTmbPMRTgU%XZ#jsVL!Ke6Yev^KVUPUtJ*ZDTG(kwxL< zkdl|vK1zA4St(pwzT19qOLx~YSLv`M`kZ+-37~NsO9n4v|3Tn0-BlT-+2(C z<&^Z?FQfM*yzP2@>fcpyoAlK_BqrS9S4)E3e9T`*u)$y2Wkaid%Tw_55@ao>^`&s3rPgdr55;Fjra`O^x+ zOq*xSwwet##8i(Mma};`)A}H0EOOVWgaxx6Nl+?JwtT*EHCYagBGe~(wn_3h0#9OU zj4D5IhhwzRqHq*!_J(zHP3)dU7CWu|eX=HWprV zar`#ckV&TEA{tIPZeT8R2venxxlk5=BH;q-Tvj>>@I=C80whs%C?S z1%peCDVcYk+wy3HZpzxuvuDpPL2gt=L<2QgIhXoo6)i^cLD{(phL!u=_7>U=H*%$v z{aPW6rb~%pt<8NfuQN|P=!(YST@g6A_7Ff~xLPn&WXpb{_ASa#8U&r5{&gDqyBn*~h71ry^OC$G1s+YZN&lG;K>@QyFVC_QSM207R>D8!=t1cCo(l#}YrDZ+WqVgWU3!QC2_{k9c~ky+a865Z$tC`)Mg>dyL;s=6H`uRVUkR2Ixy9bzLaabn81`A)R= zkm#cbicEr6G+!I#l#||ZRKzuWQ_$>Geb_6Ns@EAYjh=fZ*>@Z3Bg0~{PuHU?~hHIj!ow~gC=?O9#50@aVM5QR`rDbY~A+^zWjvw-vy?L6Hh*)&YWo~ zR1qheg8*u|aJ0$zqsQJdSbh**aq@ztrmCyAKKQJ*p8?v{Y8m&GOWZ>Go%=hab^yGh z{ft1}SOi;7^{$1iF2CP{1@A&Q2Fz-*2hr7T(J8?q5I;l%Y3g0(eslGgj>5-+d7Pxe z##k{TIZyD7E@F4pawp6zU`@y=J~GS=j8C}jT3Kh<_?}*|kzSdz@=GcmeQ2pv-MMWJCb12q;>H?Y>S%1aRd?~Z z8}FmR#2JL%q8TGbyEX$9PFe%JPiB<^vCBhjcJ_99$n12oMG0x>RBV5tqp#4`P&CRG zu*A$p29jVvs6^((b!F&miO=#sR0%@3LL>rsYI>n>_yjMan;^B^q6yq0-mgp{XQ0i@6UbN~T@% zZu--cu8x{ooZ{We%KGjj8-50;ktvbkqS`9wkM^ENCshe)4TY=8B{3Ec}iaE#X-lBftR!-NE<#lqhnmArD zjeG?mr>YJmO*6_Ib^&v*HsZQX)0vnmevgTp;sQE)bM5eAp~r4&eZt)x0*@&8!cua@ zIjsMXrtx2d>%hz|*Q_7sa*S{@ma`9G`~=23!HjaXkZVAcu#^JKhi=M*WifAUsul87 zN-E@SOQmE_o|v@mjdMsV(%cQhH8J-}p4x6BLbQ2OQVQI`zWsACpKu|0B=hHJiqon3 z9S$kD+oQuhX@X@!rKE{72-quUS-y#8NM;x2#0x6SRnqBMCRkHLJ9UdE_xDS%W2+w& zt`Y{Pmfm+Y4Ga7+*6AcfJgD>Y}Z~S3puEp5yOJm9vWuaxzmlRs~Mby7^^1HpMVZd2NP zy(|*ACI7VNhxIdZjuvtUe(jX3q2+%qS_*g+fy9i^_yP6jcBoM2Yjz^s~i=d|yT;FC8 z4Jl3KFXb}4tuWRhq@uClcBvKZt+=^Jy_{3mJyMpqG%dO51GFLBn5zhi)MWWJ38Ul2$1ij^%53EL#(tKm zF4^`$L2HvkE))XnjCORwMEcnX_>FOZOo+mJ9exWn+SPpA^Gi;X_EKH*As?;kQsZ*6 z{#D`%5w_aPFdUTeBFlO@I$N~QJLt{G!j1&_AURC{Gk@BsWoN+Ls1&b)M4gJo9YLxj zYLH!}m6K@9e8deW+Y}YdK$Bw8w(zw_NX%0C>;y4fDDix)g0>tGoc@%lHh{BTWK3u4 zQ(+^#17XYt+mlW(D|Qce*{p$FNYBM5a0;a;wK)VdF20NQ{-&Y`ksIPXQv6F@SxIiJ z#u_~0jx&C7H%7BQ_RIX`6np3rA8-(EXcAs9A4)4a|6wR=7SsY?tH|qw03p|&^KN8$ z;?~X}hjsVMaIb(Anr}i)<#%1F6uqyfOoT{v?y0-ve2Ecr0@TiV$RAg{kK&bM4C;|~ zo{d9?2h#Q6pC9S`&ckuxYAnk4Y^dvZqU+N&LvvRQ#Y5LcK8Nb`Vr=(2Fguk3irW{t zc?SgDymvB_3TU{_f)QLbv-gUMXkjsF6KZ6KoDRj|NU zo8AJ+HAl6muw9r2WhPzr-JqabI8nxaT!eE&oKjAXssXC=kv>$&l~9mTxmbrMpKS-r z0&w~fj=b88Wg7T4cexm*wpCS?nuiR=Ce|;>e-h{a;NiF$%b(;MyxfmCfTKz5ep=TM zXYYiu0OzcM3&l-@B^m+GsLQ*G_a&i56L^b3%%>Zi>OnRl+1?^^m1+Df>zJG_kM`O_ z{yGFdXc$!5uD3!7|54ax>j2{|q?pK11mO08v88WU8HA>9t%T2)@-V4a*G!5@>8Bw* zP?bPkQov8u^=5$h`V}B`&lScKriS~(JoS=!4LwgwF{-_&fVZWjx0+7d95Caf%dSUP zPYxyRGSNHk!&%K(xSFb8NB&F5!`Nfmu*G!h>5Y?FOz?v^qc^WCWbaJZmZEv;3{ZZ zxb(F6Bt%5`!W?juf1?4-13;i~Ou}%w2~r%C*(kF_#847p09R`G0Dy$_>eWfofqH>ehOsD+&;aO63O*g0%m702k*H&?;EfOYet;p$~5F z(K-ip2{G%hDL@Eu^8?jKWD?5H9{I~lcz8JYXK%LdRyQM6;sD5!_rvAE+6T6J@K*x% zoB=KN$;9yuw$@?-w!6r+^bB&^VF!_|q5`=gunSfZ(6@ktyQZ-WqTbrE@r#P1=Iz1w ze;HT4rvifS-pm8IwYq&nzO=mD@XM{@o7N_yZjNEXJcRUH0kX=8LhuU-Bt!27?*jPg zFZaOq#n{|}`__VEoI^Bw(Z43LW8@K3fdcT|eq?56CQ~h9?hPM-Ie$*YeYmED5={(L z8t=)-AYk;vez^Yr`>KX52`zQC{WLBCg1rR2eLFY%_g7l`DAu~T9{*xI+M9$D4!)Y) zVYNRr4Z#EeK>P%95QETutpEf%DlVHnffpWJLf_=>K9TtMFE7p^T)&Y`a#-zED!h^+ANy;v5(0BV9(`Sh2*qP_@1R^R>b*{;DJfKq<&fg`{G z-`}5(jNWN9mh6*rA3Mjs8530{`qclbr@ljP`6w|lThV({6X8LADINeIH$Sfcfc((F zA79b8(4Sv@f4oINzV8Xxr|VzRG*}#f_sD*st8d|fgPU}{H&1Ofz#s2G&QJXqLVy(C z*e~cjfZ6lC$de!U*PqtUpQ+Cq@}JbYpB*ohOJ|+NJ-2A&gr+6+?<9mA)_MWGU_^5~a$=@Fm?rEr-?=RE;0rK=#SL@kc zh7R-n? Z3^-^Ab$(B>_+>(aiE_6B;GMn!TkTe__Iyx~1MH@J)4T@;1p#iJ{}AXC z_-Q`i|58$|Ro?>Kz2Ks!J%lrXG?#n?@P63e@Q1#3-foCLLR0X&E?@BE5W6Cu!1$#O z#N0pk-*nX~*VWbVA3vsO_)vFrpC@(x{G9|UtBwnHRC974>$A%f7Uod0)6x2Oki)Qn zY?WEvj@7xFzIz6RwJOG7HLW?4C6CVgbk$=GS>jU*oA1{wD~6r#X@yG;SFVORc|6T? z0X$q1pT>oDvhCHOP>~6Wsul}3%R{n!qku)2W!mWsD?{2Cs!X}J^9`DF71bqH`t)8N zLY55@az}U4YwV^`I**Zg`{Kjg6O|MSoK7HQsDH5g^3ng3{SlZR<%#}ff0}<{F}jI# z50tl8D=2b{9JF;>;26Oe4HYPpm;(A3ew|WRO2!G8I|&6tbPYOF2Exo7vh4F{9CvNa z?o8!*>+-e3)mX88ZLB#@n<)I`Ohf4XPlXxtB1Dd=oYAJrG{^EmVOYH25KAtZ(US@n zZQrKYAI#(Kvu;~FdJ+mYX2d8S~|{?%r4D+0ht|&OiCw>L@g2^vrav zu0>hG`$%_UKt;D=!q9c%i=$e(APx|t@R*h@w5kta|q^2cAdVqpPdOf!wnSFQe3DCp^ZNj`_PLK`M75(OtEl$^5oI(dJRh(BmgWt4Zz66T@dlxe+ z?m{R7xO0S-u=d-Zv4Ripz1E*be?3JXSK2aWlc+zS-FfdaPGH)Fal(=p1_>WYoG$*; z{`rdx*iHqR2h)<~go)CDnY2v@_Qb3KqDg%WuNS*K2Z?z6R@;wFOx`&#p4~r_pA#t; z6Q+~878X0^7imXmh_YsIUT)AnMRv`K(S7r1amtb!zA=)q8=LZ2SnYq6x@Yk;Sg8gW zi~o)V5iY$kn>t#XWe@WOJZxYi?!elfiNZ+B5T%y(Ax?gM-~5SyyqeOv+;;U%QgiIs z3Mlkxx_Ubf6q%@d)eq-d`>KskK!#l0z0Oqw5r54)jAq^Ep4%PfN44w{esUJkj`VZ_ zQlb?}59G4Bdw4*0jGS$eDR}t2zSE;pP@-FbT7M>$QpUtti&=Ja<=j-26<0oVF=V;h zD>JN8QROv&Ymd2NNH9v@kutAI-JYfvV`inR*?LkKnPd%G5BY;G6|@#9DR;jJ@`sAU z-)Bxk3!CZa?1;y^*f6P#1t64r>s2F?WuZG7Sjmg*_mwmjhw|3v+^7z)D&O**V4Cq> z`K3T7pLgz^{wk0^%6^VwN-;EF2+tBtpd*MzQGP`Pn7FLbRF^OY&Jc(KJq8w1?d1lL zk9^f`0zZGd-JRt&I%WrBlQFVoK(}@LzV>oG^DsEY5=biWIkVWZ6&;OD(r~NPl-=|k zs|kHcOBG1|ekIKITqz?>NF9kE(m%>dSyvr@N0U0*-%FEr=@4ja(c)-QAoW1+s`<5) zP!u4EV&8((TrSv$-sJz*Ax5aYmUK$Sx15m!dt_;t_KP6 z18Ilgp7p{h0&ly5G^?ilp>5=Ts%fB;QS?y$iSxmWcxw)t(3sq`hpVvs0i!I4?U<~X z9P$;owxMQBOEQv%@e?Rx+wNX64yWPx{$@ZoaR+S*=$y#KYHi!nXcWSOD0%(GN#QrA zdFGR>TN>2OO6o`jXd6UHW=30EP2VGKRPRG;oGy$tNJu(=-WPF7k6dV>l7wllmrU9; z_PLKSr@ukMt5N$v{@z^8Roi(=>{7$Tlka7-s$(@U(yGKxjN*}cFRq$~)UXg37(b?J zmm(7`v!E?FgJ}AROFi&o`Ybd3vfWf4pdE$zqCIKt+1M$3W7TbybsUxtfzSg%!zec@e?hYqy?Cq z{HzFnZjsU>wc*Mueqx+OdAnqW@43{3s}KaHg0Wt9gL9j=TwEl?G1yZXxhlwcz;LUj zkAz8>^Gxr{u*B)aThVYy@@-*IN=`sMq{c}lOx=bPEl`9RdQIGkHf~g zvkt`+Z%(0ADl;-eWif|3`J3?e)+|@1++fOZE)Np?H>ro-DX$6jLzU#E$}oPrTv~$D zk3~Ra$&&*CG-6tt1f~NQ@19a}7s9hTJ>PG}sF2jv6)LVN_KKzLs;MC8120vn$_7iI z1}7|!=`$a18E5zLCit@(b#u}QTD3_3Ns(G9KJE_fs1db4>S#Il_|4gKmG25aitrO~ua}5lp87Y+-VO}kCzT#b z+7dlT!Pq$G;QQ^NjWsi$e`Q0xXV-E~VZhMR<a`+)|L`CT2Q0x)<|T7xe?bO2d+V(4ahYZOp)Z ze<-rOf^;1VmQCl=Or550^{ihJ5Wu|DH%`>IHj40w-*RH1-Sy`0A08s`T#VqJq#ZZA z=<)ahrbp>p)-!fN2~ur#9B$YMPno7>MoIL^JP<6OKy3Gy9IP`3|&GE%q{}JR!61Kz$RKk6@GWtfvtAYA@-W z%22W=x}9P8t}R|pi{^a4C>?mNo4XG;5>3T5h4?@(!~Xn{bHt3gJ$ZR{RtZEgjS~W} z;amYcbO;ho-Xwe+kB*$P;L%CHmF_{^{lj$1< z)ptvP?sT?!quoQVtX`Nb)b;SCT9%@Td^02=4R4BOw0Fs2^0y)uWcU@j9J_(#FM5M1n`=uX=*|mzo_BX26hYibaWEr2F(1XtG+w-cz-8XqtK_>UD>Ne z!!nB-XM|wtXm1hdPNoA zt9id3B|$V3TIjjPtb$;k!z7+A3rhhGBN=*dsTt;>zrHpI)JKoYOFLU3bgA^!DV7qJ zc0eOj=n+fx6w|suX7u{7W3K}hnmvXD?6jP*V0GG6l5iN1Jdbl}6Gva^=}|4Rzz|5Y5TQSK4CK zko!-oAr%FE-A_Q3TIsCf2%ThW+Vk3efezoln|3N0rgyHl zTUNEX6Ejp*70H^ed;vRug>nsN;%aW4E<}R3#orOH6q;e%?2K-Ok;sATpq69 zC6?9Fu;eCL7I2sG1Cp`SE9Y6jIOs^+psjWrmi&5NTe4~P3JaCNHyx#r4(1!TQ&s5# zYKl#Qg}Y>QK*85%L&Ar|K2SXcRi$mIr_Sa+c>C8X9LS@SWb11k__=ZHaaCPqF?#+( zl6nVo$$R^chKZKDTfU71aWatsd{6b49~3`_PTV{~fx;XvWoM0ObD{ZZNb8p1&Gm;t zIhTa)%NKqkSW*k>Bxl%s`B!uB$@n_FNLU&WWJ#Iz2fKMQB%%`5?<(7D4+C;udud9P z>y#83#f(<3_DDU2k%Jy6SFy19Fed6(h*=u(cBbd()MV8W?<^9fU-*}=A%YPVw{8lP zLdRkcv~{}DO|n5bK1&gH4UcAhB66L07Zz70aksn(I|rZFEvV|WD>4nQTE|~oBLe5c zfHv3DPesvs%o_|PXH-h!*)~YQRIpH9Z!`4y;W)ui4O8eru{*^J9&!q*Lef|}Wg!A5) z@erou8GBzCC#ctUlJqt%+lxL0=s=-sSz*UI4Db`sPwIstG7@o0A3Q3|R3t6kSkHt! zbD3gOvl0jUC!GWZ;o7twW)ZG3TlHyL^X%h{!F-zWdSbW2<)^@fCgCO2Bs(8@`%#4) zH*-2ov`b#yTPKPOu}UtoJ=sRh<0+ma;H&vD-YpzoKyAe_6y&h)=xT&NJ*G}dj7Nh? z=VYj8XP4OOSvMk=>`XjTN+7L3Ei5g7rVtDZ+^2FDR_a0ydm1fw{oUQQ?a*i4NK=+~ zkTO3;F>s}p4Vu1YT2xd{=VO#fd(djRDDbL40m*mcqWa5<>nd5fkKe7PpYkLKDW`0! zk9+f0))S7_lI5lHlBfaP`qx!EJJkn^LEsOpTl~DDM;Q8R(+1O*joHY@q-b^w9R&$t zEUwj~Vt5SP1WAEX%~Yapo#U}G<-~1^?V59ga-r$x=&}J=u3Y}pw29ds5E}wls-+ek z(zJT+laQS58$?cT4#|q8uw97Jpb-31ckVt04AaXFjQ$kbRVQO{2oW!i%sA(S8 zh#}I_3P!v61aKXn0bOak87^qHyoeg@K~r-2EAen7TZr!4Xq^^>5X|(xtHNO>GeFtt z#}swS%#y%IM=*#)Y>2F(oA&$Se*Kva6*8BuT;(ESqagSJr?P1$zb7|!?3Ivr*CcZh z{fvo^Obj;d+Ig+~H6NQ)SM6mGy>JSzFb!uN6YC238u{W%!OXTY+7&Gs)rHXhfGc8_ zG6T$fJ;fFNU^}MV03Bk*+taZLxNO6iN8^SKvMxu~y`misK)b(a!Kbs%I7GG7UHKt{ zpOqmTkLhHwCGX#L&p~Z`2|kB&Udp3OcEZ z`Ugl0v>?|T4k15mY-M|+<^r@-1{r)jA+Uq5WfG%Re|wA8qLVQK6xfVg zO~xx%k|egxShf8|bV(J_1rHtPGHraLh>%kXrP%8lFY;{b-v{B;kmUp;=en40$#M1C zz`3U1gs^;r;PVM$y=$+nEf_#bv`}keVf+IV<;JPGvn|iI*?cmVec7?$ppa(Qpz(0o zgp_*<;ahptqR1ALF*g+rF<&|J8y36Nv~1h6YUb=Len&K^9>Ckj4Ng+~qP-OBcTL%k z6R8dp3x+QWO`H#nQ)i|2`C$d| zcqP0#m|A-3T;ErAuH|}a|O4X4tc=j-+_-9U|(xhU4@m0&2+aKSg$}@tHN*-snQro zQ->C;WE;~^b6NSY^gZbOZ1@nK#!Klg;7Js6C3&iv&VKF`$GgKMlj{` zhs@gf=nK5Fu$iCy-xeH8y$6ht3Kc13@+47+n^NF}QjL~$N}fGy>a;Gd(xU4EGrGHp z2<}A4H4EdNv#&B5HJoMEQ%{b{im%{RQ4dULrX>kvv19Rp$W?72?=823_{LhOkQi^K+3rQklOJPE{!;iTGS7Mo#g z;*-Q*LFnb;wIdFzw7^ZqJu@$&;p(@`8SJdtK+7Xli6T|orjX#NkMJ)JzhBolx{n$i zc!dx?9NwU6=-v&=;%C6a6ysVR1PH9MO;5(~*!9Y5i=&ZZZ{E4;{(4;dOaml(4^t)4 z0mtJ3-dxv`@Eg<(ID=O{=s=-JN7oyVd??+usQ#`kGp+}|@dDufP#d!jM33KebpmGu zkL9fRY^2xVK6Ail*%I*cy1*)T?4L%3SGcL?3;)aGM)ZNDORw4w%P}yi@F3J3=TGrJ z)*bezeMDT(v{+~GTr)~!FGGb>82O_n*Zl_PpNXsCHq%?K-G|)T0!8`=xAf-ri?$(oH7$zGEb;Y$S@`* zwF;3>0o6@toeoc4oyG#}?I|ii?l2ve-I`B&%~4`SL9quIh*YSGNXJ*ZWldFFvZG-s z6i1@vMS9Q64tp%|q#b~gQo!r}D)nilIC;%xZ~E1GbvwK$)7EwfpzPSCxyOSQ)%gQn zUcHQ+1&O#1B!OJq6cjvhafhoM9GBQ%C_%MP@A87JQx7!b$6s6xbXO_?niAQ*{4x6N z^5!)vE1U9ck-|1ch!?f@g=f-%eW_nzD@;H;y|i(h zn6BY)vvkLZ|Ip3B!J5;>>1SN>#WEf9U)zQ1k@I*2(6IuI5CU&1*%?&m_N9&1=rvS} zFr53-Wh{MCTvmy9ay?#rF$Y}UI_EwjO?wtQG;(xBO7um2&#zB1G2-R#Q8rppR4RS1 zW~*RDD@v#&YuyqCcgP9E5r0q^E&9~bLzIo8Fx^dLWm}@xdSl=Ph87K>KrJZRA-%OB zO?N#Uf?Cri_SSj`pKWdr`30!mKe&70r6-JY)B$lR{LE?VxF7KBUa93<@9$F}Ndjmg? zS8mp~#!~|oOA_qz{)p=*+$pwlW4qAL@gsNR*x~a%?pmgUGt4f4Y}02%wo`|MqpZcS ziIj2lwBNvB1td zf5aR2sdd$RYDNN+DzM7#Ae%4kj;9WTCTWx+3c;OZUSaE?qV^(O5QYOSN-~*&P(MvIJ?8VZbZJPf4WAgb&w)t zIgTfjTd^4iHjUIBdO43!`2P6(i>6E%rS2A{B*^S+Z2w=c?H{`ZrIr3Xk9F>~?Ly?-l(?{)gY+wCh_9-Y zrCu|wMWysgv@dNrpeh!8IPssC7o<`>gqwd`wG-Cu(g15S(cy0-H25v@({|E>NxGHJ zPYWj|I>M`;&7n_@b?R;<4p0i#-xdDcrSz~*`tDhV9rNjW6h%i0=ALiubb$KUuT0%} zWMXvUS%(+>U-fLW@C$QaqvJVe`=g|pL9!XsEiq)<<@&4u%p~l1JPuaXCWy~le-iHM zeiT$g6NYmhK|0OPzw5J@f^8knQ>}H-d}ut4e9xHi(OIzN>B5SPm9p!Uu*?+})SOQo zJE~8$y59C?FO&qMdhMEV<^YRXix~MS>cC`C2e1?Upto~z6?j^c6+^8l%RH4@D-~Qg z8-y3;I|GwWmMo&}1e-w~y!T@jRW+HK#w%SJ@)*(-Ot8592OBV^HSxKBe; zSys*t886ppXK}J2xYH6EyAmzMhwV%4!df(?zlinRuciOcdQRZ3>wAM z&-5I5nk;BrUMr9oFqOcrZQ;`@bt&7 zTWzA=kvTJf$e!O89%7T>V7T>nijSB|s7J@u=n-da3L;a;D?$r01IN-%hu-k%JN@%r z%rmwZtISg#JA}r5UWPM}>laD&Mtz)UUIPsiCvo>~>27|$$Rgx|Z6Vmscx473xZOpJ zfbU0ex&|hbk4!W6vI^6V%B3Gu#WGmqkvL{kMQK}f>Zf`aPMCu$Gd~(D(%1KyL-SEr z3b=FC3iTd~UZ1-eWdKV_4Rs*EK*?_Jh3?iqXEel`dhU-G!EDm5B@`Kq`@9&DbVZC~ zL*)tVj8ym-x>tI#vLFi)<_YUc8I~s&p(!YH4Bt{fyVh8Pe?ohZ@y>m03V&xX2z{bJ z)JSKZw-*$YMFipeF6o2RDGq%CLx32Ok+4vM~@ z&0&2!4daCiBy{C4Bw##dpa1ngMvQ-DD`<#7ey0>fh{!<%2kvQ%H-$nNN@3d(?bu`f zFs%%WW~0W8(E5~wWr~o>rHL7uAflHqzft2oDxD9#y2XT`4GoHVBhZ`h6`9Xs%D<}z zkz;tfvPM#OUCavDX$QmS!h{tdweSZCaN8{!QmmAY4_d1RZk7}lgiEKrwyvmUNom_v zibk(-RJXzPvvP( zcR;&F!V@#5v3@UQZCjXL*tB2~rba{MmdN96jNr+q9W!_ZIi4Ut>gzh&&z?z2U;d0M zD=B!#`eo4A}B~T?L%Z_42egp&% zV=)1c-_XD{9ArE~h`t}8iJl2Lp!t~!=U+gIvm_gm*C`Fp z=Z&3*u9=3lbmvDmqpIB$1X6aGp@A7_6!1|?i}DCSKYjrn0y)2+Y;F7q2ft7I#9C}Y z1Tk`)Ki@k@hlmIWPzQ5WBtv({w~|AV45~{B=D@dl2@1K%=M@ zptFadrG5GcB#<54n`6L$O?ATh!=F!3yC9B$uS0`>uYV}PM>z!%QFeP~J9bz*|Jx{1FfUhW7wKh4jRvf}tm&0s!P0G8#zA^0`L1JRFS+Tj8EDt-P0 z;KbQU@rg?eetLxh5aq~F63`)?Um@dfOtB|vsQN1p_hMoY zFrdWmAH1OCKtQ6}T;RKRGMhsCw)Ap*VJyif$KS~ysL;uHfiV`>Knu!m$v_W?-bPG; z1ptHm3y1;=1OdXB0QTXUk3QCPb_O8tsYZVmq6K!Z&Ols&)C~FgJM)(jCh^0`kPe{$ z^AKneY-fJ(UR#9wXW(lC0^|WC!(dTF?qyx0unoR8hNaqnf~uJifsKIePj6+J6l|PxEE$0eyP@iXntdAp9QiuQP#y{q-gT ze}1a`bV+}(?|fa}exa>ga0Lf@yI0iXPt+fL{W#*qz5`jHkO^AyC|c${4Cmf&rYDBO zmJ}936*=^gpQ!Qzehlx?ek*#MlRfl((C;>Fas|k9xVm}&g5Kty^v4xidM2Da`Y<>g z$gj7tJ|#f^AH;!CIIGyVN&*J#4_qKZ2CTnd8rQPe0rG1-Gx-p}164lb^8BxW073kI z++y@Wy=wgcvOZBZRRq^P5b(PP!F}>+NC03BY`s`91aH4d6?uSMWD_>Kid>%r-zTsR z0)(`^9&&%o&(tr;7lbe_5Gh6$IB-6gMk;tKcG_fPy90IHq~0BAPFAE{%t;@KpmQZ0 zR^5mNN!d&lI=PJVT~!Z@l}geRuPg?>yD4PtKBY54r_q7JMwn^D3;_9+xOOt`i$%2V3l=4@rL)1F#x1G$bD8nawbV zU|Le~^UtY0A60{U7Ph9eT%zFA!s%h97bW!NQ_VOD!yT#Gx>vV0m?YQiJ6JYlrN4UoIm)+druuFi#ZE|%0MPx)<;Z1J*xpG}QO?RM>_ON&2>l$<~FBuzh z{&8;osU@k~mKX7hxz)N`{R{!K2SWoibc>3){1YB)9M95c_AM<;eH94owBPkPbPoB$ zsjSf%G+G<4tsG;pTLAnOm!KL4CR1{|V9%-dcuJ9rLY^6Ji)WRxABsL(OY z$l7mBfYU*m!n$XtVa=`yL8H=pyu=1OM3;sLpDC}e;6Xg*=y&QSO^~N~U^J86!u70C z$Hac-Va_Z(33N!DZyu5*D>aI0*han+%8!$W?ZqhuK`K2d9lwNgY@vOquil6l7xCyoAL@Py;=TDsk+ zLb>P3Sf0p8GOSx4n)BlRZSofk+6{hlLi|V)5{j+|Ye(jv3#jon z+@l{HK8h8ByGUu;qRoEV`gjtH-dE&fbJO8yj~YL~#54(~oJ@JW!JoNe|I-KL@F8>BR~ zfypKup~c4Y1EGKGPPR*1xEAm&t2zff&HZg@8bWcVoGEo!@N?_v9g`DQ-*FUL_vgO9*Q! zp9peq2Q3mQLN8=0*r`36XjAJ>?aP`XYbak^u_;~}8i=eN3Er+xAo6865zz!3E6MYy zOcdoHH%3Wg2+PPPpqa=80mGsrV=|1y*j9?gdS9i1l56$}I;Dy_7Jh*D%7`V+XYw^^ zDNVJRm~Y58$qwh9Yd~~9tM4#uF=XN@S^XW2B*z~S9T4H7Mp|R(Ji>Gb3@j9EJFBBU z0kf*~tL81{m#5N~`oh|p5}kL=?OMhY-S9s&L4@HC9r;fXd4@VkDG;U^cJ7(Wo_NQ! zFs#m6#~u+&WPFh^W(g+f#!Oa=?|I%1OOUSsGV5IkqN?&fZB;0V7MOM>92=EvFKn-! zm#5w^W;3R@X(WF^cvePf-i-R-jLhi2fjQi%&&riIdG4Eb)&j~dz@k-Wk+K*y8(%uI zh850=Q}#l#NU?cJ)?R4VYjpp*bdGXq9C_+6q!qQ_^A+aNKa1oH45!3OcBb~cFBLRM zOk-q@PT^aZn{%mLxv?QSq?;G}IVv0Md^iM1Cz%}egdBC{CS`dGmEd^1dF-@`-Abzn zo4*BlZ}t0F`mOLZXC@7M)@>}cGP=3<7fw|0Ujyb_eKnAc79UqF>!y%5vWNBy+{miGiOb8ZoeMnFWFisSTVVeQKI=9W2a9nn`6&z zj@IRW}li1f^o;<%70UuIqKICf|&}U?NA8@**~Ysy~TxUSr5bwCZ*o?MOOOn2-xDJJ&P|h4dz<5Z}EK>5aJ{MqEo*YSE>!#QZ?uZ zS>##nX&Gct_Kk+~bvatsFN)3Z>}0*Zp7%n7J&sx1YMKTuKdkmZ{fxBU9%2)K|8xfQ z4t~x6WwJQd;qN*9X4;Msf{C#2P540l{FSKKcTW7A2eU##kAd99#-BpGq zJJ4>zQ?p&bQ2KiuKhoRT_pr1L_qJAC*h97uESWWxfM4xhwHu=mU%!&xpAX9CIwAk; zdCal%l*4yZ`X53ZtX4?*nRSkRbO^GwpSk%eIO@Nm?7^HMet z`JC7P@F>s>y3=c9!RKm{euE#W7Wq6QY-Fv6fkVSm4sT^Uy-bFIUlvU#W~^2w!y}$s z1)0O%XqNtqPzP4~3M3gMbCh9uH|ERQ$+Cyb*QZVvE9Fqa6K*-TF>gA}((C&hdicli z0=j?38z$j9@V4E~l7?_Rn=zZZ^NQ7+zOoq4527k@~bm zVzIHCcTB;+>vvOnX&w7Hz>3bL?rm`*s~&2fv6Jv?Q>@F|YAL|L>O2G$aR)pYNRn=b9qauqy=|nRQJGdke-yl-C?N1J7KyF;B^e(e zdts#u_PM3dycO9Whs}}j7GfFi)J^iwacY$@p=u;mi+FC{c^jZ({(8sf#IcvSv~m&S zi-VdWtN%ZBI23W38C=7*g2dlnbKGt_Q@_N`FQT8!P!23wy|I9m@ zeApQ@rBiiOo#3@ZCLa`pB2XMiB#g3juxZwIc4zP025u#nJm;YLE1syfd@q&DaqT~x|D8zEjf9=CZhZ@v5WyB z8Z;85ard5Tk^Wi2jOImEZ|2Ohba}!vAFDgd%#bo_K~UO*obAyabS<(I;|0puR3uM3 z;XnV;@q~{`#~DzX`0kt7;DkCfU@)-ZXjrxghH@HYDN=?$nG8*BCAata=4U)%_fqwt>-oV(LH2N*mkdxAGn(+x`5{+;z1 z=zax;msh$k#VX4jGeVc0$P^kRja#_Y$jZrqexo33&i)w*^Uk=m|47sHl98^XtHidq z>-&|6&(U*hYp+Cz7a}O83|&Cc)6^C9*G$P3*`MGo#2SIUy~nO`be}aP*gI?Vg8_rH za8lHM#*Gdnf$H*!a3qqK-Ts|B45(zFQ3BiNNQxV!1=6{Y{4+9AWG``}anOBrD)xu| zSefBkQ zbYyw^o#Q5KGxF7ny)Ha&%NAu`ouKH#y)UdEEK7fHq))0je$J+d%soEhsnIP({2;A6 z&tB?rocEyANI6g$GTJW3@*q%shO-%1X2~hdc8eb2yH4c7TTTz)F5AJ-a9OU|3DXTH zFaj62*xhxyZoWJf9)OY9ONK20f#5zwGA@+Xx$k<7`l&df-t9cUGK({5yG2tE6}tDu z_1&$R&o3j${?2kNWzSwPQGS%&lq`bnz+mHJ=CQrojl}5gTm*AZ#k|I>%#&;#jan>E zk}rP*I2;P4@z3NHS_S%VSEzVV^josiTrcZoWNs_h52@iK@6nSuSe>D^ODhbycQ5IO zQ0*(t)t}cJ=vWaL08dntF;u=kR~;4wAGOzxTf-q zBuhQdGUmrDlVq&dm+cgO-B*hi9Xh|}_2crD6qp?PpkbXKplo(s<_%K~vBnfV@nO~> z!Oc&}c$CM7l<3g)<_f#S%a|-1AAm!oAUIe^JQHijs;=%q3>d&B3(8wo+Vue7av51j zyTt0x<@jj4DGQVVB;WpR+m=h|Eyr6~)iJSP2upbXiD5%xOnRbK<|QIK;Cdn6HjimR5}?gVy)T2S+?`2;|A<#ojNkuGre_#2SG>SB*yGD z=0!)_fNZwrBGlBGBkhwliB00fbi!9bhFDxF&EO)Z2nL^$xeN>4Up(r$O6E*3<+Gf+ zWIVI8dcWW8!s?n|+=We+{UhNpZCGe$m@sleb~b~}+egBlVat57_@rY9Q;aeyR z0z}$N$-c&ric(>>1}$r(cZn!CqZvbD_+CZE^2h9$xEgaIx zkVH@(6Z*mWFV1wGaY<@f&8f*mGkWN8OxQb zC;YS3*OVL57%yUbfSED9Wl(02nSal*s`a!7ocUkd&}`1Kz)f-hK^J5eRwR%wr@HI_ zPu>ABpqF`qEm}|1@~*TNo##`>tYW{LCn_Xwh$joi)lcK4rHLw)uWz|cln9ggEwWPA z0l^(?1u0Q;8Vgw={kq89G#+4Ap%t`QCHZRy6aKgCFS}#T?kFAEmGkct0j04b>c%(7 zh~&WKs*ugxrPfcn}H&+Jf^9p|(I(E|%lVOs!C?g5NK_VXzj|MUo;2)q;0+ z^>OG&4F^;b>NyW(o1=%xj5;z;HA6d3*u{J_Bmj*=q0LsIUo16ure~=qdnmqM^0@kU z=Z4N2wMb>8@U{yN=Q^!O<9&KHcH2k$Xa9VkVV+}+IajCz);(CZ`GN?lY;1fC(6i5N zOZ(axS`0qpQ0=jKv)>G8$U*W@DoNH#NRK^@a$D}Uvl`t?ZU@IK#$EuaL-|Tb*~bxRW{WnZff*)VSz9;olb=2ogked5%?_$|P5Q*#w(809ddZ z2f~TEnNC{{wTQe+tTN>qlGA8YBasYJs=G#e;mKXd8AzNOT1VQgy7vT(XpPs!w-U+B zBm{fcx`PnC$NlA2e5U);z~A)>nqW27x+zjR7M6zEO*M#DkF$YTuE$7D3vp}>*HByw zrjn5I0n42o+$B=)*lS$*gesS+cfDrcT^|#j$R5)xvLu#!@Js|*#2Pe`Q0PlUK|kJU zXEThX-0bPQkE_{od>@H`iKge(a{9(3b(5mnouK2v#um}A4zswHvGPQ;u}#0EsuS0u zvJwjaVm5iQWQ9z@7^a84r0cgf-BAe}!<>QVS8;KOig%f58E7h7dC0vxiCs%@5Ri6} zE;C;wtIOlpcqA>2He#Ufws{?=S((X?gGBG5n0@ef`}VC+>laJ<@M1?VU019<8_Fg( z)xw6(isfsJ{7Sn%O>y|04@D|dCDYYAbu4lpVJ%8pjCW=|rP@VPe5;oI2z6uY(WBD5 z@?w6eLw%xn=97?$t%^rM`AULs)+D*U$GEdMro`9zdvPC|u&)mw(HY9A%be6PEh+r}n%R`Vsf(z|&mmue~o25a(h z=UEAEA;*531>KiCg<$O8q9#{QqKc^myQJ-E>si_*LH9N9T>fVN%7xljd4MLcq3<>- zxu<171W&fV<{Fe9ZxzdnG-$RF*-I3-oHtTA?f9s;Jh))%HVmM2)w#Z#7vg*A=Dr_g zuBI*4gvJpL6MXxjZ;Smv-+SQExLu;+QilKV8+0UIRl!X{5}b1%>Hu_}9goGB|CGz2 zN!n_m+S9k~qLiN-_Xu-iQhNW?PVMJ^6y2mH;>43%ep)hur%OmAtx`DUjrs)(7jV#j z07;<}9?S<=GllUdaueoGs%k|w<3alKX_xcW;LMh$Kz8T9`-rD=6+{UW=KCdAtGZ#= zkw$s2KyVKzdLYgq7P;4#A|^6SNq!f-deb(HX|LC?Jq`tx)wa zy#~|fH#<;&{hp77fG)>I62!0u|9aFaxwy5XZSR(lmEj%1YUtJ9ps{ghhvdHHkX7%n zXH!biPdYRH%MV6{tbEc8`X;y2B|v!-FgaDSr2CoyYudhQ+!j3UxC1wuQEBzzICjw& zUVJ=Z8Ox=`6nuR1B)#3S%f?FoLH8$74EleWm@)tNI@JH2iv9LRIG73k^ZI{#2!3-t zjvK59-5;vAv%u_S1fAlqDjnivS5i#TELTqRIA%!A?8SeR3lm;p!H7_!Si(A8oTj4xT-hc*Gdu_S>6^cv z38-OLhAB{V)CRih_@U|Jw5Vtwf|JJUTQ=;=+p9C+&W(@%4`bgLoLLlY8QV5Gwr$%^ zI<{@wPRF)wvt!$~?R?X3re;AiS>(t#?`>efIhx!(SvdjVwkRp=S)qpc+gztc}C_!1Snm)ue&gaF-L7W!(sFA|uPFj6*1*#6(Z!OG+&s z!!rd(vqp9?{?3Y(hkQjK24>CVwvg;XA6S9s-UiiXfLBDvh!IY#*%}xheG06@0|xKeCt%TE@uUH0_97_mvUKv{6!q%;VGs#|KcE`0VEtUIJ#%3 zJMvuCZgjvNS-q0WgVW8lHaHp~y z;=Hdjp-acX7-9bsNWGo)2pNZ=}rI& z7&C#8ON6yGAVu!Jqp#w?B;=2(4kQHDt@X|DjVsKObtL@MO56VZC9JaS2vaURlwDXv zb_vU^7~$79j8)mbgEz7`a{J!p$pj&V)dPesnUmx#InD}M!3wF1Sda+wEU9y*QC_$y|zGPkVWoXC38@Ii&lz;=0+ zafQf0frDrkm?<&Lil8Y0dz{}IWk;nbdedBWbhOBx|=j_1a zLqw70R}=O10U5CF;!&#T8G*|ccXid@#8yRV)+Nu;8ZY)GzCz%10;Qz}D|sNz_)EWC zw)WQQqKroW{JhQ=Vt#2wcX^tZ&d4I-F+(VZI(-a9nDF3l^_In~?f`Q;&6a0S`9wzu zpTO|owqZQ4BfEU8i@B@tJ32Sc@yb$5W6;2S1d0NQ0m)hu&kaVzA|{J|mZ0DkH$_E# z;hsE{$473PNI4G>YwzmPGqZpmFYoWg%iGA&$mbV&Ej@~L(ENTlB=^WOxE58P+-5>pqsO?}P?fEqYZhzb9XQ<1 zA@n#bJ6n-RDKGk@T7hu?Rhjq?8@~USSV6?h#KrvI zEfdpPGS0XhD7}{&jBSR?D1)C3I$V@d_&k5sx+2|Z)T9ttxf(S~B}0n~pZj*}=2=K3 zaQI9AR&0RI2V>{Yzje-^*-Z?L2IBd+6VrT*hJyS7WmD9KuDc?VWJr+@9{(Px>zf=v zBkUuTG*rgpJuY~C!!|U+nt~M2|GLD6t-{kJHB{yN8-zWEfuSy1F>7QP3nksc*uW1{ zCQHa=qxeg585164iGoJ8epHK+EXf&ih-jP#z#z34LH`C+( z!i+GSGSr>BF6*m-&LYuhgPP>lKpzA>M{$RPy}mYW+N686X@umJQItYQs=B(Ef(O0$FJS(>{y}U1RA>a2lSiE{qCe7lhXA)oHcm zr3gd2#Bbwvio`g4IctMs@5rGW&)D5t^nxh#r8I9T$J3-DXCrNcvUS}+w0gMLWYgwq zW&pJ~$5z_e#F`$4#JI1<^<=)4jRJ)?=T&-G_4<06(JLJzGw;pPBsOF~OeW99ufWBT zPjvz9*7?)c?i>_KcJY7@f~rwb=Sx`5ue0=IcWLXc3)u~{ioNy?dsc6#{m)WH75&cf z3(tpvMZ#$QP=Yo?%%vq=jwfCK+Ru(ocTqJ_D&eEXQg^{gR3(;dvgn1#6q=ys}Tq+)4wvA;!PlhfsFUMhrKUF^Pv3ad6E&?*4^Xm7%h|qs%*)JAYIpgTVEfyacV-s*?-7evCLe zDmgAW3%LwAYz!F78Vf!9?;NT*2VQ5Lo0i4Dk3w>tA&gUJdQfhs_slj9XdQwD%CMn2 zMz|avaoRrKOF>x57YXLr=$|2ULa=xVE6*IVl6(&RYPX5dBXs;LiK*m>aDOVlw3_JM zi%lALP;!jW&nP{b{qg3Np9Vwc6l8KdoAsXs$H^jzZtK{bLptg#^(IgS&16qxrO8KW zc{G6u7ZICgc=fbXLt)(sste~Hd?r^wh>7GH8`BKE8GJr3aM{lshbDBcab9W92f@_! zOk6{&VUzKZpVha9O5p|{9GZ* zX#igS?b=YhtsukX>EWS8QO{^nWYtWdK3NbqlGkL}VU{u)O~u!54siDYFfxEQF(Ti< z1;(uogRQrrEFg+Q@Q2t;xRRVO=rv{&v-uh3q4xd~*&YkWC1Ra4G3k2op86Z((gc}y-DxI;Z`W3xk4 zP)jIVVyqd&Urs^?_H1v-m>Q@4b!<8cbtL+v#DxhkpQ$chkTY$owizQoz|_KKvXd`1!?d7{5Oslaj4@cou$NQ02UdQlp{|rwx>1d_DGSZF|uh|hsJMG6w`=EI{m=9Jqa(JChEq;y0pSjg@n-2_c#k{? zp=dzKx){>ciZ?*(aPOi9c+g@d&!XXe!QUpW!|Nsh1;%i?-~PRf8cCwc+qk%FE@tT@ z!YkK_$4@42Sk0;0r5?GJF7$p&vcl|s%(>N3OKs4!vno>=l;=1^d`u$63?~7tf@4vzNsg1y)j98z4Vv)O`;s>1MgF%eVc4$8X00nt3kvX zQYQz6VzID^PifSeAQxCm*$j#QO}YhRO&;p`%%Nf&v^yk?3I$+`X-vBKg2F`u1G35q zY9&;r*H|siEY#1RTwSfB^%;Oz>GXHf2g{qPf+apU^*HuUJ*Qd^3--C#&)?1MbpA)f z{a0Ri#Kfp{M={*7lcCglHR^Gkp19=apX=8?Uv~mXHNg^C=fC^n#bMPY|4~@*_;+wJ zbkBUcnP~74t7rIj=q~g8yDtw+jt)%rXlR`rneR$)J2F-3;;HK!OcxXTSk!uo2RtEnj^}*TH#{T@%2K zIO_v=uWo{A=LrUIENg~FcgqlxP|PW3=J@=^hw2g8s;Vw)jpAu{&>P=QL#sEd&PSRs z$uTBijC<%y?O{u5B9t+Oyb4^XOQR1~m0@{0RHeHfymY2tmX8*|G-ld6D(%crizebH zr&G;KlT9XV)#Uv0ejcvGX#X`X-XZkSGBu)0QTy@~^C?;5B`clTs|gK#eHASZ z#f?=kObxZaYfr0&4(J;>mTi=5vCCEP%jGry;MCib%l{E%{e@NC`{wC&zb`y6+o%`{ zPV1@|8n4cY9rb?wAFY}Zu)vSb7 z={d+huSR|BN^?dlOn$dVSX`l_??f%yYBZYN-t%V?%q)oe!$IW#W%Bn19o6I**7h?c+^-4(l)9zU^uc5Yj|bH!wq+B#Q+ zi(AB2&`EEc(-1eYH)pJ_mgb*Ck=GIkm&kc&*OLBGe5J5K~|@{6jZr z(!d&xN&LKsx!(+K-!Tu$npNI!N4`KT@Dq>+p$pWYDA>=76PonyTQe)NO0i!EKL}z1 zvvvT%ODox$guh8i8JS&kK~YyPn<71zd{$J9-+JpHKOrEn9D;PvPt1bgrRtbql)wQ{ zgYB%c4q!yyg7v}Pa8TBwij|NN&q|!8PIo}t$U>FBt&oIDFtpzdk=R&f3z={rAQ3B! zDFr9gfHdPIWrH5eB9ro!lVzab`gy<*m1Abn`4FFe&(-nW2R#b^RWIxVB}^Q9rI}mc zVmF}kXg-<`%VJZwc?&gPBlVh<@?)6yX4HPL7%Fm&kMkCUtj-G$kQ^+4fGV~$lo;iS zW79PJ#(%i-1Vp{=IyT)3k$^{x9-!tMl1j!t>9VfiGt+7p$0#F#{-$=&<>)5`<>jne zrI#w`nLru3XPk*HkP#Qf?Ty8vP9+&ZDN7HCqAJs@BxPwM*w*bZrX`T{Uncga+k}*r!Th6ygk+6EfZ= z9xN1_7;~Yn^-}yT5>mc)9C>Mh1$ux(%p$!zW~DvG9Uz&?WuC~rmO$ltEI~lmvF@;# zoMmxH$?1snI#%ptQxMp@uq|?%6|2BRR{JsPyzG59<|&I0YZOp+#yho|N#u${#O*-P zD5nST%ez#vu+7>{{F8JYX~H*>9-l?WfzH8VXXoA8yhkJqdS3>d32H}fioypf9v!}n z1aw+(|4gJ!3m3A_l#Ekk_%xo6O8kr8ASl@C7~~gmLa%Dpb(a;i_rJybXl#PxJ_3DG zchLL5(ydheo2v*(8TVg7h&JfHU0Cc=#qW1M60=<7!4+Qx_JkBfZT5OO#tUI#1IjDA zn)C^#n-!le!!7Lx%DnOfN&`$nX$lxBc4|RRA;0py*F}}ITZr~dH1$-`PgG= z`GAGtWfU`MLTtK$)-3pTKuHqhbI+C0{es{u|Lo{8_qn-X^YRIk*!%Q8|Vw-m}OM?hIpY zEUav?rtF}(;7@1TqUxMg^K^2nkaMhO>1oUost9RG*BWidy1V%HpGt7I$_PhAWMVH_ zausBWp)(~>5yJB7#=-L2sD9v=3?5J4loT zw4OGrIsu18N3a7`;zB_1FHX6`pvKGZ^Np$SN$}=^;LT&K3I1o+%*`TGu=7x@yK=^) z2lB|drtimc-wHK$-}l}IH?g9c8#jv5g7!vI|DccExqHb<{_8xbcX*VEi0hj-8bI}T zn4*80l0ukKcZ=WcMW4wo9E0QfX#Ij}k3 zed;baP2y~}@>APceNoBkKaaZkrxhcqu`w*(f;>m^1|w9En!#?%8uRGWlF&Bt=B^5NTre@K6Hjo21&3|E{O?v+t@u~E`4C(Q_?)+Rv-%C0m&8+p&-ZuU z?G^$vjB9Ds{#oqMMiPzoIM;TX0-J^pe`g`^JvwQ|I()kbATe0rD7q-VFE8Nyn40c> z+$7}PcnuV9cs$OV-_wRD#D>~^O3n<#f-u60FeAD$B15lgjzRRvSSE(9daRX+3wP9$ zbse7kbuz#Zf(9Ed%Y+YK)RzlxrwS^0e!xUxL9L~_!m@`fwMGk_bzmTgbCPlr6kx|s z?$+Z$)Y#0Sdnar@>x&6*5$?7gj51V!q2J#@!nAYn{EP10$tC}HN5^Xb!$@nkrKxAP z*R~KhSwWm@5^=F@RGH@z(lRR#i)lNK#Tey~y}^`gy-2Ah59ADs%3p~gtOQ5Mr^I;1 z5sYlV6Z{3df4^xM!?@Z0zZ3;n^#Csb+38l9=HsgGio3Drs=N^d2rA_2@1}7_16GzW zyve*@h|lMd+cBK&&Pbqm;0_9KKjMM!_u#+bc(wWCO2WDy?cH+x+b%Uh9iAq_e+8;B zwvfdRr=Fl2%mRS=XHJIx3q-*7U)+pwvU2<{KtS~WzZol0lXKqWgzGugIGY1yQ&~JH z8#ZpTbTczY%vs67bMww8+gQ*{Wlh540Q3S8Q@AG25WEN@5kc_^#w(^?CDXn?lIt8@ zpP2d9MTuI}HvbtnOM|NLOdKbjrNvwz%c6b{m$F;9?FC^op~uDR35k}eX{)&^;6jlKVu$aIK`6GnAF5|Wg&IQCsL8|r9KRh}HHzVE*6Tm?@ylX(o)7N8v6sZU zi2~uI?^u+v7f9h8LI^+}?towZfl{M{_W7)%dI`7=)-Dd!(Eq#%&`D3$w40e&tIUn- zdqXIg{%)Ws!_{3CDmNF0Jzv!JaUKx7h4@GC zm2i1$zfy#2`$q>Qd(O)z*%Q9a$)$r z*3E6oQb+4ZxZ9SLQuo)7lai7qz$H%xgZ4zaL)W*muzcRW@+jk0`3^wv$_SUhn6!MH zZMhUbwrJOcpph1$hUmvK^Uh_aaF;Nq9AkaMweGY+X*C#xhJ5dtIc3b|A0z8Llc~J1FH`i z0HJ?`kR?VrQU`OnN8?c{qjoG7j8=to#^z507J~3tAPAFCY6m2w9u!Y=lLVc<=cwTbAB!I6@ ztY!66)4j5$X;I0S8wV!V^R-c>r#jqRA41|8DVdS&YGw3$=VU$aphgrFq@)VT5-Pzi z;+AKRSr&OSosXxewv;`L5BhJYPFS8A#$KRaec zxtn1bQTYd`bGzx#loT>}=iSp6&iqL}jM4UX?{w&9CM`J`v1d_b<#EG%lOi^LaiW++myC0@xKivN7aKu3*Q- z^>iN|HN4{yIEX!8@A1aNO36MIBVJIeVlx@M2WeUSS3ZBwzI_zGBI7X+m}QO_f&R6j zoV0}Z9My@``f~6XZdwyduzQ{%T>g&FbHH{fGh*_w4}Lp2RJtwpf4X}*l%nhR_gD4z zi?z$Ss6Pi)1jAqq#LOqGs<~+YP<^gSzPM_x{dp`Qa5~Z`5}3I$EphwUGkIDYZWEMo zI`4bv#nmoRAOlj+U^BG~^bF80sKQ2ftXkA1DkbWQDMM2MTYQd`=eYohMOHc5L6|fm zUEQ+ZP~Hvea@!i(sKtFW?>y3RB_;sGrMs%T8ud3*jdu@EVJ))Nbf*5!Q#>M&tLogl z_bVaF$VGcB1oN;YF+2KuvLThypHCw?4w2!Qjn%;@KXWMrxJuVr3jSzE$2CL2)nIh= zdYNWH&acaWBHuFkg+}hxGB<2aS9LX9N#wfPt8aXwI>}PjX`P{xtZU{HeY822&BN2j z>;L1S^wN0IcvbQ&2Gj6yac=E?OURIWMJKtjQk~sgqw9XrY`45*`K_jW+T3LCuXY6w zVeSw2HbVwm46g!flAO({A-k$hC54gU_H0MPC^xdTvb^$Ck?_@7KaE!0aL-fx?k}8K z$GgkJ#j&eE@DL68IX>j$T?GvY%|=KR-{MitAx*Ff^GZ=|kI1C_(u*HGU@5$*N8 zdBU+yIZeSCxi{pD>@7a0>!dfN85NdA;#O=AXhqr$ehTR>1c=x7<;lxS(P!5uqWh^J zut0QxHYcf`AaI`@)R9KG;7+ag?qJvQ3thK9$J>LU+THP?TL0=3=d4yA=t7r__x0C< z(1p{x`tgG;c2sPdeFss4K1f%bK(=gxMn_b*5qe)%J=vW5+Ji5J*-x;zqPrsn`B|S4 z1;lzHX~(3)7+#V+UN|epyi-wMPfq%&J%T=-4Shd|l3o<}mI(#1v(DjD;xiMHL zWBFz26y1(Y7@r^plxtC^m)E7iAKyT534)DNhz%XEz2d(*U=Z!+;uIuDSHNgeZ7os> z$qBl-WwgG3#y#5rA)k7SZdH=no)y#I<|&3MaNyp1hq+@eSfyZ(dv@7HtticVf78>w zww|pz%(_$z7anz1E+3&hW(!UZb7z@k9l`#E_${pRxL3x+Md8lkY84Dp+JS&+B}e(_ z%g<_ccV{0G2JF|unVz{3UC0X=)OP7b$}W@pv00>N15QR!ZMLyAc#od{+NxF=y0Q9J zPdH9Hgi4px6-*I;p3;e@Ae*>FklX&mm8<&uSt$33Ee@>L>&NVIeG=S3c=4D4O`5Y{ zxpO~cg=Pra_GWL9*V0=i{_#4$-BpImeCSaY+{c~7v2kHB6P2ceKRxh_-o`yP_kbuAg=mN2 zgR0DJ?Sy6mzZ;d1!F4AjUNbrf4$7i3yF*-<>P8MbggdGk9ADFMhS1A@B8ea5s@ zvh-wir_$p%S3jA;k{_ZNH4Qa!;yvkY+RcwgKCnY{$SG!jI9WRF{mwm~*oj|NnK?3v z%J7lL9rK^s&CWFBVTXzzIs!!8?j{BL+qWN_R*HC%D}5dqBc?b#Eo|B`=3SHN;rHty zqg8m^apP965m2GA6B7?{`WQ~xA_Ov4z=OAu8|>!a zxnHHpQ0(&q{NUYFULE~t>}Oy??PQcI{U<7j?Uy0)L)xjy>5Su5aOT;JQTs9Tk;V^w zj^~QP26C~GIp)=co_l+d`Q?{)S&YKsFo&q<&@ZgzL-h!B-A=&|Jmor=$ zc+070H98G5-dRhM>wo=fe(RPo*i_EY5mvRdm0a9?Sc=0U+VPhg3V}Wn!gl1S)spi8yQ|w!&b?rcZ5WJ=~YirQ)S1I$E0@lq#u>C9imjq`bTxdvu}ZRna!@ zIqsLLrhAG!?3_PuPqh9xT4|7=q%-V>I!eV_NJ{g@c*^(-7WeCrlV0}0tTXzaIca*b zWct!kd#hQtWSSyk!KBRR>HNcVsEM+vI*GjPuH4XSteH}go7>cL`n05jE9sc6jhq|* z0h&VZZ4IG}^FoA{^BA1x*`Aa#H)f?IJB7?-LiI1!!c$&zdkWs)+_AD6^3F8&V+;?j zZ-v^2Z7H4gaGgKX=hS53#Tw^n!wUE9Ck+eSN@tGtr^+^EMb_Qf_aLzG4jCBl%q);K zD%|^xuHrT`W*`)0Qq(lgoca-?Fu`_c1FQD=NpAy7AgDdK;uLMMc5DPlMBjCEbyF=aFG&=r!y1NHK zxWf``=>~Om>2@mQ-S7jv)m~R>wY`0v-?ELT#Ds~;BuNZRjDgTv8r+Hv^Gi;_prl|c zndU&x&ND2|&#?=nBvYpF=mG({;p9rd8$9Xjn$ABmB4Y&Qw{H#P)wgd2l(xq32@Z{5 zjEulonq1gxoag7jF;7o;0JY|Ze{Z|w$-)LMwgg6DUlD|~Kq1D};qYcbRT+)v1o(m{ z;3@-QadNJe16U!UG=ZSt}e~T#YN7J zjs?qYPWdej9Q!5t5bfz)nILEZ2!h_``N(_mNx;k>>ivDvMWN)tlo^>^UlREi##d*B z_K09Uw3?aNAT{{>vf0(K0WSgZXFy_(Q~}j=a~}c|$^fN&h_4ndAPDWSzU^<*?{E^9 zOM%#DczD}to9CMCscJc(zh1 ztB?^eW1vq0)L&KnkRskJIuelDkSvn|R>hw~)1&Osnz+#Gnp(g$`1tvNF@?1$0*kkX zTRRtj{Myi#*yxr~|M9h{jj^|Q=9p}o^OTzDtL%V-LH~0fS|LD_8Hfv5{oLYWQ$r(Y zfE!SLRRPsDA#lo;O`tyv_K)UI`M~7RKaUQBFC~b%$tkS2d&ukk{98CM&J7;m9^N0i zH~k)EbXj2Y4navwzVb05qbv zv9|&{d{J!2`+nF@%=kY8z3YPt1Hb9(GqV%sz=9UKJNJ$1r>;oif?M=ZCRa>*qp&}#xuBZGJnc+f0}B)M)S2YwLp(;@TPv+wSidSo}K^_ zFHE{&7=)|gLlO!1Bz&eiVl&%W3Vp%K^|)t3k%KRSTe3@B$oU>GJ}g#V0fZ7-rvJbSyi8u{za>VD^xcu5 zPWtalPy-&mnEtq|0EU0=Os-8#??!1eGyyV~BqCXTiSI)rqmW00KWmVi@eK{{8ghhr z#N1u}^4Ew?AlzT;Du6Se6hi>R7u3xiN23oEKL1UY|1hBv9st?@==#j)k>OrqSspML zkEi=1^fw-4>t`5nt|~&|{TcuHG23-i6bqR2_rnVi)W|1(TIh}?*2wp?HTV>X1!{$z zzTupO8?UvZ29F(0@(o`^m+Ww#4vtm>BL|HGJN>p8I9a8?ymRZ^a;g0=^0WoJNF|-Fv)A^IACw4we+>V= z{OGHTftbCWxK(SC9_;qXD~(i+TY8|$ARA{H%N!yKaVQ=LEfno_5KHg*C%r$D;W3&P zQ55vT9ce`UFt=tB?^1vNw@WlHx7Y=-M*?kN@1Bx2UdKRF!ZZd3 zOEcaYrT|4nkklDnxFMmY_)zjb&2p&lR?eYOx}klA5hpPy5!p~(@B`E@Ds&e4@?SXg z%hQ8QkDfkcgK9AvplpQ~X9Jh~Tq-w(PciWWdnOSZgl&UeheGe$8OPHf4^ToHwE|@1 z&s^hJCOH;b;xCs^=|;I}5rg$2s=fu`W&m#j+k3v)cZx@(StALW8rKqA+#9Jo?tsKQ&gx(e(XkUmUm*79R zRB0gbOc|G@-YH00P(iXQ{P^E8R;y~DhfV*)ox2@$wMc4;g zehl`9+?CiKbGinFfu4~t#Pw;cU>BjHOJ3ZIlzMBJSiE>a{b}sh2AThAO_nC;@LX@F zB+))~;1As+sJc2zUfefy@*Rj3Ov6=HKeNs$FCl}Wr<)K)=b_X?JuK$&l3h6&tSn|s zIc0YK#SE%Q!Y_gW9RW>Z64N1Q_Tj5^0yk2gGHsix-9IHxTo@+K`5r&;d8IO3SSzSb z$#PcM8+tLwL@fwOMCXWo^*IOUG_q$ziDi9~1z9A>-@odew9IWtteSrQZ7N-1-}9G* z_)vpqr04UUE7htOzWxkvDbS=I1ubYcG#yaA_EUP8G-}^E*&58#X(z*j9#W_%8QILB z+YU>hSxZTdcqzwiT7$G=9^QLIi@vw}xn%}%fd>oMQ1*e&YHpGnomS8R_%<>w+_73N zXt#P5V-%Z6#KxLC(0TtRR7fQ~Pcp+8KY zZck2}iL2GmcOT^%(h8}4>Uk{{&70uJW_?fVX+=ndIt9%Sj~zY~rR-A#o$7jNe*MU? z^v2WG$)B6(%^uZ>cq-R9(ZKY^4xL*7A~Sfogs=}aN+$A+^1PcQZR=x)8p_boh(_%! zs0=k2s)gb3;!kKj4gKkE+2doJw7S*h76KCzbF7KvWw&s=I3A)$$o)VT0Lz!>(XezJ zbGnuHT1RILd9(~h9m)!vCfs9hrp4vVvlw>PK>JuRc{&eQRi&cwP=6>l_UGuuSgU*~ z*1kz78NVt^M2PmVb&c|L_$=9+y)rqi>Bh~n*>!T-d=mUDB;NEL`@o?}xGK=`=a83J zJ&u5%)d)sE_FuT0LE2CVj8iNH4@Zqevf4D7c)wz^hiR6-p?RkZLeUVqJEM3iJm=;< z(Kg+tF_BmjEH+t@j`lEq$?p_&w``Tc?x(0|aP=Kp)39;;4=8PW}J|?4|Dx%MG(E+PO6S7yts^xJYv#bx?6ZbFl z&(2a2cS1M}nG81^<;ZZR4{UAj45ee<)O;ZUtz4nC4{Ax^LTm)ftS8)Vof=OZk$1I4 z$6p?WdNsySA=A}`V$s|{$mX558TxH67*JL$c{FSId(M5k5#Sb}7Oq2!HlX2sedE%T z;k<@&DW5Py)h~XdeYAw8wM9dws|=FnF-j%Ni{G-hIBJI_qRP3@0GGhzhi_=Yj+iZa zAqcy58&qhIm_$h*4aEO&?ZkDg!NloB&GFn;R3!912d9lF@WPPYd8hg=(pA$GTK=iP z9cT@mU>GT&ZbfoTha_7h_ALp~Sz^mNH0=BAw|Jn|R3m{jy@$+ozAnpP6}6nrm_2tC zM?uuS*hSx)9NF?g&Ppa{=!I#tK-|&c6H{L0YNi?O7TZ*Q+-W;1!^cobyMex@ zvyNkT=P_*{Oe~D+4+PAu8|a#$#k}~=`DM#iItHobwVWALNSt%Iq)ghRKEauB4N3VN zB)ID)eSqU*jk`)mE(LU8d)orzSZ3C1rf_7fSlPggN&cuKs%pz#${XT2>H4K&p!=IM zL`ny$S85_``hyw|7`m1j!^*wOQd3E5llt8TBjEle-;}tl_EJL751P%O%8#W+1VhA` znbq&NMl^%=@;&COA`-ra44Mt-elCc7$+EV+nmmNqvM#n&m}GP6cLFu2&FqwFx17;D zDNMxXi_aQL=$^$}s5%9pF>=@NCEVMh7V$Rn48wmk)@e4LfFtR-+b zZH}U1g})1{dRXYw*BK*+KTcuS6ixMl6zPR#J-{MMqhY0mltKrUjq(CiN?s)Hk$>ES zX0PCE3UnHIbIUEHGA>B_wP{e-((Gs_!J%*miDKDIvPEe zbaU<%RcSxpU4&Lv`i)_|XVxJvz+lnPk=W!zCJOFc1GOKiU$2fb1~of44x9MzzEXlt zj|{D=kx0NRWOFfqUM-ivs;wtV(IPV;nc~AN=Ut6p7GH?`TF?^i6JVtgfHDHip!nmg z68t%zaq$Ty+LAISud~3ZMs)+jqX}olJX53tR#P?iv>=F3;h*MYnY5ae`bMu_&gZu> zwg}Z30?lrt{)%zB6U9gfp}r19M3BUL2m@OY&i)RTMkXx>tR8Q7Tv4<|@>u&m)FFmk>!OUVFF9%;Ov!&7$66#@*h!(D6_|?+| z1>dV(u#2__@fS*LF;0FN$y%6KW1D;?r`!EFQFij5HhzX0kvWXB&^$sSnVQaM(;9;e zs;^guVxdr8;>nV}3&x>^ylLuKkFsNr!3l~*-J$CA#QYO%8EAv2pe~5?o5Msyw*(6t zKa&Q~%nZ(qDblEiZpX@gc!5l}2n+nVQy;!;ipsuNd=iv4KKnww+@RmIx~w^`KYVHT z6{ZwkbHmW#1x${0R{o|)l$|Nx0&VCY;cNksX3LuaJLRAr?NI7TRCt-{<6}#S?%yVT z7H|}C(=$vPu|#Brqj`;K7z}DgI^DR--=2-E`uA| zwVg=ds4>50f52~=<8V`lmy?zdyTH7DN>T2obmpEoW=k!6e;|m9)T7y-<7TH2{k(}h zsk%$f_)Y!Wxi=@3mmUiBh^G*B#Q2lUSZ4K+_ap$qKp}nn@RRx4I8PkrK@Vjdx6NBc~C%~SPh)DP89o1TS z$gc(hOC5s5jn)Y81_%oHU%Wab%ZiBS13i4GGRyDi^2^vLW!Bj#=GNj)PU9%If*Y<9gza+H zq7PtQ60@IrQ!RlD=!;9D-Od#(2&t1YHMvsJG#}lWnoya!A|RQRFQ`4}%iYPDXh&C7 z%;)V!Bko=yMXXn252_;*Ov&;!*C#utcg=?_R1VZCZW~CdLHkKwz3uL1b+fA9MME5( z6{q6DMUS4p-A6r)d~?{qdqY9LaYR9$@3A~hT~8My1bGrM^uX%r!7Fa{zjl4dFyABj z(n8c|7Jr%9ogJB65V?>ir&FGj+5hu9_|(&Y%%to#<5!cylg>htM{VM5(7$lYOo8QM zgkh^!k}*3bnlgP9ifxNkP&~RJ3uUew;vcAEMhbk{XilYQV=X9(JgmYt8{cN|3TI;i zf7@DnLM$iX|U5cnT~#-kOVd{K+fVPbajJYwYZ6j@YkB`Sw-3`>u`tes=XGHm?^OCOPE-8l7k(Qd3HWm&33BVVf5{r*Gsyl#1su-A`}WyNMisWSK4?fa?s9t z5%ey^3DO^S#H6#vqcO38A-pw`ly`yf7Di|Qfz5dV@{b^M-a;2HP2Dt~^&*EAFZMp4 zefEHH+WLG5^}L22v21?B0v82U3?HxUnzO%X?_^G07!y{sP?l?e!25MQc-;Bs>YPwQ zK67OH=8l4s4dT6&Xy2U?T6re?pSB6dKPjz(<4sg|xcZ``t}*J87hTYGJ7^>pWS@Pf z30{rsq3u(VJx26qyr!u3l_7HDN3Qg}TH10=8%$P_ke@cCqOG+-F|IjiC}9tmEJ{y8 zr-K0#_4tzY%lpBzc1-nuu4iOcx>TYZ3~hMhVhoAS*AqDR3gBq&5|ezy+%JU?ziUe~ zf7LXq9+IiDzeEVU&`cIz=1--kcu872{(N~Q>qOVy4!f7=(Gk`p#k1|09bBEJrr&IK z+TToeFN=ZPY{$2vV#|O$WRz4NIftHV?RUJ`*k&Tled2dm8^biBo?@QdMLrN9L!;+8 z%Ei%F{i3g*L;ckB@Ma96+#6qm*6694dD7~yloh^y_i3vuV zyha&&Gt5T&X;I;nW2L<8j;wt|#cE#4l}nU#eH83%;}q*51y0^LZkK^%hKoq~`lfFj z^;M`m;WXBz+|yG0&B2SVQYX@_oU2V1H- zc*k+d_~)0Nh9E8&7twLQdY=hs_MOR?P!?;6*KwO$>BzHXol(zH$L4tFP1gHRooZ;P z_|2nj|FXp-UJ9SCiYKC17_`Z3CGO2jrwK5dwoM&8b@TxT=dW=*Fc&%HwNRLt9^4_n zwck^-8o#%&#p&K6_5`ds{1BmN6Y-Vz>mR#1#%Tz6Vu^AnW+8|2esNE~EIqB#aCJIK>WO3JP@|6nYdIc!i*s`eo zPPSQ(EVK~+yox^Ux_iQ>p{*EbTsN592kAQbAB>$tkSIZzZo6;WwvF4i?e5#QZQHhO z+qP}nwrxzudodF;5wn<0MXqX5i_DDrzw@0bpvP2&%>wNh zVoSj&_1wII_P27W6LMEa>#HJ>bj2>LM9|+`#@Pa%C%20O#$%ncY%TUG-IskCkh*i( z&2&GZH39hhPLLWIX<_a=)f_F^k&CTmwGV1>$h&S>m1$IphS-8jWi*e`{(1wQ7a@SM3gIlk)1~HXSv6qcy`mo+$&q$E(vx)Co@e%R zun+=UXAzr%f_&KKYW(<7d#6#xdra?JKf0rk$ByJAASpJ6G!FfVK`oK~<=$UuH2(ho zloRu51&Qlv@ACNaqg z9FSy$Ka1!64(^2VI~Ciom~4-6V#s+>z;JTRI^!gb@%EFhh+!oRp8a)(mM5Nv@pgz_HkwPnGYYyt&k3e{(*GDb7Gh;J})us?5WFEfQVI2q&? z^sNcX2%ToRt}%Yq!Sqa6sr(&H40I5eHr;7W_!0mUm^8Nsit-((w{0IKf$1RJ!O3&) z{^9MsD#;(1V5y#bK0KE0_82N+f~sE+{&dP#idYCTk)&9};@#gz?LKHAxRt1HJ8!|o z3*pv9modA5v2VKYSU8`W&Pl>b#G}0f7El>)Fg0?0t@izijIom0j8)GozS|cOErI%0 zFNqkEkkznGPzjO}htrPX#s+?um{l9!#3hSGCVXn1rM4NN+}~d{aqJ=ozZ33dPDua@ z%Ll_xU~)@?$f0RPFizr8o%6<7OF5BME=vUq=|OW@p0?mG$c*pdeqvPP;5byJf}pet zU5;2Z=Y%iM2yMj8woGtaGV|dr@;gzbfOyp0@;|qwE|a|rzss_0 zTtX9eK}$=OSq8y*bxQZ|${W`bA;Sm=cQ)!4?>Xf3q9JerwGqvX!Tu{;L<*Ab%^Wf} z*9c0d+bB*zNGpUEES<$Mo!6D`Fa`8S1iwkBVtS^IEmu1Dlh20Lq_4~SezJ@ugNG@! zxC9$!kaO3-0eRSm=&%SY>rTX~TGNlTf(iE621v*2<9KlZ$Yv2VlN~HhMjEdAEoA1%Yibpk$WglvC^a>^X(EoOb$_A?)PSI zbnQvlH6?}u99Qj5#?hKTF)2wea0Rd7O)~Kfjo_8z^2jBO7w6Cg5KsJPz)MLce~q-b zn3rX(XESsl~Ty!dCgR5~fcb;8ix^j@bDrb-jV!Af(64Obd8Ir`m4Y^}kme5)J;K4^h^mKe zORFSJheo{`B51ivQwlq7i%KY8L>A2}z?Eb83_@ZwuYrE5pt$bRuOX&E&f~i9kg)A* zo&NH%(_9Q^8FDS2WPt+iOs>hdd6+Ju>42j?9pXt3Mi=IV>;^H8+t&1?7&wx3eoMv8 zqB)sBXlLLQjGzX1K69%OzqmtKPL$@%B&rr--NQKT1jS8?Qa>lsrQRkNRnrA$Rc1od zm2RS_rysbj=Kx9-)hV`$sL0?f!ZQa{bj>g;H zYM`o02>?!Jys^V4u}8{aA#F{!N-qk|_Zj-tiq(9Z97cQtqtZ(qooD^xYeEcHJx-mL5 z$sPebtgR*(V&o`b_fXEEaJi%# zKeYjV&tOT~G{q_E(zL3JYPDYFve`V~uxR-6)yDh9ekK7Q2*31X`Y~oTRKjXgn0I;T zJDjAk+zVp-ckXJqS4X$h$dyxvIV^JM5n1iO&r*!)h+&AsZ3d~%pXcUVRoc8@)lPoq zm98%D{-A4{lb$Jnu=DZ~o|US`t~z$P91tNV`8d}^E zgd?Vsr4Hir4&l5--$xBgarRZ)ywngf%YeX~(_CJKqg>Eo&Yt&5@}r&R|1v-^*=6hJ zD`blb`G0*16i@CT(hFAwF5^$Lz#;3kAGV7H`hvO7E}k~@V@aI|8O>Uhw*w%MB$zp( zxl|e@IF=iR2K*Zl896F6Q%I)f!Lsp`2xb(Qu@=NS6qVptNSnqi1*I&HmLRCwn6Un5 z*xV=Hl_)p;C`CnfZG@ihg66~i=r6}X3CI{xo?7|^;6Lq7fqn1>fMv9l!S|Fnwa|tL zOVscL4Wfc!8ej$wCOd=&AAitV#%6yn_Uq~JZyL0{3kW5V+|d}q3$YX~^QbHt4pi%qUI|s5CFi*_gOtzlPC7GY zp?FfZ0TQFp#bmB6?qiYu0=xR44&k|M%eJ#~nEabh1d!QOD+VF+;`q);Mx=^Z;gr$Cmj;qG#T&8~Nue58gR`|k%#s7{ zN3QtH5k>Pmf_!K?YE3~nB2Vuzb(~c&%X0I{=9#KA=OY&2StSwA{*?Thwflq5Q+o0^ z%$3P3Dh_-1-oneT>{ zdkyI%Q{oBepy=zI{tWw#I@4Cr);TDh34~eXQW;yVT1GnrPXj!3Dt-tyO(SV1c1jLw z3vHhu`5f_0UQ5!HAy7vc$Gkg9Ru;~;x;8FcV9eqU^cH0EMaIYKQl6HbWfc+-cotQLUD9fH?!>bhikES)nx1>5U)A<9JQL?#~UcWJl z_paDtEWGO~X@U3m@}@Ve$reWU;$D~OV0S8N&U=Ma>7_-6q`&*zum|Z$ft=TJU=AG9 za~fsF2WlPI;9tZ=JxlD0c5lR>V=gN@yqz)umKof$?Mp8bj6DfU&gu9=MHNIX9@^Vh zODV=mC z07rGD4|n6_VzL~nd?8(W#In^4bbMyjcI)s|{#t~oQIdsWtFGBhQp5^KP6rpKjGX7c zDuKXa`uA`Btd-1!1>07=mfNY|VP7@x8~83B@wNJ-i!4CsVLikQxy^Pjg}?v0vvoNG zvd5oOsv|mP#s3Q5M&s;ht2MUePi5OyN+J{7zp2p)4pk6TjQKi}8egAn8j|lN{$Mhd zk|Y70?<9R^N$XWbQ)QBxBQ$*oylQX-@+_ih$d_xP_}qsmpJ}4O!W5>)PJXUoFx3j# z9{)BY;o!bnvTDo1pvmFg$<0^3WRZ(yM;TXO!MmyHkjA$z zjXf$TS6jQ4(B)Psw?(620sDKIWRgCMzC@v#X&n>^Nh&44w^sIZwgv@kRXp^ScSLR5 zIYLA5>65}Qo+51ECN?Ua(I1uRQjeM2N!z$_RaO{-RpixYLJeT6Jisp8Jt*0^+}~@GN1{06&=_{R5uluGsLbO&Ja4SPuFKsM zB(acE@A*TnCA}gMiS6>G$)LeTYW;Z=Vcnbok-Ix=*LCt5oj;^c#mrqy9*(kIw2v$5 zsdD55)88Z?yzETlbKzD^;E22=tK&x=hQ>}OrU>MhNn?(cfWNT>hU3WG?g)Y^>a46h z56NJS^AJ^_r`?9cMXxJfQwvUYqjHom7JY_TGq|eMPs0B@pnv(d9Ofi`eH=mf!o(P# z(igutbQg4n@9$Gj!pLgNU491Q<{9((#SW`y^Q|Z(whQ8;8aK%%c4D)yYPIuPdGg0Px(#5uRfh@mv^m6Sm8-!fIHgac zbrt}E1%|d|s5BO!n96F|wZuHDZmBmg>RdRch4)lmk)T!j0?YMw8cWc4%IWpoP-~|3 zO0Xb;&iqn2Gp;55WiHuM|Y79RrymhYij&%5{7ws1dE zkjo&RXkK5rn$WoXYcqULxV>G21HnK;J-eLyk%+v-HzS(@0VHn z)|}j#KNK~UB@abnW~_A8Y)lu+j3UTSwHNfmOrZwhmakeU<7|Y3ig5)mNTLlf6>9$* z!DO~f!hT%U-V+9w(%pQ-)$QJbY^bgi+XTsJanXi!dyo zvn0KDWGy9)h;%usXkap$kbA&!)gUshtUJ9*4aV-t6UB4lhZk2xYXF#xL;lR5z(ogFR9fdVNo7 zfqUf_lE&iBb(|IrwDi4XtzB&^Ghc*jinxrYJlMXxQ|2g+iC?Y=vHJ|yq2y-0ooq39 zI|^X6w;U%rj71@kM)@c(^W3Dq_cu#!$1m$`4K!PwfW`5lXY08VX@=7h`+S^aOd$t{%N9TLnSQCHe2*rJ z(d3>?Sp17*pfm-2V*+!SM5pK%8b!^eSvx99!lIL-+@TYIe4&dGh60)tt!CrISa@SGZ3)m1(MEKS)Jlzv zW$8c^CeaIlp#R(Y`8wNMoV1SUV|>C*>X7Fd*@>J_4D@e4DZ*D^v13;~&h|k2gS^dP zd^}Bym8V&KMtA271!Jd;NI&bIvVuv1OD9EhSV(Qq{DUVOTYLfyWv&giH7FZ!u{vo* z({rVP78|S=+Cs`0G*)cU^=4Yd0jl*DzvSb(_5rwDln`sF6(y_@uC?dRsY4}>=MWU| zy&Os-va;a9-jv@)Gz&bMe9#lrq(;nUJu)ovgIbJu=al^`A&=p@9e5(>~RX4<} z5E@#1Bson91;zr0CrH@W60Z@G9232G%eP2wS@)6J9GREKktn+Y8zE>aR4383cM+*# zV71#LdW4h1rKc&-dkt%zD54dXe1ZQUAt%BFdjx4Emb>CZy}SsIf{dCr!}mT&lCvcK zT9>!yE%9%_QVucxwu>Y=$jXJfw(kDX8&6HACN-Hb)-AxV0!;&29V7&P#kLg$ubR$< zln7mhMCxAmMh#FI+Ss?CHtNS4@|=NM?7j4UP6ruzK%AzWDMYbT&Fz0!gTQsN8*7cDF`B12-dF0yUT$H zye)!l<#^9ojp|5yZ0nLL5W+4!8kM2JwJkLqf=?&u;&T?`%fcsr^V9XhJn9W}5o`Jp zm+(~-s|d?=SQ6s+g8uLnS5om3t~E6pYbadPvu5IiKkn5=^)829dK=3m2EtJPJsuj+-@tNp}#016lGRfhKUphaR6r zE<$e4a70brbQGeQ9_@mKk|P21R9l~~$X!iYOOW z#|b4DIa=jY_=I(X=u%*ACr3!-&s{J#mFwB2w zrUjpos1`QNRWQC;FK5L7YYUt{f34``UH!!Io-W*T-SfLT`#IE6yQL@~QvPlY*jj2h zUz{`)fNydRZ4iD?sSG5%mGa(~(aj@Fot8F?_Q$Q$Ad@qx+7Va(% zz%$}dl({_{>2&>8h3XRM04sh0pux8$fy&s)MG@2R5h^6c_M}?Xj;Q9f&E%aLyF?Jk z4={0nc1PamE1MOenx_p0R&46BoC&7Z3r#|SM!^K$jm5+MK&ZdI=Np@Qe(OgAM~_JE z{mX)Jny>tjFZ}rJ-R*j!Fuwo%sP8By1DJK7Lc$I`nxsrO<~8~Y8lV{7S&^mhFi4AcDFFEwG9(`7SQ?i|h@xaPQq24wm zgA?7n_J%3WFn+H9LJ z8FhlIAfn$S<5$1&9q~b4ztj>@)6hb?x5tEv)z5nPU2{?RJv`i7^@hkM8^%xF$tmD%jL!+{-zL(nE^ z<-t}Om0S=WA#7{IOyZraEj@vbi0d)yJ$qed?xt!U)Dn32vnJjIEzTjFmY6Gb(#Lsh zY-wU~Uun#5sv93m*b}93o^7Am&7zUMmK0N-|C&&9xOvhTGEudldB{wDVGs9IR8?=+C)tTF^S24DqxeiieiRUGlnD;#aYyfyxg;z3 zP4w|mtdG_|NY#&JZU*P+iA&D|k01$tPib{FdGq%5Rl8cY`Cx8@)=5BtDHWhvubt_P zlnp_0_?L8VM}9gZgpLs^>29N0Bl?E4g)qyFfxZ`~ zla{b(OyvQbx2)fTBEIqueCH`#t2XEVfFEoy8^FXfzEf)tWS!>JZD0konIX4$gmfQh zh!yim32Qo7ZRs50xAGU=_u5fZwqK7X5tXXf<(fbYz)F`I6RD)f%7_&%ZX@2|Fuh!>7ra|ip9C1|Ip$$1k`Zw;&`6HTY6<@{UW6+z)x6WC;E)|R$h~3 z8*T0ERJs$2rLu0|Dy3OjUzZcjVx5F{4zf=Mi((mbTgKrrxJu{jLa;MMfQ|SD$Zn`} zM2LFfPpij=O;*rj894#pI3ghX{%Cbzu-C6wg5tQ2M$%*iKK?L)=m-b2oa;I-F?7v2 zJgZ?V2)1hzUT*(~6$iLx+(gVnMN-{Sz;z@APXY<2jEUg*`A3j%+gu@5pBSy*tW8Wi z>h#au&QRes(dOERct8^(_GLGWI7TPj@Ca}*8n-P9xC&Bj1fxujL42z)Ii5!Qp>XRO z$c~KZdo-MJ=7<_^v>JzgI|VB37OVan0X8m;8!9TnotE6Q#=~2Q5V@lgPQ?r$6XTMC z-3QiC;d8Su;Eg}9+Q86ijt)J)m`gZ_ZIQMM`8M+d3kJGa+r~taZ%W^HfZj;34!!^Z z0M4l=7^_mA`oI@iq8^!*I^9`Gm8C zmw3#}{co}pNltRbrSj<%PWj|(?8HT^wcwtD1W9vPkvLl$88o|uF>(zNbMTJwi_g|S zdNx1AVk@>OT!yEw^#Mt4|D=t9n6&vzg@b@J2zS`+XK5smCOy?aSh^ubI`v;8XVQWp zFfA}~TLdDAvn%DIm|Nw)TxGUL1nlu1W~)B$?ZK56%}0*wQ;P8D(c!oD+^pfnCMX_r z3ow^$JZfIGCWG{VG8x!T!xb5$yh^eYMqy!#kr5VpR=!$u@!e}sbVECGDP<>hFv(sU zGsERU_r-fy%U@KPD+1H<<%=C}n+NIXvTCC#Xs!jS|GBkXml!}@L=b6diu06S%0#E2 zvEEnE8sum;xb){!UZh94?mseeITv>BG;k-0MN4PkNw;Dsyjb|JMbTPQaFQiH-;>4P z?^OV^TeNgOR{s+qA>dhRVxKb|-YV?edrHJDBhI+QKv1v(T4{e=C4rG@9KQKFmKvqj z=R!prT*vt%>G-dl4aQ){w!Rumvm#p|XGS(~!Gvx+&ijw$*rrj1Xi+70+EZN~mQGaw zNIB08QlhT?gkzf2e!iOR^O!<5?Yho~H(H2%#v7fePX8sYpx~ zNuwc!vs6OVgFD>3nwR^2C^g`{@CrA*k9nRVqM#sNv?^B$6R8naW ztev7`GJm&8RgBR={9uofVMzt_QW5}5uWqrWFO!b|hn=K=V_h(<#)6b%Y$%h@nx z_A?;~et5jT+a0-ljlET%ZWA85ilWEE2>X)^ikh3|Xl~<*0*pZh+#ZmCHIdtPP8>y_3aO(B4sOVCL8fMkeKgMbAsm^iaZBh>!#PPQq+6PU zNKRV6Baox&Hr1qle6it7b#=XlYc5K6dDUgJ6nu5BYdhrENfz$@;N@mRb!M4yg!Q8s}nr(HQ7iKY|zo$-x%?TLufyF#)L^<_K?RC(l-BK};nj^qc5}%}HHPDSql25j3w4$AK-i0A{~?D@9<5X?+2}0s04^ z#?gx*B2CfRv*n=yq0<3kYP#=OMSRlsT3P3(;mRAfGsd=};YTw%b;L`ZdiPO4ozBRXH}x$dwwL)8;Xd3A_CKMSPqT z>>jg>UL1BCm*j1nKQJ8uK6JPYrWcZxE)>;3GbbcQDh_Vc zG2WQ{>b@6*=T$TXRD`W0X&pFOz_MXigs+F7csTi!u|Cd>TmwK^=?u5}{@1F5sEd6{ z0a>-0kmsySqmZo{ArIORDAlNVi9zjx&vCyXfu)gzJ|=YpoBG8)LGvLQq+E<+pC?j3 zA|WC66>Q48mKq_XLr{eLWs(ficGxA}fJ6xe%(#00uJe-3dGISKr!eA|smu);tlpMM z&FNY)9KgO$41#ndq#s_?1n2yE^*ZYvz%QsNVTm$>Snw`0rx7a<4a*9rWke*t3zB+0 z`v8U|uYB;{?l$7-a}o2lv?r->bpJIgOQSDa3F94YT@tQ>CnNE*yjhRw9Co403T&-> zz&?rhsXjHdE`F*5l6DviV!nbK6 zpcR^COwP1RNAss{ia|TBrjJ^@T0%X_`CQW%xHev(uNP-TSPeU+J#NF`NPqVeheeKJ zPADNlo+76i2Wq4K6%cW7N*NeWLj0mP4hWUbKcMShZscvBKY&;~^1A;UP5X)WxWB#vhu3ws-o{gUEKjHfSLDMs^v(o*)+OGctP2UJ2n{k0j9od26;x9P2dwmT% z1O)sG)Gy1E%VSH_?JI|OAiI!jZ#K1V7)`8ooP7RFb|s_{U(~r&y=cscN|qIm5nAt= zf+pKJ+8O}X*FymiCy_k*VgookODj7&!y>DzQ-@~Yyz<&1tK-y0{2iR*-)(^uN243P zA|VB__n=U8b_5`A-2n8>1i+60h*j~;!s+dsp8m-Z5Jdy@MIHsx2b47iA!p<8)sizM z!O7~>!dG6lrak#Qq4n*{L;yHEIWhWfz`?hMbM{LOzy=t{XSJyPng~0_=kzTuUKa6U1GP5^1zZdGNgfUt zfSRojZv9T0b!>Ee0B-XIqy^**Wnb-kDjM4A`*Zonl^rLSq6S#j=?~|pQstuxAmi@M z1R#K#-%sRkMNSMqdaNr6!Kf zJ3lUdD9-3*(XPxnzHekJ2f$Nmka|5n()4Z!_N*yNP=j$@L*dz(qf zOVC|o6O)spJuu%aKwVk~i)LQf*?Z?dKWV_<2;OtMHy4Mez_p%nfX^YS{yN^Wo?864 zy1p3^oU1!8FM~cr$oTNOfb=dvseV=Xu;f3|J`e%aKmD{bJ0SZYbh} zKMh+ymTx}}Z+HsdH6lMcA`I8g&OXN&-;}REhy2g*oHspxwKFfSpX))!qiH*KZ+nW` zcYBmo`sb$ieH`wsb5pe7U25w;PB00o8Q^JagD?lDHs5JGK2cV_4dyQKVRe~BRYvh@ zPywJ~v%Y-nX*Z0lKknacz3vWkC~hb2KVRbJVUMFxeJnA+Sm6K;_y63B==szkg0Zsp zqP^Bfqw3c1YC-E7IN3USm;rW%K7grmwC8@_3AwcbTJHM)p1q*0o5rK@D8Arvh)d{^}qaGOv)>eA=9$8B6~Z>(KO`4V^{zhy!)Yenhd|2Blxv+!hU7>15G{w5fIY`Y3$& z4^J)JwFIM4U;n;<8u$0%o$b^An~Q1dh?tmwdYn1(zFYFS&9SkdTZOWWX5c+Ar9n4- zpsqYRu3!rzn^-Qrght)75#xUFjw96FWL}O@62PP)^8;Jk9Ve7sm=+lTA3oAesH2SkUgUK=32x#~_r$ z`TaSV^YSWVkN_7__|G2Lw5QIOQgrHuSxylHHS7v3Ats@h0K=-}4 z=UXtT`4vx3SmcPD1G))2#?wa-w>-S2zT550_n4?L4ty_`)>(H4;(TUUVGceROki~d zV+g`jT(9M;o2p*#W)weCif=l=0#ioKru^CKfV)qvqX$2?(o_Gs+2<;B%*pf0hUH|B z)lA_qKvzQ2EfK!F1wd=DyKiph5aVl=fWd%lDF{Z(xjhD>Q}~fuo6aO*{MnSlQBC*# z;1*@HpcQk&KLyN4LkTysFI1EyR6OthMpGhxAX6BhJxe0hS1GYTK?AVKTIl1#X%IABT&F$%P)low!t&NCzS<0?s-XzXuuUs!V1O*@|MtioSX)pXlhVp z7pVGf2X3Ms-jHADFtsY)vV2+^by4tkVJJ!6{@e8Q-C9F=O~V)|(SN->M880g@FidH z!2U1GTtRL)=sWNU2Kg2TM}a(pO1OY$y++hK-XZx4Skr3s$OAF(-Led-R|*cFML~D6 zGOCtTdN<93IcfLA4Zb)Lp0O}Q7wQbE>m*I`MER3FNgL)XVC-Zs${%q^qFTKh~C2ByeqQ_gG0-qRD~=;hZW1optT@(>7I z;3(F*XepmCFk2zXwGB?5mJw1N79zJgWu8%M@6=Q;NfU5|GcOoEHB}V$kYS>WuD}4K zKnOkbJgubyaEYV3a!@{R?NP=>aiB!eGdCj29e)Vyw%H>Cx;|{h<`OZO{ZzUxriHwqI3x zujmc6bn^>70~9MgOw#Ene5#GZv#mD{;rT(s6@L>ClOL}@t;O&Lf(u``24IoRQt+Zq znd4)gOcPY*Au?v+T%@5Ic%k2~&cD2fzVSB6_L5t&%3j3Ivu#9=0uCscx?w$ zExr7a*$W)BJo|+3(OwzNRzcl9Zlc7F$`PeMJCjj@7#{w`WNCi4O6i(=l*NrzxD&S4 z<6^X6DYX=7oyCL)dfV4d1B-NFy;$?=s0i{UfZG*?phd+W>D}yKGhXq4OJ2??Eh$Df zbs5z2zB(entNu3t%88S$UgT8~-+13=XjUKu!eulFP7)r^2k9b zbaT71(w3VgW#-6G%;WzI!R;c%ws2Qlt!fUJpz#EqCzR>Y+j})->d8CJGrFCi0_;k& zgf7jNAkHpy*x>GK-6@bPQm`(3La&cPYqB zgf-=n;Zkjb;304M#ln8Ap=j9>nldhDcU`|AQu)`C-?*Ssezw!RyJ^&I8Eym)jTg2) zf+37E7Zn*;200b_N=}4A3?=m14IHe)GR#)r_%h(F3|?^-pjbX33$%*NSIYudM#oOd zfne_l67DBbPl}m*>=UJMY~|)lbI3#imKwz)jb_|0vF`{E5{U`Ny64dnSk?!e$?b`w zKlIX}ir_F1@kUt>_}*;RjeJQPFjp0()^f`G` zAn>T5Mq0m;scWFRzGg4eTlnpP`Np>+-h868R&7_Tw+1YM1msY34BkzS;CjK+Rgszr zZ>2w-$j60b!SJXpH=c!ZdnVk9S60tQ>xL=EN`&gpt>RC<=gjne_p6adDnqPZ606P1~;oj?h&5EAI|FEq13UNE?mGQaea>+zuU2 z0_$^^+Nf0XK_WrN`da8qaKf=T;wZ>6?=FCV^<{(jJjxA@E8v#ZfH~5Y^EEsp{cX6A z84xzg>}Y(@{bkbA(XA8zQ5!0~B(aEC(SVgj>vEUbMqWA6~*f~x>#=g6sO9_ zB7}BcsOSCP^(ojo!;cWSB;kS8N0$eRLTl~ca@Fx~E2rv-f zD?^Oje#q^Wsoa)WQUDLe$hRlpdxMiXI}mS!}XI91M(h6X1Pnxyc0u}FD9veR*i^xP|I^Byk=r1X)Dvh_02noIh@xN#Zp=?p8DsAZq|@V5e&+X*b`~p@&THoivn)UijVx-y=FH^1I#WEx*gz;s z?fettQqSQ}dQn|o$&-o^mYINVTS@*eDr22(mYrEg{esa{oS2RLH!UhS@!}}N=VC+H z&3QR)gKIDCm7KQBhOa%wW>dLu!}N#qMcK2Jfg>Q0&|0c3NIJYa!<4)mj+gkTMtM_l z*z?0UP6)DT^5EVidI zWq*54HG;#~`TD==)|*+7##>|@R;2%dh+v`(XE&1wl5jR@HbYN{M@LO#3RLydz?ShV zJP^lKAJKMV7s#2xYQT?sQMr4I8Wn);RGvV7lwJyOwa{v*Ii#{zJ@Pe4y1lN)$5I3! zs%vmDcw54QMyVwtbr=jpu)ZaRq!)f+2)TW0zixp#@lJmco%7B6dhqZks#ybR^oLt| zJP|VUNnfqkuFfu6S{bAtj|;a(*$FX4SNXoC^NNrUAczWJS^Vf`xA-$>bhrk{=35I2 z;>Idx&A{aoF6Ircg?=&A%v*aAbOAbM0u=+$9 zAbh`=7mGdm1i<58)=3D)J`8d0Iu2#gFu9QSxlHqWQcc^(fhK9l!EC;K>{dz5aDmP4<#mOnXMj$}_fugWig?g&!D z4sAV)J#}NVSc{ijc5R(}CJMNjenIdPMlNhzFEJuQtrhsn#IT!>b-QgO*H&5{sD0{f z`it~zYQ6i>p`D<<5;@bAz5~wSGM373ExZkXTD}mbmr^3Kp3aCNoe%c6^0V^uh`e3X z=%+15_$yOQzWHmp7!SHZbCX&~SsJ8PZ{v$}>0>nmFi806t z*?IseHikNkBdA5}>8_xzD(kStz-F>oSbd%ha@bBigk#GrO{UyZwsl<9Z2QO$s8xXz z@Z^2EN^}Sc8UAhaRyWr4Qdu^(L?n?>9TgqqYTFWMqDI}lQ^B%waPQdWuE0O8ac`SmN8MDWowd9kQNI?b%;%X>*LtAHJ*FNpx#Er9g7CVYeO;b;d)a{qXavYI4(aS;fQ54@{X0QM6w<~^mQ0gqTV}@m6k5@%PF|+C=}onYH>7SBc6|osyVoCvU-}t0{-4 zjC~^=g~P)F%+C+Q>&s8<>yvfu@m()^(tgK?B2Vs#WpJUveT{>tXQ7%j1|JK#yxF3^ z4#)TUgaHST*=W3y z`9RW2XJ6^zg+z}W1R43b$F$<0J1w97;+L?0ePIZnFq0VI&DS05S0&p;l2u4eth$d% z_$ew(hT1h~Rh!5^+re}}D3Z@$f1P=NGib(75>^ zJ&acQTQ;EBUPIliFasJJ-Dspsg*Q5rRw--xvwgN{?c`d`2)Hj{)gp26Nn2JibyU2t z6ZePq?&q1T5Cp^4{RCQT4w5pbNaZ^K?jQf82gd5j2*8{ka(#DZU7=>|r>RmluU0-O zG*T7--ss5BQawK+$`%}B?nfmUk7)uNYvN;fo4hMo_w=92DrgENfS+(4U63;c{}jLN zcgEKN{z{@Y%B(OK>ofK_wyZ^Nijt{kH_XZ7OjZMyb-+4mdVe0<=r)L7G2`Ep4s#ce zrUvEuSd(6K8qQ5;$U-Y)bEn_Knx0N8MYrz;r^=eIGIy$^&!X)WF=*kp2l)+NN0o88 z0q`l;5(gFnck%=Aw+VELZk>3 zbblDnil>M|9j-$H(Gk6fNiT?#gqNQmecdO>*8eF+W1yr)i6Cg!e)C<`;mLY#f&o~> z%XE2I0(=&2CdYK6dh>h2qM5Q+0;?W_ii3iC57ICqsk9Z5$r1r>6G(J&U5*^^z469K z2DNu3agIR95Tn`} z0wdwH@?{PS&{I=5rA8gBFo}%{MgfUxHSw#GoLQ*E*LI}!DC>2Olt984M-^0SxXy{{ zMgT6URE?t4uA#L}`nR|ohKqM|8pEkcP>|g~1z&^_l_OhYToo3|+upT1_nKOr1y&Y( z{Fg+Nt$L51p<9|O4)1$gJ{kTz8snQoOR&`8$g(T?T-6ul8DE#_3N)8Hyc2 zB1|Z#N1cT)6@qCUa$K(?Bg)jcl;2InEClEC?y_G;e~WIp=U;R7$t;I>L^(QsBimt8 z`}H-9d>)SyE7>lVOKXuh3mpac8KsT;ePrk&%c)}XDm#a)jiiTqb7hzicFhyAs(LvvZmdd8FMzf*FawxQqF%c_6}R3 za9xya+O}=mwrx94+O}=mwr$(CZTo(=Q==MxquyeVwPQx;PztC=PRzN?3#q4;9cHm3 zEL5YQE5xuf z7l@7_`~*4-@W?aQJ*5JFD@=yf)9JE(71s{D>LsFFtf1v@G4j=t1cV_%nI}I!LnblK zy=HP&NP1iu~4;;fAnTs?AY`mi^uPnLSoRB;AQ=0R+-&oIv(u9VIt zM>~5`W8>KSSmBOCZsTixIS7>&p?>BI$5k2pw>uVj7O8%Dp#yyR?YO7;sc{nJP2%@)W#$_1CkD zk2U;i_KIcJFIJ$gfq^+HntgTgb!h$o{uH%kGsO!i+a8 zSZ>{SI0H?0!~+n`R*Mw?KVf@Ai`6Rf`Lb|!605qAfCBrG*H43S4I2L3yeKz)C%_&b z{l;_=f?Sw4%ta12D8)$?>iSfRz=@K_#N!wv%0e0mcfgUeItEh#c|QwgYs%l9T(*NY zHc;Q1C#Q1-$#z^on2vH>+Rz-E^H@iIkQ!auA8%GiEUzp$ddi>VtHQ+yffadi@=yo< z?<(%L`$%|4;f*(%+S7TqGO6D} zOG7PSjR^BqOoHdGEjjLMxe)mevvC;+XDCZER0)U(+xUq&QV0X-U8 zOe+j%JWcHjrM~8VRn;t+FJu@u*&CqR>xY-Oq}e&qIgE%*Tkis4!>)z(K^XYIgg!KZ zqN0HFdjcdEDHxxWq}&|m-7PckkO;*|t)GlILwtpL{m>7KSl^ZJ2!jV^oKcqzl0AC% zZDG^dDy<<)G*ES)7zdwkHC&cW&M8)y-hj|$%y+f6OHUM&tTsdOc zYl%wuI!^4qwa5Ea6uXo8w?+4$kwdP4%K5YTjDqSw8$b?$piUWy0o3RKZdV9^IDS{l z9xTcDsA`+&D7Zbu#u>C;gdGxMroR-~W=QhT=+X;M=^?s*nPY02T`>@(gul~mjm%zJ zu{m3KP847Hl|h2!YwL#pEMr{CvM!OYHnmnGVjqWJIKdxFOzd8)7mUhk{MWX~!V$ zcz3v+hV#PRm_){{YVNd02Up*_`>DZQinyX#(vS?5CD1v; z4!r71JWROu^HbU^A}x%J<(M87!MdNkul#YkV(GPID*50wwdjopx0l-S+J~5SZ4s4} zwqJf?*NuM03qhlvU8z3+icN7Gel3(oBW1|;reUkOvn}LA0Q2IAavMnFcy;!ia_ScG z98!l}K(b;1vCQhDD%@^SrN*XCqLXt-vEy%ab{}@H=Mh$qGv6qxy!eRQZ?9)K3%W{W zn*rX6I@m>aKLmZDCcf8^V&T(piF%}qx&o18&F>u3hXn2Kp>`87;M*m9>$zM`UaX5} z;8o%A;7I2*nW~{V&@pBHc=j7Q-<#)Y!9*~7pSyuhK3WWE)6V$desDD3SJ)a^#G<_9MK|bNVmi(70uk501b8(A43w6#=8CU z>3I?Z0g=UZ{xHdoQ^v0?M-flPF91w4f<*R>ubCrws>%m_d z$2q*!GdQg7mSxk$(X%!ei!J<`H(o3!VQ^`f7hl%$8Yo|9IChd`0ixBNDO?S)m+H=7ophI`&(Nc9KW~UbKf#AN6<); zFYGeexaBR6!(O>o(e6qmj;6a`V}kXwO zRVoycRT4eTNtdYS^sVCNhZl_bd;wFE=a6tWzBs5JqDLHGxC$SMsx0v|tt2r=lTfi( zIxGBrXZ9LxIWy>v=%O%J37D$htub-+pX?|vC>5J_pWs6E#hk~g)j^&CVKwxH?YBf( za0J|fUnN0;_4Q2^{I8JWY~WoNy7YOa0@_`snrxCoURi@*>!UB(f$+~kyWDC{EfK~1bOz_!Mj8xT1vKn zbOSynKlbAVr>HN7FCWtn5GvV_d{>ThAoG+b4 zjUOd7-g6Wblkkh`5L4Str2>=F!~O#IY;5WvgYk62oP35-69}iiC>qX4$qo3C!>E_; z=mfgmYkV0UeA~@XDIj`NW@OeFP2W&Ftr}%Q zjY6O|45PU6Jm0>2on967rBD7PX9U8+UYFMfZw5;7t?DFPSaN49W2qrC;+1kttgF|rdw%&IY>9X&j{E) zKHVHQtpaETBusAF5<08%iJS$CiGas6VoL|oN$2606*^z<&~x zK>LuKHtS{REd7ivv*BF<)Yihb!RVeeIRHCqc_J>9i9R91D4!!fiiXRH+U9|w(Qh0Z zw#b!1dM9Zc#%6b19iB3i5ck!2UR5KC?c{@^fehJ7k!g1upb2Y9&hyLlOw83JXa$1@ zP9SOh=2Jf3qQyrWKK6hp_Ch30k<@;ZH$;NA&Kl#;lz!0}?A_hj3*rb@$=ye)rN9LQ z;+^N&&`O@Chq_A?e=(FqXkEDAIV_pm;TH2RxI_NcM$*t)=&&5o^!oN7Ve9IX{zY9` z-FwdDK}K5VD+EV93Grgi;p3i+_YU-On)yD@DCkb+p z&}$8a0+#D0VjBgbk+hNA4UtAo+KmGKV)BzUl2p8mrc;*SQo+AlT6q z_jdViUBtY%$pq|1>UD(b`pHph&qbK!kVuCXvyA3&-X^5z`sS7^w(_*qYkEO*%BJi- zCXpk8@|85i9hucIwhqexLzU15v_>v>$g?_Oq1@sCUv-Gjhv_Mz-$jav32_B9PhWduZpt~C(TFye+wmffeQ0S}(YWBKux2;+`b%-=#lxch8 z&-+2geK8LZQ;T1aiRs{F5-b_mVb(qJBdXFDYc&91s}7or9f_#hxH@}`3H2r z&-YR%PxV~kM0y8YV)2=pY_>1EHk!$lLs$%hK$?lukg$D4qduKSd_gC%*)sdB>kax) z30>iw=9LflaY6l3tr(XyrFt!Seun*boY9m2(!<8jucs#39LFbIyWt*04!gaxT6>SzbR5xPmZtmITC_z*IdPN1g7P z-zWzMkqMSV)oJs-5x9Ky>}5{~OKBW{ke#e#jjDAty@Xdi$w`bKEd5*@&=(V{e9S&8 z4mc-ustI{A5AKFD`25c$w)pnRCY!sQ(Js!V5 zc#%ipW5sDIHJf!FA@vd8&C&9Kx1z_Ia7SHsE#Ad}e5ylngqdlmLspg+lc6dZ#rk{Z zArgh_EkZXteCI{wv+N4wW7mZ^UQV~jgu31^Q|DW-?y(gE?XbO!y7YNH>3x-CL=SN( z!|MAb8{Abs$hK5|%e9$9gnu&5W4|ZFoZI$D%Q?#`9cOG1zf;qD66iGXM=qX?*jrrV z_M3ugpw&*+b|E|RtPIigdaS5#VFmqB5P?$W@=k3Kl)tKp+zhBwi+TlWMcfbIBNx#P zSCd;dcGf5lYA%@HX4l@a`Ih#?Iq1z2INHZLR5`x9Nn!*^+bnMoVE4hX(PKhx7J*uwut?!CIIJ(H$oXF;O#YnVC{Q#iGV1B?geC-LRHql&lH;pC zA!k+y#dOIyUZ}Ftp*QCHFr}e+gz97JFZ6~0sR91?8g#=G&-39e)OlI`)XT*DH!Z%h zgJhACifT)CTYGV!69?CpEq$nQ?ds*J*f$&`f)*83@;JZ4Lv~pOFu4CuvP-4>WIH^v zoHDg-rlj{y!n5@RyGa*DDkifrA2jx65I;xa#WCFpb29`d0TOjD>0?*0N^nhqlx#?Q zSE3;dS*I5q4Ej_wenlCKS1JO8l)|fR%QS{yyk&sxfs%3x{bBlNvD}~%fqP@*`6x=W z9g_ZtQ&#~-+7dz&y*C>1($7F0rpx12@5_)snCLbMfO%zFUVi>a7c~P26*!1LgVYYT z>?q3&x`q9vo0qoOke_D0*z1((J)+YMc`Ub)V!sf3RV(t~cSanJ8nXBpGkgUW*YL*i z8GFVl$=>1^)~1nmuSy;hvz76SSV%Gdx_8m4CgL7P*ku9GGSy(iLMZoFN2E#E3f(47exP1V` zw?mnUtetA?S|}Eq9W_>dVirn44wD$9G9K(opz8AgoB)6jLStWO=}C3_8r3ahva6si z#QdQ$yk!3Qg)?;{F|>6dv&y%3e3_AQi!^DW2ZHk{q!t_5cUPfH0fH<^8>%VTK^$po zWOKQYi*gwzcT(LX@0J|Z0c*QHJa37OL-FuH5ukCBm!R+{WjiQj+TfFS-0=2D zrmc^U@faT~D88Pst;HO@kF@vBJ2pdo!vdWch969`Ua(Qw^*M~EXK?3b3SHIGuSxK6u zbkdDukoL_ONW63^fso~e&%s9tV?%rl>r1#Kav42YcK@|k6?BmhEk{c5qog-YAj4Q) zv4R2h%6B6E>cDRx{{4G%MHI)77mz~8(SFpT(W`uAWnP6T)veq8ScxX)+f!Xt0(``_GZ6a&lj5g9r&*yu<2a#q9aH$(PJo*}GdT7VUEfvQL zKhtZFA4nVc?oboWP9L&taq3KDwv3lsrZB!w+|UYR8`0!0ejP_tNPmT<=QeR}3rPZo z61Ch*h6D^#p3j;`Xt~MedjBwKV6|8t&wI| ziIEUEXqOZqlJN#PT|&Rc@dz_o3A^~SY~IvsVOPPxQzTgmR3z8U@oVmOJ(QY4^|t7$-F{*|4_CPLmk|&C0c>bW#5^`33JD3{J2JFji+j zlaz);jqL2RpfvBD`y}w5b(u@8VXE4I-f?=g&7Pn*e(y+{a>g%~vDOL+Uw|6(k-SyR zX@O8?Hag6V$E2xaK1qV^_Fpazu{}$XLAa94Y7=DxA>12OYSXD^nXyngW;}bj78&Gm zy!LwsOrzUf97guSvFUF$1720n5?Lr=wWzzD0IHqmwx;d8hn(8mE7y=Pb#y0FI$fc`IC2x}e;-@YI$Wb@tc!%0 zeX(&?vkAb~T&Z0wiPpx03_zM2%-a2aIA_>$@>+M$v2+AKUctam$>JocB2P$M&5<}#i}l9@gHJoKF{9IavF0v zT4L5|9v7f`mR>SR#K=$Z1r%!?Nt3=6fpn5XhE=n+Qcl#)cn`?WkvWs)uf6v3q5MXX zyea3I~(m0{#QC_c%4mH(%tL zius`Y_77+oG4t5PHhjE3QR$1FWD>uF4OqA7QC43*CB*%CsbE#cse}1bVxuY?^I`GT z<(EE0PkyEL*oC+Iprbo$XORgd!)M+?^k&X-G3X?wa==&GXM`gb-HgN!KNjU75D%R> zoqho6kdhLrT|HOevgraNC=nDuv)N^&>@!z&B;6ww#8iZB*~**>*}?`( zpjBKVu4i;ulLCVVcA~N@HuX`joU$3`CrMxIE%0VGZ~!fjcb77-PNn zWWqrg!Fu|Y3WKg}D>Z($MegLn3FB@u^a1|d2uW@HD5+h^s<#>Le(?t^V2A4aza}!A z|0_7j%Km>%WH=bvIRDo|hLeej>HoEBAJYcTl6`~5R*hWP7Hr^LIDM|`tXTBMh5=(7 zx*#3?Z=p~Wvaszu2Z6}*nU0Gv98IKdkL1p4)@%0Tucg;+MvHl__qFA%=gmj|OK+~8 z$@1cHe3Ph}Pzs`*8y=rt0*9cE(3}JeAOOT&kigelO^vsl8|INcdd?C+uu~Ax{^5^c zoS4wS4W$&oRs4Yk!QQ_T9HyTfU>_On3>gtT0N|S-e!VXoqL@Pf@EWoO^xr*@3Zi{D zHeVIb;0QQmi<`YT?NgmNKo~5!zr2i0@RvM?z$#{7@TUI(0Bn61@GxdeAuI;iyy&_B z;eWx*ltAIdft?*u9Ej(~$3sx=t_Py{*Tw8@0Q&MSU;*$$FhNftYrsBiuz!I$gnllg zQFBo9PX3)gAy-7#+dcgf5CEY4`D_U7*i?hSw$Oq=3Q@q$s>^_LIt2H9NsrcY7DVvA;PGP=ClUtqp=4UH%7r3hli8a8N-2xs(-8onBo|!2R}Hdm;?eumO?a zUV#M+^{kQiWsVF2l4{rhVyy3OUbbu!v0xBrKrTGNkehgmW+yW3F zKoJm800gxF;cYR%_imoN_~_&K4)D+5ma=)utaa4R6koXc>5p961Bz+OTCw-WH< zPJMsQ-)$jtW8n26o9)2Wgs=bkN%%Ju8HR7^v0dIJ%Gvu-f*0}d0iM5}?#P{zyR8xJ z)93h~`OlzP)Kr+27S2Aaj{Lrkj}dkO`0)r80pR-(Ao|D1$v_YUd3pZsShNhz_e}kN zBUA&n2my@zRHHUa|4W2_v;lDZ;=#%F`<*R{Qtm2%H}v5Ciz_R}mWD7peva*z}{H z7s-vm3f5@vwcf{$cv%Ya61r|FxMPF!yEv)e{(FZRBzS;88;t$@Rsytt037f;7KTNG zO};#G5Q=n+j}F4h{?}7Xv<+tX<<Hp&!1{(`5GHW=$0v`708svn{b^i40@N(nuQ2ireIP6e2k{X`006Kl$omJpFAfL+ zf9wa6Px1O^2nFar@0S&51VC^}_C1CM2B52eC9wXBJU|Ws@E`F5VcJmucCg1*iRT7R za?CF!(6WCU@*W351du<5|J2tyISL#hvV-bZ9KAW_x8X-e1~H6n6vWRRQ=b6gP!0Lv zu16|;HS*-6VHx<+Wk^LHw@1^sa+C*AL8a3N{qzR%%>9l~+&+y7TGg>`F1I9Y-^ z?R&dQdZVkg%fy$#`m^g*tfU@mz-59%KH9fgQ(=L`D)yzT0$hgUmdDvWZUU}5f?QsX ze7sTY7DMHz<38_h6awWvqx!zDH~mqUX6eYy%5VH}{umJV6mnx9BP(xPt&!>_THnF2 z+EPQM05@mExyYHCab2}O^I@slWTJokvOfqvRq&B?*vi-mMSXitot@F4 zqy^gnZMV3;c2mdLo^s;J;K9f2R2eKNLfg2citK6f-5fp#cT156DrlnO39- zQ9Tb22KZ;G6S|O)Kq=kv>p(#yBfirQ5&qedhpO}6D@8HCz;Su28^hYTxevq{|ASCUJ8yX6r; zWt5WSZE&%6>(7re3-T#A+UplTeNiO7s(W2Mv={4mMBx~EC5CTJApvYUpYndm3iZNd z@@$6kSMYrF<}>aBDj8=Y)xH6^_6eFA>CQzAV!NQT4Kyl@_t^?9RQ;e7wAT-O6qbE9 zP)$j>HxBV`cIi!ks;{J5nX8M_Gzx^)HLqd+Yz>KtdKPJj-CgfsD;8?@f*dL|Ba?hfhxqun5Zz#APtULrpIoxx|PuI#ln-=9L%u_I3ySRcB5~; z5-l|& z-D^WG4VqD6FJV!B>#h0FR}m{CO|s6($sSAVQ$;dNEUqYT7aOq63}L>p~gx6x_`gfG}?X%;WP$hx>Y zr^L%l0tQis1Qw*ilZ;RXF!@rVVpXeNKF@=krNYmVbd~XJ6$?>+L1@@sMIXIBRNp$j zQu2n|9cg+<#m(a>a6ME#dD@OCS|Bc6=@|^Qi#-+S=PcKubrIA&bqS3dkfikK6vxG$ z8d6&sZ%d)irjUQA63>T8lRpb`kbv~wVNK~|XgcEgb`noi^MPB5xqMH=L&w4&Z5eq$ zZ2aSqB5qthS#B2HG384R{UohwLp~@;xL^4Q$u8fXfy=Vk6^X5chB)Q%bmtA>GsL+U zO#j787xt0&vf;OAPZCV}PUTY|2}n`=^h~&os$3$@13B4x1$%Pi^jL1k-syXVM}RZ5 zjBIX?`Q(g#?#S#N1PNyWA9d+?(e+kVo*`zF^o`FcxLe$etYq6mQo939?3s% zqapUl-mrHmfe-tcVVnvPNzkaviM`plVS;!E6qLq5?v>Xe1d^YORb%#8e}`GVGyv^) zwiuv-iERiXsN9LrE}*bZo2zSQw^y-JBSKFYR7;4Vn|St0vglF9?HOuiUdU307H?-< zgEc{GmA-C5GQBeuX=7wyoVnPorjy~E0u^0`ZCzM^ePO0l87`}5Q^Z+wGeCb8Foqs) ztatx5qM+P6?egM(-LNN5N={iWIfDG1WteQRz%+VlF4F61>~iW3iV`n@A~hb zXT>d`Z5Dsg(Y_9mj6_YOYOEUZICSciqr2m#q5D^COC3qO47f@Bj-PeZK3uX0O#XSe zBwpRm@(03{v`^f}XENh$V1r87{9VV;izxd$BVR|U(LI{ioJiF3=c4S5 zKfYe&6GdkseC6IrG{kPaVSWWQ=Gtd5pl}=&Rz95}%v&%?<16U8`0K8zOC*GTOHP+!QQu znH`Rk##0`3S3agL6T(i;6EEZm{tdK z))0sH>G;LuG>MJ3-Rt%1q7)-zdmc&DrRXy>c^m@}pBG<&Rl8EP2#{VM9L4F4&Fd~W z?#n19onU!j4O((jL&T8NrCncAwYp4d>C!xNth=hRDeHVVc}L{AH6_&^1{%@X+Tt-jjw+#V~1i`&plQ2vq5ltwUagw=1*j#T*Me4eJt^e&xZIB0l=+ee%Sc?jF$2|21t-8J>!m@cWkwdfA&%{GAi{9?T zr@GtCwxZJ0_A*cX1^JsfR>H-pSwwH~gQyiVUbWiZbM6x0ZDj3r_@(IlPO;z)OSng5 z+#5o@jzC4d$O0;@$}v#+qF@JG(l#e??qU1}1C~25_{v^2hv5L;8nrV;`L6Gd2@Z}z z-P=!H`DaGV=1>@*mi;Imzvg1U9m<8y%~<{?AC?ubhBcm8i@DH7?t`j~Sz+7wI$cql zL$+9wj3H3j;bILD(Tz&$$E^z?jd4SM2F3t;Rn#tu0Zi&K%L}IW4nt!``akK18m|;< zWn2h+HoeW)T5o6FN_OkY-aPB^t1(95xB*>xtJ2d($5%v~Ynom1DSRi z5MvP`WcM!Fu;tB$jD246k?g8w3WH9XFY_TWH2Q%P)m|%FI*3_obuvwoOj!ZMaifeq zzD%ZfS)-c(EAr3d#LLtk$@;8p?mqj=3sHJ~msIj4E=1?toSAqwE%MtSK|p?>YC<6$ zbb{HbAQ4P@DrH;#-#$&4h+>s$dP_&CrLfISDTf2Hv)2vxxEH*_Wd}N5E^VkneEGi5 z+@Wy*^q+WjCoAQ+tTct@l6nq?WZ`N@^;;bJmWp4$)u@WTy~{`YN9rVGXJw-{#TcWO zKh>Y1b=6pDPj-e{d)4;76DdC` zGUf&Feg>Sr4=r^RH&-buc(U_UkDYlWL-eyYi*r1vf4honM!s~)dZpJDPs3giYW^O; z$*#oQyv8Yj2eQ-)SlcOHitE|^8JnnyFRi3M3FevlwZD^o^ddeF zeN+&mBW!I_Z(h}1O#Mt%v2pcwttrM6Ia6TUZbg(26Eb2|6K%_tbIA1(HA^B zri#E_tlLJ8wfgkY;3BCa*G=Jghz>Sc8Ka?l*-pNy$U~EqJ{YRQD8w(&dpzEPi0CGplY3;${1SC27RTgya-?I zt|Orb>QRjhZ;7!nMi!gpMtTjxGa%RCWp+M>`fN5*0D=|tTCPnDS#Oj?o0&$RZidRV#o;dhs0O%==lDT2gfM(2j~g$S&_s=(gm6!jx(h%Ek+#BJ+`LrWViz|Vw1CH_q}z!zk}Zaj?nGt| z7;uEu-IdXYt#j9Np7}B&e-b>BvdUov@Ny}R6%X8;q3)C+5deS z?X}ZUqN;oHUC2cC!x?O+Pw#MF)mF zJ;{HBO@;YTc5ue1xoPnS{xrJyD%v^gGnXy}EHmWAKjqeA7T=B(C!aBGT^x^5=mWxM z6|xI%zP&D~xrp<36@$Mbr3tn>z(z%Z*1$|qt$mz_XhU>J93$KXo4~<&MDXhyyz>@H zK+BY$$`4dcqB^M72ELwMsK%47q`Be^bCUT!`2<}!)|W>&w{F5F2W25|4_Tmg(rDpd zDMWkMpl&C;xf2;Djm6>}NkWa*Ls-Nj$gXv!0p>(lsd4T~ZVYhF z{8!z)cZBxxU-_9=7h1E`n3DqJt>ChRVv?4ILRm97T_u5`;eGF<{Il(TQ#x%zbTndn zm|B}!Ni$9;(}@4sq-AN6RX3cY4oGgP~K2v)NcerOD}2m#!3BsZdk&;Yn$W{pjcW z1Jt?ZS?Klo`Zqx}ra}GBPlBjVF#jq-&>gRCuffoA1|Z`fpO?3JD4KJg^XOzGTuwZ1wY_uUryca4!<>G^nrBOn z)!Y(pn5(b&s_(%jhK}M1rXQOq10NZvz?RsWx&uyfi$s!d{NuNI!+<$Gx67hmNuFZv zmk2T=HG3H%ld=_8N@k0H^%)aLzmdu8I1_dQ!c&r zB|h-j;jT9f-An)dk1rh)wh!Hf+Nu)dqF(5*j}rnk#{F~qYjB`h1z_aE0-lxBlVcfh z2YcIET8q@f8^X+B8vogo{C}kJk7Jm+dAp?No|Vqar`)ra6sNw-+7}G4bhO}A|~aQ*x%v( zg;}bzHBZ%y$dU@~xYLDt{D&(wO^t+6V$u=!NAqO7^h*Atm$q!tJw7y8*>SnF)S*E) zw?nTb1p?;e9RZ{0j2NGdP-tcyd`uJxCfyC2L^f1g%WHFOg58lz*AA0-e3hxWxr>P^ z-SB#CgQaSao#b?E-io!U5|@bOPCFiFEL@E3(HrHZd#5HUc4Awac;$GBKG(rc&?Lth z#Iy^7nc8K+h56R01>UL0dJUHET^pzM;=YXq7kgcWOo!~#bzBk>k4A6L7@>b}qMAn< zC?OyM3iBKc2#*@M8EP*s#Oaosf_7h5HmvGJXXoh)F?ksb=H%v27CRh|^Ky)z*HY|} z*T}*n{r_?l-l1BBTe5DhsC<--JsV$aS8m5(*%2bR)i1Ft+64!+TXCSR_LH|CR5e; zI(NHV$1jbq;cq<1^;7ipzm)3tBpt|9qdL^nUN!iHl)P9_Lt1PUu?R^2JpJZ~ znl5>1KHP#ww$NAPik3Ms4wKT`OgIc+Lr&p&Wyl+|I7FoI8?i=A-HR2uD#TED;2L5) z8j1yw)>|p=1>Ld6tp4*eOYi6tfnqxT>cCQxZZ0N|P}f|iP?EdfG@X~2Jnaoo3GIJ* zla~N2I>-BfQ+v!^swNejV70JxrfeytWC4q8zQI}3-83H_iEFuy3zYoshPM)~@#DbJ zlK)zn+rq|f_cp~cX144u3bgpBNY2))?0lsH#b=%A!~q-`P8aXZivLgW0RoP5xdEc;g3Dl-uvlG?VR6b-nN))@Y$I{0QEQrP+OO&{i#tCJ8? zHK`*DdWaKP+3T{Huvps=96GAD4xB*gV;E|=^wP-GTzwFZY*xYDqOZ?AHgUojyI^gJ z+EiMUWHhFum4=?{^Baoat@BW|l4*;|wvYG({LET6sE=r?`}+?4i@67J3WcgR@x<)f z%?1Tun36FD(>$heAqoxj01b^4kYz%jcHW{(bzhEB$>r-&o7Q5=nPN1^VrD+iFZ?)T zY;NCh{i(my5US^hlgzktvO}};hv}v%I@T-Tb&pEO_QqVX1uFbd7XF7#dP~lfbAc+f zy{$F;JFsg%}``f%U=9M;U^^6GGFU2Uf) z<=>~X1=_8z)tQ1Uj-3lP5c-avdnL_>Z1WMX-DauN5jv8vSn9QXw^!DO#dLmg0jQC3 z=Mju%_5487K@?k*Bh1QE{ux@#?$82On(baYPOEy8e9Mb@k+71qsgmzqf93P=2r0fy z#dI}f#>SM+@lY$DazwUsza?+>I=bpyi}RUM;MUAOlJRr%$T>P-?t=1jvfuUvVfx5f z<{=hBMWQ}YnGgaXYn>cn2#LIJCV~022roan0vtpc@Dfuq1rnzHp|i1FAJ>zneX1R) zl*?>_tFGMd+z8$*&=sn#tE@X>5YI|Y?Emdh*(|1$+j z$+SEbQ_Pp27avL6vWs_PRCbGo(=hc$c%SVP5sPkmBXPVDEOpRMFJa z>oys8=*kyB!T7d_TuLwC?OO}TMjV-HwkLLMBxL0_NTQ1*Q`5L= z-wSph#hYQ}6;8_w0*!TLaKw0b_}cErkEh?-!Szg1I+kKDp-WHWA=ET;8dDgM(d2S1 zcW&dZLT6BV4HC`v)02_0u?_l{6J2XXSe579KBsg;kb|s$y6dZn7X~t#^lcuKkw7J( zu{tw`h|SISSQg!xbYO<^*xc!~IQ8X=)CfnqHLQPJW*{RaII<}gw zU+hkZqAhP6_Hay)wrk~stMlZ!zW*iVa|g(8)qeUG=W_}N^QdsW@H-NxMMkfV4B!Pc`J`s2mhKrfc$4yc`S7#O9PGt8DfM(svh!?q4q?(alpLugQH6lb#?D1RZ&_a1aWFGRkO8<{^3(iW0LIb;}q?|8#wt(XAn-mV(i6z`SuW zAw-$RGihZfRlXeC&OymM1J9INt6^Bb&#xsYqOIg$lX7=@=#8)gF9*Li%ciV3u-UIz#7ermj%uuwH7W1)> zu9M)VmdN2bs*?LymA~PNg*P*2qj9>9|J=%1J3!}Kf%`9!gN6A1Nun8@n%)iLstEUq z)L``AK}Ijv7vI<5vTUp>PPwxMv3jAmxRRykfZg(t#U2JRkw$)LYk92z2t zpIcwFS1b)3v%4nlIUrUSQTUKi(}uwg7mj*n2w5CliYSdN6Ntp=cm2PCjc|pu+{mX> z&$gV1H_D@vB8PlMmCzd^X{2j$g{R1Xi<-~5^9yK2rm*u}^Ld6VA1xqzXXk2B!9Ej% zK=CwjsSbCwJbCj8k!z=jem5fFPE=@jIG6)INTn!NX4)?Sdr_C6bNP=Vodi(2m}-jaG|w^Jn4|)#?1X-H)h;+i#vFr(?I#Z=b5q zlu3`pGg`W!Gl*dKij41}?g_pK4M`R9WSTx9*}w#oEOb4RPCJmc7-#>%&{)z|ht6X5 zH5I%czF5?RxRiYEpNXoC&pAPFVm0jz|Et?|dr8_w!Cw(LdV z&^sTZ_>36?y=?@EPO2?lPV}>vuecjFrsso_SHpl`7tEzH?D4r&HM}%%zAMI}@!m3* zXT(TIzPxf{W>JkQVI`reY5D}xkQ@)c9>tC<@;Gny;ASgmRVVOa@dZy!$({L5@OEfJ z{|>^XyEEIi&TeBa@qMESywexRXoumk$OY+!d^#81%+tY?or6qjKAWiUyrzoq60OJ(jIx$WKJ8zmmFw4i4CL6P*LRW%Nxob4$Yh(tjHU&S*I}NsG9XjQS@=$)a!Sbaq1&eTz;BJ$m@P$4kQYC)G?_~*K*pS z78L>D+Yedri3nH;eVrJ&sP&^Be8oEf_Fb0>|W=vZA15R5y#{3`j5j*4m zqK{Zu{||4(M8L-Rzx}-IoQ#bB&-9TSxJuI2BHLn=1gc3ZPuGqH z50vZuRt42|>`eG!_+$`@i}Qc}{s06D;rI|JBxdI9fd#txen-RCWC|ouU~Wm@@S#XZ zP-4amrVLoZ%K=@0Ecjgj0zv@s7 z5(1Ss5o5$8pdj2mJs*Q~6~FC^gJ{s{`;kLkK`;aq6^g-^;p}&q1kkUceyUh~ja>Z` zh+$sF3?bUYy#f;y0Kn`61oLevWX6rzxhatRHE|8f3t;Dk1$KVpTmBH-0sU;?0EXc| z)jRtN>yQVweZhkW5!$JNu1{f|oB-B`bn*dsRc(Bm(KFEjT${Sc0(BMaWq8(sVVnTB zj3D}?!GTp!p8*YI!u(#s0tpNuSR(O3ojPt6_qkxrvi@VzllN+E0>b}dI0Y5}5cAv9H^@kxWAy01l7CgZzJtokOf>!MbjjZQHhO+qP}n z-pjUa+cx*IZQFMzFX!bpPUAMKsypYOO2${;0MP6Ec{T}EOvl}t8Ts6O+7+kCH?A(S z`3N|zOZ`1oQ3>$|^mz{f0rUwX5&(dppn*de;(7aJo&#pMs^j`0RvVhZgKL*_)1@~n z`l($%q(^l4VI|ZF@F!aeH7`7{KfLX;TM=9gPkS$^sT! z^dT_x%fG|N2~!I76uidkpGO$uZ+s8N)`!oAo`(GZhz-)!XH2K~mn-v0rwryWu0=!< z%ktMTKruU-?}LBX2r~-1$a5`k7u<7OT_UF-f&w5;Ft9h8-Z!Q}44{W#E_G9=+r0pT zxa%5NNJjuDHTMtT#gX*!oi{SV5Y!d+r*RAjxap%&6buL$dgcvZFYIGPPyitS_+$r# zKyc`&eZ_hcH;f;XASr#=jT%(>Zu|a>4G`+dM>wEYc8E|ZSJt)obc_M&A>W-WXW4NZ zZO9<))e>O@qw3}^K>$phMi@zW)lhYM_J?!p~_wJo~e#Pnzg@3=PsO8*h zl1=aA>SoNi@*eJI5?u*Wwa6?TCwa$N4}T6|4D0?QF*{o@7oRhI>!&++Y9bGJ!KBJK zQ}4DNTbtR4V~Yg_nS{R!GhfphEJjWA+5Gz0*TDy?8PyUkwK`+8ka)vEDEClJrjLPv zm0faXdKC+~^5oIjID{5ks*r$XqJTzL&X(cpcFFVGF=mEVQdfhO@>Qz4JLOs1e8{z} zJ9fM+OKmorOvfmmh4QH}51)rD1~p96Vg%NhZ^61@M@D~uC-)d&^ME*6OpaXoV^;fs zUDRYIlAikdWHPrl_-7M2wI`?WafB0*DRs8K? zT~9omXsp@WHCh|Tw0chHyINn(asQl6V$T+sq=`*!VrcM#*S=5I{2g!l{c0|nF#R7-cUmHdGcv{K+2v8Z+EeKaF!){<|>DwUF{rk?1hR`Uk zac^x&Ht&z@6-@vgW8naJ-PeFEWzxMI_(Gt$FUeY?zDJ$kL~F??h{L^uAyNcD}R`E zVXEK5>C6jLhJlb@B>Jv1+iNJ!+3n5o_*SR+f}!v2J)i!JxSw%VM=wt5QkMI-p+4>)%Sb4R4_Nk!X+ zKil7+Y&^A4j^ypZTab0P<`aw5;BOl)oWtBrFeg{<%y1iF8jb)tN^Vy(4WpegxM3B{ zSeLLF!#R#Spl?dVG@nE47v(sBy(UWQ13oWwL;R%Y9#;0?o=`clOOA3MS6=qkIDIXn zO3LUyO`{NMKLTcL#w`XvJkqD1bLCT@9r1=%Nlk9Pp_&kb#C--sYtgR~SSp^$^`@VN zfBk`TYb+zfu#NboF|I+v5FW7)nzK_B*>LphgrD*k&t+(@)zK<&T{(>~U`4OvIc0{vgg7VFzw3K{EWBjjvL zQ*x*WV4R@rGO(50Drb_`T+ zJP^A~chi{~$t1A`lVPoP$k10vqAfLyOfE}{9(mt39mn`u2!VPzY~E;#qeN)Um$7iV z_59Dbg*v#>`<0OBW2`Lc4ARfN!jw6|RtPRq%ie!`F&4#UcU&JU9PPB%g8tcPvIPW1 zpP@|DM%!;wPpAzZ0Oidqr3QkGA`s-4Imyji(S;?h!+f9 z1qBK9re4~GL2C&b?2QQT_fTipj=GOetK;o3FUQ8UcP+Q{{{7Ir@n?&BD7NaZYSJVb zp4wi+z9u}F)7K+X^eQ9E6GhqD5paaI>digQ3n2awn%AcWX*ac15@!CON;NPO+3T=S z?{`3PSk+{tZ2Vm`m0n@CoV5}D$m;aek>#&V13$K=`pq|0CqNZrvfPc+r-6yBeN^x03E{(k>hrzQuzvB3_%hxmTj;3Aq`yj2<+VErf_ zeHBVUXtlmQDv9+@t|!UA#HmEfW*nZI9g;(mlR6f&JdD>^;Ah_0tbVN;grFF`euj`e z%JQF+eK-GA0zk>v;PHzw59}XjK$8jQ}t0?pW+6B z>5n!)IO_OrLVt1GtI#iTB&&0JuKy{btDB#j_3bjsw#?b_vDLkTee+x}QDH^BT~$7N z=L!~E;!d2liQCc2lhi_JkPcAhg}2#UtS*F^k+*&>*Ho_EFC-lw&;G+}V5 zum~aR(9rhlr6`(vrKh)CJQlfXIq@3LnHo!JuiO-_k@E+z!asd}yqw-i1I0qby6T#q zfSc+-<~{gDLTvXjW2XcoX55p6y2s>#e8+rrg=GW&2nicJ?BjOo%{Pd}uzE4q{gctf4`f(whDA8K94 z14V~uE1qza-Bm_rstNwRPdVeUV3mn^#hU68#Mg=cM+$~^Ac`QB4Mj8beK5)UZtQZ zr&v#`zjIz1g??7$b>g+kx+o$&G-3)w>X4_(rnnNEY{DKVJHbTLM;-adG2@ntqz^Pb#}A%)I$xEzjpSj-Nwi89|l``uh-?n4ExFkhU3N-BhKwrTN`lmi4{o*>4|L~Sn^5pImcPr z;VLXW;FxG2bLS?3Q4ncS5VcRr>>{B@9Lff4OJ0=&!!FUr%$M|we|J&a?VH;6HK9SB zEn{+XC#AvsnH+!FT$M{WzBrkET>V!()JX4d;n@NGoJ`Z*BF1lCJ*_AIw#RPv5y^|B z!9vtjnMk3(ojTY@`(^>CsZW$KH&ITf4XB&t$MDeNr&RfI_Sj!GsNk=@l%$s`xO&S=(FZP z)V+^ym&TNLR|`Ou^JTXmj;Vgh5mgP!B7|a_yLK<^mtTq561=Wm9z$S^FdN0_hII0i z*1)A={#mK;#&XtB8fs*j2B>MBm>TVy4lUt>rqlk-io}Qc&5twTJtCIBaMg>Glh}h zWx=r$jld@eh2HZ}6)pSPf`_HPU#4z=;#O$_DbXW}MAZkJp7T!1lG*6hWE;g>-)09A z($7=LQV*2F?%_t;*tt7ukIJc>O%#Iet2NRcJU?@!TC!!~O1&l9eo$RQj zrI)#vpWs;YX8jj5I1xn@nfa_U`IRjkAk?M(%B(pMV9(LBdF($!ijUxbJ4s#?DSr|Y zjRuUSwP0JO)lCM|WjE+tWB+)QmgO(6&dTUg_|~pyLDlEphi^SPf>2zap-&XGM{jHY zZKJfo1HsVSPFnczA}w=jtQ5`5nNgf;LRSrGHbEvaYI;MV-eV0#xai;bGPBds*vAW6 z9gne94gl%qP$H<1VMDvcKMN*zAXZ?KolA}jYgvj`7Db}<)#CGz+1^Zn;Ab2f)G~h-JYbG&EdY^W4fHd)@ zo#i_?c1KGen@+W)c&6@wKO_hI>Fv7LCYL<3IDdm3Nx)4nd8cYe?W|?n0-wT)L))#w z!2Nz5+$<1SVK*rSpW+~MjpHA){usrW+t@-hwWx1$7i7j_4Bfv(nwo}YYRLu%JzhZ#*C(zjWrfm_@5m{ z4b20VK_ISZKh~L?>USo#Lif-6`g^2>VwIwUSz(!abL+RoR`LqY_Zs$yvu2zcE;A8g(>5!NbOh$v8{Bd?m_j1kfi+n$G%+G&e&vYh9 zyTTUY;W4YgbKwNPTXHt8r}XxdZT{+iI?=+&#ixgcKPKH5QX3z4Mx~PcXW&(bFlhImJCl_9T#!1l(lwe%HpczxmVUW9C|GRJCMmoO3~TUPab7cHbs5$n28dWH z@uwQkss7(dC!52_fIeRgSG6qd{rk#KYr07EiGO>5a}lxZ8cJ=SUsuLH7C)N_;FI+f ztRog;J}^(?h|b;2%9mK4-!>4q&6PveqPp4!+MfWH3eh8{`SfGONp3neysdt*9#?4b zB~Fg~p1t|#Fka}@lPWxCp{}c&NtMIX(b?$|ikN^}Omc7tREhmjtMsphLLcW~*D*O< zw7L(YrcDV-tDn=jctvU1=Tiy6NorOz73gS(L3NH@Zb+IA!fIq@f=R;ZXSY3FACX}jaVnI^Qf!rR`=&4AEwqM*0?+nN*;6V<;$G)|VnkNjcLVOma2siz_0ybI{w z?S9$QV#Q6NPhl!3^Baq4OS%W`-!I&dzMr!T!KGhy0);L^}bB)maHU{t-<{d zw_>o7Ig&Bwhf|VTG7tBK2d9;eR&z7 zK~0r98NwJ3wHA78#=FpRZe3!H{rGd#>beGa5oAUR=~TTDMg8DfM?GZuK(q8Zm)-<= zFfh%^#(9|&jQtfwhde29X~1TXnvq^M|3(NRi7Nc?W(Ve*Bd-X?qry<@BKZBY+Q!Fz zzwON-SxsI=o=4`fX~CDz(%nO3nRS|!i>ixByJhINAf52h=C^SwpbHpJ+d7Zep5-KI z#uD8AV@TT0068|OwLv8&f7_P{ou-18A?(s0BA`oTe(^XA(*&;6P5AlhSN9=xF0Gso4q_I43lu1_s)#-1m@={rVfaQ5=dzim`Vc5Ya$ZCT?EvSA4%J- z8;&Z!YyN7mWhy2%+n>5{Cn$v%ZwSn+2z+Yxi(zzSClEkv@q8o`74!LTQ8p#ro8w9( z2tTn&g~1+7Gh=)Z-!=c%Si{wgS;dyG9+L zdUGSYTxswh?7E*1X-e5giOf=h7uESYq7{xjUi75xmR|CF@Q@k>yHgBwm$H@53L6_5 z>BN*Bp;G|MC~=?>oqknof)sNJvKdn>@;w8eGKkG5fZR6P)lq@ojoKC!FO z^0TN7rW41VC%Kb^-hFt>{&YJ=N)xBF%}7tOX-=C{?F^Iy^i2_#uN31qG4spjW5{e2 zwz?(0FGX$1_ZWh2cEV3t!5KMRUl{&SMKr+~%ZdDgrw@rfONKypg0 z&xLLETbPkuy@@h)^Zqov_IAU?(}NtuTrqPBUo&4aR_k^5=qjULYl@Q*7|pns*~Q~e zDjv5Y;6$1yqT}G$H@c?%B2%NZ4_XN~b3bMId01+;u%lDu(<7D}tDKz@$bfi?_ActK z>qBlgdC3S_QOSNzE(FFDL=9H8?@;G*aUS0-jBOp!<(WofYn5yYBam9j%`n1IJD16; zEYfj@QfckjOUXI0b^~GAy_Ncy_C)hvo48yn*A>ng(jOGg-3ZG}KcF-0NdD8v+IfoY zi++7VUk?|TW8q3l`jwkPVs`X%oEp`$=$IaQ(UE?#0}|0WTqSR9I>{E-Dic8t z-EJn%W(Jk&&PB{nJW^HUe2h4LE2&_SffaYSt^MVz3%v#Q6FvAsf;D7qnwk7L!Q_)y zB@ZiVoz!huCX;=`0-0^E{|2S`w%*q{mn#q}6YV)EzhfM!Z~4};2L6^0kN*7uGt$IUrWL#UJo z;48afdgrx9n+eVq0q&KCMWvMkK2^d6pubKuzC3(FykFxul!kA1GlTBI27lkw=~EZ8(#k>v?Z`NvV!8_`A>nzKmRQ=2kU=U z|L{5k8_R!I|66~{&cMj_f5z)Bpeo6?FLbno1P~AsFq9Ioq=ehJNQr|CFbu;mG6+D6 zQ31t^75T|7?!gig(yIgn5*03AV;rYn{---FH@ZzL?7KUk>z~`7+jEbO4VV~^6dOa= z1Xd0hQUV$X6tD^_%gf0?0D*-;0{IY>=xK~7$58K=WXDXQ1n~+SG9Uhc$%qIDP?ySp z1@#=d95DHzZlDl=>5ZJFG4dSW$A>hJ<6!?BA28a(s zggT_5Aw4}kA%nK!gB(JNaOnB_p`)CDcmfCrA><=?_g4D>c;m5;=1hW$bpVXXDIVf> zA#MU5fCvcys)taa!usRaU|6Q{f&dKQ!7(f^0G_r9>-i0G_yPR-ce?-~prL-dwsx=d zL-Xr*CkPlYZcgBW-USR}0l>?tLGtTLi6b7w?tujuKJ^9SsgYu5z&(TVYYDh%_S{bi z0x}B;0YY%^ZapLzfG%Q%poj`;`@~Q_RKdKbDjB>@+q1Ai!h{lkF62R@0s^VhHgMF9_LfZzYMul<#K?^FCzPx(ck`t2fQZLYe! zWth8t`$Yun5Y+Yk0jjSSEvko_4>fiL__RM09>-t45V|U`X#0(|DiqKlr5MC%ut7sW zLk5ZZz86lgQm~Kc0Ym|H`xwgL_e;{(at<9N0COODS{(z;0tNX|hoNSuhkgML8b*4Q zhX@(2gnjmo>9c`QlmEREMgAa2dcKhj;(fUNKy}PKZNWRm$^zxcIDuNM^4cw-X-jGgh?m1Z%!EB zF7s11oa*heNMOHj7rO0-bgnm@aa%2-Zc6R_o7`abR8# zieuMc?j8^G{NdrjTpTQJG7$sUGz=qRE=`8U<|5wY0D)0- z6pO--6t+bu_)bo*C zfn=wy>p-ZvIr^XH^U}PshGf@p2X3>iMfuSQoVdDVc#P8&z}U_W}rq83A}GJfgy5GJ|a zL5<5uEm-xsrMe%mkUC3ZxPE0jl-}Q+NW0}z^C6}YV{%P&Jlt9>Lkh5AUp;<-l>~H- zmNlkUy0Obu9_4V+M2@IO-vFs_y3*ViYOqE6UV})FmJ)4uM`i77tHkeC*z>elEKWx+ zPp`xrNL zkUUhcm}z71YyUUT-$0f8@u;eaYZoke1vKY!c$cSqhom)jsUfF+N&5ICXn{N;Zo|~6 zAyUQ)58ujv>G4yKh=Eu)LqZJ9?+W=KaAoQ}5?Os3D?Lvq?yb?sDY-?BpBdo!uv6L5 zA8i)>TBR=jAUj zVrkJKln+M~aqH~F0qgz!Ow@0@Eq&6fh;5&-dRK1NU@9A8VYc9Ma{H8v=sZ1Cgc6;J zQju!k5Z0Ou!N0sIL3noYCnb2uK{hnbYv_ZMQ#?UVP#xrs>(?%QME`-s3& zx5B7T-*%CghCn>KkvahFMB=tYf{MHv$y!rUiF4*B?YdJ>u~-jftUVmvpCt{im%tuu zd-Yy-v>VPMv&ku3nAw^@Van(58i*W@fWC$Ly-v?`%L+Z~X@WV7%)>|Xr5MG4P{sC8 z>H1TPwxySu-FjymQZm-s>KyqQ(xHdstn#YSIMZCvTplwBGa8-M3-&;xdS%*p3`JRe z?swI^a*2o_(!M8*d3{WgJL|omDg;GQfsb{h3_Fn#Y6e$eMmaGF%?B(@tERN(Kq_Nz zDGu*{mI6}F%_HDL6NNYo0q>_3L0r=2dDU%_yg$6tR&g93%ERcCEb_|H#Bs|pJ5vSM zPBU(Ll8-w7u;AFPmM{{xU*!R0yTO~byufdWTp|=|rJE@hDLlFg=~h~}n+0nsjq(}3 zQ7tYQL_rTfFRi2d&@drta5GUV?z{c9WpCtIu*pX)uG0K@0>xw0s2^MX@9ED6#OOr% zDzJ+Iwo!^YU`&toU-3lqphmW%vLEK3j*ZN;+s3V?HIL2Z;M(VP?dB#5zjTsm<6k%- zaGHzqWzH;cO&YtwCD^=3^_hf>MovcGCk9VJ%XpoL*DaQz57-4egLAEs&POg4kJ_!r zVK*LK=l3$P^D%S%C=<5T85po`o!v3ovcA0u=5nlG$kk1_ha>4dkbO6b)O9Zr7j)Wc z5-X86Gg!Nen?F*Zl;LTVhGupla#YDM?kpp$dKBS1^xb~6>irY!{{k(wtAKeg#(Wd! z$e&;Z_0g)ea(j#F9sTh&;gRp{Hr`w;T{~uMv3wc3#U$U4Y#{1lO}TiW2iOlGijX@y zsRv}+uj51&DP?3CqmYn0F4KGUIt6-3b{o!nT0n}jdLhFj@|1CzNMXusUKjgGTSj}( znxuCKFfw`w>Jwwr6rq;fen=F<)R_{~{mt$h9i0?VM_aAOV46<&gprB_8XiVR8YlDa z4TypazwaD3)@GA+ZN4X}GXgH~v*=cBahMwAP$(BXeWw?aOq*tTczS#}J`Za*+*r9l zJczth320Z*z4`<-?`RkzzsvHZDz>9?{VQ|7zUo&&B}nc=Spf3quf zKuv&ZB)l&AjqGWFw1XN4`RF-n)l`&XQF|Gq`#ovEI@C-vhV;{YZbw4iCT-6ig@j>! z>z%hQ;tn@6lxIr#>yDGca4A`~kP;q7p&|dBU zWNI-v_{idoi3~7!{c%uW$sI*+I{aF0ocn%+0a-igo&_@J!s?P3*)B7m8tJ99Tko8F zSQ|r*h}&ucpQEFhawbpI6CNVWu)%d+E_zIH4oq%eE-5*E=6woK-vN%#JV#6mRIy#) zCe{2uTZ{R2NcB@ryr(|K+LXyWL?wXGKS_9F#J)|iC^byb!s@Oun8o@`Ek^Od9TU|c zr@k@%xx;;lqkUQf<6XHod@yC4zo}yFJHC;Wuyw1VV_nOV$=W=AVzSzr{4!tgcK^2B z!t&d;G__I!;hHq+I*p(MHr}Jk^Nqu4K}7*2L5YdgOUT)~W6MX>tVyb#KhM zm+>Zq!P3maHP%*R}pjj2W9g~RO3>O?%@ zSMNj=s`dOtHhQ%CP&y(_jRMCopGv2Y<6+UqQ3A+(#Z|1Rf?Lc)gBy(8{(e~{UeQN6 z+=-$;5`}nkQDaiGJJ;Mm7^v0F$?4?9R9jEw8@2O$FGRg%Od+Nf5id`?Prl6F0$A%% z*4drn*;YRJmN<7>SEST+k!}%Lx=-N_=JT2EcY^|f(=I> z>m{PxlnPmrhIct%tR?%_qBS$eK%gWXwQsC7O*9WYLjy$bS**hyFKTt$Vm6GYE~N)J zrtmypx-hdw2(g3`$|RX^t1u4QVTBa;>rDl@-DBpnYg$KOtE5PMkfsYoLDR$?^UOl_ zumg8)@W#fIMp1C-AlDI zTW&E#UsRSYaFhrHx1>hEB>bmb?_YRG+S}DP4qr7Q;wr~BjDJVh-fCx%$`a<&vr#?? z$6#kD`KO8SV-1f)3N{rXWR_Q^Vr-10FZ;P`=IF%>4S1z9t!G0GX`>I4-3C?_I#xJI zikKLt>t7w<*=|?FYz1pZg|7T~C}@*da(lJWL(sdHozC4w{o#4dlJd~>suRhTEBA73 zTd$mwHv3O=hsRWZl$v`QN+<6AZjNcqDcwf9Zi;en7|x2_rA=BUqlV)uN$9+?2DwZe ztl#Eor*&JFs?wRDqW9-rUvS)9$)bQ=`6R*0fzUgQ`mHn@Rv}ZNju>Ce%&JRG!VZ`7 z53UMNsbRS7$k(tqd3xkh&@V`o6kV(Y{By1R1a9T^zlC4&l0mXB1DMh-f*g0=$z@mN zuKGcKRV+R=lF6$q9JKG*CivEE#NHedP zyY_vAtz)-C9G+mGw*lAZDH;@!gw|OvI+TtP8X(rvE>IPXZcR12N#c7C zm$%eTmqK+#VBwFD_th72H%`~@2Fl@Ds7yN*#0=^Ii~EFLhskk^d6pMpDZA*FW(IJva=K zxHbxRUcobnpY0~!p9j1(&Y#fXBCP@q()tVx$tuIwP1BBYoneI;t;tig?*mBd6M03# zf`(+!D9)CLghA5E)GHf0);70#qW9`1zwYb)@ogr!{8HRJZdK~UNXn_lAJp^B>KuDN zZh0DMs%WpmM!}R=p#M!ok=99BaA@SDLPcEBtn{y$Nu6w3*_l)_?1@h23w+?3s0G1k z{PG)#Di!O)q!R*W$b5ZRKq(X|0VGx`_eVcq)czn&LX$2^%@O~TG4O#$l zvS4})jXcbNg2lou@@R0T-P{is+{ba#wl0@|zWAYg!;yVgwnBT@k~q|{Muu}BHI3;= zJbbFtEb&)8F86&eqi*B@hR&GN0-P*>R5xfj?t#blUP=QMloc|pX3Iw+D3c+{R0x_S z77E*k@^|SBQso5pq#e4gH*#Cx551nu{u#mG@ zu$DdnV7k+FRBj^S;>cU-vbxLO0%@pDzKfHHA9xL0+65$|i=Ol8dyHnxck}C#mT;Xo zZLADK7XCeXY}4(FFy67)H-Uw9!mZ|g})T*3IgFGJ4w}=iP2MKj>64`Yd4!c zIKwsVuhj?=&P}BR1`=n(7t|7A)qcbL4c8R*bES#zA1MQD--Z{4=KWBkj=_@J=twwY z1tLPs<<|ylA)DJoy6p5$%}E_q@LZam3^<|_Zi*+l(mj4pYPJj!r0zW_R)AT_R3!ct zkO&Z*?w`BAJ8=MRx-xYoPtiBeQtJ9BS`BQFI*d;q_v=e(R`12E2FvrEn$o8o@=L+3i zK5G|o-N>t#8lX>iTWk^}g?kgUm#<--6YyDtoj-SVy*$!FtrQ9ev6$xIvr!Q2XZ z+JA>UabW7K_6716S6b@}B|Y?-xJZ$a4IE$g_L+%gf{g~J3YzD-IM!C(XnTCpQJWZe z$;ignPFm~$=?Gc?6`RL~5v^{EQE>$KGm{AgGVRCm=x9hwwsshS);F=(LL3~|k7RK^ zR3n@ulrl^n&_$6zSFc_tq(OM94s&Ui)vpxA$ z&FgwAs@LHw@GfmAfYsEB4|ueEW*|MjRjuh441Fp<9VjCukX%3^hC7XTOiHYYQT-{K zSC*iSx3GI$EqhYQ0v8a!DabVE4`;mtmMMrtCnn?oX#{wF-P!GEK%8HdoL!8|k*rr$>Woz&A2TrO*0=fY<*C_5yFXQOzm_?Nuo#pqd6g8Mq-SlM z->Gix3t!J+ry?SczxvIPh*4j|N%jsfe8wq`kQ7zLd zh^Kqf>itOhh^<<>N4g$IJ~HNv7D!9zx#X5|!h_qrQTQQ@V%$4^lM`kh;;bc2m_DnE zY*`~)E33oyCaj0x`{885m=V!>YW;HdWtDnV6=~f|c2|GAXt;gDPWf%*@?W)2=enrP zo-sd}19JywZY|Rk#AW2=Ezykqp{|hy#8;TcYa%377cajp%v|R#+l=!1n!Z_&6IO2V zLp;UCwSQ@yw)6^oVJv;sZ8zu8+l>6nX`1vKXlL1e!}0fsPuYOF>%*pxB`(`T=h7l&y|Aosgh+bYrMpg z?+e>SQ-zrwGAb(b&P}rN;{F5By~}#C>9jU6$FovU0pHN6m*~)d{BV8VAmcZ00~>k-FFDMQjQwZ;QUy0 z+;>|kl!@)H%g($`UHB*-Ur|Md;yisHY(~&J{;eY1!wlS50=co+P9n`&o5mE3q9?uG zZ3M&hbM^ifL^~4T-_9%aY~@^R)b@<*tHwQ78LV3q<}dml*HyZLp=e(=@FNkX7?3qz zEBbj7ntrqURt$V2@oMvu^(Jc9`x5!ga{l41f$B4u!E+v+8Eh0f7mvd7eyl_M0^U7% zmAZv?ThKx*hhPj|aPfZSv?xxdhoP!shrieIbeHzB%PHVbF{NSVhQWWeyy^0%jLbdi zE+b}w)z4Um%CmJ@)@hXO3SM-O0Ds^OMA*AnXY-e6(0}kTjce8AGeEpjO(ll7?HCt! zi}R~|PUh*elTaMrnabTG6<@*nTJRYPU2YJ>NG;b>@k>4kz|DZhYTB| zahpe_)m5Z;;bboSTC3VN86xyf-EM1&SH0OPaYl>RTZA%p7!5NdN)qBda@I42Z9&WA z@ymjkRv$^YRbcCWz|%o;&i@^Or@G&v7vHd^72SqPt zY2#w*L_jZQW9VWkVrpz}VhY8_2j%SIWNK&&<*^an3aWr})=3Km;_hyV6V!#g#oBIt z$Z~T70*gn`4(gt^heV>`0FAV@ZEtRtH*xi-x7;I&`t)Jq`@{bCh{{T)@C2?@fD$~O z8X23JnqNTYo)?=sASER@BP9hlAyaF6V;SxZpOL7AY<_)Y191449@x=5KayI5%94A$lOgC2@Y zkXl_`+z$;69v}`_G(7tY<4BKmTsDE#jQ`;w55mb+@GB=T zq=k7NX3LE}wU68y+UXA9{R><}BY2wD58d$QWV{ft(ai~XQtE3AghuF#xCx{as9i%- z)ANl3K!6-zerY=Dn7yYnjrfk9bkm-(9f%)a99%pAv>hTpuLTt03w&X0WEdC1!PO1; zns@re#!iMPN2C_x1(Y2M?^K0uD?dqGasoM%cepK+E=Ua2oeh|Ew z-^D=rscEz?m-Ybl2YOTlAI@J~B_xv*gP+ggwT^#&#o1Xhy@)-+U_|u(a9E!|CjxVQ zsTlo(FisAjT>$;Z?|?Ko*@*t~$yw0-L?7Bu><3`=5#NG50BHC85$OFy_u%({8YI7h zJk@*GpTTPYG>iTS+ySB|@CN|(<3ECXXAk}e9G!#sAhES?;DJTd-~YBIe+l#)TvGTU zaBjc<9hAL*I|6C^{Uva4iTSsu`v?ytzWNc|fA8`m=wpyG!5;yfoe|kX{6^x(Z~eO# zP*UoTu(o@JKMcB(!MPSF{=<(XH@l1E{mEb5=N@C*HwUHS_;RN4N54&*d_qJy+O>z4%R^QQ8v z=oqLYyoLRgfTN$@k#nuB@Av)PyTbh~A25mCs}qaIoj;J5=Uo3GcKxYSa}LUa-vO`= z=SMySQNOV`J$az_s~r)JKrHeWr)7Ykkc->X+FOIPDYuUi~yXIf1!pz0}_o*c-d` zztjJf2MEj+U>+Xf1ZNIZ$m*Pr?ZQ$df-lX1EWo_Lt&x9{;rlb2V+UXEK>4(s7rdHd zFQP2wwV>Wga$YN%I-ctbr;WWww2`Q?iSL^ijkF_w-Aqg;a{%W@&x2BfPasHOriA`} z{CRa$g=z9xiuzE6<64`9OPR&wiSC(XJzMET-In=su6?nou8kW>-J9{d=cZqhRiSPL@wJ zKSJ*59K*>bdPv-wMitI}`&eRO>M+oxS|33J9?EDN3Yp^>$J?~=;mcCqQMcl2)9}ZZ zn;jHEN}462B}YYjBii;zrXX5*+YTk>SZm4X55kdR9ec`I1UXobvAgk6Nbh_|N z0~f6I>5YetqbAk|+oTirU%Lpl0yS_>L|@Ifu$>Ey_CEkKK+L}Y1h`_- z-`FM4kk4-gW?Zfd(Zxi)SVXm~X?Tb>ED_gc&JF_CkA}yf#VFxAIaslUCyrzQg{8Eg z*A$8vuwUnrvTZiKvqT=q;#-8OT=eVKu&)Kf%7yg1bs(wMCEi7993V{odg4yWnf8>< zQw0r`6JSbqOTx}Hv(38hlglPxEo9$sl!$WKd{-DJk zu8U7Se~+cYA(=-W%EVubL5s2RGAW8GhgQuDv)ErJE;j)o=UN6q)91qj`;ogAkupeg zvTw5c@W-6Y52B>YXqM7%s8aKm9u!hs$?+cNYLQgF)vrMgs)7@{6KP0DQ^x*Hf?1?& ztfjv2>92zA`}U^|&G!qR*G8<))^bDFEB6E88yjnCGT)657{9yZNj=0xG8)T;(M##N ze$Kkt?d`5GN(JaUZ&BlY+HWKX?^t*&fqVzXhPO?lJW~hxqHPN9oCAm zcy}M}b^PQx{kuK@lyi>LNCpK5fza)n2LBrCXwR0V$#{2 zh@>Q5%XFww^0eW7?8>Y&nrT(svMN+mc8~iH6)j9jcpG}%_=mH=@sa4eAwqZp`LTH# zc52IH(`xUCTe&fUbVfG^f5i&+ethpWx5V_^h*|Ep8SQV2Q3iTZ%BNoWzD|5uf7f3i zpNwlpk3ahT_NV@tWsYkl&AZaAxbOW}k04m}Lyyj+UmaAr=1ThFEt!QAOUgHM-$jbF z*geVic%8@<%%`iih#U_6x7jpVVur%aQdvx*~yzi-w?G-Z$!_3K*0&C*GJ1X|Yc-1IwwEVne2i`(&l`&@kt-t&9mk{lxZ0!QJeK zJr0a@V{tdlFoojLfqlP7v(}IBO8mk~`xR4a*2PaSZy$^^4&nOqlGc-0EUx>q>^iAc zB-!)$Ni{|3)x;E7ehHT0o^WB6iD!!ztlwtY2~_!vb|cYIwk>GGfTUm(Dd3|aK0$=? z`n+FoNW|#rSI48^L^8sfn@Q8cSbrf-=tS|_R@{5#4lK{DHSD}K zam^-!7g1(A%wx%dkUA$zZsPDFrA*&4LsL|opOhZZeO}djV_)&w=KVcJDgYJ%)2{5k zoT67wxC#ippeYuwB}VMGt4aS6dPQw`*_wbc?=)zwnbMhQ{Ds`<2Xh&Ipf%ay5(%7Z_BoaVlk`Z z6&Z$19RtG!d{)cG5P~XIIdJzhH3b&(I>sYsP*E_el$n*YH>?>uczMg`NJEbL!ow_c zg!F|rL@1;-9^|F&)bmUqKP7Z&2F2OY*;!WgWG$IaSH`ZAx9pYuNc}OY|MU6Ygj1Cb zuV&02P|mmMq*>HbGFAjgbTPC&&UZ17%LJi%C-lI>RTk_P^3M?~WP1}B#9^G3IU_|C z<(GxHD@k-kD@yb5QOPP;ztAL!E?5%%1le(WK}N_S#7ikRUI@w~>>R3$7b?ezisFBB z4^IkMo3_iR*=@Yj*_m&kU7Uc>TAJJmq3O`Bk~UQ zdyC2x{m9{fMD$|5(988~-CT8L6LqUB%R+V({m!h%S)jJSZt9WDUI65?AC zON`a6A`MWalau;ymkTiPIO-RAcoJahY)T^sDbqV zfsLO<<}Ve!kH?USmFQ3FZ#$v{2aEGkwg#|5vC7`KbQkjpHcH2%h)WuWY3}D+ZFG+G zQ{$*6O-L0vsC4#kPGN)uP?de`q?qF1=(ttko98>yjdkIRfTT6vsw71@a$eH9=T}ND zIvRGFxgJVxCKG|R2todANTRhGM#IkOfmv$jjr5CZmR;)qe7}Z*Y$dP1y)s$W$skdb-*6O(Dv3rI}fE#n80!8DH!f-We z^?Ic?d7k)cc!u}sb4Pm4MVU{-I@beO$2v|xzmD1kV&tOe+XbBnm4_?D2`NYo$^4_s zmzc8|`H=1(XfiRhb&bN1x~d`*XtIkNuG9tFuc@EA^}f*a^wV@bBtG&|jqA&2hPIie zYrUWYf81kZh3WzW_+^tqjXcQK0iUNxO!v)Gh4q!TU-_I#S8SiC0u=tsw+oftesj4#bI8Ot74b>%nnQvo7Z)ds_Q5lQXVwbPZ8|z7{l$t0LfSBO z46}4m`D9MTG^Kx2Ju#a}qaf(`6&kYz%?=CMx79zhfp_nLd89wJiNRuG$lL3SdkEQ2 zqdGC~s&5fF;aBYM+-E!BVWAE#JFe#=`m`ZU3dng0eiYgxrY=X|TY4;#!y&@o@$5(; z=!kf!8Tg-vC#-((}SLP_p z&Lh_@_I%ms!t&-Ms>zb>s?-xll@ZldSg&f6cRWejWuPU9pX@yqp8+>EP2_{UR~5Z= zBSDn=$i7YQjnfmb1uL^&vWqt6DqC3DfeB|g-7X9e%f*sRf1tsKmnyjr@ezQTEjIo3R||sPHgng#vP0o zh&3jynLPd?FBY+O#trOm>RBPHPG~_CPTsTos_K{!PFS8FFhk!R-jsFUSaiV>D*&fP zK#OeHdd3N2S_BXWT4SzaF^NyjSvO<keai*M87J6tB^B`(bFc8y$+WdJp8cL~8k<{m`Ws^nkpgGuscpuG$Yr`tqm^Y|;YY^f z$c*lrq6PLM>LxA%5;o;p-1AWDf(%wD5vdm8%Fvc+#jV~2ait4}s^LGAv>%Vw^qh+% zRpMtMWSCSm1TtZ#iw2lQh40%rXhAk8(p|*EIzu#ePf)}e3H54c=v!@ z$?N8|Lgjpsx_X)7hG^ku=G4c))#K$){=91NBkO_auKNg8gRv5_%Qct&mo>l4MQ)dJ zSpPCzl@U-mXrDw%v+Koa5*Amu!fkJ(pGlfO^5=QKcSv?vri`vWb-c#0`$9JaDaxex zmLdMes93BQb)b^^W=j)?5Pp^R;l{fTdu+MHJ6xt2j?h~Y>#cbik(G}@7T-gjZClUt0GW@bAv*fd)B6;{S0BIm{s(5d_ zU^v|>Eq^1xRSsL|F?84ty)EnPbSnCV!$LH8T?fP3ts<~@b-VAPbL#YH8dJv^eV;_) z`i4I~cFCL+?tRglRX~!cD+cl*Q`tvGZ2HYMld{5*Hml9=e0sAbZm;layZC(ai3Fh- z{p#|iCfZcn9+o3XP0As9n^2z7L{38?1zymybg8c$Ht1XmC1tYRW{rNnR;1lj3EmQ$ zSQ_7ZKYFz5#4>a~SLpIjobL92FC6&H_VuFCE?^PZO*8~)>~<#tMd%A%aYTkQw-UM6 zkTGbu#7%U$YVj&j^99lC)%%5ttJ?_^c_%yOWY?`&|6d=)M~qTx~1Ni(J9|BqlH^` zd5_5)nG~jIh6^6woXQ&u1B@HKQ1=?A=AW#79dRjp*XBOjK4_@_^x zOfA9~mOHxELbDwx5MmcgG!Qzxr!FlIEXPf@<374INaaqY3-)1YKX|RSlvPYZJ-qFJ z8n(Q7<$R~jZqWOY^NUQzcz)*mMTTL|q>}>Bq3-i1jpIvyV$gi#K@R&=O zLf5HEc{^0x?saN}>N*%7D3|f86w+QfCrVCs-(^C4r@cA4?Yj??tmY2;0yLYFQa? zD|SQ*zs~26y!!tHZX9b$$o=q5YirX+^P4IWca9py8&n?_9o|E-z<-ANRFIgg;wJzT zMKRMMe=|clk)WR2j4E~epubD_d}}zH^oE4+4U#}QLbvb1dw_&~e=v%S+bs91>cI2l zC)zAkj$u;)Ps)}!GLB0!wK4uO8&izqW$G4Jxdb>C;ct1$uP2{LoHf^idI>xYYFc4C zgy}a=b9x#L0`0Qy-*7o}q3iADO-c!%Gb+)1p~bQ;jnc1GQtgqwkeMC7nk4Ifr_O&Y zvLJPex2yDu1gECmv&vd4SV7-zwV^c!8`Q~Z(JCd;Y!$!Eyil(WMQ^AEGsQ$22J-NG zW<-kARcevMnG}b-s=h_iL5h7318nr}oxM5Z=$O_=Y+7(VetFUP$z>dmC*^OH>Ddz- z@(1LWQ>#cKqWl|ap7>dl)MlAh!~>#x+~l2#I5;F=vR z;Rin5qxr&)x^~&HO$}y>?mE9j;Z$``RlN|5$+`D3%9Hs*B3v|teNWL``}pxQ;-{xf z)zAjLl{G<)9&LVN=-{R0cV-MX)El)3$4c!hVrpD`;ddcD^^mb;*%WguP!b612kQee2Y5c`q;U-&koTw`x0=DFkc!dPF>cU@ zMs+}ks=A|UkCj4P(^4Hc-B;V@ z4tMuf0}=~fkmAiU9IBwr9mKJ~ZN@QFD?MCs8We=4fgA|y9N(9hOW=Nk>w3rsN=~L| z%Bskpq}7p|WpiS&Mkk-;+LMCB_efG>sEB23PV>)B8h?yU-Js1Z^}(hRMXPU#*t8Tf z8QZDGsPJliC4m(ka*t{L1f|>fDF~T|$HBhL6cqx0`$mo~PoXKOrjKDFm-9m8C&jvc zN>lU}sTag6={NH(1swhnY}Ip$&L2Zmqk)t>x~HLRs%gTdoqLY~A=0crv!wW=VkicEBlKQ*WXf=190MI)Q%HedmL{F%t?(%$cKfezwZHn_KcIqgtK{=_qcNS&Jt)>DDkAx9oYxfk|v^_eR| zrc4y?&E>YY%7`>#@C#7#5PKH9W3zkDpY^U}$b@m{OI06E+GjhaRw{3)P);NUG!0!L zr=R;Fh&_eFlGT)l^+DzBx=$pxaQpyXDW>j7Tt^vqSJ?hzwok*1TIsv9HG|DWb*BaF zX5L2;F?6)`i%!U@Iab>k+upve2!>KxIfNQCS83Jqio~O_V)xUC)SUnVau?>Dl>B+M zXwF+>Pm@t^%|qU^6<>mNEfG2@7v*Wj`ehi#8Iz>_L2CN@-Tk5}@0xEmx3mHiP@vBc zxeb#U6C^9e*Cd1I3F_H8H8unEOJw0OgTjlToA0Uwt3^RDA$YBBd!DQM={ArG>CsZ& z4k{mtabSD#6}*&DRtsnOV5S;v%Dq=f+q9NtW5jtYXZBJl*a8fmnI9JlN>z)Mk|MT# zMqXTto%HU_Z7;VZlT2|K z4Vi-;0;O@_8hfE5eAJQdl+@MT{#}hxkI=yb^!24&qw|yYzk>B3i$S^|QKNW1<`J*apN81I2rG=!BosK&cgEm?( zB*oD$k-N88@f~zSSqQg$v?9W_iO25UHsUxO@|O@WvJV|%u`h!4Y8eVur+y^OY?@0* z+%okajt{^6fpIMW;__z;B4sOLu#{$l#th1(`Ke$SFY9b|ejCt+-g`>WW4Xx&(`F-g zv7WKDPUL5exY}B#oNbVZA(y{};Y_RHx;zBuPY-2;t+*V{Q5mg~l?BQym-B~|AK%>8 z7B~C6%yL<~qJs#n6p@yRjueW+c$2MO{DrHQv96!vt(DBY17SOLm~m`0(nKb;0e-#C z!c9)8At69?{_9lu!qu4EBp!$NMEQ4IqXg$q0u+IzlKt?SQ5?Yf9(BaGO@&9aaFQ=b zZWSEv(PuQM-5C4zBWLQv4{3U26hQRDyL5@|jghEbU!Y(@e=)o50wreB zQST0oe3IOWjZ;NCVjegS>bP;LVGJJ@37tZx-F|nX10h@v!Okh1H|`PaEfh3TK%bP= z_>Q=@O3Yl~GbbLa9({NnDec85e1zZN##F*~BNvD}uXPbfW%yJ{E;a?4YGn;2kRj_C zPsO`&evZeoTURw&lwRlRqxIL?Psp5tG5iR^4rTES^NrYX-SQg$csp7f(w~l_AHoKh z2_juvSW<$NkJrQ|oBRH`72Y1hUNhw+Hb9mT%2+M`#aHtvm`D?%Ou4J$zGcZ^1E&eq zz1CAOD(GntYOG8Z2Y4!GZfjGNsfK2%)ch_sd9#&u_Ip?BGki5jaVt9YD>{6h|6J5* z`*4CHk_`ERYZJYHHwALSU3+MEnyIdP(W`y5H3-gsZo7qRJ%Fk*i0|p z-<)K^C}UpH7@T)&+did*Eq|UKi%c8(LHCH5>)&>;5I=XCL=@?v<)hcrT!2gw@*(sS zwx(k=+Qn6t^FS&qsoXKFT1aIjQ8gP$-r*Qqe`j~E<-yXaFC5|M6=qs1=oxKChSZGV z*y}^=j=bJp1RBg&m&&wH9xF@VDjmMxKHjmCNjP-nFQhqn$xx9cNBWG{9fA}(ctI4f zZ~Pg;hvS9eQ>rQI3N)Vp*r8*ctpS^-~PB8=TcXb*$7N+xcyjAe;# zjhr7A_v6CEyMg2aWqcVD1)#1q?1yIIlHC?iAN3_|{PxFaMg@eftmLY8=pUXBvo3zc zjpZMr(Nkz%!!L(}s3IQ7$OeOgv)V%lMPW%wueN@%R3E+gl1;VAedrt8zX(;tYhS^G zlzX~9NP0C>ED(50x3U|SvSV5VvST0!$zpXs+JMf0lVZ{vMW*Ep>2gD)?&nUQ{6i~Xe5>l-@Ce_i_S3j?jP*I}`(DEXe zc5H4LV+Aq=QMd%*eXKU5>ZdGy#Nv!V2>+!cy3d`F3In+wAt%x|Zz2Dh-m?;AkS z4zzQjHoaxP%*aMOvfV-eI?+dbC;;u>9_6)M)>d#2*B`t48e|;rQ%0mnF&g3qZw`Gz`5AYLvK�^#F zzAG~~PJ7c=J?vwMdecZQ?jo1@8EATIlRGhY=nM!o-uZ5|TEcG>WFVkP$w?LJ`vAgX1!eZiJVdMRe>>xPwUdkkr#7I)I!J zWd@#|^lgP2l8BurG3Qm=elzndlr<*gI&vHdW`m%CyaAf$U}i(A7rvMwB}~W1yEdh* zN6A|Nf#AJ1nj)&ignOKTkwGM~(mT}mxE)O@^; zVKvxRj+M@fRIVcu5z2yzl07BJUPkj071{O3Qmn_t4Oif1vSYTQW9xx69zznN0X50Y z!Iy)UlU;nNS=BQ1mk55gKdaf`JZ~d}CO(=o5vh%a&)b$@EN-^ukj?QL*${~KZ!0){ z{?Ug^P%}{Mj?4FpcOvTp@0j1`V(qH$j3p*_lXnS5P5oCFqlzD=+r-?-Cx{c_I`u|E zKQ4TyP-gd?s5jYmjNd?+yX{09dkyhFqI_OZRk)6e;>S5GErE@4!<%W$HJKbr6jd7v zZzDdV=VJzm?+&0$R`V`$S6?Tr5O>gE4S75iF)MxuFYYDDQz>?npQbwag?h%qO8FCW zoqp|GIqP@%!n1tYqpMu?1MR>V*3$fG!KAhsD4a--- zg2+7)d`a2D+L-TaP)P38DyLWcv_d|UN6EC}wD~^r{&uVms;xI`_l+|b@LuaAtAcxT zOz__1ksXP#xJn$rzAV(XdWC(_A^!q^X-BOIAV}rsF zT9#^z^Bc|yRz&VISvSepgUZL30!`PMr@-NZ%JF+m-%vm{Jx4bhkfV+H62+A6ohwv6 zHSD+1M1a{M88l*+pODKMXAnmBHwdErS=)M8HE~GS>GxX?fPlOnzxPbj2q`94$h0b6 z6*lELZ!YO98HD@r(T5}v2uR7lxD-NHv~PE%!)kdL)5>fhjN9F>226CN z<&XMptURSuAYjMI66U-_rYOY5P|?6=`vv-=eeK+bKGnbwC+OLRO+~|}d~yOAGCkoT2m9O-Wx23wy0D?X}Lz#UTun_3mkh<3T(=t z;0+v@s~gq7%?E@*Mme9n5kplUxu7Z!G1n}GJKl1fRkWRONCmOw_fPRR9+!x!+jWk! zh`38`;hYi=1R~8=zElY*NxONq8lCnidwL@Z6HdkOVeJIjD}ji0=Ql%vpGaDV?bBiv zY1xvCzMT^;71OK0)$9vyATaM<+~vs&*K;N=P6-^_9T&1eXl`Tp%WnF*NiEcmh2f|( zU^h`#J)+FmSh!F5S3R4;T!`+go zO&gERL`Dp_*+h->LN!|E#AkQ+ab^0ktS&>P-5dGoXs^s_uShgv0s&2R@Tt6UWF10# zecVjWlQ>62 zVt+rG=^QU^)^zOxzQhcEHVy+1(1a~?pl9IVa>WRB+n`cwIf&gJSvMfHg@28dxFW$R zsBHNw9D{d6+Co|mGGjO+^1hrhbq9v2F;mN*2=6jw!Er|5l#c|vaiwC_`C`PNOx^(1`HpWi4m z@(Zs7)|#7P^GEZUJOCsxmXoqE?^fCOoIkQu_R{w>;Ux)m9rgBNCkdDAp(b zvE}*o9^sP3@3Z!sVl%$LU zZsCe=jIV(W+j{h7TEf#STUQtx#K>Af0fti5{$%UY;tQ%_M**0x9|$WP$19=@%@;!W zt1P>={Zxj^uYK^t>d_>EAs!bN{e9w>2`+;om{|wy-jXq>kC(M(4}=#5_y`4!QP@9W zz}1i^!K6Q8>h$=(`DpE{l*5gSlVb;qy`WEFd70C)LsywO<+w2upk<3gEn6%4F5*V=0HO~DKUL7|GJbGtln%k>IkTp}qtpZjR3mj?<3yps zoaR22+8`ExF$Fyt_ui^OFPAuf72=&cGw*9BOu}<9jk%tW zX#D}*T#<{DFY56lLh$qxWVd*aPTh|$F4-*-PYOuygGOO;6rj5$Q%<$Y8yszU>V=Td z`6yL?$eha{_y{OLKU_e35_2&Pntqsqs>>{=+Y$;KeDLM5MVoZNzf>$pd0rCfV&Pv* zqD_$fp#*hUdi5oVzE5l8oR8iyGle;{V;nVrNIQenN$f~WZ+OoqM0I!-m#GUe`P&W& z3&AEXpSO~0?|@$!rQ$JTzxUFra?$AsKfz7RmfTccvl~qR`647D2`kdqZ<}8PM`Dw* zvW!nB&lv3d>MlNTl{le?X zY-OICFEuBAkXM`ld(FmF-rfVTw1}CsfM{T2&rI4!d$l#!38_Ya4FY28WjXb*NTgv; zd+^rGx$48oHm0Eg$in^b+B!f2EfQ+DFqQ7mw~zS+&_?QS4`tfxU-7!Ae{A7uZuQOQ z%a*DTw|s3VOQx!ggG(J@c^2{sq`ha?ybU>&c1K_P%EQ)!&+k~>I!Nz2QkYtf(bclO z97B6B9wIPRjXlx3`%)n$#glmwSS3Qx&^lSP2#*B`+nGRhQM>*ruhf$Y!SjO(p-A=& zPz_6}Sv7*)KMV6`#1vqfZkSK zMG~E%0jy`4ocf<=3)9x4f_v9Qg@bF$b=Sjh)K*-^+@XIM9z|JJ$a>=+5xXNV7y|_# zykzF3Mqi;iYayN3p3C3lxptP7aJrAt6bzsk@#ad;vot+?MRVMEOfp}aCfJ-sYNm+B z78ImywbidOZXZuOlq4yG9*@-f#Gj`qY=`y@9d!FG?q2@kU`(I!CH^fOQ&2?dg?u*I zF_)c9rO0_-#yS~yxt%(?xp|1z_1B$Q=hUx5;{fdM@hos7kCa`^ld-U7-S6IY2iL48 z*5WlreceG_FQp_OD#CZxAW0`U!uAmH$^PI7H#}iX-0`#0x=PsNn;m^UzTS5XQhZzy zCDtw`9v@-3M)<6gKrOreTbqeR3*-fiJkZSB0e^#nqq4_J#4&t(`D`zJ`nO9Z{oleV zqdhl6!+sf?#|k1B|*E*+j4y3h=z&T|4`I>ldnl&6<_5(d^_3 zKzi4Fc0Eolht2VZ{|YO>yr4@*KaxSmt)U=Ozhdmyy_c5LtV3W2>xKQHhEyKIT;cbb4CY+VK`TJ zf1jr4PJ+Vq@pWudI`Rv^Fu8Fo@F+(AT!M3u$Wj&J8Iz7jto71-JS*QMz`K+Zs7SZI z$zMl_*7V_Q*|1c{?cO0Rq{cCRe)=?Yz-;jy+l{2mmtX+*>-SnLNF9b?fLAH(N%1@y zV!}yiF+40Ct>w@$X~+GV*m!Mc5cSs(0=e<($vBkrL&e0b1%wxib(5FSL-y^rC~Zpu zHFm85n#1rdky$@L5BmVVr%V0s6_H4~+=NC?yl6Kz-uSqn5}}rknO&RkMAwI`{<{W0 zRqW^@euma-s2B%K)6u#5;f-P0)$%Zg0Ik#!`y0%~ek_qWCZf%cCi?!s{U0zPDkGwV zH)NVe+3Fa?_Z9O314kMcnmD3}3SI@4k2Ok_3cQ`!UP0v#aZMoG1lb{_C2lM)#p9(l zI%Z*+dLCMIqZU^LUmdPe<8BN-UM&TePs2H7C+Q@EQFUEO-F<@fvc;zQvg13XqHtX7 z%~_w!Y00AGimrX{_4m##)dnOQ(<)UY0HEN0IwzQ0Qjl-H1o%o*EH zguGWFT1;(OEfhBGxi~|PWKYt5&9S*?T<({tIKf#R)*;9S&WN}gXx^z008Iq8?)5%; z)S2mApv`;|T|m>eJ={mG_=qErEB4a%anh7~mCFm+X@7Hqu#w9X@d+h7yhfN855Lc7 z8e2cbrhWFyetCISr6#VNCmJU@D^~d){3R#qXlunGOQI)M*Cu?80!)tcu9(RhG%IiS zr=Xc;B)0&=lyZiC>xOE9is|;I_{g7cCTG8ownB-xnj;083HUdZ&8!u#NMHc#sp-D5 zBbbwa$g*L5EN7R~H#&Hq1siV4ZV?HJS6qIg52iYRKX2&JJV}}mBQ*^ZuY5@EXiIhS z&vDe2$b_izcDtK~RE<7O>i8V7UOe^9V^HoLO89Cj(Q-e0J~uu>ZQ?;ee@BTm#lt$B zndR6R?`5Z48~oVY(h>VHPGgcy*hKFaHm6dOj!&*m_p&=i>UKUZHudxDI>{@|x!0{n zvS%vp7hIXaj!upJP`XG%ZXDOmC$fFKrE&y9FkkhX<|(qIxeq_(jUW;BiMOC2 zF!aXdEO8jiQd!@8Gk;7v2%|2%bagU+7D38tO*`{9wY<7DXT!J7)ohni}_}$ZDll_DG2s!e)JQOzEu~ zE&KS%Pf@)7h=IDKfV>V`?}t8=iZ$dq7fY5zjsnL0$~r*RgRmIg2wcFAy;m5$x1iu} zK29(t1wF9zFhv%?Uu85Sy9s7hmIg_kms|)@9X_|pP|(ubBSGPTjO`m=9QwD3vyA&K z_280mAsxfHGuT(;8GJhGdx?rWuJ>yi4olXVUoZG5x6#u$>r*SB@IO~Eorvw+?xTjY z<#i^VyXEeA(T;?&OGSH&%mMRM`}sFmP0A#yYsCokz^A;;Um*L}&r-k-Q z-qQ+Bi&z+ut{k=d^H)oK6S*VVczagg>XeclvAX^SR%oe5Bw1&eF>+g{<}0#2HKCvf zWLIhe?X4SYHb1Au)xFC+Zv#r(t|?l?yhUCC zW^A@Wjm&1YHla9NY4-{nm$RL+!WBdd>8Glsd@t7Kr_0pRGrscqk5};0AJz((a3x6= zcr%e*yW^WLBQV~3BE&S_+dLv4?Yt~=4;B!_=asstQ+5p||8xdX+*+U?19pw;Y>t8y zgp=Pi#+maoN1Jub)I;x}_!aiJ_lHDNi z{n(+Kr-!pmqZ7s;rn25g@rxfWF0LVdH%QFjvf zIwxWyZW}B>$g+s-75B?7^00~J*>xhD1)>L9d{SYkm44`hInn||#!${mvmuSSka8#1 z+h}Nyq)~SO2Hio<98nxb?L)F4bUFIy=v#6A1b7_@*j{FOZnYxu?;@>j96!R0SyJmT zd^|3tLpk<8dzLq=YaBT^p#Lh&-_M?f<{qU;BM>Bo)(e7T#%pzOPMV)7huto89!a;*GU4v}dEjg;tdAI{a4y@> zkoSZ={M9jR3({poY0TG%BHgAn-Q+9+EjG1+x@>SB+bI6lpogE*Cc2($L$rO4J|yMo zv)%>i(FsDbS;vP63Q%t9bX=(FEG5aH_M(knFO$MVnVVlDMk~*t00X-db*{+4Aunf_#oCTm_p}P!ZtK-)#a7aT-Fnq~BDkfnayUM&@J!wKs-ZrFkQ`5vA~=vQdSyx3VM-S* zcxx!-qh1Wtx^aZMRPI!G0*P$lA{&*xBz$S!)k6JtA6?JfjczDp zz%Dw|@SQ=qvUZJbFRW-zjV&{PxbX~8eYw7 zJeQBfk4}r;Iq;iXTI8I_5npIW8ngE7OJ`Imn6y(9eo@^@a=C$GoBd9qeNFrAg17G! zL&L-xZt6r}FtmN(aWvojr=J0~e%72uG?~P^2U(VI&3W{S8t1ECH3KVoac&t3U-M~C zSs&70;!0CY1Zm9`$zH6BUwNFPG`?ot-Z(tfO@Nx$@h}zWRmJY-cL&2Xf^{Z;yfB3*+nf^zg~V5X$6y~Lo}v5C zKXW4U1puhiS zy!~omvWc3x*zW|;N{Z(EYW_?8PE8)&H?9~AbNOc*?4RQM={h>HcDc4VzmH4?Af`+%hJ7_dfZA6bqx|`$YY&UTRsU4Ugml;rmhJg*qqR4rX21- zs%I)XZYs}trfG&O8q4Y-zZNU;EWLZrB1pT^Jk9&(3{{sJ-e_y87lvzG zMeK3p*QZzNl~RTF=ql)ymd{#^zg#jb+|7F*okwGRVo3aqVTWTitFFccu6lp8)jM=tiyHEWcGlA3quCdfP`FJia?~2o#+k*Cn}~Vj4|aGH|$0Uzn3{}m5N=GYR zhD&X+IAh})A%eA45o_E`N1aGLwRei)3cT3jDO|lsa|5c78LdYFGH67^;fxW#?Ntfs z0buh4=T{ZDFV8W6OO^#xoyggmymtgg8)0>2??3F>aC{4jA~`Q0yTy%O#tFgE&0wtW zy}aL^o=f+0MJp40j}Ap!YKdlO5QRV3tVS<0VNmnYc*@K~XzJ{Cs!7mm){wj>Vj9JB zmnvF0#9;WqhkfM`w?pt5>626bjI-U5$aZizoK(e*W zXZ$QP6uv0PHuT{!=*>#?ge_-Wp=r^F)xbGBC6>DF{0jwr)&3;Z5hLO`rv%FDex55# zw)W;CK|9N;+hjZk+Gz&o;F-Y8Lo7X)kVQ&2zh)PbBY#gZmyUjUQdlSJee z4c=v+g{&4wae=?pQg<00*s*?o5)jrphD}WJ-3KJ5ll~o?owBCak{;YijEq3+d1u5h z9vdCt>+2rE{?{%qp+ zD%>Rt4JxAj)DVahR)=xaCHnmPpNgskG-(T{BHTVVjI9hZoG9;+kWnl-uUxD zCnzx#W<+_}dFRW+PWF|3PdeZW7NW_%D3BXV6760#-185l_-+u(IG7%_;!pdv5OI=} zr{RuAZNePkVhAXgF0MlJJZy^3bbL&UV%-gRF7+KQ$d0fUmL4Z7@UFA%DdXjGMai~4 zbV2YQFx0^6Z9zO+-(_PMe8cuxSTWx+E9*|TJosqbdlNDeeH?}>ldCi3wrdhKFfOZ! zZfY4!C8RK9Ni9TaAd*3<%=%$0SXCz*Dt~W}q|&X1Y5(KkSCmM&WaQPCQ(&M`obD;U z-&hz9>)g34g)-$HXy_8d^bsRl2b>FxLO13h$a9{{X+<83cJO&Jp_-_jHrBTOmY5yS z*?jFX6UU=1JDa`x-=M$KbIqz^vBG2O+YB)6#OqC7010AI~~`)IngNMY9-vF-Xzfm1}08?unEMB-_O49y&ZR3o-k!-Z!>y zauum6gnKCYPAE#)yw^j0bW4`P5P9OA6-1`U1S*T;S_By|TZ~I&BNYl{qkVAbTb5>D zj>j$*q)7I$B%qijxT&bmG@hvqR76}Ry`T#2Luc1i!yE}VsP|JrNegV}Az1>81xV!s z`2$PHY;I+Kt(!xP8eD~IV9{)*Pm0K3Q8B#faJN|^cbDCJ;;bEV(y7TDwmdD4Xie5| zMJK|fNk|-I5>jC=^O>uxRai_nPXUNe;n47Ou&BpsrpcJeWq?fQqhFj)Z0DN^WRwuh z?XIZ+9(E+*##))_7smJ7KXz}US~*xf8_j7dDg+xTd=FfQL}}XREe0iWYMO|fwuTbSD z16K-lcJN+pzInB^=r{Ez5SWtzK@2#P02y`;Y*rKbqBv@K z#2cYw;ar@hd{^m_7|5jX14yCi`X zR-5dIl`h7*S-HC!$QQI&Y?Pj>wI<8@JaVf`TKWF?%nE@XRt%>(?GiS2 zN_DLP{(^GcHDe=Ve@M~uZ^d4{3(D+C2U?r?>1dP=q=imd$?B)5S-LV}NLSps;#ySH zz_lw4dV8v|p?%@O#&Yjmp<8A9*-g-OzxanoRAsAXC~r%i#7mb;;sF(+UHJNEC71=~ zU%xcmGkYov&)*(Yf_pj#jWn}kDHtVPs?HW|7dN`YhrZib&@ z9^J+gC5k2lU1(DIH=u!qej~b|YF()pOAu0%{8ft-*e=G!?qmKa8F#6qU;bQV@&>buW*wkU3UprrXm^gr48gK zpEfdg84c=&IFJRVkZxKFH@J|g_~bZbVEch}aAsr2RLkI?g5F&D=xkO!Zas_}&Mq&p z$`u!^6-Y))%Rg5)fg#(Ff87Gy{PZ`5)=NE%KR@UZS7 zWd={C*6Oq$K1v$kmua?bM~Tx#rN*)>H)Y7m_nFRp+OUNbj@=XW{(4sU_E6UlxiAI; z5c@Yr7MZU8ZuiP{ZOov6F1VDa)a0cU>oT)^lUcFP-eh?7R$7Y7g+z+J-9FionX(|+ z&qrhWv?A7O4}1O{(7vff>=?&_AWA{`n%^L!R{4gA~m9@V{b9{Jc6c}|0r!3ipmvCgr zd}q70e_%tX5P!inN$_Qj5d>BvnB^(XFev+<@nR0}4H&&Slu0wi1lU>z7ElIFk@eUECZMzdQ5Ktkh+CzbYeSiDUPs0*hl#eQKg zC<^|@3%Y*_Hzap(f-*7*iU%zo+V`^Vc04L9*_c%1`Nn_kjt$lleE-52m?>`vM5!kd z>|z1YjwzEDvRReh)w~a+>bh#+HJB54;H0TIZ9TRb5Q9YzrY&&qn2Hp_aBeX=R>GzaMmBkcmTzq~c2 zgo@7iiPGEn?k~p{YkER;j&Nh>L6U7ypvjPwRO9-vDiNZMbZa1{Y#z$j$RtpK@cvdL z6M~kY&Ey5u`zU!_j1uKA5&6u5{~AG1PB z04jyj2Tr+s?j+WYBz$*2Z!vYuLl6L1xhKR~bZ_VSth-;Dd!N50AoMz<3@EbkzWexE z-yw^dQDWN2q_mlA%XKa*Z@uF2W~%$1bt^y|NN$abp&3n4M0xz z(gcP{x#gQd7_WSm!}TZh19gmYei1y7o?irW=@_fx zd5yUUT1UqYhIIs3b7%9gEQ=_S9gU8=&}fVOw03HOwgvdXm@* zj<(IDJ-^84#P(I}S{u{cP^VVqad6`PS)IZw>5tV->-^JtRRF0vw-M{JTxH63KH8^S z+Yib`ntOCDq?KdX!L`Ag66nA@*U;-kA@V&*48RZR|E}8w-!7Uy~A7XR}Mp; zEY0$pS$U3|`nP8tFqPjZNKJrtv!ar2+8yCdv0svFqbsZ&p3bCMi7~p5?RQxo4L0JY zd}V&fN?5np?2V~T4OtueJ(v@6S}#Q592PWbXY?BPB5&BovD3HIo$+klSXws3287C_ zb+Nb=%-yi|7z86LlLc9UO6J#E09N-Ph%c-rIcgaQFTTg)Asu4QZy@XDKWzE*$Sya8 z&|Fk4qMJ5rY$)C3W4aHKzA`9IftOx=1`Nz&3)%v6dNS1M)Fr{I+#{LsS=MM4QSe)f zqLsKNXP?mrDW>xPwpONyQwHaUwWXU=sG$2rP&KhLp&7lUu|;x=PmpwG=$K-AP#{75 z-nExdnXiH$USs^w{XKdo!YdZ-%j|UKg9Q6s7d%g~IxEY5`Bs>3sdgPnTQ^A?8^NsY z=+VjPUy(o35)?+Yu^QR_zHY%3s*S^uB!yC^IgDJVI;>M09>J3ZrgJ4XT_zIWsOStn zvB^mv`XRAm%R~No%yI9o$x)1k^czZiqRIqf2~trj)uIPgYwt>IbY`=J`dQLplemfx zzAo%t#o^%&NZb7Q?2ztFlP6j#$9*VsrNZrZydV#! zL%b^1XdJT>J5dU$r)D>4D#>k!<{@N2|Dmin90;`)*Q#7D#~u4B?m*|EEttoUE{&JX z-^|rMiEqs?0xIPkHcQl-c{6$Xs+4_5K;W`c6Z)dLFrL%fuM6{d!R&yZ=xYAcvvT}3 zl>d3f0<$^~?c+HW9|<@>v9Sz=(i$G-=^Am0%6#azmjx|kYs%ccZJ zHdx(Wvexg9ddJP=iBl_qS~hcyS;vj+Q2RH$!qlbF3R)MXoF^M_Jl|Tyb(x!vP@e2n zV`N~az2?_ShR8n@2`hrP7m)qRfdU7|s*M9S8!~yk0E=Dr;|LvGxOVrJ&|1n6m|^2z z*-ZLwUXy`#q=c$D})wjym52~P58TBfhfxFP}f85RD0&3C{Olh!3h7nXohi&6A{ve#N!d{DJ%* zB%js!S*1tJt)S0_{{l?oNX;Cps5}@!YGEI@sT4oFjYfXn7_wp`gQM!ji?L8$Vd zGFn1=9xNj)zN7Z4f_Q_wJ&8otv%)gM=1=C>y^#k|k_QHQahz+dQ~T}=`>dWp6V5N# z)e{R0<^U-Ro2aQQX7SCMA?x&AzAW@S*|1QJK1Ep{_q+K;(^aE6&~gCmWF_<*2`6IIuMDbCkk6+Af@~-!BZ*;d=Tx zr`z8Aq-n3At(|zOFFxy%{3SOG15@A6ggFMA^xJI6DjcJ#xsmbgD*ombJI;k=xj*96 z5%SFwJ|Y^JS58&lZ{VyNCw@A>SfnXNz?d`Nb|T5gHHfO(UQIdV5!NKi5SKA5Xb3rT zf5Rm2mz4FD^ujonw<(vj#ZPs)4xuj4vj5X|Gn)Q}%p&!Oo}y^y7BIl1zd?zMqpG~i zob~~=Iv5TZDK46nCsTiK_q(RMfE$866D%6XcXg`R^lj%dO>$2yKW0rY{E;O8+PC7> zx&=c7GE@^+S=3?*-$j~Ib;}YQYwobJWr)}Dmn8hc5hPKV(H>p{n0zOxO>zq}>dZF| ztqNAaHe2k}i9>n3i+4+pXIv|8DV_)H(OJFhCYEyGFD>hrk2_D&NJ%2P_}^AjRVY|70Mar9@_f|aF!)|<$DoiQH4mJn0I)nTh5Mbc zOU&F$`zH%xWPwLR{3;)P^vQF+3s>y!kly1(S@RRcS3n2BNkGxzV0mm|yiV|1dx5|H zFR8Nb-21tX)C+du;BTjjMFRcV--Ff1&Sv-|P3s;***{>;wN)Sjeq01hnwOJ5llXrx zzBPGYzSyhG_-J3_7_`cLVA$c4cbZ#Abhx_&?zcX&6T?T1G*6RQ`Cub_4(zXS} zRU`vW0~-M34JP_AlO*v@$H_~G>ktYhq+hkt97&VM9Gp zflI+!n^odH9S;ix!{PMB_Xt?Dp=na2~F)x~+I|+1_&wim^4v+Y`JABA! z-OlW2EEM!CaCV~P3hoC%YD3VxOkDwNJ=$Efn*NW5si^w_ejjE6bowH`v)AiS!E%EI ztIqInn&UXXxC81A69#s0I}jyoG(k!&@Lz#z_+iLSCVD#pLIKJ6UK$P`p*Pq|Im%AQ z0|^2sCKr}iW@Ep5ETst@l}kkpyk$_i>T33U;YYKF13e$LOucXRzQzOB;z0lh?N}Vx z*;T1+EIJm!HG)X-&i>0|WA}F!I1{;a(Frna)ep2lyE+IFG4PEjrT6-j$)>hPd&S%; z_OQ0b5b)tXv&seJ+miG?VF_gqhQ$Ygh?~Y}{*&zfcbC@{LD6^tgZxCBt3HznA zeO&haP4mO_-o7ZnT7i2sB~7rdl}^QSJwP0Q);w}hmMduUcLo@*i~}ZX13-(t?C)h> z;Y~@&>4^q|#EgqIVuJxmJi^i(y9Sm6C41%YoI81$jiN!dqv|V!YQci3;WEGL1B#AS7@V>*argGV7Ym+u z^lQ5e;|d#kbl7xs0#FWQY>iZX*B%1ftiF|-?KG_vgRd4L+%yb5iL!uB@wb$KmtC~fe++L$Xc<+c!*a~Ci7SM+vHy4;&lD{UuXN+>t!?VU$!|H`Y`3VJ`@Jf zQV79&1A<0vCy!-NQ3Cur-Q~z=%T_6Vx9j)^4l^jf9n@`wNMbtLTVVV306;wOz|LZR z@xehZF;K>1Rf*WMLf`B^*oaB{oO_4cQ~D+^ZJk19nyAP5lxsm0zyEVAFrIkW{mPm6EilB0^{QJL zI&6s$i^lJ&Ro&jH^8gQLS7F&YeLDF)r&18LEN-D+PveF7{w_p80y}mTi}4s8n~`> zdSKPH*?JWd)pN?!7-ntKDVdG?bb>9fHeFE=$Q+On4ph<;;i}4#XURVZw=3H@j7>i| zUIh=Z?NSVV&5;8XU;}>(Qpt&J?yQqt@*$iWgz8G2e#M2(9hu?F;u8-HA=^VlU{R6O z96WY?RaXlK*_60OmtAE|sB7oEo`Je`NR+29dj+8F8MGssthB^5$NAVbQ%Ol53}d6UC5xp7aUCud^v_lvJXQl>sA;WCR}Uv= z7zQ9@ufT_ySl+koGilZOS)3S3or~YuuHqU zut`g}KuZus0VOWd=|D*MdCq&|Pd$JAYj3rh)@F6M>w8~)^}fr?Ro0EtT3ngIr#S=+ zZgg-32m)H7$uO`Wi!MvlD z9D)E*c5nc6cmU}A2O3D{EU| zuPSH$zd#u@8Gt$j2>{#rmjIID3@d9xFhB~7!J7fN`BYjNoB%C3G&X|_^?yYMNR5Gm zIiVb!ygWP{GdQ}OIR$G*Gd2M5+8M9{$Tv`7UBR?~{or5~S)4(Cc`?Abcm=k`*PrdW z)00qVhG3w;c`$HoXa*72%3;_eNHCy0sNfcq6u>Jvg9-h?sef<=z~9bn0CaG5e+xg! zKiLy#kLpdCp`ppe&6p$8XhyINO|AgID<>(O26+r@0hl9??gg2_)yv9#ncbPS!I>Y* z1NynyfF~rZ0A}*Qzsz~npet*bXH$n(*ALzzbNejvh{mdA-{cca&rLHTV6MPkpFY}; z`w_X&(Fc~+fWR2QwYP;9{u=l*2i5$K%csM)ynyt8^IOJ20e*kK&+`|PduVbA;Pm{5 z{<`$#SUq(mB}v!%$$#VJrKTp44~FN4p$*Q@j)4L|Kmmb#1OoQ`n=7(6f0scYOfkXUEJSx zH2|~s7O-SQ>#%>^;+pE*8nR8L9dvWUhc=D>wyPg~W-u*C&E1LB*Ow|_gEL^@-}GCH zCfch!efV`U(VtUbKH7P|^pp@y4voJ(20K3g01OoClMpx`WMpAP|7uB|iknLCOz2l1G%vZ*U%w z>MwyHK>3w_0s(t~@)P_Kpo7(qU=M)YE&oL&dhQ>=0&@8#{_}|CFF5au(Lel=uaU>+ z6^`G?U*Dvhw7(!70J(?$1LdIE{|?=4|G{!4IDdk5WYiP=hsdc*`O9*#yu4Tb_e+hO ze3je(UPniMwcsyEepTlW_`{F5f%{!Pv>f*^WK&?!Un2i55BcoynLerP(Hi2it1h|Z!C?QF zgiE%+HhpmBt{LFgt$S2V*0gRGQY-W~K?e6H;LBDy?NZ7p@oewBpcj(0hgh@tDg8cI zvgj=RR_^&@endE#6g(+5Sj8gcW($eC?~SgnEATbq_JKF*8I;a0XyZy0WE~IqF)uba zRr=Vlc^iwn^;-(VJyrRpk&7`b(3JT(^sG}~GQW6WqcX4YAm8g~M&~DEY(C$oL{Y{> z^o={_l=8*1bqv@2Y1O+^D|@>&Jtpo3l@j#`_4gee48O9MMKp;s|8Yt6!sAo@=q}QA z9EC2Nm+anFb=Lagx04b0rvw2RlaidMP{?J*YJ8exoN0>$Wp8KMKB_to>Ky3ytj@+t zvMt^U4k*?q3!~t+Z~I&9o>zse2+TLlK^D7cMGQ-VU!Mcj$B!7;P2^wO%Y!b>WYl59 z=;H>Hp))qbwn|!6FSo%kSNR~ZgTH3B+jI7L#L!G;(VI%h*DqN#@Zn{tXxp;F{9H(N zDRCyF50$U8bHat5uDDen3>dX2i=#1J>NdOrHzV5a$P}1-+uN@!b}pkb3zJ#A$y$^d!weczyMl2yX)@ z>aGRvw?m_&pV3G~Ms9_W;w3Fpk7R?X=npX|}zgf@pENTVmcDOxyKaC69d#TdRP|^i6gSqj2{Sm}d>h|$P z55Fy248;o8{RQlif|f*Nj^}IxDX0XW1X+QZ?8)M2Ofy8hTKW==!Zco0h^QZjW|FBD zI+{gw-e;7;Y$CiE9niW!^sy?YyHQ$3&kjzUM_^g41iE>3@^Mnhk-g>3eh#PBqGVM% z%Z%YP5ixD!xZV5Ja$6w12nWg@1?EjRUAjvgjKu#+FV)ujJw3smm$gHqv zYFR`h`+*S6|2f`lmo%>_V}U>_^$(!nk@9MeMPII2_G>O%5GD1&ECdzTAg$djhjK4zLUW*$yLw<(H!1vt zZf6PD+D8U6sCWwyWInfz8Z&L?Yxdwas(fx*31-!C76$wa^L5i3O)YY01x4$!vWJ=m zT@$L|F}>eTY6acDDarJ^g2+u0kB-b*E#kddbPC7(dolT?%%<@>S-04MuAa?*LawmX ztL?njF|*}xsr*`EzJ_Zz7gzj_nApRI2cXv2qFHQ zn@$ng93_PEhsh{loXu`Bbg9eRGI^14&0lzfwnm7@8&A$Z9ZW7nl7eTli?pZ9nUgm# zv^eK=&I`Bm7~89T3Ph}gK8m$Gl5iIl~vsS5r0V5J@AHVFcmx)tQ|->>J#y+j;o z=_bFuUdz7~-W9rrAyFYvthLL3mbo0AbYuakq~ksDtf>UT3+ZN{kyhO5!OP+t zm-UwdxtBYaAGbvwM2vlG8)a3cEHVz4FcgcAUr@!&@U8Wh3?a+Bu!kj4TaX~^M$kkQ zll(iqqjnmJ=OXTJAO(zeU4)ND)W(l>S0nHg*B=+D^}o#HY9l@vUj+$ruSlv<)vAFE zC_khh^-fDOOW6sZ&T{QmyHD`29Flh#%n);X$UM)k-)_XTa9lb`Gwf$(@B-OUAeTdM-oQSGqA8%EXRFnF8k zbN@N0<5>=&aQ{BzY@FoI4w%(J3X*r&S8ovu?zrbYku|HiDvulAw#CJFHuCtW7f5eHxx)fqs9L^I~ zS>;Qv>vL!c7S2{ymis2-p52>VnX1;<`LgOw|D)P+=cHAvb>C@^UnZ8FTiU0p4YNB50p9S4GlaP z(-=27RMZ_TZCZwqM#ytrt}(3)QB*XEs{QJWkkRlaA!+2{M+-wKX)*e2X@U^kI&9I> z!Sj{w?GaG+3YY2g6JsXhq!om6 zxyTs7QS-c`!<8Amr-)*BEBiiX24B_#y<+c+5));uiA{Sh3RAo0LhK3t5ZF{7c5p-N z4ia)A<3DMPAm|6siY4~G?CFER!=BOxwDcWM!!1l`iFch~7m3BUsUN{)1%H$aYQQA~ zN?kg9%r+rZj~OOdim~W=i0BL5nicQJckbs}HXeEM=k2=TOvk9IR8I?;PGJ2xfV5?> z{CN(E*)o~dQ|f3Z!nKdI@jsdoa=iNoD(F181%8ERrSejdE4t9c_#LaGLtaqXT!QbJ z?r?kUoQTe}va3q+8$C)J_F=ZX7ajh`+*W0dghZeS5`b`r{6|65r$>Y|P<@JNel|*( zzSa$;V~TRr{KnuXrZ`9_M}`r~^D*=zx`M*Nc=lUySiK>$KI;#5ed zYdHpacAhDDVHkzn?nXB8bWVyTB*JUTu!au@<@J;cZK<2qW|jAAVT zW{a))bflMw&W0b-{Cc71=&|{ZtV3>3VZz8jDHUICmRv-=~2B9UU}dPJX8> z^rMU`6mCabz#9s8a{HwT+^_wO+_DoA-el+U65M`R19L9UygHfI+B_~@yl$?_jJDX<{2 zP@IJEt)koGtS(rHCANpfM0PEL)cuPKlfBAV$o_xYRO6Pz-EAn)kywQOY+<~4Zo#6) zyZ`V|G4}+|=O%lf`Ka;H9v^|oIC=yt;4^khp=Cld9S`FzGVmf0U4-o;UC$C5m& zv;X9N#43k~trlG^`4PJB%XIX^&Ts7NBO)>2zz`bTKnGu+f}SNMNTV**8FvL@srlyM zM)EHd`7I{Y=9!!aTDG$JbRH+2@JLvH7;N)qk%34fVXm0E5X1%&9%GoBW9i8;~h=3DgNiYmOAjozL{`;rOX zNU8>k1#r(%l>W2QH0R6kK0v&@9xPp3P0v)3 za1`)}CyDF4isOWn+4Z5YeN#QU8E`d?mc-R>d2(8J!=dUTKSy5(d6)>nf|4BeS*Fjs z@U&*w+U7c+tzb~ikjuegW%G|BE>9@tCi|O4W9jsMGLtWI@y=+jklSp5n3EuLJUI!) zTpA~5>%F;Dw%fP8dMuaK1x=aNqE1^mLi~XftvE*SW{DanKI6#tLAtxeW2M=m=6t+I zWJj~q5$qPVXS5w2X^RR*DXA5LnskDzWZ5Gs*!s5V^;sOX4jMp((ib$~`7DRhz32I| z+1+_tynz&suqN*tvR&$)z%{zTMX`lRdC5h5c7GBqBcEqR2r1uVP>r=rp{I=k|s zPSrDOgB$5;($v(Gob7XLX?LbeL(|2>B8P++8V0uH>PwDbAA`oj6Q+ftY(R0et2wrp zfLT(gvqG_?aJ(6{B56zAFj-^0@NPxW_qoBiqWL>sXy(9~2tRHhx)aj8b!qoEp!Ei|TKLsuC&%bP06R}@MSWd!^pn9&r-t0Q*PDEe` zd|Za%bUI5mX`gfH(8Qmj8fpj;`PMocv$(&&ngM-mb~Q0ir{LUS78gpASl>0A7eOlb`?!ZTau85zTP zdkgU-68q0|-_c50Bz4EB%&EP$3xwCEzEE*)eS-XolFG`Hx~) zH)UR80`7D${Xw4R<2-Wl2jBg4pM&0~M4jDMb6duUYSo&7GW^9&)!rZc_Pb_32jqtZ zuuHAK#+}Q|=|aO(Gy|%gWX3gdgyT)p-u^Tb)&Ms8&ZVbC$9}{enOoYjGfBqY%ql=G$9(i8#bP(zC+VYR2KNvEHJWxtGbG2L@UU zyFqro=_G9)ZNsDpj>S%Un_%hfkI*_4y(?$b*WQ+-BWLys%a*Rxj#{xx!;&9ulwCf0 zM(^_9b;}u7D3Pr(N35(oU$GLv_y{1VVuE{IF8As!nQZo>o}8`1vhjTI8OD{1!UxZT~bSmCVGTa>f zt9hyzOeSytAKhz2WZrPf@i-@14Ljy;%CpS~Kau^txH34G7|w_k+T-u_7*?SX=mWOT^Udj|y#`W$-G$k3rFfIPVq{r1NmkvEI%zujUX;EcTc^77u7T$9M;09`*W6phS&@aIQr~E%QFr4prb+ zfyT_QF0!jtD^k9^T?Mt|dcYzu`q_!N7Klaahm&u{$mO-yS{Vu&3FdJDhfjmvn?^{FnhqzQM7W^oC^vN)|I;;Z9y$4;TuOUzWkc?Jd%s4G7_ zqM2Q33!INlHcD=FZP}>2kH{U7XuO%Idu{R9L{(n79ySU%jC6?1l>7Gvxm+9b*WBvQ zTCGT9_#=iPd(ue`_&vcl3DJ3n5y~^kl}+2t&luHjjEekv z2=?ysY=GAB7$4$~el+=JhwKxO9m}k}AejQxC->R-)NR zAZb~yES4-aO2R~ZkeD9*qTUsKOEYG>hFBCnC!k?0Dq57Zc4&lds0UG?*V9LDb@CcP z89hdvhHBXanU=FbQ#>|qYycuZR=Mv&l@{n{!K~qQr~jcQ!)BI`)8~dxe}?GoNK9ew zc%zQxKTRS2IA0ZnMwOscpK}jfZow=m(m>I|Zfs_)0C$@~T4L;rX%$3R;hko$zjK`r;>7*naYbXOKHsPbS0U#;20)CROR^cd`xkea{_hgG zcH@sWdJn4z-IYZ+o91$7VyjOo#j=~Z*Bzrg-Ji;j8kHd*cV}#m+?PK_9rP1CVkfL? zpNP)W8Kp*D_ETT?G;~aR^Jvr{*k06&<@73rb18>fK4~p{GWiD&EV@OWFGDSnn>0di zC}Dj+%<`Ep>Fqpo_3Lni=AG_o$`(pPaMNp^nip@*;IK{BVnbNUO0DpgHnOyui1pB4 z#2ZTK>yG)=J*S6X9Jc1x?b|*7C^Y^Fg({nY1ZRgK8x}Ms7J83XcxuXn(iW+4 z7h{sJK1#BDJA9{&&0MO@&lKP%htE(BvzFebsD{JezD&9H0p^fLn|_TMiSM=*VmYF@ zNYL5eczGues@A#E`&4`MV*HjiBeOmW?zB)rj~qjr6D>df%iC0W z=K=2a{0+7Jy#*n0Y~c4ItLmNXH!Owu*R4+#aFe}0NpD^}Y6Z%0`B5ttWyJ>~<9^SE zvGEjX_NHE;u1YdNBo3qA5-(36&=S!Cy_3DafRES6;(mc@CzHd42O~AP&BG`rYU2Eq zn%7A>rmtq1QnMxURm5Xfb98;mA)9Z4O#LR|6N4h9h=e{EYJy{CYDWT>WxSbW=bY|G z?aquUDtdCCnK52fWag>YI{bIDA(kA1f4g$A=Ct2@|4NwaeQFFiI#~*<#;o)v0nF*h z>UzyY%Pm>r?uk&gjG7p7UZoUzJsdjrObEHqaLUY8DV?jD58!q&Hyx3#ZB8_^Ax>x} z%IQ`DL&J+{R7IjY_EJLa0wiFed`Wo03q^dYFizQX4`wR@^Qb1;^}TSS7 znPdgRIbAYJx~WJrkSPqj)F*JyWD{*$Q<2iMlt68qlzE6y(Ty2Vn*C(Tcf9JK^1V3E z7DLm2tF#TlNkJlI+JDaq4E>+Ex6uwJ(V)n(Efru^l~(E1q~hx*?v3YNjkwQ-anjAb zyd{>077$HP2tv;=jHZ+MgBWebv>LU0E+<^9>BT=-mCG~cI&BZGFMvPzBxERvWYp&T z8NKyep!K?%x9~<$XYiyl|9vIOQ_n(hM`SKkrs5En(p8rDDX2{-cC60lBdQwBW&RTN znHoWf#_bX7v;2f^P-+E@4ecfC5QI;ON?VgEoKLS4P$*jsq0{%~^ybBg$plgl1`{S} zHQTP|5N4^JBnj#(bWcqyTEP- ze*}ZzX~Hnce94Xqb7>OI9oJir+c=z2RIEr7%XQHEK3WP8jC_^ChGIqnv+n+KzBiDr z8;6$$zl`|2t%OzzbY={{|EUsb0+OczRq~<@mtl7Fj1y@Nk*0F|PBx>x4U1~X)AZF9 zoGafPE!?Km%w2_izF@SQQMsn6Z`~nx=1A=rf|ddgHRS`G_EOI&j*i0R6^_ryw_!w>_kOgFQQByqt86E0GN={Z>t! z!Xo&X{n@2=+LM>T)}LlOlsr-`L$4I#sT9ThyxUCDH;0Lvq}rdKEDw8EXy|Qkv=S}U zzSF{^S+HcYs**t01Fj^-D@y&x&9jBm1a#Ecopd-*;-oM&i~n~0GkSe$ehh9Ua;>S55iA2Ac_95)9xjcUoI z@7({c2uF|r%Uf=jWK^?13M$@SQ;xgo!Xn_zS+|m|!VN=eVWyt}E1&scb^sB7tm%kH z=#N^SX+CU_*XI#Aw@WsSpn>>jm_g%>!xNL7S0ki&xc{C&@aBB;u$yYAXQ?Krg9&T1 zQX$y(JxAo}`BH@fHrP;g;SOQ;WhG8BJM10F{e;MOzLHx`LnmizHeb{5PoI;wjmC2X zt?y|91b>%DTQw5m;!Cs`!KmdD(ce>~4!j2fCC=dFonywQ(ctdOG;wpB$oySE#4v?3 zGeeQH3lcQ)nt8Cvr)l`*nK}O{iAtRBRg`N>6U|Vuo~Ew*3uns`}M?eio3q z#H4zkT9DuVStAXQ-V_nU`QWCb(R9mNTZ)d}H3fsTRn=21hUE!-we_Xizcup^tiOzD z$x2oS9*+bWO4@Fhzun!0=KwyCs8bFhV*fu2e}bX^>Ma_3Xb~wkm8#675RvYdl4G$s z=@4>8W`}`w3L+&xmLKbB6!y5{NaG2ry+cW?3IA-EsY2&f@;XgwJ>#;q&+XW5Kw|LRdr8KRw6rroEo;AB6zjiwaFJb82&}|}oG?M*}>5fN# zY-r^#J54{R47TKG!Zlhd@g!-L(Z-s#<7IpHf6;P67Y8Rb+^S<@$>JM*#5J?k1OQfo zVMko``@Pl|m^tCFjlz^{adGDzl>6lH!nQ9|ht2T>)XAy$# zrVPKHblZ)))I3kDvZ+0)~_ zl_)@0@z1E@=R0GK$z1gFV!IPhov|)InG3oozX>rgBhmt)mp$3=6|%NXN#wfOUo7A} zd?0Jkj&jLF4g;Ywwkl{DofSNBIs}|5o9GA`KInjF=c+O~=(94ccf!{?BG!ZzSS~fu zHpR(D%M-Z#drQEXV|~~KW}*qn=zocvzR(Q&R>pQ;{C4rht)Ccl5$LImTP?pn`@KW> z=xxJgG~Kj}i`_W6sQc^cb}?66mBJZ}p3iduz3KI$8sn*6xo2>&OkU0A=hu3^cHHd`Qd~z1$H)Qq{YD&Cw{|eYE ze*|z5G0$WF1ey+|059!>nagTQYJCNeG(UjN= z_nWbR1a+8XI$UWPL&r8Msn*Y4aVfqoRO+asE;vhcxuax-;ju8Yn`t{8HEDAV?I*T= zT(vLc-9z=>^3Z?SzwOgWL~w+&bsntpZN1UVI^?eDl+WNxqY(v3 zK_Skongo;6RzMylxj;ORWKb0mh871Ryy^YgHa?V#Un`I8?#GO-GJK z!Qb_BXbX$Y?~O_Hb6KM=SmZcrHN=2yr9yo?HJwisK-4&lal&bkH{bj!>kRZ9i?M&+< zXZrGNWO1#X;i1iGYezfS<;RKa^+vD#Ueqd`v!CL4uOo!M53N1yJUkfRPqJm(KqHlk zw=trTmZt9s`e!|b^xdhsZ(UQS^_{v$>kM%u4N#GKQZ<{aYRyNCcs3{mK)qjGe?p;< zSdBTP$#o{z+Z_;=WjD}(zn&%9Zh2!8UdjuS0;8?l7Nxcv724zTqj*4kqF7(FxQhC{F3;T; z+hTln`Ny0m8B};ORxXRy(>%XgpGR@?BlXh{-tFNR))+sb&&ZyIU5z`f=-j< zJVBegv-4THM$?-1CCF#O=Xla_Ib*i}^ibdPe8vW@N|z?!&T!Yk|QOAqAgu{oD<76r)84~Y zID~$@^0T)~BdB6<>Dxln5P^?cp5OPI`2i$+RItxJa`gUS=)#)=SgB8Ny;+rkg1w7h z!+mD*=`{MCs)!ciDmaUl1$xWP)|`wSBY594499jUsEpXAFumvm+#!2!{ugCtha-g> z6?KLx%ik1Lc!8U2(OFv{qclEa`HG;$qoqfW4BCCaJ#mb*;5`d4sHZ)Unp}lwbhLoD5 zJ-WqR2qSOu<|93%9mSy_X#UyNbN_(!TU~ge7@c);7Dz;N3bp2~Cn%DS(5SR`>y;*_ zPU5nx_R^@Tv;K4K_u{hDEBO;d?<8}6Cd$tw+JA`PPL@S+>3d}F{QBpMqshte1H({A zS(Kc;B?}_QOy>-NMqnxu4?(QBz}pL+l^5MqIyb(^0c$azx*tYUOYdY_$E|x2fc;zf zkwTl_gpQ4M0iXtjB0-unht1e=&pJHj=RH6!!|xrMIj!xs=4%=UMaefA_gGCRB&N9Q zj}@cO=0xbVHo3QHRbmxY7t2pbyACm&P?6eN*L)qi&OWpJQu)YmzcL9|Ih z_F-s6l~nHgHttfr{bq>fx@|E#uNaj~T_^7BchNHY!@zW<4oGLLdo3`Sao)i&Hk|`< z!GUapBt^Ngh+A<|Ds&bju|cuvB3|51Q##gicbql+&8xDRG0fv6jSEN4tq;@rxRlu> zZ`c=17O9pG_kaldh%EeLb>ojlPeXs7k$oUu#$QdvBp@>HZ|YO>FJnDd!Il1lq|fis z?&QQks_LH$qM@t7!(5CKf338l?l(1=G~wHxR*}ewfAOA>-U1@+#*x2`r31L2z}{D#1WbBxF1@ z*3JBXli@X{6rF~@lRe{v&KZtRbL(&Qtn7VwJ)n)1a7{QlMH*yK(Kut*3VC*}ZDaIm zp*>xraVF>5szc?QH0mg`QQMKkr8%(S&P3I$D!7CSs~jZcz%hD)Nan&wA*rntP)l8@ zz?$<`0c2IJ?wBy644c8sfP)n2C+C=U(en7oP*QtrB= z4`=_8+|rM;Z@j3?b4w(k>NN1<$s9Dk{zQGwO`Zh{d@_GM?wwU~k&d3)ubB62cB3I! zeLmcuz$tRB1YF^Srz(gN$*2A7+Ne9W}|T>Hn<9tr>XX$M)}1iWY!^AuUu(4zWov*%@D%2qx{ zx(Tm`8z6*ir5L3(M6h{3KQDdeh43*E;$*H(1pU_RG8`t^K)J7_=Ln>W@gthOVHe!f zEEz+nii0^+)$eLo+duPc`ckXBhodpP9~?*qIf1&$=_)(??iQKvl>-q)+tBi?%Adps z$h}7-a+yUbVmoJV5CI7q3~@bctmSbkQzEOi=qNcL?{tr)M?Z%XEUIt#y60oTo3P-+ z_nMv&x+C)A^QIL{Yc()u2CXc+TW>YRyS*5;mSRwnhHqCn?1-V^-9gH6T0M7ZoGaP8 zv;c`BVwFUgD39mBmcRYXMV^2~bUCLnD+iTNIJCzu=`9a&yhXu!_HU8uKLrK_{efo= zr(O6@WCh26A}g5KSpOTPU?gB=VElia#s35=*yveV{x4TS@V@{nTtJnSY+q?5pd=*8 z?a7NVB|17g9WlT#Fig(kZcsqZ;gS)GxQYZ6IEx1PI~0E~c3;1Jce^dOJ7+W;XLdf< zKes=m})krN`ynOcES6a|(dPi>4GyQKSi14SW_`YH1J#Xh@o66nJ_2MF{*@Pl3%05|t) zBLam0YluO>TpYZ|B1H|b($c~O;NaZc++68-nz|GvHj^V$?ZG+L12X5&$dR#?k=$A8 z@uOP7e=}inu>$8=13Ug4t_o_jw*_YB^;HAI1@a@#v|`pkNR}bnb+YFb=fRY5@FV*6 zP51&-_3d^8vafUeYTwwt)C$rM-5Sw@1T?t<5OM26SoT4Ig#uYLOkC08(N+Oq=)Xfl zgm4krKK9$_Vc=NVL%(fvV8kWQ0ra&3|KQGI9)LL7*_*hA^!rAS-B(Us(@qjl7stK4 z$OT0*z102`>C4ECUAK5Td~v9Afh^$eKd;sW{GqP)fz?01=*tiEw;njf?1MjemF zJWA0?5d+zJCa;K~Oql@!<8)Brrf48eYvU~qa1k)1Q&+`jp!*O}xFzJhWR1Jmj3%eZnGhYR@ zgmhx@yDJZhepd}gjIeU&YfChxj&=grtQ6YLZ}k&*9IJbpI<`j-qJ(=6^XXg(V3kEM z=R0hZ3|imW&5>n``OXE>jXJ}Znk2vL0`I#b^Gr>L%eXv@RYZQbHRm5S($s1coYZPDe(+F^O3D_{>~R~zB&j;EvG3fV}eAHDzJ%V#Kb6O z=!|;)H*kNRS$+C}a6YXSEPGi&HJ--g;c~=d)Tl3q6t(7ce_Ej%uEtVAWNJIF+-o)B z2d)$l1w(J(1_;hyZ}Lvl(O)htpc6gi`4^SlK53*|(Jj|lYRw_Y7A?5&28JUP&OuL? zOD&+48h}5H^0cej?TUDeNV?>@j^!Rjw$C(1{(j^4ORIa0m{aY-V}c6EwO}+Vcry#P zA}A@=IKqQ>nfZz0va-#P_z~#0$3hRc@Wgmi8(FYmqo!n>O{aEL@IZ`&@C}-tTx6Cn zjAz%M&H;+u*!?cXsfpTs@a|8sO<&uI1=*B3#mAfEWmB}9J;Kt0yYV?!%#kk&%&|(uWI6HjZrYew90TqWp z#-E&DgBWkG5UtCl3A4Hhq9AnF%nvd{SA~LH)}zS{z5L@N>~2(2d&`XIaZeVADIzhI zG%;<`PEyx*_P!v9NorX_*D)Y2eEneHRM90IqjO3)ZQzNnmCLtV+@EFsXHjbCKb5TQQ3tnWfSXw!P)aHMw2fTcYi-yQO({DyJo<&q~!x#umTs|DCxC1jO zRCHZZF)V*$(EE3ZtJ~Nu%@`Dq$=LPyAm%L8ej8U{1QKsQ5w^BJqLu7k93%cjj$j)|Py5$KK z%O~oFS}>%n&C$!+6mLH$2h=zBCPe=DuE$RB4h=cv3%z}N;~5AREXa-ykJif*@;ze9 zG-zQzg$gsrha#VVrs<+H?Ox`{@_HD`$PWGa=voP|Wxf0;zg7ixfLVd?SOa^&o;^O( z5T*LudLvl1B(?8e_$sa7yj>B*2>Kv`KRpmq<0oX48lIB67;hALUm?7+IH9NpO&WaE zc|Cy%bW3n+3)u-Gdt^z16cgPK&~_-HD*VW}rJ~ZoY9;V4wo0~YLHAO`W*X6<-Av?s znv|))Pp^FG%A!f-r-CHVTR(V89UJZLxuu#vL<<_2=P5|gf-g!)Pjl#-GkY$3e6@my zu8W7{bYvP>N{oB1US&D`NTSKY`Bxf`*NpA2jG&p)~fNwai{Kzx1>il7-OGCf~{_?UI%+BC>ZYD8BKc@Rj%qtj~6lYRU! zwL`L#>4UT!oOZZjXWk}qg)l2ai+yCcPDQX89m2nLDO9)FQNJI zQV|y_-yZ2err*d+nNFVBofnjn1fK*e+p>%cX^T@CM5)!_@zh%R@b2uhB7OfB(<+yH z$7n>EH)}3{T04Md9!iR+v#FLS!2=fNjf2R$3i6IYb5|UDs_>RvjlrhWDFoet1i#%b z+U%&}q|$a2HaGGO_JPu)P|1OZ4MH-LGLsp)mj$^WQ__!bT=dZGZZc9#SRnfGcRY6I zbMZ;Br6hm-09QTpfW&-ua0v??9RE33Z6O2W<_rFF}y7|!yU?` z7A;PiwK7EyA*rjOW+oGjqF)cDp=VS$mRu?|sYm9pBfkq1Gxyr_ZA1aRTS`fWf59;#K!uibQbbZHk(LEDRnQPQ>!k z>ev~D=$Es>)NZ^nrl8?ZWUY51K3E?mE!4vCWuj zGl`WGWJ~Y6j-GJ`q!a846+%;Sl4FALb3OC=OW*o_d=eidn_z;WiZ!g7n5KLVMYUos zKN`wbjjxA_VHm}j7S;1bn}Lr1reW#$GuY{SY#qU_WRA9W(M z%VnC|^tAz4H0b_N1NO#OGWc+nOy!r?%;cN&5IYZW^Tb%RJcUARlr3yXbQACEdr<%h z@fTZuNp8$wPkJh9&q}pYi?QbIK21XNfX5HP{&693C2-E-)+lRKX@=Dm>QzS57|FhLe5YLgm=&x#y)CV`VN7I|H{ zv|<;0X@tMlnT6Bm6Ho&Ny!14o9YUZ=7HBkCGGb~z>g&j5*yi#}T9qZKBuZ!sAKt6_ z?{RF|o}EQJ42=(Y7Y@W8EjhVa(MV=iQor*_C|Y4u*7j{&?%3BtkyfsfzLuXnkmT+h zH~6S-X;-NK3vjwhc`S)-JL7a?Q?qg~@YFl3LUXhTHh&;X*6Hu?UX6FBC&kIuWZvS> zv8RO_Hw$e&eXHNXzHf;1p*fcAK0)=u<`No^6ywmZuine>ASF}74(zTZKsx9`p}a@Q z*m^dWH9n#oy)XJ|V|6p3{{RiHaIXd>fT->Yb)tFJoul|H$GDu1$f39hF3gru4zN3o z@(etaVX`PijfBOn zP`RRv^&F}T`|>T}A8UBe?vu+|s&;F&gL+Syo$K^dmjFWkqpoh@eLUJWd~`1b*eTA$ zSPJb>ge0m;^wpPNeEm2qde9)Ns9dcMc!54REUnp0I3;oTH#7zKxQm@T2;AT5CY8VK=(* zptqt73gp^73v`1=bI%3(3(24UG>}w53^RTZa24e`0dUE|79!4wakQmmT z4}i%cY(}g4lASb{F}l}_M1`VO9Ak2vJzj5&($R^PEg@J-#z$9pPS>C6gy zMpS*~ylYX6n9B=^oV2Qbq8@iNgnWqGH&>5;ICDUxE>yrZR7pgnf}&LcP=48?#{~b( zda;*cQfY|W^gh|vqgL2#WUKd@;1d9Tl*MY ze%Y9=nS3(@He`fMN>V#W17{^B&4y)IFh@+SPS&8TU|evIWI$3ny~FfWI_-8A*4_Nb zZEnI%rBYuodo5uknrwJ3nFJa3fD|TVMREz;)Z7b$$(t*pz6{X~FL1q#Z{1=Jwi!(u zG#~)Q^6`+8Mb;eI3d5|4B8sxCF!*-8_q2$ITK9^{ICI+~huYXDfAq^-f_r{^ID#f& z!^IboD%LGNZmgcPi7TznI_&U77N+rwUAxdU$EP_HKh?=8g=bl;Xc=xKvYOHzs^X0} zipU5_N>cBDM}HcT5o8z%8KP#@_J-MXrYHfpCdpSL0(&T4C=f$e*hr?=?$hSD5`&H_ z-3~=;_9r5OdXIoe@a}`RGlf$3KK>G6r z`N4BJ-S)jDV}7m8bhCFK22lRgpszI>P0nzEN5i=_-{JYA0TwX--cyHPdu%Q0r0b-3 z%&3B=b<}S>SfmZhs2CW=Yx|*H7S&PyU&JD&@RFnIJ zHnykKPZ^|?AFIQ9BDQd8E86|E{kL>brJi5`DrJo$I)UWSlut9vX8;lrx>%B|I6NyA zrN4~*W4)2nQqY43mvk+bb~LuFEX74i?c3kJI6+p4JHNiz%%3moWk-q2yX(ZKw0gOp z?5qIr+g@N&aR%3zvk!!%mKHaMKwfLyg%OV-DVbyCH<@vc=ruv9=NXa8!yH_lc=1wW zWZH@dwi_UL03PXO8Ao|fvIg?p4g3+i4CB!zQ**|Y)X_QBTgNB6TXh_L@`4#WBTiVUMuqNAR%Y<#5=N))Cb3^OZJ_Z$?JCt?u;1ghFsk)y3r68LM zqpi_Ri;z+9XmkiTWvXvn3#4}>`}Hg5;_O-o{nPCU?(&SCHJYd9z4pvSkBk%9%luxz z{mm{pe3(8_{XO*w_6|?<{Gk~nD~Fmw%E0VH;*n|5ROp?qXndx){1PWgCy}(*G(<${ zl9`ZY;&uYf0Iovc=GKStpwm;|(A$*d*rHb9(qGk2TybCmA-|npw|WS%x#8{5)#+-m zUsG*wdZY^mLb^X2-mKj-@4!672>ypXVG4yZbgrGniAI=Ev;p`Nr28QW#=c`d zy)8H7&+KwINksjeU?ZD{ltm?=Kis@WT1sIW6YT}*b+qbnEG}y|4qAr?CU=ygXQ6oo zddXU%(7qvzYW_e5DX0qb!@=fE1QC8nQHKn#Tx-F7*ZbFFvgJ+tRM2Jp0QvIN(w2}# z@m%g&Xa45k{jHr~rWjZNm(HLY{t!L|e1{j_p&Ze>k~M#rL*h&DWTRXtxFz5oo0RL- z3Ch=ZD`PxZb=DB!UL*<1Z8Ks^)S{|7_F1N__A$wWEUR&`DWQEz;uMuqxvKn{p>5HI z!p%%BM#v7bG_!JtYtvS7a&eLbc@*R@bvhR;rAKE4r}TRM0!amWvHoqyt`>cbs{lGm z8d)fY1Q|}wvhTG*NpSj+#!tN!V?E|ABt~lY#FA3a;IpZ)h9wKpw2L<$ z+$2F}YJY~rB8&Z7f?Wq}|-?WE7?b0tT5-NVWGD49b%e28-z z;Cg9)Ki`+IdnNCX9fqHP75;4x9fbZw7qd&ZBjOvy)ns~U_U?`PZGWOw@j>`E02$4e zSxyZGO;!BI;lIekB9!yZpV0<@^-*BQ`k)Fz(^HqE9h#BtC6xe89LZ%S3R3D(l0rqD zS}>B8+j8QAdbqfROOmM8`Gx#4SiS5zMEj(4FF2Tzli4~=O1Ic>mdg)2fF4=$(lx+k zZi0Q|UDBABYn<8{oTGgo!a2pdY7kA-53H^ieHE634|bed@T?{%^zkXB`pQm8DtXDH zXA@m^pLeU574N1) z;uz5wFTw-^{iNce;)*aD!H}l`^b(Lxl5GZxplVM}p1=s!Q1W8jFZA))65SCH64qu$ zGG7?Be{;#<1eVR^4S@U1_p2i%V(b&Rzq8P}6J52L&(my;l3+}Cu`Huue5~T<9HN~F zmaOt5mx_Fqgm;N)!>DKSERtux@tP9kj~5Bn#3mSnEGY!c!`Vpi?2!H{iQP5oG-Zg1Hg{8Yn0kl8#S$k`RrU2r!+Cj=yX|g8eHv%b!|+^Y2#668kK)stb`@xZ>6uzkrWqT~hyHA;`|~pB91~^c??xA;`eQ z#=!R9pZ{|s$iU3b!Ti5ft+j&6;jE$2L|EFrf+1~fZ*SA|o9EfPrtaZwX$OM4x(0ND zxx&K5rnkS&Y<>DJdoC+Ksc+6~oK|^vy#1{xlAyCPumnk}Yql>iHPJf&44bI515Qg* z!~Ay;c)b;XIn)7v8wkA?065tLtgPLB_R*aIusFLnhhVaI29K<*0T^dg08CT>n84wg z$l#HY{er{8KX?6G;J5)8gwW$4`EvjX3@w43{=N}gSf1VhFfzG%>>lq*0wgoA_@!rN zCf>|C`PH$^0UBAE0mrd9F@kIK-kMpNfyyXT15fwBlAz=9KEHgFRv_(FV6u&xUs4E zNBOhH+(OQb3U*odNuEVgWD#Kl)C5Q+>t?5@hlv!bV41 zS6{VV zA^!04*0rB6XZkOF@8j!BQ)4r5T2Cv$6IeRXZZ85iF08g602#PxUh63z?r$_gS~?&p zfgzb6;v9@o;GOHUE7RN)-IvcJ906OOX^HDT!#@+++m~taXAR9impaw!KN(k-mIy8? zsxu4j1|RlMtmNOJ71%xT*$LP@Q+-n)dZu~@0QOz5e}cxFHj&EHzpjqy8g zupsNHsvpNN0#V2~?76>?M@CjZsY*W$mA?#nDg@Yh3DrbrvEZQmvr|J)d_Aw_j4fWi z%s9KxZ>7+0yv)Dd#ck2`)#Lb!!viyb^iFp4PNHtT2d+bKcSb(=LdbcWxlmyAjB9J0 z-K79Kn~z{=8=M4R_PID$03!Q*Qoes=01D515y+7Jo(eEHD; z3eWlWxS$(-`(7PRe*JE}1AhQ_&DDQ^dmbA;z`e*!zS)d?O7$P%-(&_~Y&UM}Z*RZ& zwr-oQeq4G_H@f*+SXKBHOM9!Qej9#RsD2q7yE1plhFt5TplS?a#r}mR zgL5OG{Y@g{Ow}ayaNxeB1&_Uukhk@5^jw8s%GkUaQTK-Isn@Wl)>e}XkrSsQZ8m#3 zydycdi`0PGrFfzk^KV|zpnx~hZJAr7sqMQyv9|iIecVk6r#^JrVE#e=JVy63+?eYS z&3I}zu9tNdzGpT^wpPogD%%r3HZ)J@mixCJ&EvwV;V<8mdzEroJ-f@k_t0WL zNkEq{erCZP3Wr!izxo|Dg%+-wljR8&@wiBVq)xG@F}t34El~O2HRhL5hYCf;^)xLxQuoZc_BuuPvKZ9be?>=`pI6r`3nHdf zn4N7BS$wH@KdUYhCKB3VpW$djq&e7g$EMIkpd_N`9C7%@j1Ja9{UQ0$v?9)qWzz{2 zAL^ZkFo&;)kSlyb@B3zgko2rtw$_-ecJXfHK4eVn*AMY~BQBfHzcIbjaj4!Kw{^B^ zcq4cTug;C}Lgw;Wug;N9Y!~)V$VPL`kcnq_E1~70^0glLk>t@dX4~A^w31?(pUHHB zWh-@Q%9*e$hw)^=Liy?yP$7(3bWloIh2nOW`_w@GH*Qzs~W4YteD|yN@qq5}fpJxR) zkpP>E!6w*lmcT9**(+a7Ncp)T&yNJboj(9EbJ+qQS~VLLTWT9LOn2iAxI0t5s4i}h z7LeitUfALJdRA_AO30zc`I3*JeZ=vD^9kbyVFEX3qh$gg-;!WiLg^|A9<%i3RCVaD zd1}Y!lU7p$sbJ8H|N2ej+hL^3pv{=iZM0k*80Q7$l>6qYA!d2Wil*bDz{z$v7E&G2ee8KUgKq__8u4Mmj0s} z1#ec{RlhD)dWHK{4p2XdXh)c77z52iH)iKU1H^};=L$G6Wa^`pJ5T&v#kY#V$FawZ zxCs2z#_lDC4rJsz&LuRbDbw8UOAN)jL6*5GFK_D2F{CpfmLA)EW3LNae3yWHIm0!5 znqy@S1ASt8pUeCdD=TXZe7>ed&6M#7fmutvzR-+BX|t%D^$;AMSCXZ2hFqX4ibi{( zw0S8Q)qmvVS+_QDNInu)z(ip8!8Cy84HP2X(yLco(~&O$i~C&esN%Fhzudx!jvNB3No-k`tJ)5@z5x=7=j z0WYdm6Y>|t-=Zl5-D(X=l!{e_^tYjCRI=Xc(5j?fy&=UHe*88~T2Z<0zIcW07J|Eu zG7{lr(~!HEM#(R&?xJ!G+QIMoaj%&xMG{I(I#wZZsu zf>y!%;n;w!@SKawC3v=$nerxPe3uvR5rZLT1ro4HF<8_HKcAjkS~7*zOM#urRP1IC zf3F3Ev8+?F9Ibzpch7+GbuiTV+#Z2NGD3<~F7hD51V$~`Ii2PHcZv@r(yRRPv6|dU z0HcX$6k!&UH^#;+T)g2M1gM*|rP3a8;JIziyWs9fjX051(E&}a^@Cp9DDlQS$2qN= z=dF_Z7s93g9pa`Bh|_hM2U=J{mX3gmM`bRSIzqCokxNHB=C7l?pFoTidG^dCtrYZwUU^2_dI)?-vl|0QOvB5wI{3v&9<&M!sLsCOou7Bk#5N zE(5K>m7C(cC0vxpx&D2bT=za>@u2|zZ$9WF_;Hnlhsy2JkXM2-3y74msfV@} zc?Pr-uxtl@j}jIvpXRHh7;D5?iuMJUXP}svx#_91Q>0Cq%y^TPAU{uT1yC=lCA<#R zU1U33Bi7hH`(RMx0UdKJFJ0?S$gL_S-9sHXOeNq~>*)-6nFqpXSraCPy^S*`OBW%b z8Aos_P}ll|9`+YP4l7(HpOs2yD~n;3R3opP9NmwBF0rCgtK=hAOU-0*xp%3rRn?cY z({NC%rY(}rEBMN!1@#r@4CiXr>(lx?w$i({K&Q7rVxxoGi_=j8aAEM)k+CLmx83uH z>%VMFIP+)t=7neUi%*5npeFr;1MRCctQRjUg@tp0&iSZY4cO$zd|Hova;YZWPUb(6 zp+@-=!|uQ=NNyuQQ63jsJcCRv4yV}n5=y|8#;;pRD1`^uyI3YkDmw>fo79v0Lw?aX zgR=X-2w5k`6=5*=d&6cr!(hZqDd_sQHOfDGO<8n-rExyZSO{A`xDz@_37x{vr8Vms zZ@Z~f>pE|vIh6wDI4I&T@_ z!u_%s5fTq!i!qcN3t!%{Sj+}FD-o2{+NF^s!0B}z9CgY~OuRS}@^+cQp#3M1+|&%Q z{$Zgkl?k53px_CCAD1B!Y7jjy#5!h=9kU>5>jr$(sI5!f&4Ow{`T;MQPSCxUycDW0 zZI`YNd*dhc@MqBa;_g^&@3(~`ZQ80tXPL_x-sh<{PEcG#; z##$3OgP!JiPZIif){K`ctuO=Se%_F@!(UX+c0^-Fu@C2`2K?#jb@dum>MlT{OT$jR zf2TN!tTI5k0<+aKI{XYgA#CFOm$i{cx=tfsR|)E1#b!cDM~-CHVYxGFF*|S`?0X3$ zpnerHR;zD6?fIKT(h7kUfa7?)eede3NolM#-WDrW4!zt_wL2b5aE4+W(bnbFGBZXv zOE#Nv3g(GwX+2%`p|K6uBFr`=)7v~y=T3zPj3`fTRlQ-Cejs{7-Wi9*_ih2rEo0V1 zxt8+=Pb&hltp@wAWKrGd{;?xlwCBaUR~-LbUwFMZM4d3X%ca6vn>l%Y7`h~&6IcIU zs~C)fUeum}G~LMT72cc)I`h7qkJ<~HiBHM*x##_OZV8}Vl+IQho3|d!Ul)Bd;qJgD12JSa~-n0o$i01$h}+5hvBk_r zWbpJrjBU~UJVJ?a-cp*aS!S>pZD| zG7;axy=Mc_H^0LrZmBFj1nXUYh7(UsD|jHQ48JWX(=!%GZ*UN#GotWCm#*cE{{K#P_C79TM)FGSI zT?d)j$=mH8f|g1xRwOnxoda1gcvjm;w5*u0kyrmZPeeOwYz-ZT8ML2yfR}KT43XKO zBT2H>kv}LzRqr?ERAC@c(eHu)=DiN{`bWj0*DNgn6wVc!r%_+eEG`kc+O>am$AaTv zBc~1i6OtNL=qKQ#3FIm(HhPNGA>SojLp+DTV(_kPo?b zdv;p-`4SJiap;D=&Nw#q5HKf9uOuS96=*Ibxhs`yrEOiU*k#D7zvUGD*3K);g&8l0 z`Z?vt1sw?bFK0F3`y$eMvG2M;`(;DsvXMEKS47}KgRah# zZX3SH-1^o{N&AfO;nX`8gB@GFzan3E4ydIZgdyC(3%E;#igbFd*&&#KV?0@k>3vcv z!!lMa0cRuT$`yWBQpxKty%b4@om5~G$Lj!9y|nm!isd=SaJg%9ITMbWzA~0m;kals zU~(4(sEhO|NhjwO`k}R`GYY?L%Y!neh75G*U=G_nTRc9t#}}Gh;o8<9{z4t}FFRpn zZM;mQvcJzCVJB?=Xz61^MI-zqHQ)pZcN7II57N6szCxga9 zuy#MvmsI}GfPL`a)9hl}K6j+d#0!4^>2%J3UZc4f=K}N}e&o>NLK_iwp4#Z>RF^OGrH#qe-ViD8;0S zx!xz9WsJIzo4^JDdDG{TgtpC;7#v%O$*ttQHdPy?Bb;zsxENTP`^LqG*i@S`D zE|7>So&OsT)Fl}po36e~JJir?<0ngOIXri7{$$~|8|^OCT8YB#85eVnITDE9N%C)w_$lOZoIAtl z2E0sC;hSUgMXqgiOz(10*l~kJa#Il~-@^M;(!v^QJ6y&$WcGiOe_U2I{+mNWadM{Q zrrDn%`7|r8F3ZwRIGv0>kK7jBv|*k*RsB%OCdb)Ek*u2?_C=NN?XB1$nd{jb-3}H7 zS8w{Y(~L=H#A>?9taCg-+&vxSZwh^m@p}P(s}K}ZP#bb{=70kgnAu;LlW1qclIl>@ zCzLd0+$K(kdF_1hLeHIo`a4AXz))tM_FSh?t<0=% zBfHF!SER7~2O89U@3BPJbgQysazYU2E+8(mwP^5yX~jYC{ zEI3-<$)j~8>Y5xF^^s^<1Y><{yYAV_4rYm*ec4L5RsuS@R zeh{*Fu_=_kU~aQ#8N1V};67XSs5{@_WS54C*hWiY_-+@4j_P$}wy#%#hu*X~gV;G9ZMHrZt9jaMt>c+@XjG zs%9u%Zw97rk$WXEPzCxl#XD}@qtvhB%{TW+e(8Ty&@^1x;o$mUIeCI!^x<}!)HW+d z2T|OjRaZ{ep9(fxT8TLPa;QljLH zqPrvbmz-)5$0|q=H^Xf1Zzy`Al9+n{^g*N;UekxGkhct!#{@I$8Ye^uL|tjR7?M4X z5$1sm4ykb_e=u6PVP85EzP%qqx93Xnc7vVCX+Vc6K#cTVl9?BM&fW)3WJN;g2JzvI zv_bn&ull6$D>EC5_0vjW3LtiTIlI>r8z!V3Ob}+*)=Lebm#cNT29O;#jMzn?xuOsM z*qIV^qw!y$84~+D9#ngwn!n@3ybVJkVOuk~Rr5?(0AsEN3#)4kTWCQuBnJ=D`-Rck ziZ*|Win>xQs*k1-%%5o3V2w@>3Fmgd`8InBL*9E#-&Cm?KR50i$G z;YxGs*bT>ApP^gzygDMJ3mCj>T$DMotkYptg22aR^0iE{LKX%LrnfdOs{;uE#*Qx3 zOQ;dfXLWRq{x$RenmB;Nr;gs5t~di9&^~0ZMdCTb{P+3Cp?{l)OQ%2iMW_PsE>$Rcuos zP^%rj#Pjf{v}Bc_aOwMbpTfTG7Ys$KRh!d!B&79G0boiAZ@l%2QwhSGWZwo?s!>t2 z$0!>XuzS-vG2EcRe$Y7P0^+pg=Ow^BszXg?JrB#R@%y#C0l#ouhEY!~9;(aqUt z7E00qgZGB^k{GMZ!u2HV@-G?Yu~`*KQtMUMBzMWtE!D^!;g0wTj6nQ9E{4vB$XEKV z!U+^SSEIWukdlt{PS)#F&mMFTzX(%PGpT6X?Y#-{A%?ZKEA|eF6`Pe*h^jasJp?nf zxCzlq-UDjVdinT0K+6S$z7LWE_1nS91=|tb571aw0fkTK;`1$pcmFh74c=0+XS>Ha z>dd`wSe03(;6Z$)mdfzv5r15p9FT+sQ8(QzSUGn?S!9ifw;gr5c=iD#O z%Tg_dpa)5axlgg1%~MHxDj1fHzu3bYo%T9jh!=<1b`U8?uw!x35;{-}hagIJ{dP*> zcI{x1jd{P9AQg5GX3KSnjXvkK4wj@y`99Pmsd;`6Z8G>OuyJJAucX7XZWPpVh0Z*# zJ+^%G`^7x2uJ>%Yd=56DhBcps;U*u4+xUmy?#NI!9!P8&`cYebK!0o09lz?gwSh#@&Ci<^n#!$Om~xYi73K)PYz zJSTs)PFBiiLrkVVe|y#r1&#?W+_P27EUXFHJX_%!y)Zo;zM*-ulNB8VD&cU+wU;6T zYBLb(P6CN<;)3YCRr}mx<91F>LX!|%{vuFF=HRM;i42X_bvR>n!xK?x_PQ5o-SLJZ z(Z2EOaLBS+jdNtKe3u|HY@hU>y-plPDwd!1UJXpk(xgkVM@E&MZ!{cJT{p#oJj#lp z`KEDk`EPp5=-ZKT?1V5bgV(ec;+%{TXP>Di1cy#N#EVH zoUT^(@bZPR^44ax&CG5+a4^bRX{~UtkNmm}TD0PLwnJiGsQ{G8^MKfhv$+}}Q}>G4 z4+CJh(~m*{?gkH!qp3O*1Ax(7b~q%rk@2$2LWwd3mQA4IyjJkErUB&jiW?HUwKM8DbvJ=V~FMN&YnGf^umON{` z#uo2W=5<0y`HVDMjz zol}o!(Y9{OcGW7|wr$(CZCk5s+qP}nwr%sSpyA|vwYYKA*uHm~asDbx-%U}%hSr}ig` zQZZ2tfhY4hLaxEtz>H`1ed6jWihc=>6|)}ltH%9=eJbJ=i6=J7HC+tk-n|s}M1wJO zf6RzJY9}l#2<76?F9JU%CltL#O-d_$-fX!I5ZpL3V$Q5=MgzWCIM?~SbJ4mq0{DSgFukIR`NB8YTQ8*XlxQtA}STIJzTS|hGbP$dZ52Q0-60mn={#r^e*Wo z$|>n%STpuqqd2a}iZ(+1zSq~%UcNlPv~Ufid~{T8=)|So%+jnst6zlvy^B)Go3a_1 zPGLBo2UH@-&ZIJJq%s>C-QE+8dQx?QTYZLQNgIYGJ!k;5OiE<^>RAXO5}C3SvUTeP zeM>E7JkW!!LG3wTwQo;sjVVpPQyGk%z3avh2WjtI_KBSG22#e+m8vXyQ~2!=Im5Gq zR=mgLs9N$R)|4`3S*vp-0mwgw;&?-&Pu`p8H* zYubCTA?3E^1s^cmnTCNRmLn$gYK_-ivS_8+I0Y5q+o{=hf9rEVhu<(Scmu_AGeNiB zU9Llh$ZJ4sua7?^|0C8qU!O!35>+^uuBuO05Umbn|47Fj%A%$oQ;uwIZs8s-ZjhA~ zb*%5?9Yz+`7GV7kez}~SxYMfeC-webQw-n&<`M)ah?K*_q71*Otc)3E9^gH|+*LOh z0cA_=3kLAWI+IVFBogT%!+kB{GkOpE_AwS;1`0)bRNATis)FZ&Os!~v3$H(*X0loY zA)Br4R%kHoP*dCuWy|BJN(SKqPX)u3fw;7seTozb`6w#DIshJXj@fH>i|626SX*er zxA%;OV^+8u`gWM`$$xW_VaxuL?Pv0a^mxHQst@j$q$qf>hfwIxwJ%$b&$oCEF%cP0 z=Gh^cUaFil&-=oX$^4?l|f-LQoYVC9zusVCp?d{E1#1n zkV9rmE8!D8j`?$7A?)jAo!L^tx=&i9OGpBU!aWlCbff1PcL5st@bK}cvj&ji%3d1| z=_yjTW#RN_&3bA)l7(lc?Xk!ne1(BvbtOSri8TkTI4n@%ush@5t^dU|2WPzLJ>Gh? z%~DfvF`ZOymgViOts(WLjgi?iNDhUN$R-%{t*`UW8T}dTa*ztKgR{xFtIP34Ys}{^ z7jnvkE|yDW)S^-G-=%0dVF>LIc6m!3v60V;uk4oIPY1|GE#$@9_%>r;4!Go=0y;Y%OQE=QW!vWRaJxIp1{lajj3n?JHEFsit!Hxk<<*9hoW{ z?C9a=cf$d7JCVNfW6gSSZ}`=>Sy^ZoWWsUvkj{V#%BN%qn<;fO_+3@Ag>H%+qN?@@ zbghHuaW>&)nYFr^5y}D!XYi%inBOJpWoD=ZSS(QtIMVce{X7)!+8-psgkgl|J&0QO?+;#wU z_Wb}DW3y|EqQxbrYlrk{tH%qTStDuAcM4k{#1116MLiEFy{77;a;MbV66S$tLXWv0 zS<5y}VH=^|A!e65)ibNKCC4=S{<%d-By)x(K)MulqXf?t=T@`K|BgaZq-O4zTn70a z>u92~-Rr5cW(5b%?Uit;YsBa<{a)HJY>Od~wlHOjwR?-^5AO489h$i5 z-iq@dsS0y`#zXIgJB&!61m3I(NQP$l%S=RI%j#ZyYv)UGA)|Jx??*v=umO_(nD2|=mfVt5 z`rx}Pt+s|J1ov4If4OyU?NgTT7&`YEYZU#GQQM&0{Ygbd{RQV-n$Yg6?rJlwV5>vO z7U4eE1x>%LmAJ6yr7%V`xr(9x3d-0wf_1;Wd*hbf2-=Upo9sQhh(>iUjeJYJX54a2 zu8V-@YnvY}wrv%D%ab`Eaj&!33ADfFZNoIbPca#L2WBjcpmpQ>(>H@gDpZlulSp?% zSdJ6iiC>sncjTIX0p`&+K{K=f z{`u%W(=aQu^4vXCP)}A zUqC8@Ly@0Te+0^dp6gStp2TyZJG^arp& z^+Bjw7=yc}-Z1CGLV`OZP*p`iGV})etsX-157unBpe{Lz9+*B@X(xOk_X~e)jecW% zfBzDozoZgETS(7}f!Ua=@hmOJod+7242xASeCv`7?)6c6^4A~#MQIKC1R2Iq==2W5 z%m6lui?!5QNjwSB&BlY)H+Mf_=v1CWs&YZJ*OMToforqrM9Wy4I5Hz#ZV>z4)@7=_ zn26FJ#;RbkJh;Y)cv})^a^n1e#ig36ItcNzcBcF6=)F z+yKuPq(8AiJG$J=1;)*1;V0eXNHePuMZ)Agg#~zRoB0wcY$KH3tlD4gy zWA6Iwf+i#_DcGYT{n$jrqK7)^9+`ZMY8DD*VUv~8#jxZUcM(oQ!KIF(2cjT!j&(M7 z5IgoGN|TxA6}I7Y&VA+s&j8nn1Z)|ZcE)BIf0z7}Yo(W-OFzi3IurAAp(+K$zsL40 zJO7p0lRdDYA55HG$zCn8f`0ya$Mz0Vot`|1Gqlp*&O@HW$ctX~1qw8V#fOFN+_GXT z3Ct09cFAx8(hesaMSrs}c=ALAHJ{t04`WSy{@Y#uLw zvOhHmPimPFCIPBb(h&^XObuj%pkE=zL!k|4nRl+zK=dP``8UP-?%y!h*M5`iPfZr+MZ`SW+ z*wr=vAr;aL3!*|AWrEn6k;WY9i^ajfh5&P(YrAr(+xCfmx;f2q)#uOTRV~8)hw;<0 zapK7~1i+{bsLFLrI1fY5BXANpyYfG3@`asI+UI3-*1=Lj`D2D8**H{znJRWE5ypO3#OtK;U=Ny$ebK20JU*|Dz_+2)ddWE{K5;aaaJ*;cwEdwoi$ z7@)UvaQi+G!@mtTo3nWHX>kb)h@0{?hTx^R!tanbW6`K*9E*wM84Z7WeVjrDS2aiE zN}QYPHqa6Ihl&4@gR-%&=qgp-T52Wrq(m3x)!`rsNWy^1-0t~SRwxv1Elf-3bC80s zGi>s-GxpBowAD|9^xVLagjxCz=seN}|njk=mffz73i()3UwALm9 z&%~yvj*rmjv5vPb?!_D3EuC4I1dMNdzmL+%;_S~KHjk$-nRS-p!CPiOq4CDV1z?OY zDTdF4d*=)HF8`)v54 z1g)qYMbj~>efd^H&6s}~L*nxGjQ0XnZeK!R57Esz1h*28+b}fSuEF=QG>AL&NqNta6_=V?3a!sY3|td!lN>g7xVS4yoDB zdj&r`LB7mU(*AfZ^!caz&lm!V6Z0Vr5nwXIqb2WZfmDE~q3oba;%j~ES}pS}`>x!q z=40=!vK+hJh(}|$!y1f=8N>%4{VrH!uqI8*?HNbi5@AzL)~4>6Zf@~4qa`o3cw>Qx5!+Oq)x1`f6?~4Q@CzbI zU7DXaR2aGDkghmIWi-X7{mrS%4|a1VpjkA8)v`ZA893s*i9|~Eiof`YG*X_@K4cT! z@w6p49mY&Dq};VwP1+;-l00~TK2v`K#)us$Vfk{9{ijRxT!?{e+bQ10y9NR69)1_e z1KExRxh|l5DNcDh)Kx}l<;+RnJ?FAGIsX%0hz|G#a*Vp7Ov97;0-c-^H!kG{BBx&{ zLY~c~ixw4?1Wah#B97(w<=mz#$zm$YNIJErInyuNgJIhdi&o(qj57b?V)x^ZCDH>w zE4gW)EpQc&OIX%a+Vw9^bgh&ay#cc*GBmo6stRN}VmW_!!%Vx-DnAei5nQLR5>Z;_ zxz27t>sX|?A_~mj$W}m4AS&-Wd_z&)zl92&gR{iP+zW zhU<8Vc(>PWAeJW?frX38WyCmq#9A*IEfW9d%rn9-J%~vpf(7PD!LcUvLA2&f3XEIr za?~m1LP1PY-Bk2U4-Bm9sU6>>)eSQgb=GYcj(x~8%iKN|LqI2#_L`|A?V(#Lyf@SmP$4C}pt_vR@HPq4kZtD6Z;pL~P&v;AQ9% zE4VAzUhHKkZlKGLNWjcPB^cSoVv7g?#I2;`?-NPu8Oivo(XGHnEo%*YEYmq%;-YYT zOApF`-f`=2EbRJ#;VUr~dmwZDiuLKpj(fD)CD+o#b~-7it=K!P4^EM-ES+Aa)yvgH zyc!LjIzFH+y{RJnSo@$LSO^#1>F#Dcd~v7g;rFzdqj+MrY3vs+7&Q6X zmjNof#P#8#o2lCSz|TPPfXw1oA*!++`Qs1@#J*3|eDFT(KjaQBa1U`f1Xh~S?}I{q z+tJzj)JI^-aiC)9#z$m@<-~B)(ga9~1rIG!cn1LLt(j295QeBXV_nc!f6g$oai23M zdc6{}QhSD%A3amXU(~+dE7zkSLlutKPDwN(KWcBtLvUnN(oD5qe`m<6fa?w-ubb_& z%laOSYj*^r{Gm+WlB zcw4ICAQ8Q~vcLv?4=$HTmu@6J64=B?WjVDa0U;RFu1KBYdA zzXo=<<^(1+L8LDb0Gk*$9i&u>0z#zN0+04WE0tqp$uZl^71;WuRTJfBFq%2ZT!`vO zVC=*e^`YP144xK0AUDnnh20C9y6LFC3(TOIm0R1Yl$CGp!X?v{B~#K7HF=!4BP{&Rk_yRWF^4{$3PsFw><<@6~pFdfhegb`V$ZcrhK3dbVXLuB* zkRLGsk*A5_qJ>D_Z0VlMAyH@&>@stFn&~Cib1GNw0-$q0!wH}eP%!%KE3uA zjs*UaNd3A$VH9P=_JTOe5HkFP!8Ux0)_-%7qBLFGntg8VsHdMqjbt&zvK^82wjjQg z0_^UL>UDT!hq7e0N8S(nhHSvJg#=U$`h2CAM*B-JUql6KKU`%J?@NZD?r)la6@@Y4 zA(RT_MI-y^H^?nrw$jzM7$fNWUVG*#3;6>{zNyw$F=HcsfNEpWMTmNhQT88xf2RNo9QS$#`sgN$*@x1B?r3-n}hXFJLh zeY#9=|BK~1=sMYG$@nAr6Hn;W81A2$&&vZ>!uZgl>XOZ9*|tnydMf##jtF@j9#-jw ztH2QpUdt5oWb=DQ3}nKpo|NRt1gN%P=j7h#xwe)tTV}loVh^nxzXJ)0G69JcVhL>= z^5wn!_#mMf-zQba{X+s|qsHEdK#9=U85*(>%T{b{)p4Q&dS0@SPmw<#LHVX`XM-gu ztbbepQ+Dzx;GC@lJPiz&_!(>D1`C@FANLY!7+JGE+UsQF!7IEY*o6lYDm*{7xPjD< zfY5uh;75=Rhuvs-2I3ood0_Dpuy9QV`gXVRdM&UDE~&z3Me#iO-*8IY@sc2k)%987 z+c~t*geDs(Fh&KF+I=b8%5t;g{uaNxhOkTmf(d~b0V(CSuH^9p7B{1@;q{?ZV9!vC zo`q!h)xekDCy6Pr_^6Xlyal+}++RPi{U{Mu7%&%r8?QI8OIM^3kjxUCjU6$cry+Uy z&q^eJ1uyA1lb3I10BN6?RX6t!p)QazPTS2lL%bO|2wN;2FAblFy33;2jx5ghasfpW z+8>`5ttAR7TGG2HGk!bcv`s@iB4+V1jBA3L$b=;I6_dKe$toSAtUAUm*(N;y=$crj z_~yaWmBF)Pn4cpc?nzc)L`0kyGs7_J@TiE3N?%6{D$jrK!-iwkKzJNu3xmwxgF3|U z=6VEI=S2&HkG)QUO{H|WFT$4cc5?}Y60q~sPqyUF;T9ZywkWH*p_#AxQ43N6$u6}J zf+F2VBW)Ak0GmLI#wwny!i7L+7HEdWUXBac&1hGiqd87oK1It5 zvE`(?FUva!czzH_=bZxEZRoquI1-abBE$`nlUk~OVRPuGE( zB)^4Nh&SOJe_Gk6V!uTBy1#5uhTRPz2Tc-QGb;nS1DLq~1qR7LT>o#F>Obxj-_Fny ziktgCBq{?w12Y@rf2M!EwQTJ4|C#;MV-|=b6-Psmr_g(Hzv({x`PJNQZBTuufAom{~Fa!`8!1p_JrxrzU zgC_@~{lS9)bqj+<3ZdA*R}iKF!OpvZ1ipg?dJFk?mK_S<_Xj{Ae_=!1r-hSmx)0m{ zY;p&@fM6d2juipizqo{Ru@^3QdH+Q0gF6AZiwqC9|8)f)Yv|%{>$~V`ZP7ZOq zn+6O5i2xJ<2@QP@jBg7N2EP`6y9x%@Qxms4vP)kP%I~KZOx1_00!EBr2`}KY_wKdk zE&w3zCMTZv>xcQ%K5%#nz9!Hw?oTrW2sQfY=8OVU|7#U}(aW_2t`GOGUknf6>-l3f z5meH^6@q>0b@yqP<|L7cMOks~;GfE^H|pU50?(f>)*szpOd1_x@AMQ6EG!HH5a<^J z+!**fan$dvqW>BZpuTrOBztj}!s~k;;4>F+AK;5Ag%zk+8^Zs4SI`dz1t?I#?(5gA z{nz#VxBN>j=~w0KH#@$84CZBX<_B&6w|=vY-=N12o&4C7P(dj#gnt_7tG9e4u2)nI z+7SHN`Q5G(a{-J6*3lk3slek6?;Z&6J4A>lDW4aC3jqbv^-GGyZ$Gs61Qskrh#vy} ztQHIG7!>3u6_&+V-)xEIARyty4jF_+=yyvE5>9mO8#{8KEy1 zk0sd^A$Qjh?CyR5Q9KD6K*b2Z4|hN2wX!}CfENp1d0HOcOc@W`55w>9iysgmx4IJ+ z9Vlpx=oc9E3;1_=r`G`x-yc470{P%1{NiYr9LhOhfQQEy_*We3>ii}qV}JKUaQW%= z<23{@;Elh}{a-;@op9S?<=xCACx@n8PPIeTa`R0Z@nXL@0rBORlb@K(6?U?l?Zb*I zi*jLlUP#2)c{_mS%-|$s?r80!pemy>bey?l5Z1#ecZgkYZjY-!{ThKeHmL}s5vzDi zg3Eb$)%0yfV=?Bej!4)Oq;2n)w)ggRy$xv#xIJJ}4ldL+9&UZU!S`ErFOc z9x_>6N2ZwvW*LU8ZXsU?srH!Lh=SkiHoe>!?)%%l%+8#C$(}^Ks9&|c3^B&D51-4( z*L;$J<--y8Gb%i@sz<(4NW>E{=><}%_{tv`tN7$xCJ`Z=@xj0x8MqB7f>-C9C>AeP z{NR(Khfh`6vnp06*q%p3`R0-#cE?o{#>vK|jr{CbW1MBE0jQ5#MS6fb%#KvsW>W-{ zW3-ZtGrWw$y4+w$P2Ze?j;5Gdi4(Ls@zlU@I6qGUI+#F)wwMhpzqSNv@VNQ9xPT@4 zCXDPAZZSN^M_(@nh-yZUI4HhN3!g=f1vHl^ecmE6KePnnh2%!Iy3DNtQsprm?Fh zo7R`&V-xbGy(HAQ9!hQnV?<6=p^ofef~v+Qa=B^iVt>=`Y(A^b%ld?C2sU6)6IUK- z%?B@r(S1_a<$-kmu}r>xXj&gFv6hRmkDa5&Eku+DgVOsXbrmPV`K}?cLPrdtCqk?l z*=E)3H$Fx$(`LK(@6&X|xHh3}nm5cAcGb|ag?VAmB)KSf#%!gs z1o%G3Gg{(7z4E-J?%Bl?L3C#0e@TKId#+a(GRFC9$k77^ib3<5jLTzj$g*Z8eNhod zO!y>{OPk&9@(AvLNQJ;pw8Kp~tLkAEDu1jM&XL+BzHl{BYZS^KUvz*9H@e%@m}-4( zm3$V7+Uo^p(4~xDqkN_@Uy@Ax)WeUksfaS$&EB|Y`ScGr*|zzy`e}|G(M3I9%gbiB zEj6zW+{RE;jM^W1GF-yJM&L!Ml-NL^u8Cd;qYz-zrF5^~KPeb}U@hQ@7alH(MN^C0 z2mi88RCM4msrcB*&gN&WaP>VcD2eNlw`Z1Co`s3YuoGDgXY)xjWQZ*tOG_f!S;23n zD0PBp6sWNpd(oZ5C2y2>t2{fIg6lzqzJEy@hWTJM)bbfZC|cFMuBMftzvhMa@nN%7 zUsH4MZN7SDvs>t{y*LHrt0an)%Dd8Ou~0K6D?5S?rR4n>I#Y~Md8BxSwa1Uo*GWsA zR2j&b(kv%C(P|Gx+UF=*LJr*`w&e>ZQEF9X6B>I^r{NmaE#q76;zH)#FVjRrSuO5E z*b$e3MNE17jtZg&VATZbeG!Sw-h!^5mw%)EmQhF{iHsgIjZYK)UR}AoKh1Bq_u+L5 zMZV(#y;wt)_E25As1DMZ=}u_+V+bo)x5dEFkx58fw-9z!I{;+qbFo-5BlFBWYCv+hDo>)YZ;RBPCJtNjq z*NrePAA{~mvZ)JDO3YU0TOUVZ@KF#j?f=U%gN$;9$HVia+M-VybV;EDmvlGd0=i~8 z@aMq! zpt@xWQN8^`wQQ4Gt_nuVPHH_^J+Y5J3D}vx!s;{7s|(V#NM`4q$f;F$ z0$5{Ic22%bEhrd+nYUg7NCfFJik=!I=5XsHmcKID1@KQ7#l2CtedI-Kdy6k66r(hC zK44rd$xam4GsfY-eIbcw9?r=ujm<%;&Mn7|D+xJ|_8LXKQRU6O})44 zM%HZnGwdc!u9YvO^+hHx`;LNQoELcPl%y5)%|?b;3m}%bWw49Pq-zSB2A_*=z!IIG zmb5Y1WBpF>7cGWYnuYpMUr1w%L!!lPz(e3sjJLkf2-<0AvG0{iH}DI5V`2&rH1!a_ zb9?2bPwE|9QyXLfT^&Fw{m@kAcZAqdht~BG%YI1D>==+DGM_sSKF@(?g0glWeO$>B zh^+gsB_ffCmAPF`?MYUSA$&W+zZx^B@o;Sr3TEH?1>P-FMMStEx@|J{A=o1 zLg|ZWsY9r>8lzonri||n%t}RFSY*iMx>A;&+tveJeHZ*^rI7L5>W6vrqHxr_r0%~J zeBHbcVH>e_?fD+_x7nt>8t(jBQ3p7o`C{C{yQ}_^;5F0r%%&fFnsUdXs|6Jf1z0;( z3Uo~qHYLs7H-ZBlmt@Md(9`oUg5KPuO%Z2A{0v#qvjlMwLyDgZw#;^?@CwQ>sTE(? zgzU%R@+EKOKZWw9_}>FE;zlaH@i0w)lbAGMj3H*QwOSMkYsi+ab$Ox~PM zFq^g3(}D&dTplbQ<^}D%W^fqzrebJ<%tMm#djO9TUyk~##HScRcuoaM)VJb3kE%8n z1%s8U_X9>a(qokjxaervR^CWbY5cagDr?`qE!*iuripZzVEW@CO%dR+9acORhDkY0 zHku<2A!jP z=7@cojrF^ayTcv`Gdsu+YOU@Yby?w(^^#y1kl$)sKQ)H;bbETs6sD1x+1b|8>OkBK zT9ZOhtKZx{GA3)1xhSi5FWCevfX-WYyyU=>(nskVc@^bBzdvLIlNio*WBHBWKQrmX z3+w}Gp10%liVDO#sVu8kEso|@5Mpbx&&4(<9+P};0Jo;44Dn<_8Ew;1`|dL-U({}( zN=H~ke1ODT_VfkZpmn*K;f}y$l=4!Sz$XpqnpuO_k_Q--q@V)&tN;u-2ajB^m@8?fAFnGQO!glgQWHJdw|nNp&eZU zZ%6t2!wEaHjes1@`$SS`%GxW^xX8fq0gv5wH~2X21=|RgZ9)9KE+LhHTp4`fB}S%4 z{U`r;^`v<805@SaMGN!;y>~~CA?gD$E;8jF;j%MM;VtL8$>6F6i=6oG;6lfL$wnLQ z;#E2~P8OgH&uWxN?8*v5NO12&m68mXCpD;2o8ArQ)v6qzloF5tDWo-@uzlC`UMYsr zGLsSQEG)>q_l_cUaiPZs3l!A^|M_8M!)V?k{j7`NErxlCCpd5KG;W#$Z8cHonOwNg zTIbtSbgX*$zGkZvzrVpn=Yfvr0Y=nJE-iLADPn^nA*<*vM{^9I!ZqjJ%VWP`#lQg%xF};&cO;@C2<@m+&!9D4$-|}|isgU$aJ+$ngs9fkL72m7kwQad{ z%jqKsbifQNJMCXPM&#sFB45u-!%y(;y7Dhm&O;U1*r{O1dy7A7m$6#{TV0*a!H&A7 z6vy#{aqEM-D`r~_FByk&M8!!n57BWpcvhiKa+kXI=8ifrgJ;3@RYPQ?+`k&tzG|I@ z?~N);+VpokJ@HKX9tVlP-Z=5u{t5_~yNumTit^j--lQKp>5i-zN(--ya+`^Lq_AGC zMO{{LtHK_IQ?8&XB1D>{9fmd@SorOn4C+}P^V9S)PV!=&ot^6A$zY^akhUq*-UpK>4Yvg8 zHg6=tQ_1rcSl!aCkAtl;EsEFL$s>gwYdKPcX=Ip-e$C0d`{Dz8qiQ#zZ?j*h&mi(E3Lv*$31+a1ZJBDb2` zQxow;Pkpar&bvmtsO{#&Z;c-k;xjKtMj>rk)@ec_Bcv3VuMfK3CWl3Bu1t`uZNPj2 zk_$5<9JzP zT#dUawFebBE`FXxO`gUvSwDMug#u``pMme-k5uKK%(;T6kH)Uo#-RP!L#Tnt%oxF) zjn0kc)LEJV70%zx>w1z8Bq&$9RVD^KE^gNaHHW>o&N_M0fin8@+*+A7(%(wzi^#*BTG zFHcU`WjHi8F{XvVK};=cR*J4lEICE&Y0r~(f00%ik2Z6UOYD`0vGjQLm{f{ekL7GM zZ{=}b?4IGURvMYJXYxspM!aUKw10SoR2=Sy!bC@&K{nku8?SlILqs$xh??x&#d)DF zz3;o^MT`KC*6xHm=ewS3Ho}%|o$G*R>H$M`C%C+}Y_!MIqng?(-j)c%cb*Y`E_=H?KLM7t|SFW*0Lw z5R=m7qH5)&W?rD+^;hb{#aK^#y^#ydbv+rENOw$d1p8-#V|GBSdt0Sg5jnEhXM zBf*DxN80m;PbTY7$}JMtGQCzQ1f#p_`)~R+#Vz#8H^gV65wt*~ZpczVbjAcUIbJ^m z(X}3r^({V@&$CC((4ax>&Y6YgUI(BA%Bu*)i4i~AOCxfFLkA1tOBe59kZ5wSrS&k0 zeW@=?&7M45qH*{`H1o;j%SLU)I!4;XJr<7%+u0y<^ z-x?edPJ-lH)iZ02u^)SoR^G?3-kAB&+u1OQg&nnxn|L+n`&48U7Zi0Cy+r7cHucXC zGaeml49DEOtc>yhZ06z13Y7h$T-!gFQq$B{tGJR$8f&bLQ2Os(8Y6yP3e*e-59iT-q%o)j&j>QgG(i*CZAAuW7-{o7 z+D?>H2e%Y04$iW(S?6y8{}ag=LkD*w1;B^J5aC*Z@&M1)N7C^lU7E}g5weXEpFk;I>?id5Q7L0iLm_i9SpZAO_2bOgFDJDQn|#DsKuf59gmNP9 z5eSk2f}%Yp$fJ`V2Czml4vDDJ5)p}=Udqs8W?YhM1IC=Vh?w+@ESoA@v%Fja_}AX z2J#5UiAH-?QhE}nUW|Io1mA&BYiOifk6M=m&NCyNV1%d`2P8v?U;B`NRl2eItNgxZ z=71a&nKu~B1nD8QEu0;p+<(iH_3#RUHNd@(gFZ!5X(<%k*$S%4sUC-Q`RWeekmjXU zEd=Z_H0JUSCfU-2iQoUu2wnSk_ok=Ps$-D9>$WZ208z`*Yb(g>yV$68!cvXj@xzhZ zDD0B90r7!!k7wdX90`OL%P|9{Tl1`NU%FWJ-&uih%bubJu<;So zC7_eH0HgJ8R;GQ53J7Mjn`8?yA6z4*1!2J`NEgbMl#WQm@`q^?yX$H*Sk^kpd-M}2 zoP3oz(>Ax>W#uR&`V<8t5qeY0q;W^9kItaYX!N=rU5hZCfnyPa|qdVE6EhUOUw2Q`eMP*k!B#UT(@ne)Xz1QNurP2biIoo<22Pd zZYoY0+v2TgH&m^xEZbH85A{@?<*e_7=TMVNL2j zOCR2PNUvOLh|DfU{2PTO{ki@UUmTO%$s7Dj8v{MdB%Tek9;_#0x){CpPc$$oLJomi z%dLHvZ0%aNX6I=jx30VUFJEhnrkXEwP+H$EyU#oB*BFnQ+*{)b>PH<2zvqO_z4h6kR+~^OK6~Ha;<;K%2AG#w_LQgO)<5O` z3=JQ|EqF!~s>0oTlB4_eR9&4*$L;N(=+$=E-%LuXbD){0`{Do`g-;24a{5NxCVr>T zlk2G#%GizT+&?s&;WjRuPJAF?&l8`R;odt}SNq&yD>y?Ok11|xlDfBDE4?>kvnCm} z!N(i8xt|hE%Vy>8GrX!9qux9nScez7H&r3Kgpnkh;0D(|v}rk@mw4d<7kb{f`uXr2 zdu#hn%UC_y8dufE1xV%(Lz9YuMG!iUu+%FaN$J^j^Ltyhc2u7!&la1kny-JR*B!EX zqni3G?y%#8We)#di$sfdA$9!(honjm-qyc-53Jo?S4Kla73)~vz=p;5aUoIANP=LD z`s5(E+||vO8s57xheiS|RxjAS7oP4GF(N*nVYc$YFSh@%W`Bh#jozAZ(X~A?$Ypk{W9>Kh#PZFq{a4s1q`f^=COqTN<@YW5_68={0qj!7!DzMPh+H##QQTHa#o&soQT_+lO^yzV# zlvGx_{f!vKz+80busv8aMrY|UM{XOVAYW~IkhaQIPWw`zUGlt#P3GK?l-9k}UBg!} zIFN4P^hh@5w&a$_eXFyRNH>d)TB|Q+v<*ga=X~!w!jUKGJTV|uZbte>bE0Q#%&Idw z%Of6h5gpm+YY+3(+VJB9MI}-Dg{*TDSip99khUhQ>#7S}`=5us^46O4++xjc!_pd! zGLK_|v6Zq;o+bdO|G#cGV=HBd)RK%o8S}Kjk5|vOG2t@WmWJEb|I6= z*5vic-S)sC+3nBx=nb_R)e0RSZSn-47Nf^aR}p~#0`P+j(v{ERH5?hv6^Z%IO_-gf z>v_0u|9lUjr>O4}?TsZbH|snpi6rN8?)j)HRr zD^!BxN>C|Wo_`?eawe5p-QuLkS8~obn`I&rOy?ff{6)9NP3)OH8UF%IJy#N23VzF_ z1cte4Zap9!NLS+n-S1MF?1-b}htF&Gg0r1B#N>1+4_(33j2J(>;%r0bHNvNqHsMZQ zzNHUKiF}-ke=NlPnEc+%Rfc{XuujW$yVL*&OI+&=?RwZ4y>n9F>eOqY*AZ<6w_%KJ z=HAy8cvxFMdnwY{3EFZlZ;Jbn1;b__V>L_ENK>9aq%fA1IsVuYfc z>)v2hq)`c)U=_rLFd|<+;ZaI}yqt`OeWn9SwHqTaIS&$ECpSUwZ$?ZN#4e%JZLn-L z?E60HmCp~0(j9^8nuyy5(4)2&l4fgJ<%HbsibfS` zoaOm#tZo&rQ<=50?M@*UP=%k|A>){+N4c+c#deNwLzzLo6Fb?0Cr))Ue!5a=Ej23h ziUxfmuAgJC6nj6F#ST{04Nb<)Wz30P1OY*`j|zmC7{n_EKvr|!aW+rdo=Cgeg`?%f z7!TgqjQ)|)!O2E=$D>+6<^FH!Hp_oWw;35&nEsPzGvYI_aj>%dXZ)Y>HUkGE%m4SX z{_k4Ws8?Y7;>{I*=uwGL*-@$%o6Q!ROdKv8H*2@img^#;O;)=X-ZP(`-`b8=Rh5;` zC=T{h^hX^6f;hDTMEVvcX2j-3mlA`#;!_ZaadIj8IpDMNbo29bjC=|4f8METnIEFR zqzWt!&JA^q$6tR#;|jwA9!sUy`refkMrKg)&kbSq^?~T?92x5z78Zfg&(Ar23e8W) zAQ4#Yo9V&E=75N=t!1+EB!aK5c(7@vrn31CzfKYPZG{2#_xAJ)e>So4^^Fe94UF}n z;~4B&+3Me;%#HP7+cd!9~X$Jkazc)YV#86xOu&~fE*4Njt);!hMG61D% zs$>8h3l^GYZf2GMfVB>LQDCdGuXwLvwPC5NU}5Y^ zam{mTsQ;=EZR^?cwrUKmsE^Hzj0~-;Lw?kL1=C>5MDf0E2i@%cwKB0fHNAYsV{EQt zVg0UzF+%g={G$a8j)n}m?|11Pk@q_`C7lIG{q*#76?FxG4DKJ^8PBn;2bjcjCG(?e z{3i9K5fq!+oz2tt)Chx&2d$JiOJ`0;2CRnc-&hzK9=pni_LG{2fetW&DmnuogvkHnXyE82hm+CQVjDn@>q7_k5f1 z+euDtehPP2U|+v`%Gf>y53F-@W2;cBQq;#_w@dE|JSMW*XH53cJlY(;dkTgmyJjP&FZpu zb^N#Z?zhoa-^k$l-Y$A}#>L?$3kaigR-^8_x5AS27gGlV*$5gf^S6_7-};UN7O2HE z7e{8WPg-jBi>^H+u`HxByuK@>G5)=`<3!Ifx%XsxV_-#iXJ-7M7VBg&BIoC~$_Fkz ze)*K<;AuU>k1pMNX6|?7Pd!Tm(~s2}x`sL+SWFBU?p&_fw*)l+UFd8%GpoaIXF8yB zQ;X|NE~)=4rVl`gYs{P<4mB0Dzw92}d~etvezLc}YXHuIeqlKLWM6;T0h|ecNmxAr zvd{1g0p`NL2}Wk&zJ;U#IK%m#FyubqeMS=Bg>vtWf9K4&+kcTh&A8wHEd=i2eMIFy zgr)#EkNKW7sweP1qG~?=@)lNp=g*#9{F21XvIPAiJ(_U?m(GgT+c$g^K3M3#{pDR` z`7pXmA3AL|e;ggw6O%Ffg8$lLO!V6`16lm{kud%3lXE-q%ko<>zA>=-@i6$Ee@oK% z0_Iz6{Q&nZvHXVrnp!@A_thnE{&1hvhfNH3M zwDhV%>T@kz&(t>##cGRb3sKzs)9=h94}oyt+hH&ftBrD&u^H>VAReI%?`VFk>_vX%dmBY5J$>yY4Tu$6jowX|f`z``ojYp#gx*m;~=+?VItw(*(m zKs+L|p?rTg`300vwV#BFYD~z9^gzYMg-k6j-^nlP6{6qVccuLoq<)d*cSr-M=4@Wc z@|T=w@}?TVKR6S2p6!mE(dd6k3aLbxB3qCu2hb zs!IwwG@*UOZ=l82HxcI#=CV*$EQtxN4o`PZUA1)z3Mba)I8SDrVgcRr5vu@$jk8H} z<2<7%&}MzEo0wcfe0f#oqT|5k9nHQXr)Eh3ExJH<7)U_Dp=IbDNCkgOz!gv1P&T{Um&45*v%=z7b zWeZM>G7|Tz+>Jq@@_470D>S}z(hEfk6w&LQ(%<%wXZ*Lx++;--(2MJ>CpcO2^4YO@ znznIuwK=uRrKou4<16W@mK1pXZIsJKB@T%6$GnN{aPu9aOZ{JbiCqJhVj5oFbgXZL z#L1ji6Caj3w_(Uub~Kid;kA}W1$mDPca18kC#Zglm*FXaG^I5}zMdT_-@)>0g%iV@g>5`3 zJ>C75J4YympO1~a{G45u3NVmJ)t0TL>^Qts$XPj~1V!cQ6Jy4LKtx5xq}L=To;dog z?utdJ7UdLuA`kYyWLxpYT>V{z3#*W}-vFOYeQ<^a#LE{_Ce`ymd;q3Xc?%)w&ax