From 4549d9e427b1632e206cff6dba29e55a04834f99 Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Thu, 16 Apr 2020 19:24:06 +0200 Subject: [PATCH 001/709] adding ManualSelector (enhancement #174) --- CMakeLists.txt | 10 + examples/CMakeLists.txt | 5 + examples/t12_ncurses_manual_selector.cpp | 35 +++ include/behaviortree_cpp_v3/behavior_tree.h | 2 + .../controls/manual_node.h | 50 +++++ src/bt_factory.cpp | 2 + src/controls/manual_node.cpp | 203 ++++++++++++++++++ 7 files changed, 307 insertions(+) create mode 100644 examples/t12_ncurses_manual_selector.cpp create mode 100644 include/behaviortree_cpp_v3/controls/manual_node.h create mode 100644 src/controls/manual_node.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 13a4076fe..33e41f84c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -178,6 +178,16 @@ list(APPEND BT_SOURCE 3rdparty/minitrace/minitrace.cpp ) +find_package(Curses QUIET) + +if(CURSES_FOUND) + list(APPEND BT_SOURCE + src/controls/manual_node.cpp + ) +endif() +list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${CURSES_LIBRARIES}) + + ###################################################### if (UNIX) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 188ea1a55..1de5c782f 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -46,3 +46,8 @@ target_link_libraries(t10_include_trees ${BEHAVIOR_TREE_LIBRARY} bt_sample_node add_executable(t11_runtime_ports t11_runtime_ports.cpp ) target_link_libraries(t11_runtime_ports ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) + +if(CURSES_FOUND) + add_executable(t12_ncurses_manual_selector t12_ncurses_manual_selector.cpp ) + target_link_libraries(t12_ncurses_manual_selector ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) +endif() diff --git a/examples/t12_ncurses_manual_selector.cpp b/examples/t12_ncurses_manual_selector.cpp new file mode 100644 index 000000000..ef6f8d102 --- /dev/null +++ b/examples/t12_ncurses_manual_selector.cpp @@ -0,0 +1,35 @@ +#include "behaviortree_cpp_v3/bt_factory.h" +#include "dummy_nodes.h" + +using namespace BT; + +// clang-format off +static const char* xml_text = R"( + + + + + + + + + + + + )"; +// clang-format on + +int main() +{ + BehaviorTreeFactory factory; + factory.registerNodeType("SaySomething"); + + auto tree = factory.createTreeFromText(xml_text); + auto ret = tree.tickRoot(); + + std::cout << "Result: " << ret << std::endl; + + return 0; +} + + diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index b376af25c..a9e4719ea 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -21,6 +21,7 @@ #include "behaviortree_cpp_v3/controls/sequence_node.h" #include "behaviortree_cpp_v3/controls/sequence_star_node.h" #include "behaviortree_cpp_v3/controls/switch_node.h" +#include "behaviortree_cpp_v3/controls/manual_node.h" #include "behaviortree_cpp_v3/action_node.h" #include "behaviortree_cpp_v3/condition_node.h" @@ -39,6 +40,7 @@ #include "behaviortree_cpp_v3/decorators/blackboard_precondition.h" #include "behaviortree_cpp_v3/decorators/timeout_node.h" + namespace BT { diff --git a/include/behaviortree_cpp_v3/controls/manual_node.h b/include/behaviortree_cpp_v3/controls/manual_node.h new file mode 100644 index 000000000..61219b81d --- /dev/null +++ b/include/behaviortree_cpp_v3/controls/manual_node.h @@ -0,0 +1,50 @@ +/* Copyright (C) 2020 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 MANUAL_SELECTION_NODE_H +#define MANUAL_SELECTION_NODE_H + +#include "behaviortree_cpp_v3/control_node.h" + +namespace BT +{ +/** + * @brief Use a Terminal User Interface (ncurses) to select a certain child manually. + */ +class ManualSelectorNode : public ControlNode +{ + public: + ManualSelectorNode(const std::string& name); + + virtual ~ManualSelectorNode() override = default; + + virtual void halt() override; + + private: + + virtual BT::NodeStatus tick() override; + int running_child_idx_; + + enum NumericarStatus{ + NUM_SUCCESS = 253, + NUM_FAILURE = 254, + NUM_RUNNING = 255, + }; + + NodeStatus selectStatus() const; + + uint8_t selectChild() const; +}; + +} + +#endif // MANUAL_SELECTION_NODE_H diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 2a5344e96..1a4c72e76 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -55,6 +55,8 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType>("Switch5"); registerNodeType>("Switch6"); + registerNodeType("ManualSelector"); + for( const auto& it: builders_) { builtin_IDs_.insert( it.first ); diff --git a/src/controls/manual_node.cpp b/src/controls/manual_node.cpp new file mode 100644 index 000000000..9519a24ee --- /dev/null +++ b/src/controls/manual_node.cpp @@ -0,0 +1,203 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved + * Copyright (C) 2018-2020 Davide Faconti, Eurecat - 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 "behaviortree_cpp_v3/controls/manual_node.h" +#include "behaviortree_cpp_v3/action_node.h" +#include + +namespace BT +{ + + +ManualSelectorNode::ManualSelectorNode(const std::string& name) + : ControlNode::ControlNode(name, {} ) + , running_child_idx_(-1) +{ + setRegistrationID("ManualSelector"); +} + +void ManualSelectorNode::halt() +{ + if( running_child_idx_ >= 0 ) + { + haltChild( size_t(running_child_idx_) ); + } + running_child_idx_ = -1; + ControlNode::halt(); +} + +NodeStatus ManualSelectorNode::tick() +{ + const size_t children_count = children_nodes_.size(); + + if( children_count == 0 ) + { + return selectStatus(); + } + + setStatus(NodeStatus::RUNNING); + + unsigned idx = selectChild(); + + if( idx == NUM_SUCCESS ){ + return NodeStatus::SUCCESS; + } + if( idx == NUM_FAILURE ){ + return NodeStatus::FAILURE; + } + if( idx == NUM_RUNNING ){ + return NodeStatus::RUNNING; + } + + NodeStatus ret = children_nodes_[idx]->executeTick(); + + if(ret == NodeStatus::RUNNING) + { + running_child_idx_ = idx; + } + return ret; +} + +NodeStatus ManualSelectorNode::selectStatus() const +{ + WINDOW *win; + initscr(); + cbreak(); + + win = newwin( 6, 70, 1, 1 ); // create a new window + + mvwprintw( win, 0, 0, "No children." ); + mvwprintw( win, 1, 0, "Press: S to return SUCCESFULL," ); + mvwprintw( win, 2, 0, " F to return FAILURE, or" ); + mvwprintw( win, 3, 0, " R to return RUNNING." ); + + wrefresh( win ); // update the terminal screen + noecho(); // disable echoing of characters on the screen + keypad( win, TRUE ); // enable keyboard input for the window. + curs_set( 0 ); // hide the default screen cursor. + + int ch = 0; + NodeStatus ret; + while(1) + { + if( ch == 's' || ch == 'S') + { + ret = NodeStatus::SUCCESS; + break; + } + else if( ch == 'f' || ch == 'F') + { + ret = NodeStatus::FAILURE; + break; + } + else if( ch == 'r' || ch == 'R') + { + ret = NodeStatus::RUNNING; + break; + } + ch = wgetch(win); + } + werase( win ) ; + wrefresh( win ); + delwin( win ); + endwin(); + return ret; +} + +uint8_t ManualSelectorNode::selectChild() const +{ + const size_t children_count = children_nodes_.size(); + std::vector list; + list.reserve(children_count); + for(const auto& child: children_nodes_) + { + list.push_back(child->name()); + } + + size_t width = 10; + for(const auto& str: list) { + width = std::max(width, str.size()+2); + } + + WINDOW *win; + initscr(); + cbreak(); + + win = newwin( children_count+6, 70, 1, 1 ); // create a new window + + mvwprintw( win, 0, 0, "Use UP/DOWN arrow to select the child, Enter to confirm." ); + mvwprintw( win, 1, 0, "Press: S to skip and return SUCCESFULL," ); + mvwprintw( win, 2, 0, " F to skip and return FAILURE, or" ); + mvwprintw( win, 3, 0, " R to skip and return RUNNING." ); + + // now print all the menu items and highlight the first one + for(size_t i=0; i Date: Thu, 16 Apr 2020 10:28:28 -0700 Subject: [PATCH 002/709] Add extern "C" to correct the linkage for Windows (#175) --- include/behaviortree_cpp_v3/bt_factory.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index c0dd233c5..ac7c424d2 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -113,7 +113,7 @@ See examples for more information about configuring CMake correctly #elif _WIN32 #define BT_REGISTER_NODES(factory) \ - __declspec(dllexport) void BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory) + extern "C" void __declspec(dllexport) BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory) #endif #endif From 1fb010263a6731ec332a386c983e89b409f75241 Mon Sep 17 00:00:00 2001 From: s-trinh Date: Thu, 16 Apr 2020 19:29:00 +0200 Subject: [PATCH 003/709] Use CMake 3.5.1 as the minimum CMake version for Xenial. (#176) --- CMakeLists.txt | 2 +- examples/CMakeLists.txt | 2 +- sample_nodes/CMakeLists.txt | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 33e41f84c..6e4d6bb99 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.5.2) # version on Ubuntu Xenial +cmake_minimum_required(VERSION 3.5.1) # version on Ubuntu Xenial project(behaviortree_cpp_v3) #---- Add the subdirectory cmake ---- diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 1de5c782f..2ba4fa288 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.5.2) +cmake_minimum_required(VERSION 3.5.1) include_directories( ../sample_nodes ) diff --git a/sample_nodes/CMakeLists.txt b/sample_nodes/CMakeLists.txt index e93d850ea..f156368d4 100644 --- a/sample_nodes/CMakeLists.txt +++ b/sample_nodes/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.5.2) +cmake_minimum_required(VERSION 3.5.1) include_directories( ../include ) @@ -36,4 +36,4 @@ target_compile_definitions(movebase_node_dyn PRIVATE BT_PLUGIN_EXPORT ) set_target_properties(movebase_node_dyn PROPERTIES LIBRARY_OUTPUT_DIRECTORY ${BEHAVIOR_TREE_BIN_DESTINATION} ) - + From ac9c9b9b65097ab959437c367d8a7f465adad320 Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Thu, 16 Apr 2020 23:07:34 +0200 Subject: [PATCH 004/709] minor changes --- CMakeLists.txt | 5 +++-- include/behaviortree_cpp_v3/blackboard.h | 4 +++- src/blackboard.cpp | 15 +++++++++++++-- 3 files changed, 19 insertions(+), 5 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 33e41f84c..445421ba2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -105,8 +105,9 @@ elseif(BUILD_UNIT_TESTS) find_package(GTest) if(NOT GTEST_FOUND) - message(WARNING " GTest missing!") - endif(NOT GTEST_FOUND) + message(WARNING " GTest missing! You may want to follow these instructions:") + message(WARNING " https://gist.github.com/Cartexius/4c437c084d6e388288201aadf9c8cdd5") + endif() endif() diff --git a/include/behaviortree_cpp_v3/blackboard.h b/include/behaviortree_cpp_v3/blackboard.h index 2366cf9dc..63bfc8edb 100644 --- a/include/behaviortree_cpp_v3/blackboard.h +++ b/include/behaviortree_cpp_v3/blackboard.h @@ -183,10 +183,12 @@ class Blackboard const PortInfo *portInfo(const std::string& key); - void addSubtreeRemapping(std::string internal, std::string external); + void addSubtreeRemapping(StringView internal, StringView external); void debugMessage() const; + std::vector getKeys() const; + private: struct Entry{ diff --git a/src/blackboard.cpp b/src/blackboard.cpp index 835c12a57..ba6a516ad 100644 --- a/src/blackboard.cpp +++ b/src/blackboard.cpp @@ -42,9 +42,9 @@ const PortInfo* Blackboard::portInfo(const std::string &key) return &(it->second.port_info); } -void Blackboard::addSubtreeRemapping(std::string internal, std::string external) +void Blackboard::addSubtreeRemapping(StringView internal, StringView external) { - internal_to_external_.insert( {std::move(internal), std::move(external)} ); + internal_to_external_.insert( {internal.to_string(), external.to_string()} ); } void Blackboard::debugMessage() const @@ -72,4 +72,15 @@ void Blackboard::debugMessage() const } } +std::vector Blackboard::getKeys() const +{ + std::vector out; + out.reserve( storage_.size() ); + for(const auto& entry_it: storage_) + { + out.push_back( entry_it.first ); + } + return out; +} + } From 15816fea45598be48c94d2b03fda36059419aa2d Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Thu, 16 Apr 2020 23:08:48 +0200 Subject: [PATCH 005/709] New SubTreePlus --- include/behaviortree_cpp_v3/behavior_tree.h | 2 +- .../decorators/subtree_node.h | 47 ++++++++++++-- src/basic_types.cpp | 2 +- src/bt_factory.cpp | 2 +- src/decorators/subtree_node.cpp | 7 ++- src/xml_parsing.cpp | 63 +++++++++++++++++-- tests/gtest_subtree.cpp | 33 ++++++---- 7 files changed, 127 insertions(+), 29 deletions(-) diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index a9e4719ea..83eef0dce 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -78,7 +78,7 @@ inline NodeType getType() 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::SUBTREE; + 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; diff --git a/include/behaviortree_cpp_v3/decorators/subtree_node.h b/include/behaviortree_cpp_v3/decorators/subtree_node.h index 36f6afdd3..54b604875 100644 --- a/include/behaviortree_cpp_v3/decorators/subtree_node.h +++ b/include/behaviortree_cpp_v3/decorators/subtree_node.h @@ -29,15 +29,51 @@ class SubtreeNode : public DecoratorNode }; /** - * @brief The SubtreeWrapperNode is a way to wrap an entire Subtree. - * It does NOT have a separated BlackBoard and does not need ports remapping. + * @brief The SubtreePlus is a new kind of subtree that gives you much more control over remapping: + * + * Consider this example: + + + + + + + + + + + + + + + + + + + + + + + * You may notice three different approaches to remapping: + * + * 1) Subtree: "{param}" -> Parent: "{myParam}" -> Value: "Hello" + * Classical remapping from one port to another, but you need to use the syntax + * {myParam} to say that you are remapping the another port. + * + * 2) Subtree: "{param}" -> Value: "World" + * syntax without {}, in this case param directly point to the string "World". + * + * 3) Subtree: "{param}" -> Parent: "{parent}" + * Setting to true (or 1) the attribute "__autoremap", we are automatically remapping + * each port. Usefull to avoid some boilerplate. + */ -class SubtreeWrapperNode : public DecoratorNode +class SubtreePlusNode : public DecoratorNode { public: - SubtreeWrapperNode(const std::string& name); + SubtreePlusNode(const std::string& name); - virtual ~SubtreeWrapperNode() override = default; + virtual ~SubtreePlusNode() override = default; private: virtual BT::NodeStatus tick() override; @@ -49,6 +85,7 @@ class SubtreeWrapperNode : public DecoratorNode }; + } #endif // DECORATOR_SUBTREE_NODE_H diff --git a/src/basic_types.cpp b/src/basic_types.cpp index e81697240..fa562a2db 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -208,7 +208,7 @@ NodeType convertFromString(StringView str) if( str == "Condition" ) return NodeType::CONDITION; if( str == "Control" ) return NodeType::CONTROL; if( str == "Decorator" ) return NodeType::DECORATOR; - if( str == "SubTree" || str == "SubtreeWrapper" ) return NodeType::SUBTREE; + if( str == "SubTree" || str == "SubTreePlus" ) return NodeType::SUBTREE; return NodeType::UNDEFINED; } diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 1a4c72e76..0fa6536c3 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -43,7 +43,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("SetBlackboard"); registerNodeType("SubTree"); - registerNodeType("SubTreeWrapper"); + registerNodeType("SubTreePlus"); registerNodeType>("BlackboardCheckInt"); registerNodeType>("BlackboardCheckDouble"); diff --git a/src/decorators/subtree_node.cpp b/src/decorators/subtree_node.cpp index 7a70b7b78..ea518ddb8 100644 --- a/src/decorators/subtree_node.cpp +++ b/src/decorators/subtree_node.cpp @@ -17,13 +17,14 @@ BT::NodeStatus BT::SubtreeNode::tick() return child_node_->executeTick(); } -BT::SubtreeWrapperNode::SubtreeWrapperNode(const std::string &name) : +//-------------------------------- +BT::SubtreePlusNode::SubtreePlusNode(const std::string &name) : DecoratorNode(name, {} ) { - setRegistrationID("SubtreeWrapper"); + setRegistrationID("SubTreePlus"); } -BT::NodeStatus BT::SubtreeWrapperNode::tick() +BT::NodeStatus BT::SubtreePlusNode::tick() { NodeStatus prev_status = status(); if (prev_status == NodeStatus::IDLE) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index f60ba252d..c41fa13e6 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -462,14 +462,16 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, instance_name = ID; } - if (element_name == "SubTree" || element_name == "SubTreeWrapper" ) + if (element_name == "SubTree" || + element_name == "SubTreePlus" ) { instance_name = element->Attribute("ID"); } PortsRemapping parameters_map; - if (element_name != "SubTree") // in Subtree attributes have different meaning... + // in Subtree attributes have different meaning... + if (element_name != "SubTree" && element_name != "SubTreePlus") { for (const XMLAttribute* att = element->FirstAttribute(); att; att = att->Next()) { @@ -612,18 +614,69 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, { if( dynamic_cast(node.get()) ) { + // This is the former SubTree with manual remapping auto new_bb = Blackboard::create(blackboard); for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) { + if( strcmp(attr->Name(), "ID") == 0 ) + { + continue; + } new_bb->addSubtreeRemapping( attr->Name(), attr->Value() ); } output_tree.blackboard_stack.emplace_back(new_bb); recursivelyCreateTree( node->name(), output_tree, new_bb, node ); } - else{ - recursivelyCreateTree( node->name(), output_tree, blackboard, node ); - } + else if( dynamic_cast(node.get()) ) + { + auto new_bb = Blackboard::create(blackboard); + output_tree.blackboard_stack.emplace_back(new_bb); + std::set mapped_keys; + + bool do_autoremap = false; + + for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) + { + if( strcmp(attr->Name(), "ID") == 0 ) + { + continue; + } + if( strcmp(attr->Name(), "__autoremap") == 0 ) + { + if( convertFromString(attr->Value()) ) + { + do_autoremap = true; + } + continue; + } + + StringView str = attr->Value(); + if( TreeNode::isBlackboardPointer(str)) + { + StringView port_name = TreeNode::stripBlackboardPointer(str); + new_bb->addSubtreeRemapping( attr->Name(), port_name); + mapped_keys.insert(port_name.to_string()); + } + else{ + new_bb->set(attr->Name(), std::string(attr->Value()) ); + mapped_keys.insert(attr->Value()); + } + } + recursivelyCreateTree( node->name(), output_tree, new_bb, node ); + + if( do_autoremap ) + { + auto keys = new_bb->getKeys(); + for( StringView key: keys) + { + if( mapped_keys.count(key) == 0) + { + new_bb->addSubtreeRemapping( key, key ); + } + } + } + } } else { diff --git a/tests/gtest_subtree.cpp b/tests/gtest_subtree.cpp index 4f873d9b9..b04451fd8 100644 --- a/tests/gtest_subtree.cpp +++ b/tests/gtest_subtree.cpp @@ -142,29 +142,36 @@ TEST(SubTree, BadRemapping) EXPECT_ANY_THROW( tree_bad_out.tickRoot() ); } -TEST(SubTree, SubtreeWrapper) +TEST(SubTree, SubtreePlus) { - BehaviorTreeFactory factory; - factory.registerNodeType("SaySomething"); - factory.registerNodeType("CopyPorts"); + static const char* xml_text = R"( - static const char* xml_text = R"( - - - + + + + + + + + - - + + )"; - Tree tree = factory.createTreeFromText(xml_text); - auto ret = tree.tickRoot(); - ASSERT_EQ(ret, NodeStatus::SUCCESS ); + BehaviorTreeFactory factory; + factory.registerNodeType("SaySomething"); + + Tree tree = factory.createTreeFromText(xml_text); + auto ret = tree.tickRoot(); + ASSERT_EQ(ret, NodeStatus::SUCCESS ); } + + From bfb8681150691683b4348cc245a55b239f141b7d Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Fri, 17 Apr 2020 09:12:44 +0200 Subject: [PATCH 006/709] fixed ncurses dependencies ( #179 ) --- CMakeLists.txt | 3 ++- package.xml | 1 + src/bt_factory.cpp | 3 ++- src/controls/manual_node.cpp | 3 ++- 4 files changed, 7 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e7aa97d52..faba3e572 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -185,8 +185,9 @@ if(CURSES_FOUND) list(APPEND BT_SOURCE src/controls/manual_node.cpp ) + list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${CURSES_LIBRARIES}) + add_definitions(-DNCURSES_FOUND) endif() -list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${CURSES_LIBRARIES}) ###################################################### diff --git a/package.xml b/package.xml index d881df4ef..b21194b99 100644 --- a/package.xml +++ b/package.xml @@ -20,6 +20,7 @@ rclcpp libzmq3-dev + libncurses-dev catkin diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 1a4c72e76..4c6764fe7 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -55,8 +55,9 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType>("Switch5"); registerNodeType>("Switch6"); +#ifdef NCURSES_FOUND registerNodeType("ManualSelector"); - +#endif for( const auto& it: builders_) { builtin_IDs_.insert( it.first ); diff --git a/src/controls/manual_node.cpp b/src/controls/manual_node.cpp index 9519a24ee..5fce7770a 100644 --- a/src/controls/manual_node.cpp +++ b/src/controls/manual_node.cpp @@ -117,6 +117,7 @@ NodeStatus ManualSelectorNode::selectStatus() const uint8_t ManualSelectorNode::selectChild() const { const size_t children_count = children_nodes_.size(); + std::vector list; list.reserve(children_count); for(const auto& child: children_nodes_) @@ -165,7 +166,7 @@ uint8_t ManualSelectorNode::selectChild() const } else if( ch == KEY_UP ) { - row = ( row == 0) ? : row-1; + row = ( row == 0) ? (children_count-1) : row-1; } else if( ch == KEY_ENTER || ch == 10 ) { From 4a8cf33f3c20190542fe1ff053202dee90eb1c23 Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Fri, 17 Apr 2020 09:49:58 +0200 Subject: [PATCH 007/709] Added an option to repeat the previous selection in ManualSelector --- examples/t12_ncurses_manual_selector.cpp | 21 +++++++---- .../controls/manual_node.h | 11 +++++- src/controls/manual_node.cpp | 35 ++++++++++++------- 3 files changed, 47 insertions(+), 20 deletions(-) diff --git a/examples/t12_ncurses_manual_selector.cpp b/examples/t12_ncurses_manual_selector.cpp index ef6f8d102..a30647e19 100644 --- a/examples/t12_ncurses_manual_selector.cpp +++ b/examples/t12_ncurses_manual_selector.cpp @@ -3,17 +3,24 @@ using namespace BT; +/* Try also +* +* to see the difference. +*/ + // clang-format off static const char* xml_text = R"( - - - - - - - + + + + + + + + + )"; diff --git a/include/behaviortree_cpp_v3/controls/manual_node.h b/include/behaviortree_cpp_v3/controls/manual_node.h index 61219b81d..895385b42 100644 --- a/include/behaviortree_cpp_v3/controls/manual_node.h +++ b/include/behaviortree_cpp_v3/controls/manual_node.h @@ -23,16 +23,25 @@ namespace BT class ManualSelectorNode : public ControlNode { public: - ManualSelectorNode(const std::string& name); + ManualSelectorNode(const std::string& name, const NodeConfiguration& config); virtual ~ManualSelectorNode() override = default; virtual void halt() override; + static PortsList providedPorts() + { + return { InputPort(REPEAT_LAST_SELECTION, false, + "If true, execute again the same child that was selected the last time") }; + } + private: + static constexpr const char* REPEAT_LAST_SELECTION = "repeat_last_selection"; + virtual BT::NodeStatus tick() override; int running_child_idx_; + int previously_executed_idx_; enum NumericarStatus{ NUM_SUCCESS = 253, diff --git a/src/controls/manual_node.cpp b/src/controls/manual_node.cpp index 5fce7770a..d27ec982c 100644 --- a/src/controls/manual_node.cpp +++ b/src/controls/manual_node.cpp @@ -19,9 +19,10 @@ namespace BT { -ManualSelectorNode::ManualSelectorNode(const std::string& name) - : ControlNode::ControlNode(name, {} ) +ManualSelectorNode::ManualSelectorNode(const std::string& name, const NodeConfiguration& config) + : ControlNode::ControlNode(name, config ) , running_child_idx_(-1) + , previously_executed_idx_(-1) { setRegistrationID("ManualSelector"); } @@ -45,22 +46,32 @@ NodeStatus ManualSelectorNode::tick() return selectStatus(); } - setStatus(NodeStatus::RUNNING); + bool repeat_last = false; + getInput(REPEAT_LAST_SELECTION, repeat_last); - unsigned idx = selectChild(); + int idx = 0; - if( idx == NUM_SUCCESS ){ - return NodeStatus::SUCCESS; - } - if( idx == NUM_FAILURE ){ - return NodeStatus::FAILURE; + if( repeat_last && previously_executed_idx_ >= 0) + { + idx = previously_executed_idx_; } - if( idx == NUM_RUNNING ){ - return NodeStatus::RUNNING; + else{ + setStatus(NodeStatus::RUNNING); + idx = selectChild(); + previously_executed_idx_ = idx; + + if( idx == NUM_SUCCESS ){ + return NodeStatus::SUCCESS; + } + if( idx == NUM_FAILURE ){ + return NodeStatus::FAILURE; + } + if( idx == NUM_RUNNING ){ + return NodeStatus::RUNNING; + } } NodeStatus ret = children_nodes_[idx]->executeTick(); - if(ret == NodeStatus::RUNNING) { running_child_idx_ = idx; From cc3f0d9fc7c241933b416a279e9897b1f71e95e0 Mon Sep 17 00:00:00 2001 From: Fabian Schurig Date: Fri, 17 Apr 2020 20:12:11 +0200 Subject: [PATCH 008/709] catkin C++17 string_view compatibility (#178) * Use static_cast instead of to_string() * Fix to_string to static_cast --- src/blackboard.cpp | 2 +- src/bt_factory.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/blackboard.cpp b/src/blackboard.cpp index ba6a516ad..667ba1440 100644 --- a/src/blackboard.cpp +++ b/src/blackboard.cpp @@ -44,7 +44,7 @@ const PortInfo* Blackboard::portInfo(const std::string &key) void Blackboard::addSubtreeRemapping(StringView internal, StringView external) { - internal_to_external_.insert( {internal.to_string(), external.to_string()} ); + internal_to_external_.insert( {static_cast(internal), static_cast(external)} ); } void Blackboard::debugMessage() const diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 4c6764fe7..76e47e877 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -168,7 +168,7 @@ std::vector getCatkinLibraryPaths() splitString(env_catkin_prefix_paths, os_pathsep); for (BT::StringView catkin_prefix_path : catkin_prefix_paths) { - filesystem::path path(catkin_prefix_path.to_string()); + filesystem::path path(static_cast(catkin_prefix_path)); filesystem::path lib("lib"); lib_paths.push_back((path / lib).str()); } From 626571a742aa61cdd5deb915b8511f1f04301670 Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Fri, 17 Apr 2020 21:16:42 +0200 Subject: [PATCH 009/709] fixed --- src/xml_parsing.cpp | 6 +++--- tests/gtest_subtree.cpp | 36 ++++++++++++++++++++++++++++++++---- 2 files changed, 35 insertions(+), 7 deletions(-) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index c41fa13e6..94dbb263e 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -656,11 +656,11 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, { StringView port_name = TreeNode::stripBlackboardPointer(str); new_bb->addSubtreeRemapping( attr->Name(), port_name); - mapped_keys.insert(port_name.to_string()); + mapped_keys.insert(attr->Name()); } else{ - new_bb->set(attr->Name(), std::string(attr->Value()) ); - mapped_keys.insert(attr->Value()); + new_bb->set(attr->Name(), static_cast(str) ); + mapped_keys.insert(attr->Name()); } } recursivelyCreateTree( node->name(), output_tree, new_bb, node ); diff --git a/tests/gtest_subtree.cpp b/tests/gtest_subtree.cpp index b04451fd8..8c182cc69 100644 --- a/tests/gtest_subtree.cpp +++ b/tests/gtest_subtree.cpp @@ -142,7 +142,7 @@ TEST(SubTree, BadRemapping) EXPECT_ANY_THROW( tree_bad_out.tickRoot() ); } -TEST(SubTree, SubtreePlus) +TEST(SubTree, SubtreePlusA) { static const char* xml_text = R"( @@ -151,11 +151,8 @@ TEST(SubTree, SubtreePlus) - - - @@ -174,4 +171,35 @@ TEST(SubTree, SubtreePlus) ASSERT_EQ(ret, NodeStatus::SUCCESS ); } +TEST(SubTree, SubtreePlusB) +{ + static const char* xml_text = R"( + + + + + + + + + + + + + + + + + + + )"; + + BehaviorTreeFactory factory; + factory.registerNodeType("SaySomething"); + + Tree tree = factory.createTreeFromText(xml_text); + auto ret = tree.tickRoot(); + ASSERT_EQ(ret, NodeStatus::SUCCESS ); +} + From d895042350e073b8c47c4c76e13bf6754fa88366 Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Fri, 17 Apr 2020 21:52:56 +0200 Subject: [PATCH 010/709] string_view updated --- include/behaviortree_cpp_v3/basic_types.h | 4 +- include/behaviortree_cpp_v3/exceptions.h | 2 +- include/behaviortree_cpp_v3/tree_node.h | 6 +- .../behaviortree_cpp_v3/utils/string_view.hpp | 879 +++++++++++------- src/basic_types.cpp | 8 +- src/xml_parsing.cpp | 2 +- 6 files changed, 563 insertions(+), 338 deletions(-) diff --git a/include/behaviortree_cpp_v3/basic_types.h b/include/behaviortree_cpp_v3/basic_types.h index e6407a41b..d451da499 100644 --- a/include/behaviortree_cpp_v3/basic_types.h +++ b/include/behaviortree_cpp_v3/basic_types.h @@ -256,10 +256,10 @@ std::pair CreatePort(PortDirection direction, if( std::is_same::value) { - out = {nonstd::to_string(name), PortInfo(direction) }; + out = {static_cast(name), PortInfo(direction) }; } else{ - out = {nonstd::to_string(name), PortInfo(direction, typeid(T), + out = {static_cast(name), PortInfo(direction, typeid(T), GetAnyFromStringFunctor() ) }; } if( !description.empty() ) diff --git a/include/behaviortree_cpp_v3/exceptions.h b/include/behaviortree_cpp_v3/exceptions.h index 4ed3fb60b..b28081083 100644 --- a/include/behaviortree_cpp_v3/exceptions.h +++ b/include/behaviortree_cpp_v3/exceptions.h @@ -24,7 +24,7 @@ class BehaviorTreeException : public std::exception { public: - BehaviorTreeException(nonstd::string_view message): message_(nonstd::to_string(message)) + BehaviorTreeException(nonstd::string_view message): message_(static_cast(message)) {} template diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index 1ed6ece23..6f505ef83 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -211,7 +211,7 @@ inline Result TreeNode::getInput(const std::string& key, T& destination) const "but BB is invalid"); } - const Any* val = config_.blackboard->getAny(nonstd::to_string(remapped_key)); + const Any* val = config_.blackboard->getAny(static_cast(remapped_key)); if (val && val->empty() == false) { if (std::is_same::value == false && val->type() == typeid(std::string)) @@ -261,9 +261,7 @@ inline Result TreeNode::setOutput(const std::string& key, const T& value) { remapped_key = stripBlackboardPointer(remapped_key); } - const auto& key_str = nonstd::to_string(remapped_key); - - config_.blackboard->set(key_str, value); + config_.blackboard->set(static_cast(remapped_key), value); return {}; } diff --git a/include/behaviortree_cpp_v3/utils/string_view.hpp b/include/behaviortree_cpp_v3/utils/string_view.hpp index 1b1d923b2..adf178b3d 100644 --- a/include/behaviortree_cpp_v3/utils/string_view.hpp +++ b/include/behaviortree_cpp_v3/utils/string_view.hpp @@ -1,4 +1,4 @@ -// Copyright 2017-2018 by Martin Moene +// Copyright 2017-2019 by Martin Moene // // string-view lite, a C++17-like string_view for C++98 and later. // For more information see https://github.com/martinmoene/string-view-lite @@ -12,7 +12,7 @@ #define NONSTD_SV_LITE_H_INCLUDED #define string_view_lite_MAJOR 1 -#define string_view_lite_MINOR 1 +#define string_view_lite_MINOR 4 #define string_view_lite_PATCH 0 #define string_view_lite_VERSION nssv_STRINGIFY(string_view_lite_MAJOR) "." nssv_STRINGIFY(string_view_lite_MINOR) "." nssv_STRINGIFY(string_view_lite_PATCH) @@ -55,6 +55,16 @@ # define nssv_CONFIG_CONVERSION_STD_STRING_FREE_FUNCTIONS 1 #endif +// Control presence of exception handling (try and auto discover): + +#ifndef nssv_CONFIG_NO_EXCEPTIONS +# if defined(__cpp_exceptions) || defined(__EXCEPTIONS) || defined(_CPPUNWIND) +# define nssv_CONFIG_NO_EXCEPTIONS 0 +# else +# define nssv_CONFIG_NO_EXCEPTIONS 1 +# endif +#endif + // C++ language version detection (C++20 is speculative): // Note: VC14.0/1900 (VS2015) lacks too much from C++14. @@ -108,14 +118,14 @@ template< class CharT, class Traits, class Allocator = std::allocator > std::basic_string to_string( std::basic_string_view v, Allocator const & a = Allocator() ) { - return std::basic_string( v.begin(), v.end(), a ); + return std::basic_string( v.begin(), v.end(), a ); } template< class CharT, class Traits, class Allocator > std::basic_string_view to_string_view( std::basic_string const & s ) { - return std::basic_string_view( s.data(), s.size() ); + return std::basic_string_view( s.data(), s.size() ); } // Literal operators sv and _sv: @@ -134,22 +144,22 @@ inline namespace string_view_literals { constexpr std::string_view operator "" _sv( const char* str, size_t len ) noexcept // (1) { - return std::string_view{ str, len }; + return std::string_view{ str, len }; } constexpr std::u16string_view operator "" _sv( const char16_t* str, size_t len ) noexcept // (2) { - return std::u16string_view{ str, len }; + return std::u16string_view{ str, len }; } constexpr std::u32string_view operator "" _sv( const char32_t* str, size_t len ) noexcept // (3) { - return std::u32string_view{ str, len }; + return std::u32string_view{ str, len }; } constexpr std::wstring_view operator "" _sv( const wchar_t* str, size_t len ) noexcept // (4) { - return std::wstring_view{ str, len }; + return std::wstring_view{ str, len }; } }} // namespace literals::string_view_literals @@ -189,16 +199,17 @@ using std::operator<<; // Compiler versions: // -// MSVC++ 6.0 _MSC_VER == 1200 (Visual Studio 6.0) -// MSVC++ 7.0 _MSC_VER == 1300 (Visual Studio .NET 2002) -// MSVC++ 7.1 _MSC_VER == 1310 (Visual Studio .NET 2003) -// MSVC++ 8.0 _MSC_VER == 1400 (Visual Studio 2005) -// MSVC++ 9.0 _MSC_VER == 1500 (Visual Studio 2008) -// MSVC++ 10.0 _MSC_VER == 1600 (Visual Studio 2010) -// MSVC++ 11.0 _MSC_VER == 1700 (Visual Studio 2012) -// MSVC++ 12.0 _MSC_VER == 1800 (Visual Studio 2013) -// MSVC++ 14.0 _MSC_VER == 1900 (Visual Studio 2015) -// MSVC++ 14.1 _MSC_VER >= 1910 (Visual Studio 2017) +// MSVC++ 6.0 _MSC_VER == 1200 nssv_COMPILER_MSVC_VERSION == 60 (Visual Studio 6.0) +// MSVC++ 7.0 _MSC_VER == 1300 nssv_COMPILER_MSVC_VERSION == 70 (Visual Studio .NET 2002) +// MSVC++ 7.1 _MSC_VER == 1310 nssv_COMPILER_MSVC_VERSION == 71 (Visual Studio .NET 2003) +// MSVC++ 8.0 _MSC_VER == 1400 nssv_COMPILER_MSVC_VERSION == 80 (Visual Studio 2005) +// MSVC++ 9.0 _MSC_VER == 1500 nssv_COMPILER_MSVC_VERSION == 90 (Visual Studio 2008) +// MSVC++ 10.0 _MSC_VER == 1600 nssv_COMPILER_MSVC_VERSION == 100 (Visual Studio 2010) +// MSVC++ 11.0 _MSC_VER == 1700 nssv_COMPILER_MSVC_VERSION == 110 (Visual Studio 2012) +// MSVC++ 12.0 _MSC_VER == 1800 nssv_COMPILER_MSVC_VERSION == 120 (Visual Studio 2013) +// MSVC++ 14.0 _MSC_VER == 1900 nssv_COMPILER_MSVC_VERSION == 140 (Visual Studio 2015) +// MSVC++ 14.1 _MSC_VER >= 1910 nssv_COMPILER_MSVC_VERSION == 141 (Visual Studio 2017) +// MSVC++ 14.2 _MSC_VER >= 1920 nssv_COMPILER_MSVC_VERSION == 142 (Visual Studio 2019) #if defined(_MSC_VER ) && !defined(__clang__) # define nssv_COMPILER_MSVC_VER (_MSC_VER ) @@ -208,7 +219,7 @@ using std::operator<<; # define nssv_COMPILER_MSVC_VERSION 0 #endif -#define nssv_COMPILER_VERSION( major, minor, patch ) (10 * ( 10 * major + minor) + patch) +#define nssv_COMPILER_VERSION( major, minor, patch ) ( 10 * ( 10 * (major) + (minor) ) + (patch) ) #if defined(__clang__) # define nssv_COMPILER_CLANG_VERSION nssv_COMPILER_VERSION(__clang_major__, __clang_minor__, __clang_patchlevel__) @@ -263,8 +274,10 @@ using std::operator<<; #define nssv_HAVE_WCHAR16_T nssv_CPP11_100 #define nssv_HAVE_WCHAR32_T nssv_CPP11_100 -#if ! ( ( nssv_CPP11 && nssv_COMPILER_CLANG_VERSION ) || nssv_BETWEEN( nssv_COMPILER_CLANG_VERSION, 300, 400 ) ) +#if ! ( ( nssv_CPP11_OR_GREATER && nssv_COMPILER_CLANG_VERSION ) || nssv_BETWEEN( nssv_COMPILER_CLANG_VERSION, 300, 400 ) ) # define nssv_HAVE_STD_DEFINED_LITERALS nssv_CPP11_140 +#else +# define nssv_HAVE_STD_DEFINED_LITERALS 0 #endif // Presence of C++14 language features: @@ -338,9 +351,12 @@ using std::operator<<; #include #include #include -#include #include // std::char_traits<> +#if ! nssv_CONFIG_NO_EXCEPTIONS +# include +#endif + #if nssv_CPP11_OR_GREATER # include #endif @@ -384,30 +400,64 @@ using std::operator<<; // - C26481: gsl::b.1 : don't use pointer arithmetic. Use span instead nssv_DISABLE_MSVC_WARNINGS( 4455 26481 26472 ) -//nssv_DISABLE_CLANG_WARNINGS( "-Wuser-defined-literals" ) -//nssv_DISABLE_GNUC_WARNINGS( -Wliteral-suffix ) + //nssv_DISABLE_CLANG_WARNINGS( "-Wuser-defined-literals" ) + //nssv_DISABLE_GNUC_WARNINGS( -Wliteral-suffix ) -namespace nonstd { namespace sv_lite { + namespace nonstd { namespace sv_lite { -template -< - class CharT, - class Traits = std::char_traits -> -class basic_string_view; +#if nssv_CPP11_OR_GREATER -// -// basic_string_view: -// + namespace detail { -template -< - class CharT, - class Traits /* = std::char_traits */ -> -class basic_string_view -{ -public: +#if nssv_CPP14_OR_GREATER + + template< typename CharT > + inline constexpr std::size_t length( CharT * s, std::size_t result = 0 ) + { + CharT * v = s; + std::size_t r = result; + while ( *v != '\0' ) { + ++v; + ++r; + } + return r; + } + +#else // nssv_CPP14_OR_GREATER + + // Expect tail call optimization to make length() non-recursive: + + template< typename CharT > + inline constexpr std::size_t length( CharT * s, std::size_t result = 0 ) + { + return *s == '\0' ? result : length( s + 1, result + 1 ); + } + +#endif // nssv_CPP14_OR_GREATER + + } // namespace detail + +#endif // nssv_CPP11_OR_GREATER + + template + < + class CharT, + class Traits = std::char_traits + > + class basic_string_view; + + // + // basic_string_view: + // + + template + < + class CharT, + class Traits /* = std::char_traits */ + > + class basic_string_view + { + public: // Member types: typedef Traits traits_type; @@ -429,27 +479,33 @@ class basic_string_view // 24.4.2.1 Construction and assignment: nssv_constexpr basic_string_view() nssv_noexcept - : data_( nssv_nullptr ) - , size_( 0 ) + : data_( nssv_nullptr ) + , size_( 0 ) {} #if nssv_CPP11_OR_GREATER nssv_constexpr basic_string_view( basic_string_view const & other ) nssv_noexcept = default; #else nssv_constexpr basic_string_view( basic_string_view const & other ) nssv_noexcept - : data_( other.data_) - , size_( other.size_) + : data_( other.data_) + , size_( other.size_) {} #endif - nssv_constexpr basic_string_view( CharT const * s, size_type count ) - : data_( s ) - , size_( count ) + nssv_constexpr basic_string_view( CharT const * s, size_type count ) nssv_noexcept // non-standard noexcept + : data_( s ) + , size_( count ) {} - nssv_constexpr basic_string_view( CharT const * s) - : data_( s ) - , size_( Traits::length(s) ) + nssv_constexpr basic_string_view( CharT const * s) nssv_noexcept // non-standard noexcept + : data_( s ) +#if nssv_CPP17_OR_GREATER + , size_( Traits::length(s) ) +#elif nssv_CPP11_OR_GREATER + , size_( detail::length(s) ) +#else + , size_( Traits::length(s) ) +#endif {} // Assignment: @@ -459,9 +515,9 @@ class basic_string_view #else nssv_constexpr14 basic_string_view & operator=( basic_string_view const & other ) nssv_noexcept { - data_ = other.data_; - size_ = other.size_; - return *this; + data_ = other.data_; + size_ = other.size_; + return *this; } #endif @@ -488,24 +544,27 @@ class basic_string_view // since C++20 nssv_nodiscard nssv_constexpr bool empty() const nssv_noexcept { - return 0 == size_; + return 0 == size_; } // 24.4.2.4 Element access: nssv_constexpr const_reference operator[]( size_type pos ) const { - return data_at( pos ); + return data_at( pos ); } nssv_constexpr14 const_reference at( size_type pos ) const { - if ( pos < size() ) - { - return data_at( pos ); - } - - throw std::out_of_range("nonst::string_view::at()"); +#if nssv_CONFIG_NO_EXCEPTIONS + assert( pos < size() ); +#else + if ( pos >= size() ) + { + throw std::out_of_range("nonstd::string_view::at()"); + } +#endif + return data_at( pos ); } nssv_constexpr const_reference front() const { return data_at( 0 ); } @@ -517,79 +576,91 @@ class basic_string_view nssv_constexpr14 void remove_prefix( size_type n ) { - assert( n <= size() ); - data_ += n; - size_ -= n; + assert( n <= size() ); + data_ += n; + size_ -= n; } nssv_constexpr14 void remove_suffix( size_type n ) { - assert( n <= size() ); - size_ -= n; + assert( n <= size() ); + size_ -= n; } nssv_constexpr14 void swap( basic_string_view & other ) nssv_noexcept { - using std::swap; - swap( data_, other.data_ ); - swap( size_, other.size_ ); + using std::swap; + swap( data_, other.data_ ); + swap( size_, other.size_ ); } // 24.4.2.6 String operations: size_type copy( CharT * dest, size_type n, size_type pos = 0 ) const { - if ( pos > size() ) - throw std::out_of_range("nonst::string_view::copy()"); - - const size_type rlen = (std::min)( n, size() - pos ); +#if nssv_CONFIG_NO_EXCEPTIONS + assert( pos <= size() ); +#else + if ( pos > size() ) + { + throw std::out_of_range("nonstd::string_view::copy()"); + } +#endif + const size_type rlen = (std::min)( n, size() - pos ); - (void) Traits::copy( dest, data() + pos, rlen ); + (void) Traits::copy( dest, data() + pos, rlen ); - return rlen; + return rlen; } nssv_constexpr14 basic_string_view substr( size_type pos = 0, size_type n = npos ) const { - if ( pos > size() ) - throw std::out_of_range("nonst::string_view::substr()"); - - return basic_string_view( data() + pos, (std::min)( n, size() - pos ) ); +#if nssv_CONFIG_NO_EXCEPTIONS + assert( pos <= size() ); +#else + if ( pos > size() ) + { + throw std::out_of_range("nonstd::string_view::substr()"); + } +#endif + return basic_string_view( data() + pos, (std::min)( n, size() - pos ) ); } // compare(), 6x: nssv_constexpr14 int compare( basic_string_view other ) const nssv_noexcept // (1) { - if ( const int result = Traits::compare( data(), other.data(), (std::min)( size(), other.size() ) ) ) - return result; + if ( const int result = Traits::compare( data(), other.data(), (std::min)( size(), other.size() ) ) ) + { + return result; + } - return size() == other.size() ? 0 : size() < other.size() ? -1 : 1; + return size() == other.size() ? 0 : size() < other.size() ? -1 : 1; } nssv_constexpr int compare( size_type pos1, size_type n1, basic_string_view other ) const // (2) { - return substr( pos1, n1 ).compare( other ); + return substr( pos1, n1 ).compare( other ); } nssv_constexpr int compare( size_type pos1, size_type n1, basic_string_view other, size_type pos2, size_type n2 ) const // (3) { - return substr( pos1, n1 ).compare( other.substr( pos2, n2 ) ); + return substr( pos1, n1 ).compare( other.substr( pos2, n2 ) ); } nssv_constexpr int compare( CharT const * s ) const // (4) { - return compare( basic_string_view( s ) ); + return compare( basic_string_view( s ) ); } nssv_constexpr int compare( size_type pos1, size_type n1, CharT const * s ) const // (5) { - return substr( pos1, n1 ).compare( basic_string_view( s ) ); + return substr( pos1, n1 ).compare( basic_string_view( s ) ); } nssv_constexpr int compare( size_type pos1, size_type n1, CharT const * s, size_type n2 ) const // (6) { - return substr( pos1, n1 ).compare( basic_string_view( s, n2 ) ); + return substr( pos1, n1 ).compare( basic_string_view( s, n2 ) ); } // 24.4.2.7 Searching: @@ -598,190 +669,194 @@ class basic_string_view nssv_constexpr bool starts_with( basic_string_view v ) const nssv_noexcept // (1) { - return size() >= v.size() && compare( 0, v.size(), v ) == 0; + return size() >= v.size() && compare( 0, v.size(), v ) == 0; } nssv_constexpr bool starts_with( CharT c ) const nssv_noexcept // (2) { - return starts_with( basic_string_view( &c, 1 ) ); + return starts_with( basic_string_view( &c, 1 ) ); } nssv_constexpr bool starts_with( CharT const * s ) const // (3) { - return starts_with( basic_string_view( s ) ); + return starts_with( basic_string_view( s ) ); } // ends_with(), 3x, since C++20: nssv_constexpr bool ends_with( basic_string_view v ) const nssv_noexcept // (1) { - return size() >= v.size() && compare( size() - v.size(), npos, v ) == 0; + return size() >= v.size() && compare( size() - v.size(), npos, v ) == 0; } nssv_constexpr bool ends_with( CharT c ) const nssv_noexcept // (2) { - return ends_with( basic_string_view( &c, 1 ) ); + return ends_with( basic_string_view( &c, 1 ) ); } nssv_constexpr bool ends_with( CharT const * s ) const // (3) { - return ends_with( basic_string_view( s ) ); + return ends_with( basic_string_view( s ) ); } // find(), 4x: nssv_constexpr14 size_type find( basic_string_view v, size_type pos = 0 ) const nssv_noexcept // (1) { - return assert( v.size() == 0 || v.data() != nssv_nullptr ) - , pos >= size() - ? npos - : to_pos( std::search( cbegin() + pos, cend(), v.cbegin(), v.cend(), Traits::eq ) ); + return assert( v.size() == 0 || v.data() != nssv_nullptr ) + , pos >= size() + ? npos + : to_pos( std::search( cbegin() + pos, cend(), v.cbegin(), v.cend(), Traits::eq ) ); } nssv_constexpr14 size_type find( CharT c, size_type pos = 0 ) const nssv_noexcept // (2) { - return find( basic_string_view( &c, 1 ), pos ); + return find( basic_string_view( &c, 1 ), pos ); } nssv_constexpr14 size_type find( CharT const * s, size_type pos, size_type n ) const // (3) { - return find( basic_string_view( s, n ), pos ); + return find( basic_string_view( s, n ), pos ); } nssv_constexpr14 size_type find( CharT const * s, size_type pos = 0 ) const // (4) { - return find( basic_string_view( s ), pos ); + return find( basic_string_view( s ), pos ); } // rfind(), 4x: nssv_constexpr14 size_type rfind( basic_string_view v, size_type pos = npos ) const nssv_noexcept // (1) { - if ( size() < v.size() ) - return npos; + if ( size() < v.size() ) + { + return npos; + } - if ( v.empty() ) - return (std::min)( size(), pos ); + if ( v.empty() ) + { + return (std::min)( size(), pos ); + } - const_iterator last = cbegin() + (std::min)( size() - v.size(), pos ) + v.size(); - const_iterator result = std::find_end( cbegin(), last, v.cbegin(), v.cend(), Traits::eq ); + const_iterator last = cbegin() + (std::min)( size() - v.size(), pos ) + v.size(); + const_iterator result = std::find_end( cbegin(), last, v.cbegin(), v.cend(), Traits::eq ); - return result != last ? size_type( result - cbegin() ) : npos; + return result != last ? size_type( result - cbegin() ) : npos; } nssv_constexpr14 size_type rfind( CharT c, size_type pos = npos ) const nssv_noexcept // (2) { - return rfind( basic_string_view( &c, 1 ), pos ); + return rfind( basic_string_view( &c, 1 ), pos ); } nssv_constexpr14 size_type rfind( CharT const * s, size_type pos, size_type n ) const // (3) { - return rfind( basic_string_view( s, n ), pos ); + return rfind( basic_string_view( s, n ), pos ); } nssv_constexpr14 size_type rfind( CharT const * s, size_type pos = npos ) const // (4) { - return rfind( basic_string_view( s ), pos ); + return rfind( basic_string_view( s ), pos ); } // find_first_of(), 4x: nssv_constexpr size_type find_first_of( basic_string_view v, size_type pos = 0 ) const nssv_noexcept // (1) { - return pos >= size() - ? npos - : to_pos( std::find_first_of( cbegin() + pos, cend(), v.cbegin(), v.cend(), Traits::eq ) ); + return pos >= size() + ? npos + : to_pos( std::find_first_of( cbegin() + pos, cend(), v.cbegin(), v.cend(), Traits::eq ) ); } nssv_constexpr size_type find_first_of( CharT c, size_type pos = 0 ) const nssv_noexcept // (2) { - return find_first_of( basic_string_view( &c, 1 ), pos ); + return find_first_of( basic_string_view( &c, 1 ), pos ); } nssv_constexpr size_type find_first_of( CharT const * s, size_type pos, size_type n ) const // (3) { - return find_first_of( basic_string_view( s, n ), pos ); + return find_first_of( basic_string_view( s, n ), pos ); } nssv_constexpr size_type find_first_of( CharT const * s, size_type pos = 0 ) const // (4) { - return find_first_of( basic_string_view( s ), pos ); + return find_first_of( basic_string_view( s ), pos ); } // find_last_of(), 4x: nssv_constexpr size_type find_last_of( basic_string_view v, size_type pos = npos ) const nssv_noexcept // (1) { - return empty() - ? npos - : pos >= size() - ? find_last_of( v, size() - 1 ) - : to_pos( std::find_first_of( const_reverse_iterator( cbegin() + pos + 1 ), crend(), v.cbegin(), v.cend(), Traits::eq ) ); + return empty() + ? npos + : pos >= size() + ? find_last_of( v, size() - 1 ) + : to_pos( std::find_first_of( const_reverse_iterator( cbegin() + pos + 1 ), crend(), v.cbegin(), v.cend(), Traits::eq ) ); } nssv_constexpr size_type find_last_of( CharT c, size_type pos = npos ) const nssv_noexcept // (2) { - return find_last_of( basic_string_view( &c, 1 ), pos ); + return find_last_of( basic_string_view( &c, 1 ), pos ); } nssv_constexpr size_type find_last_of( CharT const * s, size_type pos, size_type count ) const // (3) { - return find_last_of( basic_string_view( s, count ), pos ); + return find_last_of( basic_string_view( s, count ), pos ); } nssv_constexpr size_type find_last_of( CharT const * s, size_type pos = npos ) const // (4) { - return find_last_of( basic_string_view( s ), pos ); + return find_last_of( basic_string_view( s ), pos ); } // find_first_not_of(), 4x: nssv_constexpr size_type find_first_not_of( basic_string_view v, size_type pos = 0 ) const nssv_noexcept // (1) { - return pos >= size() - ? npos - : to_pos( std::find_if( cbegin() + pos, cend(), not_in_view( v ) ) ); + return pos >= size() + ? npos + : to_pos( std::find_if( cbegin() + pos, cend(), not_in_view( v ) ) ); } nssv_constexpr size_type find_first_not_of( CharT c, size_type pos = 0 ) const nssv_noexcept // (2) { - return find_first_not_of( basic_string_view( &c, 1 ), pos ); + return find_first_not_of( basic_string_view( &c, 1 ), pos ); } nssv_constexpr size_type find_first_not_of( CharT const * s, size_type pos, size_type count ) const // (3) { - return find_first_not_of( basic_string_view( s, count ), pos ); + return find_first_not_of( basic_string_view( s, count ), pos ); } nssv_constexpr size_type find_first_not_of( CharT const * s, size_type pos = 0 ) const // (4) { - return find_first_not_of( basic_string_view( s ), pos ); + return find_first_not_of( basic_string_view( s ), pos ); } // find_last_not_of(), 4x: nssv_constexpr size_type find_last_not_of( basic_string_view v, size_type pos = npos ) const nssv_noexcept // (1) { - return empty() - ? npos - : pos >= size() - ? find_last_not_of( v, size() - 1 ) - : to_pos( std::find_if( const_reverse_iterator( cbegin() + pos + 1 ), crend(), not_in_view( v ) ) ); + return empty() + ? npos + : pos >= size() + ? find_last_not_of( v, size() - 1 ) + : to_pos( std::find_if( const_reverse_iterator( cbegin() + pos + 1 ), crend(), not_in_view( v ) ) ); } nssv_constexpr size_type find_last_not_of( CharT c, size_type pos = npos ) const nssv_noexcept // (2) { - return find_last_not_of( basic_string_view( &c, 1 ), pos ); + return find_last_not_of( basic_string_view( &c, 1 ), pos ); } nssv_constexpr size_type find_last_not_of( CharT const * s, size_type pos, size_type count ) const // (3) { - return find_last_not_of( basic_string_view( s, count ), pos ); + return find_last_not_of( basic_string_view( s, count ), pos ); } nssv_constexpr size_type find_last_not_of( CharT const * s, size_type pos = npos ) const // (4) { - return find_last_not_of( basic_string_view( s ), pos ); + return find_last_not_of( basic_string_view( s ), pos ); } // Constants: @@ -794,49 +869,49 @@ class basic_string_view enum { npos = size_type(-1) }; #endif -private: + private: struct not_in_view { - const basic_string_view v; + const basic_string_view v; - nssv_constexpr not_in_view( basic_string_view v ) : v( v ) {} + nssv_constexpr explicit not_in_view( basic_string_view v ) : v( v ) {} - nssv_constexpr bool operator()( CharT c ) const - { - return npos == v.find_first_of( c ); - } + nssv_constexpr bool operator()( CharT c ) const + { + return npos == v.find_first_of( c ); + } }; nssv_constexpr size_type to_pos( const_iterator it ) const { - return it == cend() ? npos : size_type( it - cbegin() ); + return it == cend() ? npos : size_type( it - cbegin() ); } nssv_constexpr size_type to_pos( const_reverse_iterator it ) const { - return it == crend() ? npos : size_type( crend() - it - 1 ); + return it == crend() ? npos : size_type( crend() - it - 1 ); } nssv_constexpr const_reference data_at( size_type pos ) const { #if nssv_BETWEEN( nssv_COMPILER_GNUC_VERSION, 1, 500 ) - return data_[pos]; + return data_[pos]; #else - return assert( pos < size() ), data_[pos]; + return assert( pos < size() ), data_[pos]; #endif } -private: + private: const_pointer data_; size_type size_; -public: + public: #if nssv_CONFIG_CONVERSION_STD_STRING_CLASS_METHODS template< class Allocator > basic_string_view( std::basic_string const & s ) nssv_noexcept - : data_( s.data() ) - , size_( s.size() ) + : data_( s.data() ) + , size_( s.size() ) {} #if nssv_HAVE_EXPLICIT_CONVERSION @@ -844,7 +919,7 @@ class basic_string_view template< class Allocator > explicit operator std::basic_string() const { - return to_string( Allocator() ); + return to_string( Allocator() ); } #endif // nssv_HAVE_EXPLICIT_CONVERSION @@ -855,7 +930,7 @@ class basic_string_view std::basic_string to_string( Allocator const & a = Allocator() ) const { - return std::basic_string( begin(), end(), a ); + return std::basic_string( begin(), end(), a ); } #else @@ -863,78 +938,230 @@ class basic_string_view std::basic_string to_string() const { - return std::basic_string( begin(), end() ); + return std::basic_string( begin(), end() ); } template< class Allocator > std::basic_string to_string( Allocator const & a ) const { - return std::basic_string( begin(), end(), a ); + return std::basic_string( begin(), end(), a ); } #endif // nssv_CPP11_OR_GREATER #endif // nssv_CONFIG_CONVERSION_STD_STRING_CLASS_METHODS -}; + }; -// -// Non-member functions: -// + // + // Non-member functions: + // -// 24.4.3 Non-member comparison functions: -// lexicographically compare two string views (function template): + // 24.4.3 Non-member comparison functions: + // lexicographically compare two string views (function template): -template< class CharT, class Traits > -nssv_constexpr bool operator== ( + template< class CharT, class Traits > + nssv_constexpr bool operator== ( basic_string_view lhs, basic_string_view rhs ) nssv_noexcept -{ return lhs.compare( rhs ) == 0 ; } - -template< class CharT, class Traits > -nssv_constexpr bool operator== ( - basic_string_view lhs, - CharT const * rhs) nssv_noexcept -{ - return lhs.compare(rhs) == 0; -} + { return lhs.compare( rhs ) == 0 ; } -template< class CharT, class Traits > -nssv_constexpr bool operator!= ( + template< class CharT, class Traits > + nssv_constexpr bool operator!= ( basic_string_view lhs, basic_string_view rhs ) nssv_noexcept -{ return lhs.compare( rhs ) != 0 ; } + { return lhs.compare( rhs ) != 0 ; } -template< class CharT, class Traits > -nssv_constexpr bool operator< ( + template< class CharT, class Traits > + nssv_constexpr bool operator< ( basic_string_view lhs, basic_string_view rhs ) nssv_noexcept -{ return lhs.compare( rhs ) < 0 ; } + { return lhs.compare( rhs ) < 0 ; } -template< class CharT, class Traits > -nssv_constexpr bool operator<= ( + template< class CharT, class Traits > + nssv_constexpr bool operator<= ( basic_string_view lhs, basic_string_view rhs ) nssv_noexcept -{ return lhs.compare( rhs ) <= 0 ; } + { return lhs.compare( rhs ) <= 0 ; } -template< class CharT, class Traits > -nssv_constexpr bool operator> ( + template< class CharT, class Traits > + nssv_constexpr bool operator> ( basic_string_view lhs, basic_string_view rhs ) nssv_noexcept -{ return lhs.compare( rhs ) > 0 ; } + { return lhs.compare( rhs ) > 0 ; } -template< class CharT, class Traits > -nssv_constexpr bool operator>= ( + template< class CharT, class Traits > + nssv_constexpr bool operator>= ( basic_string_view lhs, basic_string_view rhs ) nssv_noexcept -{ return lhs.compare( rhs ) >= 0 ; } + { return lhs.compare( rhs ) >= 0 ; } // Let S be basic_string_view, and sv be an instance of S. // Implementations shall provide sufficient additional overloads marked // constexpr and noexcept so that an object t with an implicit conversion // to S can be compared according to Table 67. -#if nssv_CPP11_OR_GREATER && ! nssv_BETWEEN( nssv_COMPILER_MSVC_VERSION, 100, 141 ) +#if ! nssv_CPP11_OR_GREATER || nssv_BETWEEN( nssv_COMPILER_MSVC_VERSION, 100, 141 ) + + // accomodate for older compilers: + + // == + + template< class CharT, class Traits> + nssv_constexpr bool operator==( + basic_string_view lhs, + CharT const * rhs ) nssv_noexcept + { return lhs.compare( rhs ) == 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator==( + CharT const * lhs, + basic_string_view rhs ) nssv_noexcept + { return rhs.compare( lhs ) == 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator==( + basic_string_view lhs, + std::basic_string rhs ) nssv_noexcept + { return lhs.size() == rhs.size() && lhs.compare( rhs ) == 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator==( + std::basic_string rhs, + basic_string_view lhs ) nssv_noexcept + { return lhs.size() == rhs.size() && lhs.compare( rhs ) == 0; } + + // != + + template< class CharT, class Traits> + nssv_constexpr bool operator!=( + basic_string_view lhs, + char const * rhs ) nssv_noexcept + { return lhs.compare( rhs ) != 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator!=( + char const * lhs, + basic_string_view rhs ) nssv_noexcept + { return rhs.compare( lhs ) != 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator!=( + basic_string_view lhs, + std::basic_string rhs ) nssv_noexcept + { return lhs.size() != rhs.size() && lhs.compare( rhs ) != 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator!=( + std::basic_string rhs, + basic_string_view lhs ) nssv_noexcept + { return lhs.size() != rhs.size() || rhs.compare( lhs ) != 0; } + + // < + + template< class CharT, class Traits> + nssv_constexpr bool operator<( + basic_string_view lhs, + char const * rhs ) nssv_noexcept + { return lhs.compare( rhs ) < 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator<( + char const * lhs, + basic_string_view rhs ) nssv_noexcept + { return rhs.compare( lhs ) > 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator<( + basic_string_view lhs, + std::basic_string rhs ) nssv_noexcept + { return lhs.compare( rhs ) < 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator<( + std::basic_string rhs, + basic_string_view lhs ) nssv_noexcept + { return rhs.compare( lhs ) > 0; } + + // <= + + template< class CharT, class Traits> + nssv_constexpr bool operator<=( + basic_string_view lhs, + char const * rhs ) nssv_noexcept + { return lhs.compare( rhs ) <= 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator<=( + char const * lhs, + basic_string_view rhs ) nssv_noexcept + { return rhs.compare( lhs ) >= 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator<=( + basic_string_view lhs, + std::basic_string rhs ) nssv_noexcept + { return lhs.compare( rhs ) <= 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator<=( + std::basic_string rhs, + basic_string_view lhs ) nssv_noexcept + { return rhs.compare( lhs ) >= 0; } + + // > + + template< class CharT, class Traits> + nssv_constexpr bool operator>( + basic_string_view lhs, + char const * rhs ) nssv_noexcept + { return lhs.compare( rhs ) > 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator>( + char const * lhs, + basic_string_view rhs ) nssv_noexcept + { return rhs.compare( lhs ) < 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator>( + basic_string_view lhs, + std::basic_string rhs ) nssv_noexcept + { return lhs.compare( rhs ) > 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator>( + std::basic_string rhs, + basic_string_view lhs ) nssv_noexcept + { return rhs.compare( lhs ) < 0; } + + // >= + + template< class CharT, class Traits> + nssv_constexpr bool operator>=( + basic_string_view lhs, + char const * rhs ) nssv_noexcept + { return lhs.compare( rhs ) >= 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator>=( + char const * lhs, + basic_string_view rhs ) nssv_noexcept + { return rhs.compare( lhs ) <= 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator>=( + basic_string_view lhs, + std::basic_string rhs ) nssv_noexcept + { return lhs.compare( rhs ) >= 0; } + + template< class CharT, class Traits> + nssv_constexpr bool operator>=( + std::basic_string rhs, + basic_string_view lhs ) nssv_noexcept + { return rhs.compare( lhs ) <= 0; } + +#else // newer compilers: #define nssv_BASIC_STRING_VIEW_I(T,U) typename std::decay< basic_string_view >::type @@ -944,113 +1171,113 @@ nssv_constexpr bool operator>= ( # define nssv_MSVC_ORDER(x) /*, int=x*/ #endif -// == + // == -template< class CharT, class Traits nssv_MSVC_ORDER(1) > -nssv_constexpr bool operator==( - basic_string_view lhs, + template< class CharT, class Traits nssv_MSVC_ORDER(1) > + nssv_constexpr bool operator==( + basic_string_view lhs, nssv_BASIC_STRING_VIEW_I(CharT, Traits) rhs ) nssv_noexcept -{ return lhs.compare( rhs ) == 0; } + { return lhs.compare( rhs ) == 0; } -template< class CharT, class Traits nssv_MSVC_ORDER(2) > -nssv_constexpr bool operator==( + template< class CharT, class Traits nssv_MSVC_ORDER(2) > + nssv_constexpr bool operator==( nssv_BASIC_STRING_VIEW_I(CharT, Traits) lhs, - basic_string_view rhs ) nssv_noexcept -{ return lhs.size() == rhs.size() && lhs.compare( rhs ) == 0; } + basic_string_view rhs ) nssv_noexcept + { return lhs.size() == rhs.size() && lhs.compare( rhs ) == 0; } -// != + // != -template< class CharT, class Traits nssv_MSVC_ORDER(1) > -nssv_constexpr bool operator!= ( - basic_string_view < CharT, Traits > lhs, + template< class CharT, class Traits nssv_MSVC_ORDER(1) > + nssv_constexpr bool operator!= ( + basic_string_view < CharT, Traits > lhs, nssv_BASIC_STRING_VIEW_I( CharT, Traits ) rhs ) nssv_noexcept -{ return lhs.size() != rhs.size() || lhs.compare( rhs ) != 0 ; } + { return lhs.size() != rhs.size() || lhs.compare( rhs ) != 0 ; } -template< class CharT, class Traits nssv_MSVC_ORDER(2) > -nssv_constexpr bool operator!= ( + template< class CharT, class Traits nssv_MSVC_ORDER(2) > + nssv_constexpr bool operator!= ( nssv_BASIC_STRING_VIEW_I( CharT, Traits ) lhs, - basic_string_view < CharT, Traits > rhs ) nssv_noexcept -{ return lhs.compare( rhs ) != 0 ; } + basic_string_view < CharT, Traits > rhs ) nssv_noexcept + { return lhs.compare( rhs ) != 0 ; } -// < + // < -template< class CharT, class Traits nssv_MSVC_ORDER(1) > -nssv_constexpr bool operator< ( - basic_string_view < CharT, Traits > lhs, + template< class CharT, class Traits nssv_MSVC_ORDER(1) > + nssv_constexpr bool operator< ( + basic_string_view < CharT, Traits > lhs, nssv_BASIC_STRING_VIEW_I( CharT, Traits ) rhs ) nssv_noexcept -{ return lhs.compare( rhs ) < 0 ; } + { return lhs.compare( rhs ) < 0 ; } -template< class CharT, class Traits nssv_MSVC_ORDER(2) > -nssv_constexpr bool operator< ( + template< class CharT, class Traits nssv_MSVC_ORDER(2) > + nssv_constexpr bool operator< ( nssv_BASIC_STRING_VIEW_I( CharT, Traits ) lhs, - basic_string_view < CharT, Traits > rhs ) nssv_noexcept -{ return lhs.compare( rhs ) < 0 ; } + basic_string_view < CharT, Traits > rhs ) nssv_noexcept + { return lhs.compare( rhs ) < 0 ; } -// <= + // <= -template< class CharT, class Traits nssv_MSVC_ORDER(1) > -nssv_constexpr bool operator<= ( - basic_string_view < CharT, Traits > lhs, + template< class CharT, class Traits nssv_MSVC_ORDER(1) > + nssv_constexpr bool operator<= ( + basic_string_view < CharT, Traits > lhs, nssv_BASIC_STRING_VIEW_I( CharT, Traits ) rhs ) nssv_noexcept -{ return lhs.compare( rhs ) <= 0 ; } + { return lhs.compare( rhs ) <= 0 ; } -template< class CharT, class Traits nssv_MSVC_ORDER(2) > -nssv_constexpr bool operator<= ( + template< class CharT, class Traits nssv_MSVC_ORDER(2) > + nssv_constexpr bool operator<= ( nssv_BASIC_STRING_VIEW_I( CharT, Traits ) lhs, - basic_string_view < CharT, Traits > rhs ) nssv_noexcept -{ return lhs.compare( rhs ) <= 0 ; } + basic_string_view < CharT, Traits > rhs ) nssv_noexcept + { return lhs.compare( rhs ) <= 0 ; } -// > + // > -template< class CharT, class Traits nssv_MSVC_ORDER(1) > -nssv_constexpr bool operator> ( - basic_string_view < CharT, Traits > lhs, + template< class CharT, class Traits nssv_MSVC_ORDER(1) > + nssv_constexpr bool operator> ( + basic_string_view < CharT, Traits > lhs, nssv_BASIC_STRING_VIEW_I( CharT, Traits ) rhs ) nssv_noexcept -{ return lhs.compare( rhs ) > 0 ; } + { return lhs.compare( rhs ) > 0 ; } -template< class CharT, class Traits nssv_MSVC_ORDER(2) > -nssv_constexpr bool operator> ( + template< class CharT, class Traits nssv_MSVC_ORDER(2) > + nssv_constexpr bool operator> ( nssv_BASIC_STRING_VIEW_I( CharT, Traits ) lhs, - basic_string_view < CharT, Traits > rhs ) nssv_noexcept -{ return lhs.compare( rhs ) > 0 ; } + basic_string_view < CharT, Traits > rhs ) nssv_noexcept + { return lhs.compare( rhs ) > 0 ; } -// >= + // >= -template< class CharT, class Traits nssv_MSVC_ORDER(1) > -nssv_constexpr bool operator>= ( - basic_string_view < CharT, Traits > lhs, + template< class CharT, class Traits nssv_MSVC_ORDER(1) > + nssv_constexpr bool operator>= ( + basic_string_view < CharT, Traits > lhs, nssv_BASIC_STRING_VIEW_I( CharT, Traits ) rhs ) nssv_noexcept -{ return lhs.compare( rhs ) >= 0 ; } + { return lhs.compare( rhs ) >= 0 ; } -template< class CharT, class Traits nssv_MSVC_ORDER(2) > -nssv_constexpr bool operator>= ( + template< class CharT, class Traits nssv_MSVC_ORDER(2) > + nssv_constexpr bool operator>= ( nssv_BASIC_STRING_VIEW_I( CharT, Traits ) lhs, - basic_string_view < CharT, Traits > rhs ) nssv_noexcept -{ return lhs.compare( rhs ) >= 0 ; } + basic_string_view < CharT, Traits > rhs ) nssv_noexcept + { return lhs.compare( rhs ) >= 0 ; } #undef nssv_MSVC_ORDER #undef nssv_BASIC_STRING_VIEW_I -#endif // nssv_CPP11_OR_GREATER +#endif // compiler-dependent approach to comparisons -// 24.4.4 Inserters and extractors: + // 24.4.4 Inserters and extractors: -namespace detail { + namespace detail { -template< class Stream > -void write_padding( Stream & os, std::streamsize n ) -{ + template< class Stream > + void write_padding( Stream & os, std::streamsize n ) + { for ( std::streamsize i = 0; i < n; ++i ) - os.rdbuf()->sputc( os.fill() ); -} + os.rdbuf()->sputc( os.fill() ); + } -template< class Stream, class View > -Stream & write_to_stream( Stream & os, View const & sv ) -{ + template< class Stream, class View > + Stream & write_to_stream( Stream & os, View const & sv ) + { typename Stream::sentry sentry( os ); if ( !os ) - return os; + return os; const std::streamsize length = static_cast( sv.length() ); @@ -1059,41 +1286,41 @@ Stream & write_to_stream( Stream & os, View const & sv ) const bool left_pad = pad && ( os.flags() & std::ios_base::adjustfield ) == std::ios_base::right; if ( left_pad ) - write_padding( os, os.width() - length ); + write_padding( os, os.width() - length ); // Write span characters: os.rdbuf()->sputn( sv.begin(), length ); if ( pad && !left_pad ) - write_padding( os, os.width() - length ); + write_padding( os, os.width() - length ); // Reset output stream width: os.width( 0 ); return os; -} + } -} // namespace detail + } // namespace detail -template< class CharT, class Traits > -std::basic_ostream & -operator<<( + template< class CharT, class Traits > + std::basic_ostream & + operator<<( std::basic_ostream& os, basic_string_view sv ) -{ + { return detail::write_to_stream( os, sv ); -} + } -// Several typedefs for common character types are provided: + // Several typedefs for common character types are provided: -typedef basic_string_view string_view; -typedef basic_string_view wstring_view; + typedef basic_string_view string_view; + typedef basic_string_view wstring_view; #if nssv_HAVE_WCHAR16_T -typedef basic_string_view u16string_view; -typedef basic_string_view u32string_view; + typedef basic_string_view u16string_view; + typedef basic_string_view u32string_view; #endif -}} // namespace nonstd::sv_lite + }} // namespace nonstd::sv_lite // // 24.4.6 Suffix for basic_string_view literals: @@ -1103,57 +1330,57 @@ typedef basic_string_view u32string_view; namespace nonstd { nssv_inline_ns namespace literals { -nssv_inline_ns namespace string_view_literals { + nssv_inline_ns namespace string_view_literals { #if nssv_CONFIG_STD_SV_OPERATOR && nssv_HAVE_STD_DEFINED_LITERALS -nssv_constexpr nonstd::sv_lite::string_view operator "" sv( const char* str, size_t len ) nssv_noexcept // (1) -{ - return nonstd::sv_lite::string_view{ str, len }; -} + nssv_constexpr nonstd::sv_lite::string_view operator "" sv( const char* str, size_t len ) nssv_noexcept // (1) + { + return nonstd::sv_lite::string_view{ str, len }; + } -nssv_constexpr nonstd::sv_lite::u16string_view operator "" sv( const char16_t* str, size_t len ) nssv_noexcept // (2) -{ - return nonstd::sv_lite::u16string_view{ str, len }; -} + nssv_constexpr nonstd::sv_lite::u16string_view operator "" sv( const char16_t* str, size_t len ) nssv_noexcept // (2) + { + return nonstd::sv_lite::u16string_view{ str, len }; + } -nssv_constexpr nonstd::sv_lite::u32string_view operator "" sv( const char32_t* str, size_t len ) nssv_noexcept // (3) -{ - return nonstd::sv_lite::u32string_view{ str, len }; -} + nssv_constexpr nonstd::sv_lite::u32string_view operator "" sv( const char32_t* str, size_t len ) nssv_noexcept // (3) + { + return nonstd::sv_lite::u32string_view{ str, len }; + } -nssv_constexpr nonstd::sv_lite::wstring_view operator "" sv( const wchar_t* str, size_t len ) nssv_noexcept // (4) -{ - return nonstd::sv_lite::wstring_view{ str, len }; -} + nssv_constexpr nonstd::sv_lite::wstring_view operator "" sv( const wchar_t* str, size_t len ) nssv_noexcept // (4) + { + return nonstd::sv_lite::wstring_view{ str, len }; + } #endif // nssv_CONFIG_STD_SV_OPERATOR && nssv_HAVE_STD_DEFINED_LITERALS #if nssv_CONFIG_USR_SV_OPERATOR -nssv_constexpr nonstd::sv_lite::string_view operator "" _sv( const char* str, size_t len ) nssv_noexcept // (1) -{ - return nonstd::sv_lite::string_view{ str, len }; -} + nssv_constexpr nonstd::sv_lite::string_view operator "" _sv( const char* str, size_t len ) nssv_noexcept // (1) + { + return nonstd::sv_lite::string_view{ str, len }; + } -nssv_constexpr nonstd::sv_lite::u16string_view operator "" _sv( const char16_t* str, size_t len ) nssv_noexcept // (2) -{ - return nonstd::sv_lite::u16string_view{ str, len }; -} + nssv_constexpr nonstd::sv_lite::u16string_view operator "" _sv( const char16_t* str, size_t len ) nssv_noexcept // (2) + { + return nonstd::sv_lite::u16string_view{ str, len }; + } -nssv_constexpr nonstd::sv_lite::u32string_view operator "" _sv( const char32_t* str, size_t len ) nssv_noexcept // (3) -{ - return nonstd::sv_lite::u32string_view{ str, len }; -} + nssv_constexpr nonstd::sv_lite::u32string_view operator "" _sv( const char32_t* str, size_t len ) nssv_noexcept // (3) + { + return nonstd::sv_lite::u32string_view{ str, len }; + } -nssv_constexpr nonstd::sv_lite::wstring_view operator "" _sv( const wchar_t* str, size_t len ) nssv_noexcept // (4) -{ - return nonstd::sv_lite::wstring_view{ str, len }; -} + nssv_constexpr nonstd::sv_lite::wstring_view operator "" _sv( const wchar_t* str, size_t len ) nssv_noexcept // (4) + { + return nonstd::sv_lite::wstring_view{ str, len }; + } #endif // nssv_CONFIG_USR_SV_OPERATOR -}}} // namespace nonstd::literals::string_view_literals + }}} // namespace nonstd::literals::string_view_literals #endif @@ -1174,7 +1401,7 @@ template< class CharT, class Traits, class Allocator = std::allocator > std::basic_string to_string( basic_string_view v, Allocator const & a = Allocator() ) { - return std::basic_string( v.begin(), v.end(), a ); + return std::basic_string( v.begin(), v.end(), a ); } #else @@ -1183,14 +1410,14 @@ template< class CharT, class Traits > std::basic_string to_string( basic_string_view v ) { - return std::basic_string( v.begin(), v.end() ); + return std::basic_string( v.begin(), v.end() ); } template< class CharT, class Traits, class Allocator > std::basic_string to_string( basic_string_view v, Allocator const & a ) { - return std::basic_string( v.begin(), v.end(), a ); + return std::basic_string( v.begin(), v.end(), a ); } #endif // nssv_CPP11_OR_GREATER @@ -1199,7 +1426,7 @@ template< class CharT, class Traits, class Allocator > basic_string_view to_string_view( std::basic_string const & s ) { - return basic_string_view( s.data(), s.size() ); + return basic_string_view( s.data(), s.size() ); } }} // namespace nonstd::sv_lite @@ -1256,40 +1483,40 @@ template<> struct hash< nonstd::string_view > { public: - std::size_t operator()( nonstd::string_view v ) const nssv_noexcept - { - return std::hash()( std::string( v.data(), v.size() ) ); - } + std::size_t operator()( nonstd::string_view v ) const nssv_noexcept + { + return std::hash()( std::string( v.data(), v.size() ) ); + } }; template<> struct hash< nonstd::wstring_view > { public: - std::size_t operator()( nonstd::wstring_view v ) const nssv_noexcept - { - return std::hash()( std::wstring( v.data(), v.size() ) ); - } + std::size_t operator()( nonstd::wstring_view v ) const nssv_noexcept + { + return std::hash()( std::wstring( v.data(), v.size() ) ); + } }; template<> struct hash< nonstd::u16string_view > { public: - std::size_t operator()( nonstd::u16string_view v ) const nssv_noexcept - { - return std::hash()( std::u16string( v.data(), v.size() ) ); - } + std::size_t operator()( nonstd::u16string_view v ) const nssv_noexcept + { + return std::hash()( std::u16string( v.data(), v.size() ) ); + } }; template<> struct hash< nonstd::u32string_view > { public: - std::size_t operator()( nonstd::u32string_view v ) const nssv_noexcept - { - return std::hash()( std::u32string( v.data(), v.size() ) ); - } + std::size_t operator()( nonstd::u32string_view v ) const nssv_noexcept + { + return std::hash()( std::u32string( v.data(), v.size() ) ); + } }; } // namespace std diff --git a/src/basic_types.cpp b/src/basic_types.cpp index fa562a2db..fe26bf363 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -104,7 +104,7 @@ std::string convertFromString(StringView str) template <> const char* convertFromString(StringView str) { - return nonstd::to_string(str).c_str(); + return static_cast(str).c_str(); } template <> @@ -198,7 +198,7 @@ NodeStatus convertFromString(StringView str) if( str == "RUNNING" ) return NodeStatus::RUNNING; if( str == "SUCCESS" ) return NodeStatus::SUCCESS; if( str == "FAILURE" ) return NodeStatus::FAILURE; - throw RuntimeError(std::string("Cannot convert this to NodeStatus: ") + nonstd::to_string(str) ); + throw RuntimeError(std::string("Cannot convert this to NodeStatus: ") + static_cast(str) ); } template <> @@ -289,12 +289,12 @@ Any PortInfo::parseString(const std::string &str) const void PortInfo::setDescription(StringView description) { - description_ = nonstd::to_string(description); + description_ = static_cast(description); } void PortInfo::setDefaultValue(StringView default_value_as_string) { - default_value_ = nonstd::to_string(default_value_as_string); + default_value_ = static_cast(default_value_as_string); } const std::string &PortInfo::description() const diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 94dbb263e..696d5ea29 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -518,7 +518,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, auto param_res = TreeNode::getRemappedKey(port_name, param_value); if( param_res ) { - const auto& port_key = nonstd::to_string(param_res.value()); + const auto port_key = static_cast(param_res.value()); auto prev_info = blackboard->portInfo( port_key ); if( !prev_info ) From 8842f82d994f821019ff1238819bbf4db57b1059 Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Sun, 19 Apr 2020 21:15:31 +0200 Subject: [PATCH 011/709] minor change --- include/behaviortree_cpp_v3/basic_types.h | 3 +++ src/basic_types.cpp | 6 ++++++ 2 files changed, 9 insertions(+) diff --git a/include/behaviortree_cpp_v3/basic_types.h b/include/behaviortree_cpp_v3/basic_types.h index d451da499..a9392ccf9 100644 --- a/include/behaviortree_cpp_v3/basic_types.h +++ b/include/behaviortree_cpp_v3/basic_types.h @@ -81,6 +81,9 @@ int convertFromString(StringView str); template <> unsigned convertFromString(StringView str); +template <> +long convertFromString(StringView str); + template <> double convertFromString(StringView str); diff --git a/src/basic_types.cpp b/src/basic_types.cpp index fe26bf363..293c02d9a 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -113,6 +113,12 @@ int convertFromString(StringView str) return std::stoi(str.data()); } +template <> +long convertFromString(StringView str) +{ + return std::stol(str.data()); +} + template <> unsigned convertFromString(StringView str) { From d9ffa1f699e7c1dff2425072221afe58050bf47b Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Sun, 19 Apr 2020 21:17:08 +0200 Subject: [PATCH 012/709] 3.4.0 --- package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package.xml b/package.xml index b21194b99..8baf49f61 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.3.0 + 3.4.0 This package provides the Behavior Trees core library. From c831e0a7473992305626a1de4f5fd8f60719b129 Mon Sep 17 00:00:00 2001 From: "daf@blue-ocean-robotics.com" Date: Wed, 29 Apr 2020 11:06:41 +0200 Subject: [PATCH 013/709] added function const std::string& key (issue #183) --- include/behaviortree_cpp_v3/tree_node.h | 4 ++++ src/tree_node.cpp | 13 +++++++++++++ 2 files changed, 17 insertions(+) diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index 6f505ef83..aa39138c2 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -138,6 +138,10 @@ class TreeNode template Result setOutput(const std::string& key, const T& value); + // function provide mostrly for debugging purpose to see the raw value + // in the port (no remapping and no conversion to a type) + StringView getRawPortValue(const std::string &key) const; + /// Check a string and return true if it matches either one of these /// two patterns: {...} or ${...} static bool isBlackboardPointer(StringView str); diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 74411c92b..7b71f46cd 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -101,6 +101,19 @@ const NodeConfiguration &TreeNode::config() const return config_; } +StringView TreeNode::getRawPortValue(const std::string& key) const +{ + auto remap_it = config_.input_ports.find(key); + if (remap_it == config_.input_ports.end()) + { + throw std::logic_error(StrCat("getInput() failed because " + "NodeConfiguration::input_ports " + "does not contain the key: [", + key, "]")); + } + return remap_it->second; +} + bool TreeNode::isBlackboardPointer(StringView str) { const auto size = str.size(); From 5c0c83510de3e6a8000fbb02c4e9dd7ace53653d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 6 May 2020 22:50:52 +0200 Subject: [PATCH 014/709] Fix issue #188 --- src/blackboard.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/blackboard.cpp b/src/blackboard.cpp index 667ba1440..f86fdddae 100644 --- a/src/blackboard.cpp +++ b/src/blackboard.cpp @@ -74,6 +74,9 @@ void Blackboard::debugMessage() const std::vector Blackboard::getKeys() const { + if( storage_.empty() ){ + return {}; + } std::vector out; out.reserve( storage_.size() ); for(const auto& entry_it: storage_) From c66fc239f2b272a2a422f5bee2b8038a4d288da0 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 May 2020 00:47:22 +0200 Subject: [PATCH 015/709] RemappedSubTree added --- .../decorators/subtree_node.h | 21 ++++++++ src/bt_factory.cpp | 1 + src/decorators/subtree_node.cpp | 17 +++++++ src/xml_parsing.cpp | 49 ++++++++++--------- 4 files changed, 65 insertions(+), 23 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/subtree_node.h b/include/behaviortree_cpp_v3/decorators/subtree_node.h index 54b604875..8c622775f 100644 --- a/include/behaviortree_cpp_v3/decorators/subtree_node.h +++ b/include/behaviortree_cpp_v3/decorators/subtree_node.h @@ -28,6 +28,27 @@ class SubtreeNode : public DecoratorNode } }; +/** + * @brief Subtree that doesn't need any remapping. + * Its blackboard is shared with the parent node + */ +class RemappedSubtreeNode : public DecoratorNode +{ +public: + RemappedSubtreeNode(const std::string& name); + + virtual ~RemappedSubtreeNode() override = default; + +private: + virtual BT::NodeStatus tick() override; + + virtual NodeType type() const override final + { + return NodeType::SUBTREE; + } +}; + + /** * @brief The SubtreePlus is a new kind of subtree that gives you much more control over remapping: * diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 1a35c474f..b789b2016 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -44,6 +44,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("SubTree"); registerNodeType("SubTreePlus"); + registerNodeType("RemappedSubTree"); registerNodeType>("BlackboardCheckInt"); registerNodeType>("BlackboardCheckDouble"); diff --git a/src/decorators/subtree_node.cpp b/src/decorators/subtree_node.cpp index ea518ddb8..525aab3df 100644 --- a/src/decorators/subtree_node.cpp +++ b/src/decorators/subtree_node.cpp @@ -17,6 +17,23 @@ BT::NodeStatus BT::SubtreeNode::tick() return child_node_->executeTick(); } +//-------------------------------- +BT::RemappedSubtreeNode::RemappedSubtreeNode(const std::string &name) : + DecoratorNode(name, {} ) +{ + setRegistrationID("RemappedSubtree"); +} + +BT::NodeStatus BT::RemappedSubtreeNode::tick() +{ + NodeStatus prev_status = status(); + if (prev_status == NodeStatus::IDLE) + { + setStatus(NodeStatus::RUNNING); + } + return child_node_->executeTick(); +} + //-------------------------------- BT::SubtreePlusNode::SubtreePlusNode(const std::string &name) : DecoratorNode(name, {} ) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 696d5ea29..5f0eea8d7 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -14,9 +14,9 @@ #include #if defined(__linux) || defined(__linux__) - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wattributes" -#endif + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wattributes" +#endif #ifdef _MSC_VER #pragma warning(disable : 4996) // do not complain about sprintf @@ -352,7 +352,7 @@ void VerifyXML(const std::string& xml_text, } //recursion if (StrEqual(name, "SubTree") == false) - { + { for (auto child = node->FirstChildElement(); child != nullptr; child = child->NextSiblingElement()) { @@ -462,23 +462,22 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, instance_name = ID; } + PortsRemapping port_remap; + if (element_name == "SubTree" || - element_name == "SubTreePlus" ) + element_name == "SubTreePlus" || + element_name == "RemappedSubTree") { instance_name = element->Attribute("ID"); } - - PortsRemapping parameters_map; - - // in Subtree attributes have different meaning... - if (element_name != "SubTree" && element_name != "SubTreePlus") - { + else{ + // do this only if it NOT a Subtree for (const XMLAttribute* att = element->FirstAttribute(); att; att = att->Next()) { const std::string attribute_name = att->Name(); if (attribute_name != "ID" && attribute_name != "name") { - parameters_map[attribute_name] = att->Value(); + port_remap[attribute_name] = att->Value(); } } } @@ -493,12 +492,12 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, const auto& manifest = factory.manifests().at(ID); //Check that name in remapping can be found in the manifest - for(const auto& param_it: parameters_map) + for(const auto& remap_it: port_remap) { - if( manifest.ports.count( param_it.first ) == 0 ) + if( manifest.ports.count( remap_it.first ) == 0 ) { throw RuntimeError("Possible typo? In the XML, you tried to remap port \"", - param_it.first, "\" in node [", ID," / ", instance_name, + remap_it.first, "\" in node [", ID," / ", instance_name, "], but the manifest of this node does not contain a port with this name."); } } @@ -509,8 +508,8 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, const std::string& port_name = port_it.first; const auto& port_info = port_it.second; - auto remap_it = parameters_map.find(port_name); - if( remap_it == parameters_map.end()) + auto remap_it = port_remap.find(port_name); + if( remap_it == port_remap.end()) { continue; } @@ -543,20 +542,20 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, } // use manifest to initialize NodeConfiguration - for(const auto& param_it: parameters_map) + for(const auto& remap_it: port_remap) { - const auto& port_name = param_it.first; + const auto& port_name = remap_it.first; auto port_it = manifest.ports.find( port_name ); if( port_it != manifest.ports.end() ) { auto direction = port_it->second.direction(); if( direction != PortDirection::OUTPUT ) { - config.input_ports.insert( param_it ); + config.input_ports.insert( remap_it ); } if( direction != PortDirection::INPUT ) { - config.output_ports.insert( param_it ); + config.output_ports.insert( remap_it ); } } } @@ -612,7 +611,11 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, if( node->type() == NodeType::SUBTREE ) { - if( dynamic_cast(node.get()) ) + if( dynamic_cast(node.get()) ) + { + recursivelyCreateTree( node->name(), output_tree, blackboard, node ); + } + else if( dynamic_cast(node.get()) ) { // This is the former SubTree with manual remapping auto new_bb = Blackboard::create(blackboard); @@ -630,7 +633,7 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, } else if( dynamic_cast(node.get()) ) { - auto new_bb = Blackboard::create(blackboard); + auto new_bb = Blackboard::create(blackboard); output_tree.blackboard_stack.emplace_back(new_bb); std::set mapped_keys; From eb9f0645441492bb82918a954398676ea4537381 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 May 2020 01:25:20 +0200 Subject: [PATCH 016/709] reverting to a better solution --- .../decorators/subtree_node.h | 32 ++++++++----------- src/bt_factory.cpp | 1 - src/decorators/subtree_node.cpp | 16 ---------- src/xml_parsing.cpp | 28 +++++++++++----- 4 files changed, 33 insertions(+), 44 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/subtree_node.h b/include/behaviortree_cpp_v3/decorators/subtree_node.h index 8c622775f..f9ae66d40 100644 --- a/include/behaviortree_cpp_v3/decorators/subtree_node.h +++ b/include/behaviortree_cpp_v3/decorators/subtree_node.h @@ -22,31 +22,19 @@ class SubtreeNode : public DecoratorNode private: virtual BT::NodeStatus tick() override; + static PortsList providedPorts() + { + return { InputPort("__shared_blackboard", false, + "If false (default) the subtree has its own blackboard and you" + "need to do port remapping to connect it to the parent") }; + } + virtual NodeType type() const override final { return NodeType::SUBTREE; } }; -/** - * @brief Subtree that doesn't need any remapping. - * Its blackboard is shared with the parent node - */ -class RemappedSubtreeNode : public DecoratorNode -{ -public: - RemappedSubtreeNode(const std::string& name); - - virtual ~RemappedSubtreeNode() override = default; - -private: - virtual BT::NodeStatus tick() override; - - virtual NodeType type() const override final - { - return NodeType::SUBTREE; - } -}; /** @@ -99,6 +87,12 @@ class SubtreePlusNode : public DecoratorNode private: virtual BT::NodeStatus tick() override; + static PortsList providedPorts() + { + return { InputPort("__autoremap", false, + "If true, all the ports with the same name will be remapped") }; + } + virtual NodeType type() const override final { return NodeType::SUBTREE; diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index b789b2016..1a35c474f 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -44,7 +44,6 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("SubTree"); registerNodeType("SubTreePlus"); - registerNodeType("RemappedSubTree"); registerNodeType>("BlackboardCheckInt"); registerNodeType>("BlackboardCheckDouble"); diff --git a/src/decorators/subtree_node.cpp b/src/decorators/subtree_node.cpp index 525aab3df..20ffaf502 100644 --- a/src/decorators/subtree_node.cpp +++ b/src/decorators/subtree_node.cpp @@ -17,22 +17,6 @@ BT::NodeStatus BT::SubtreeNode::tick() return child_node_->executeTick(); } -//-------------------------------- -BT::RemappedSubtreeNode::RemappedSubtreeNode(const std::string &name) : - DecoratorNode(name, {} ) -{ - setRegistrationID("RemappedSubtree"); -} - -BT::NodeStatus BT::RemappedSubtreeNode::tick() -{ - NodeStatus prev_status = status(); - if (prev_status == NodeStatus::IDLE) - { - setStatus(NodeStatus::RUNNING); - } - return child_node_->executeTick(); -} //-------------------------------- BT::SubtreePlusNode::SubtreePlusNode(const std::string &name) : diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 5f0eea8d7..cea398582 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -465,8 +465,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, PortsRemapping port_remap; if (element_name == "SubTree" || - element_name == "SubTreePlus" || - element_name == "RemappedSubTree") + element_name == "SubTreePlus" ) { instance_name = element->Attribute("ID"); } @@ -611,13 +610,25 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, if( node->type() == NodeType::SUBTREE ) { - if( dynamic_cast(node.get()) ) + if( dynamic_cast(node.get()) ) { - recursivelyCreateTree( node->name(), output_tree, blackboard, node ); - } - else if( dynamic_cast(node.get()) ) - { - // This is the former SubTree with manual remapping + bool is_isolated = true; + + for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) + { + if( strcmp(attr->Name(), "__shared_blackboard") == 0 && + convertFromString(attr->Value()) == true ) + { + is_isolated = false; + } + } + + if( !is_isolated ) + { + recursivelyCreateTree( node->name(), output_tree, blackboard, node ); + } + else{ + // Creating an isolated auto new_bb = Blackboard::create(blackboard); for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) @@ -630,6 +641,7 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, } output_tree.blackboard_stack.emplace_back(new_bb); recursivelyCreateTree( node->name(), output_tree, new_bb, node ); + } } else if( dynamic_cast(node.get()) ) { From 47be42054265cbc9b8d8d6cf1d40066903a3d5d6 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 May 2020 01:35:07 +0200 Subject: [PATCH 017/709] unit test added --- tests/gtest_subtree.cpp | 31 +++++++++++++++++++++++++++++++ 1 file changed, 31 insertions(+) diff --git a/tests/gtest_subtree.cpp b/tests/gtest_subtree.cpp index 8c182cc69..10ee48660 100644 --- a/tests/gtest_subtree.cpp +++ b/tests/gtest_subtree.cpp @@ -202,4 +202,35 @@ TEST(SubTree, SubtreePlusB) ASSERT_EQ(ret, NodeStatus::SUCCESS ); } +TEST(SubTree, SubtreePlusC) +{ + static const char* xml_text = R"( + + + + + + + + + + + + + + + + + + )"; + + BehaviorTreeFactory factory; + factory.registerNodeType("SaySomething"); + + Tree tree = factory.createTreeFromText(xml_text); + auto ret = tree.tickRoot(); + ASSERT_EQ(ret, NodeStatus::SUCCESS ); +} + + From 9eddc315f21c7d444782b7b97c084170671254a6 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 May 2020 17:14:53 +0200 Subject: [PATCH 018/709] issue #190 --- .../controls/switch_node.h | 23 +++++++++++++++++-- 1 file changed, 21 insertions(+), 2 deletions(-) diff --git a/include/behaviortree_cpp_v3/controls/switch_node.h b/include/behaviortree_cpp_v3/controls/switch_node.h index 46dbc818f..5095bf825 100644 --- a/include/behaviortree_cpp_v3/controls/switch_node.h +++ b/include/behaviortree_cpp_v3/controls/switch_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2020-2020 Davide Faconti - All Rights Reserved +/* Copyright (C) 2020 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, @@ -18,7 +18,26 @@ namespace BT { /** - * @brief The SwitchNode + * @brief The SwitchNode is equivalent to a switch statement, where a certain + * branch (child) is executed according to the value of a blackboard entry. + * + * Note that the same behaviour can be achieved with multiple Sequences, Fallbacks and + * Conditions reading the blackboard, but switch is shorter and more readable. + * + * Example usage: + * + + + + + + + + +When the SwitchNode is executed (Switch3 is a node with 3 cases) +the "variable" will be compared to the cases and execute the correct child +or the default one (last). + * */ template From 5b4890dea1c60e0f584e1333021cf70afc17c9ff Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 May 2020 17:17:22 +0200 Subject: [PATCH 019/709] added IfThenElse and WhileDoElse --- CMakeLists.txt | 2 + include/behaviortree_cpp_v3/behavior_tree.h | 2 + .../controls/if_then_else_node.h | 52 ++++++++++++ .../controls/while_do_else_node.h | 50 +++++++++++ src/bt_factory.cpp | 2 + src/controls/if_then_else_node.cpp | 83 +++++++++++++++++++ src/controls/while_do_else_node.cpp | 72 ++++++++++++++++ 7 files changed, 263 insertions(+) create mode 100644 include/behaviortree_cpp_v3/controls/if_then_else_node.h create mode 100644 include/behaviortree_cpp_v3/controls/while_do_else_node.h create mode 100644 src/controls/if_then_else_node.cpp create mode 100644 src/controls/while_do_else_node.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index faba3e572..69bf801db 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -163,6 +163,7 @@ list(APPEND BT_SOURCE src/decorators/subtree_node.cpp src/decorators/timeout_node.cpp + src/controls/if_then_else_node.cpp src/controls/fallback_node.cpp src/controls/parallel_node.cpp src/controls/reactive_sequence.cpp @@ -170,6 +171,7 @@ list(APPEND BT_SOURCE src/controls/sequence_node.cpp src/controls/sequence_star_node.cpp src/controls/switch_node.cpp + src/controls/while_do_else_node.cpp src/loggers/bt_cout_logger.cpp src/loggers/bt_file_logger.cpp diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index 83eef0dce..5e2dc8d0c 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -22,6 +22,8 @@ #include "behaviortree_cpp_v3/controls/sequence_star_node.h" #include "behaviortree_cpp_v3/controls/switch_node.h" #include "behaviortree_cpp_v3/controls/manual_node.h" +#include "behaviortree_cpp_v3/controls/if_then_else_node.h" +#include "behaviortree_cpp_v3/controls/while_do_else_node.h" #include "behaviortree_cpp_v3/action_node.h" #include "behaviortree_cpp_v3/condition_node.h" diff --git a/include/behaviortree_cpp_v3/controls/if_then_else_node.h b/include/behaviortree_cpp_v3/controls/if_then_else_node.h new file mode 100644 index 000000000..2e1ab401e --- /dev/null +++ b/include/behaviortree_cpp_v3/controls/if_then_else_node.h @@ -0,0 +1,52 @@ +/* Copyright (C) 2020 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_IF_THEN_ELSE_H +#define BT_IF_THEN_ELSE_H + +#include "behaviortree_cpp_v3/control_node.h" + +namespace BT +{ +/** + * @brief IfThenElseNode must have exactly 2 or 3 children. This node is NOT reactive. + * + * The first child is the "statement" of the if. + * + * If that return SUCCESS, then the second child is executed. + * + * Instead, if it returned FAILURE, the third child is executed. + * + * If you have only 2 children, this node will return FAILURE whenever the + * statement returns FAILURE. + * + * This is equivalent to add AlwaysFailure as 3rd child. + * + */ +class IfThenElseNode : public ControlNode +{ + public: + IfThenElseNode(const std::string& name); + + virtual ~IfThenElseNode() override = default; + + virtual void halt() override; + + private: + size_t child_idx_; + + virtual BT::NodeStatus tick() override; +}; + +} + +#endif // BT_IF_THEN_ELSE_H diff --git a/include/behaviortree_cpp_v3/controls/while_do_else_node.h b/include/behaviortree_cpp_v3/controls/while_do_else_node.h new file mode 100644 index 000000000..21d393a92 --- /dev/null +++ b/include/behaviortree_cpp_v3/controls/while_do_else_node.h @@ -0,0 +1,50 @@ +/* Copyright (C) 2020 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_WHILE_DO_ELSE_H +#define BT_WHILE_DO_ELSE_H + +#include "behaviortree_cpp_v3/control_node.h" + +namespace BT +{ +/** + * @brief WhileDoElse must have exactly 2 or 3 children. + * It is a REACTIVE node of IfThenElseNode. + * + * The first child is the "statement" that is executed at each tick + * + * If result is SUCCESS, the second child is executed. + * + * If result is FAILURE, the third child is executed. + * + * If the 2nd or 3d child is RUNNING and the statement changes, + * the RUNNING child will be stopped before starting the sibling. + * + */ +class WhileDoElseNode : public ControlNode +{ + public: + WhileDoElseNode(const std::string& name); + + virtual ~WhileDoElseNode() override = default; + + virtual void halt() override; + + private: + + virtual BT::NodeStatus tick() override; +}; + +} + +#endif // BT_WHILE_DO_ELSE_H diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 1a35c474f..c48aef0c9 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -29,6 +29,8 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("Parallel"); registerNodeType("ReactiveSequence"); registerNodeType("ReactiveFallback"); + registerNodeType("IfThenElse"); + registerNodeType("WhileDoElse"); registerNodeType("Inverter"); registerNodeType("RetryUntilSuccesful"); diff --git a/src/controls/if_then_else_node.cpp b/src/controls/if_then_else_node.cpp new file mode 100644 index 000000000..bdba763e3 --- /dev/null +++ b/src/controls/if_then_else_node.cpp @@ -0,0 +1,83 @@ +/* Copyright (C) 2020 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 "behaviortree_cpp_v3/controls/if_then_else_node.h" + + +namespace BT +{ + +IfThenElseNode::IfThenElseNode(const std::string &name) + : ControlNode::ControlNode(name, {} ) + , child_idx_(0) +{ + setRegistrationID("IfThenElse"); +} + +void IfThenElseNode::halt() +{ + child_idx_ = 0; + ControlNode::halt(); +} + +NodeStatus IfThenElseNode::tick() +{ + const size_t children_count = children_nodes_.size(); + + if(children_count != 2 && children_count != 3) + { + throw std::logic_error("IfThenElseNode must have either 2 or 3 children"); + } + + setStatus(NodeStatus::RUNNING); + + if (child_idx_ == 0) + { + NodeStatus condition_status = children_nodes_[0]->executeTick(); + + if (condition_status == NodeStatus::RUNNING) + { + return condition_status; + } + else if (condition_status == NodeStatus::SUCCESS) + { + child_idx_ = 1; + } + else if (condition_status == NodeStatus::FAILURE) + { + if( children_count == 3){ + child_idx_ = 2; + } + else{ + return condition_status; + } + } + } + // not an else + if (child_idx_ > 0) + { + NodeStatus status = children_nodes_[child_idx_]->executeTick(); + if (status == NodeStatus::RUNNING) + { + return NodeStatus::RUNNING; + } + else{ + haltChildren(); + child_idx_ = 0; + return status; + } + } + + throw std::logic_error("Something unexpected happened in IfThenElseNode"); +} + +} // namespace BT diff --git a/src/controls/while_do_else_node.cpp b/src/controls/while_do_else_node.cpp new file mode 100644 index 000000000..4757e2730 --- /dev/null +++ b/src/controls/while_do_else_node.cpp @@ -0,0 +1,72 @@ +/* Copyright (C) 2020 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 "behaviortree_cpp_v3/controls/while_do_else_node.h" + + +namespace BT +{ + +WhileDoElseNode::WhileDoElseNode(const std::string &name) + : ControlNode::ControlNode(name, {} ) +{ + setRegistrationID("WhileDoElse"); +} + +void WhileDoElseNode::halt() +{ + ControlNode::halt(); +} + +NodeStatus WhileDoElseNode::tick() +{ + const size_t children_count = children_nodes_.size(); + + if(children_count != 3) + { + throw std::logic_error("WhileDoElse must have either 2 or 3 children"); + } + + setStatus(NodeStatus::RUNNING); + + NodeStatus condition_status = children_nodes_[0]->executeTick(); + + if (condition_status == NodeStatus::RUNNING) + { + return condition_status; + } + + NodeStatus status = NodeStatus::IDLE; + + if (condition_status == NodeStatus::SUCCESS) + { + haltChild(2); + status = children_nodes_[1]->executeTick(); + } + else if (condition_status == NodeStatus::FAILURE) + { + haltChild(1); + status = children_nodes_[2]->executeTick(); + } + + if (status == NodeStatus::RUNNING) + { + return NodeStatus::RUNNING; + } + else + { + haltChildren(); + return status; + } +} + +} // namespace BT From 9fd7ae33c59fdb047b68e40aa135760647fce2e2 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 May 2020 18:16:43 +0200 Subject: [PATCH 020/709] changelog update --- CHANGELOG.rst | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 72d34214d..72b907900 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -96,6 +96,26 @@ Changelog for package behaviortree_cpp On Windows not only MSVC compilator. * Contributors: 3wnbr1, Christopher Torres, Davide Faconti, HansRobo, ImgBotApp, Jesus, Kotaro Yoshimoto, Mateusz Sadowski, Peter Polidoro, Sean Yen, Sebastian Ahlman, Steffen Groot, Vadim Linevich, renan028 +Forthcoming +----------- +* added IfThenElse and WhileDoElse +* issue `#190 `_ +* unit test added +* reverting to a better solution +* RemappedSubTree added +* Fix issue `#188 `_ +* added function const std::string& key (issue `#183 `_) +* Contributors: Davide Faconti, daf@blue-ocean-robotics.com + +* added IfThenElse and WhileDoElse +* issue `#190 `_ +* unit test added +* reverting to a better solution +* RemappedSubTree added +* Fix issue `#188 `_ +* added function const std::string& key (issue `#183 `_) +* Contributors: Davide Faconti, daf@blue-ocean-robotics.com + 3.1.1 (2019-11-10) ------------------ * fix samples compilation (hopefully) From 366ace1cf435968ed58699acdd0afb68eb3e90ba Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 May 2020 18:16:47 +0200 Subject: [PATCH 021/709] 3.5.0 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 72b907900..c761ad888 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -96,8 +96,8 @@ Changelog for package behaviortree_cpp On Windows not only MSVC compilator. * Contributors: 3wnbr1, Christopher Torres, Davide Faconti, HansRobo, ImgBotApp, Jesus, Kotaro Yoshimoto, Mateusz Sadowski, Peter Polidoro, Sean Yen, Sebastian Ahlman, Steffen Groot, Vadim Linevich, renan028 -Forthcoming ------------ +3.5.0 (2020-05-14) +------------------ * added IfThenElse and WhileDoElse * issue `#190 `_ * unit test added diff --git a/package.xml b/package.xml index 8baf49f61..910e94d3f 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.4.0 + 3.5.0 This package provides the Behavior Trees core library. From 082685cd2d0126c4d4c8565ebd20a70e5a91fc02 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 May 2020 23:24:20 +0200 Subject: [PATCH 022/709] Update README.md --- README.md | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/README.md b/README.md index ab5ac9799..0833fe230 100644 --- a/README.md +++ b/README.md @@ -43,7 +43,7 @@ You can learn about the main concepts, the API and the tutorials here: https://w To find more details about the conceptual ideas that make this implementation different from others, you can read the [final deliverable of the project MOOD2Be](https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/MOOD2Be_final_report.pdf). -# About version 3.3 and above +# Design principles The main goal of this project is to create a Behavior Tree implementation that uses the principles of Model Driven Development to separate the role @@ -55,14 +55,15 @@ In practice, this means that: You should be able to implement them once and reuse them to build many behaviors. - To build a Behavior Tree out of TreeNodes, the Behavior Designer must -not need to read nor modify the source code of a given TreeNode. +not need to read nor modify the C++ source code of a given TreeNode. -Version __3.3+__ of this library introduces some dramatic changes in the API, but -it was necessary to reach this goal. +- Complex Behaviours must be composable using Subtrees -If you used version 2.X in the past, you can -[find the Migration Guide here](https://behaviortree.github.io/BehaviorTree.CPP/MigrationGuide). +Many of the features and, sometimes, the apparent limitations of this library, might be a consequence +of this design principle. +For instance, having a scoped BlackBoard, visible only in a portion of the tree, is particularly important +to avoid "name pollution" and allow the creation of large scale trees. # GUI Editor @@ -80,13 +81,13 @@ the graphic user interface are used to design and monitor a Behavior Tree. [![MOOD2Be](docs/video_MOOD2Be.png)](https://vimeo.com/304651183) -# How to compile (plain old cmake +# How to compile (plain old cmake) On Ubuntu, you are encourage to install the following dependencies: sudo apt-get install libzmq3-dev libboost-dev -Other dependency is already included in the __3rdparty__ folder. +Other dependencies are already included in the __3rdparty__ folder. To compile and install the library, from the BehaviorTree.CPP folder, execute: @@ -95,7 +96,8 @@ To compile and install the library, from the BehaviorTree.CPP folder, execute: make sudo make install -Your typical **CMakeLists.txt** file will look like this: +If you want to use BT.CPp in your application a typical **CMakeLists.txt** file +will look like this: ```cmake cmake_minimum_required(VERSION 3.5) @@ -145,7 +147,6 @@ published by CRC Press Taylor & Francis, available for purchase The Preprint version (free) is available here: https://arxiv.org/abs/1709.00084 - # License The MIT License (MIT) From 68f2cc70f5d74d8fb4c3e29e562c7d39fd519c2d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 14 May 2020 23:24:32 +0200 Subject: [PATCH 023/709] Update README.md --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 0833fe230..56524e51e 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,5 @@ ![License MIT](https://img.shields.io/dub/l/vibe-d.svg) -![Version](https://img.shields.io/badge/version-v3.3-green.svg) +![Version](https://img.shields.io/badge/version-v3.5-green.svg) Travis (Linux): [![Build Status](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP.svg?branch=master)](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP) From 3190e20c5fb9fc0e3f5ab856ca3b21cc673e0e5a Mon Sep 17 00:00:00 2001 From: Ting Chang Date: Sat, 16 May 2020 04:39:23 +0800 Subject: [PATCH 024/709] Fix pseudocode for ReactiveFallback. (#191) --- docs/FallbackNode.md | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/docs/FallbackNode.md b/docs/FallbackNode.md index 750d71fae..3d6789ad3 100644 --- a/docs/FallbackNode.md +++ b/docs/FallbackNode.md @@ -81,13 +81,11 @@ if he/she is fully rested. // index is initialized to 0 in the constructor status = RUNNING; - while( index < number_of_children ) + 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 == FAILURE ) { From b48b52d59a6189531c1c8a3978558118f2d84042 Mon Sep 17 00:00:00 2001 From: Sean Yen Date: Fri, 15 May 2020 13:44:37 -0700 Subject: [PATCH 025/709] [Windows] Compare `std::type_info` objects to check type. (#181) --- src/xml_parsing.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index cea398582..2181a0aca 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -527,7 +527,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, else{ // found. check consistency if( prev_info->type() && port_info.type() && // null type means that everything is valid - prev_info->type()!= port_info.type()) + *prev_info->type() != *port_info.type()) { blackboard->debugMessage(); From 162d5b2e69c51cdbe772f836e3a7f4183fbaeed9 Mon Sep 17 00:00:00 2001 From: Aayush Naik Date: Fri, 15 May 2020 15:32:01 -0700 Subject: [PATCH 026/709] Fix typo --- docs/SequenceNode.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/SequenceNode.md b/docs/SequenceNode.md index 094141f05..302669b88 100644 --- a/docs/SequenceNode.md +++ b/docs/SequenceNode.md @@ -1,6 +1,6 @@ # Sequences -A __Sequence__ ticks all it's children as long as +A __Sequence__ ticks all its children as long as they return SUCCESS. If any child returns FAILURE, the sequence is aborted. Currently the framework provides three kinds of nodes: From 4d055f283a63ddba89f18f3f85ced045d14eb0c2 Mon Sep 17 00:00:00 2001 From: Sarathkrishnan Ramesh Date: Sat, 16 May 2020 20:14:21 +0530 Subject: [PATCH 027/709] Add XML parsing support for custom Control Nodes (#194) Signed-off-by: Sarathkrishnan Ramesh --- src/xml_parsing.cpp | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 2181a0aca..62d0e4562 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -251,7 +251,7 @@ void VerifyXML(const std::string& xml_text, { const char* name = node->Name(); if (StrEqual(name, "Action") || StrEqual(name, "Decorator") || - StrEqual(name, "SubTree") || StrEqual(name, "Condition")) + StrEqual(name, "SubTree") || StrEqual(name, "Condition") || StrEqual(name, "Control")) { const char* ID = node->Attribute("ID"); if (!ID) @@ -309,6 +309,19 @@ void VerifyXML(const std::string& xml_text, "The node must have the attribute [ID]"); } } + else if (StrEqual(name, "Control")) + { + if (children_count == 0) + { + ThrowError(node->GetLineNum(), + "The node must have at least 1 child"); + } + if (!node->Attribute("ID")) + { + ThrowError(node->GetLineNum(), + "The node must have the attribute [ID]"); + } + } else if (StrEqual(name, "Sequence") || StrEqual(name, "SequenceStar") || StrEqual(name, "Fallback") ) @@ -443,7 +456,8 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, std::string instance_name; // Actions and Decorators have their own ID - if (element_name == "Action" || element_name == "Decorator" || element_name == "Condition") + if (element_name == "Action" || element_name == "Decorator" || + element_name == "Condition" || element_name == "Control") { ID = element->Attribute("ID"); } From 6e0512b26ecb7a672d480cd6bbe8654d66e0dc8b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 16 May 2020 21:27:15 +0200 Subject: [PATCH 028/709] updated doc --- docs/tutorial_01_first_tree.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/tutorial_01_first_tree.md b/docs/tutorial_01_first_tree.md index 5193ee1c3..a73c379fe 100644 --- a/docs/tutorial_01_first_tree.md +++ b/docs/tutorial_01_first_tree.md @@ -168,7 +168,7 @@ int main() // The tick is propagated to the children based on the logic of the tree. // In this case, the entire sequence is executed, because all the children // of the Sequence return SUCCESS. - tree.root_node->executeTick(); + tree.tickRoot(); return 0; } From 3d22c6f020f158275aa1d8219738c528aee6f449 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Sat, 16 May 2020 21:32:29 +0200 Subject: [PATCH 029/709] Adding ForceRunningNode Decorator (#192) --- include/behaviortree_cpp_v3/behavior_tree.h | 1 + .../keep_running_until_failure_node.h | 66 +++++++++++++++++++ src/bt_factory.cpp | 1 + 3 files changed, 68 insertions(+) create mode 100644 include/behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index 5e2dc8d0c..92394aab2 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -39,6 +39,7 @@ #include "behaviortree_cpp_v3/decorators/force_success_node.h" #include "behaviortree_cpp_v3/decorators/force_failure_node.h" +#include "behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h" #include "behaviortree_cpp_v3/decorators/blackboard_precondition.h" #include "behaviortree_cpp_v3/decorators/timeout_node.h" diff --git a/include/behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h b/include/behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h new file mode 100644 index 000000000..af9c88fba --- /dev/null +++ b/include/behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h @@ -0,0 +1,66 @@ +/* Copyright (C) 2018-2020 Davide Faconti, Eurecat - All Rights Reserved +* Copyright (C) 2020 Francisco Martin, Intelligent Robotics Lab (URJC) +* +* 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_KEEP_RUNNING_UNTIL_FAILURE_H +#define DECORATOR_KEEP_RUNNING_UNTIL_FAILURE_H + +#include "behaviortree_cpp_v3/decorator_node.h" + +namespace BT +{ +/** + * @brief The KeepRunningUntilFailureNode returns always FAILURE or RUNNING. + */ +class KeepRunningUntilFailureNode : public DecoratorNode +{ + public: + KeepRunningUntilFailureNode(const std::string& name) : + DecoratorNode(name, {} ) + { + setRegistrationID("KeepRunningUntilFailure"); + } + + private: + virtual BT::NodeStatus tick() override; +}; + +//------------ implementation ---------------------------- + +inline NodeStatus KeepRunningUntilFailureNode::tick() +{ + setStatus(NodeStatus::RUNNING); + + const NodeStatus child_state = child_node_->executeTick(); + + switch (child_state) + { + case NodeStatus::FAILURE: + { + return NodeStatus::FAILURE; + } + case NodeStatus::SUCCESS: + case NodeStatus::RUNNING: + { + return NodeStatus::RUNNING; + } + + default: + { + // TODO throw? + } + } + return status(); +} +} + +#endif diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index c48aef0c9..9f01e206f 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -34,6 +34,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("Inverter"); registerNodeType("RetryUntilSuccesful"); + registerNodeType("KeepRunningUntilFailure"); registerNodeType("Repeat"); registerNodeType("Timeout"); From 561f4fa86b45c64c9bb2fd3273f81363e6fd222f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 16 May 2020 22:15:21 +0200 Subject: [PATCH 030/709] Create FUNDING.yml --- .github/FUNDING.yml | 4 ++++ 1 file changed, 4 insertions(+) create mode 100644 .github/FUNDING.yml diff --git a/.github/FUNDING.yml b/.github/FUNDING.yml new file mode 100644 index 000000000..accb08cd7 --- /dev/null +++ b/.github/FUNDING.yml @@ -0,0 +1,4 @@ +# These are supported funding model platforms + +github: facontidavide +custom: https://www.paypal.me/facontidavide From 003c8e614f77b9a51dc4aa7e70f56974a27df60c Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 29 May 2020 10:26:20 +0200 Subject: [PATCH 031/709] Always use nonstd::string_view for binary compatibility (fix issue #200) --- include/behaviortree_cpp_v3/utils/string_view.hpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/include/behaviortree_cpp_v3/utils/string_view.hpp b/include/behaviortree_cpp_v3/utils/string_view.hpp index adf178b3d..aa52d94ee 100644 --- a/include/behaviortree_cpp_v3/utils/string_view.hpp +++ b/include/behaviortree_cpp_v3/utils/string_view.hpp @@ -26,9 +26,12 @@ #define nssv_STRING_VIEW_NONSTD 1 #define nssv_STRING_VIEW_STD 2 -#if !defined( nssv_CONFIG_SELECT_STRING_VIEW ) -# define nssv_CONFIG_SELECT_STRING_VIEW ( nssv_HAVE_STD_STRING_VIEW ? nssv_STRING_VIEW_STD : nssv_STRING_VIEW_NONSTD ) -#endif +// forced by BehaviorTree.CPP +#define nssv_CONFIG_SELECT_STRING_VIEW nssv_STRING_VIEW_NONSTD + +//#if !defined( nssv_CONFIG_SELECT_STRING_VIEW ) +//# define nssv_CONFIG_SELECT_STRING_VIEW ( nssv_HAVE_STD_STRING_VIEW ? nssv_STRING_VIEW_STD : nssv_STRING_VIEW_NONSTD ) +//#endif #if defined( nssv_CONFIG_SELECT_STD_STRING_VIEW ) || defined( nssv_CONFIG_SELECT_NONSTD_STRING_VIEW ) # error nssv_CONFIG_SELECT_STD_STRING_VIEW and nssv_CONFIG_SELECT_NONSTD_STRING_VIEW are deprecated and removed, please use nssv_CONFIG_SELECT_STRING_VIEW=nssv_STRING_VIEW_... From b23491fec4f0844ded026b58f193a7688d10b344 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 30 May 2020 15:26:27 +0200 Subject: [PATCH 032/709] fix minor issues --- include/behaviortree_cpp_v3/bt_parser.h | 2 +- include/behaviortree_cpp_v3/utils/simple_string.hpp | 7 +++++++ sample_nodes/crossdoor_nodes.h | 2 ++ src/basic_types.cpp | 6 ------ 4 files changed, 10 insertions(+), 7 deletions(-) diff --git a/include/behaviortree_cpp_v3/bt_parser.h b/include/behaviortree_cpp_v3/bt_parser.h index cd929d04e..c5f979928 100644 --- a/include/behaviortree_cpp_v3/bt_parser.h +++ b/include/behaviortree_cpp_v3/bt_parser.h @@ -16,7 +16,7 @@ class Parser public: Parser() = default; - ~Parser() = default; + virtual ~Parser() = default; Parser(const Parser& other) = delete; Parser& operator=(const Parser& other) = delete; diff --git a/include/behaviortree_cpp_v3/utils/simple_string.hpp b/include/behaviortree_cpp_v3/utils/simple_string.hpp index ae45674f3..1bab0c409 100644 --- a/include/behaviortree_cpp_v3/utils/simple_string.hpp +++ b/include/behaviortree_cpp_v3/utils/simple_string.hpp @@ -31,6 +31,13 @@ class SimpleString { } + SimpleString& operator = (const SimpleString& other) + { + _data = other._data; + _size = other._size; + return *this; + } + ~SimpleString() { if ( _size >= sizeof(void*) && _data.ptr ) diff --git a/sample_nodes/crossdoor_nodes.h b/sample_nodes/crossdoor_nodes.h index 09a2b707c..876e5b2de 100644 --- a/sample_nodes/crossdoor_nodes.h +++ b/sample_nodes/crossdoor_nodes.h @@ -1,3 +1,5 @@ +#pragma once + #include "behaviortree_cpp_v3/bt_factory.h" using namespace BT; diff --git a/src/basic_types.cpp b/src/basic_types.cpp index 293c02d9a..38e7e6db7 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -101,12 +101,6 @@ std::string convertFromString(StringView str) } -template <> -const char* convertFromString(StringView str) -{ - return static_cast(str).c_str(); -} - template <> int convertFromString(StringView str) { From 98b41b9efc0f211554d4fc49f02fe24df56819ea Mon Sep 17 00:00:00 2001 From: "G.Doisy" Date: Tue, 2 Jun 2020 22:45:40 +0200 Subject: [PATCH 033/709] replace dot by zero in boost version (#197) --- CMakeLists.txt | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 69bf801db..58722a816 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -17,11 +17,12 @@ endif() find_package(Boost COMPONENTS coroutine QUIET) if(Boost_FOUND) include_directories(${Boost_INCLUDE_DIRS}) - if(NOT Boost_VERSION VERSION_LESS 105900) + string(REPLACE "." "0" Boost_VERSION_NODOT ${Boost_VERSION}) + if(NOT Boost_VERSION_NODOT VERSION_LESS 105900) message(STATUS "Found boost::coroutine2.") add_definitions(-DBT_BOOST_COROUTINE2) set(BT_COROUTINES true) - elseif(NOT Boost_VERSION VERSION_LESS 105300) + elseif(NOT Boost_VERSION_NODOT VERSION_LESS 105300) message(STATUS "Found boost::coroutine.") include_directories(${Boost_INCLUDE_DIRS}) add_definitions(-DBT_BOOST_COROUTINE) From a5fbc4068e5449fbe33c00f96d53c13f35d0a5cb Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 2 Jun 2020 23:19:42 +0200 Subject: [PATCH 034/709] move to github actions --- .github/workflows/ros1.yaml | 18 ++++++++++++++++++ .github/workflows/ros2.yaml | 17 +++++++++++++++++ .travis.yml | 34 ---------------------------------- 3 files changed, 35 insertions(+), 34 deletions(-) create mode 100644 .github/workflows/ros1.yaml create mode 100644 .github/workflows/ros2.yaml diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml new file mode 100644 index 000000000..e6d2f9be2 --- /dev/null +++ b/.github/workflows/ros1.yaml @@ -0,0 +1,18 @@ +name: ros1 + +on: [push, pull_request] + +jobs: + industrial_ci: + strategy: + matrix: + env: + - {ROS_DISTRO: melodic, ROS_REPO: main} + - {ROS_DISTRO: kinetic, ROS_REPO: main} + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v1 + - uses: 'ros-industrial/industrial_ci@master' + env: ${{matrix.env}} + with: + package-name: behaviortree_cpp_v3 diff --git a/.github/workflows/ros2.yaml b/.github/workflows/ros2.yaml new file mode 100644 index 000000000..9f8c5e764 --- /dev/null +++ b/.github/workflows/ros2.yaml @@ -0,0 +1,17 @@ +name: ros2 + +on: [push, pull_request] + +jobs: + industrial_ci: + strategy: + matrix: + env: + - {ROS_DISTRO: eloquent, ROS_REPO: main} + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v1 + - uses: 'ros-industrial/industrial_ci@master' + env: ${{matrix.env}} + with: + package-name: behaviortree_cpp_v3 diff --git a/.travis.yml b/.travis.yml index 49f226c9a..c0d1fdb3a 100644 --- a/.travis.yml +++ b/.travis.yml @@ -39,40 +39,6 @@ matrix: include: - bare_linux: env: ROS_DISTRO="none" - - ros_indigo: - env: ROS_DISTRO="kinetic" - - ros_kinetic: - env: ROS_DISTRO="lunar" - - ros_melodic: - env: ROS_DISTRO="melodic" - # - <<: *conan-linux - # env: CONAN_GCC_VERSIONS=5 CONAN_DOCKER_IMAGE=conanio/gcc5 ROS_DISTRO="none" - # - <<: *conan-linux - # env: CONAN_GCC_VERSIONS=6 CONAN_DOCKER_IMAGE=conanio/gcc6 ROS_DISTRO="none" - # - <<: *conan-linux - # env: CONAN_GCC_VERSIONS=7 CONAN_DOCKER_IMAGE=conanio/gcc7 ROS_DISTRO="none" - # - <<: *conan-linux - # env: CONAN_GCC_VERSIONS=8 CONAN_DOCKER_IMAGE=conanio/gcc8 ROS_DISTRO="none" - # - <<: *conan-linux - # env: CONAN_CLANG_VERSIONS=3.9 CONAN_DOCKER_IMAGE=conanio/clang39 ROS_DISTRO="none" - # - <<: *conan-linux - # env: CONAN_CLANG_VERSIONS=4.0 CONAN_DOCKER_IMAGE=conanio/clang40 ROS_DISTRO="none" - # - <<: *conan-linux - # env: CONAN_CLANG_VERSIONS=5.0 CONAN_DOCKER_IMAGE=conanio/clang50 ROS_DISTRO="none" - # - <<: *conan-linux - # env: CONAN_CLANG_VERSIONS=6.0 CONAN_DOCKER_IMAGE=conanio/clang60 ROS_DISTRO="none" - # - <<: *conan-osx - # osx_image: xcode8.3 - # env: CONAN_APPLE_CLANG_VERSIONS=8.1 ROS_DISTRO="none" - # - <<: *conan-osx - # osx_image: xcode9 - # env: CONAN_APPLE_CLANG_VERSIONS=9.0 ROS_DISTRO="none" - # - <<: *conan-osx - # osx_image: xcode9.4 - # env: CONAN_APPLE_CLANG_VERSIONS=9.1 ROS_DISTRO="none" - # - <<: *conan-osx - # osx_image: xcode10.1 - # env: CONAN_APPLE_CLANG_VERSIONS=10.0 ROS_DISTRO="none" fast_finish: false before_install: From a331b211eabc4ae1b82f112192be43ebf58b067b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 2 Jun 2020 23:36:15 +0200 Subject: [PATCH 035/709] fix ros2 compilation? --- package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/package.xml b/package.xml index 910e94d3f..2016dd1fb 100644 --- a/package.xml +++ b/package.xml @@ -21,6 +21,8 @@ libzmq3-dev libncurses-dev + + ament_cmake_gtest catkin From 7bebbd96e3ae26cf666405a97eb4593601569d55 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 2 Jun 2020 23:41:14 +0200 Subject: [PATCH 036/709] readme updated --- README.md | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index 56524e51e..85d6bbb36 100644 --- a/README.md +++ b/README.md @@ -1,11 +1,9 @@ ![License MIT](https://img.shields.io/dub/l/vibe-d.svg) ![Version](https://img.shields.io/badge/version-v3.5-green.svg) - - -Travis (Linux): [![Build Status](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP.svg?branch=master)](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP) - -AppVeyor (Windows): [![Build status](https://ci.appveyor.com/api/projects/status/8lawroklgnrkg38f?svg=true)](https://ci.appveyor.com/project/facontidavide59577/behaviortree-cpp) - +[![Build Status](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP.svg?branch=master)](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP) +[![ros1](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros1/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros1) +[![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros2/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros2) +[![Build status](https://ci.appveyor.com/api/projects/status/8lawroklgnrkg38f?svg=true)](https://ci.appveyor.com/project/facontidavide59577/behaviortree-cpp) Question? [![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/BehaviorTree-ROS/Lobby?utm_source=badge&utm_medium=badge&utm_content=badge) From c58d0341ef92774509e2500e6ef9c539ea2c403a Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 2 Jun 2020 23:58:04 +0200 Subject: [PATCH 037/709] more badges --- README.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 85d6bbb36..0140e7f4e 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,11 @@ -![License MIT](https://img.shields.io/dub/l/vibe-d.svg) -![Version](https://img.shields.io/badge/version-v3.5-green.svg) +![License MIT](https://img.shields.io/github/license/BehaviorTree/BehaviorTree.CPP?color=blue) +![Version](https://img.shields.io/badge/version-3.5-blue.svg) [![Build Status](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP.svg?branch=master)](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP) [![ros1](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros1/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros1) [![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros2/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros2) [![Build status](https://ci.appveyor.com/api/projects/status/8lawroklgnrkg38f?svg=true)](https://ci.appveyor.com/project/facontidavide59577/behaviortree-cpp) +[![Codacy Badge](https://app.codacy.com/project/badge/Grade/f7489a1758ab47d49f62342f9649b62a)](https://www.codacy.com/manual/davide.faconti/BehaviorTree.CPP?utm_source=github.com&utm_medium=referral&utm_content=BehaviorTree/BehaviorTree.CPP&utm_campaign=Badge_Grade) +![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP) Question? [![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/BehaviorTree-ROS/Lobby?utm_source=badge&utm_medium=badge&utm_content=badge) From 9e346506034a12e81bccfbb9aceaede6530ee6f7 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 3 Jun 2020 00:00:02 +0200 Subject: [PATCH 038/709] Update README.md --- README.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/README.md b/README.md index 0140e7f4e..3ed357b84 100644 --- a/README.md +++ b/README.md @@ -6,8 +6,7 @@ [![Build status](https://ci.appveyor.com/api/projects/status/8lawroklgnrkg38f?svg=true)](https://ci.appveyor.com/project/facontidavide59577/behaviortree-cpp) [![Codacy Badge](https://app.codacy.com/project/badge/Grade/f7489a1758ab47d49f62342f9649b62a)](https://www.codacy.com/manual/davide.faconti/BehaviorTree.CPP?utm_source=github.com&utm_medium=referral&utm_content=BehaviorTree/BehaviorTree.CPP&utm_campaign=Badge_Grade) ![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP) - -Question? [![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/BehaviorTree-ROS/Lobby?utm_source=badge&utm_medium=badge&utm_content=badge) +[![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/BehaviorTree-ROS/Lobby?utm_source=badge&utm_medium=badge&utm_content=badge) # About BehaviorTree.CPP From 4aa25409755d8b47a4e9d8ef8f9dcc44aa2cc1e0 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 3 Jun 2020 00:03:43 +0200 Subject: [PATCH 039/709] Update README.md --- README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 3ed357b84..30eb17670 100644 --- a/README.md +++ b/README.md @@ -8,7 +8,9 @@ ![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP) [![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/BehaviorTree-ROS/Lobby?utm_source=badge&utm_medium=badge&utm_content=badge) -# About BehaviorTree.CPP +# BehaviorTree.CPP + +

This __C++ 14__ library provides a framework to create BehaviorTrees. It was designed to be flexible, easy to use, reactive and fast. From 3f093fab69542c3b4a84b47338782b09fcee1f0c Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 3 Jun 2020 09:29:35 +0200 Subject: [PATCH 040/709] Update README.md --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 30eb17670..6f591d9b4 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,7 @@ [![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros2/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros2) [![Build status](https://ci.appveyor.com/api/projects/status/8lawroklgnrkg38f?svg=true)](https://ci.appveyor.com/project/facontidavide59577/behaviortree-cpp) [![Codacy Badge](https://app.codacy.com/project/badge/Grade/f7489a1758ab47d49f62342f9649b62a)](https://www.codacy.com/manual/davide.faconti/BehaviorTree.CPP?utm_source=github.com&utm_medium=referral&utm_content=BehaviorTree/BehaviorTree.CPP&utm_campaign=Badge_Grade) -![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP) +[![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP)](https://lgtm.com/projects/g/BehaviorTree/BehaviorTree.CPP/context:cpp) [![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/BehaviorTree-ROS/Lobby?utm_source=badge&utm_medium=badge&utm_content=badge) # BehaviorTree.CPP From 2820685a3c0a83ccba45aaf7c6149fa5b43e2b6a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Dar=C3=ADo=20Here=C3=B1=C3=BA?= Date: Fri, 5 Jun 2020 20:16:31 -0300 Subject: [PATCH 041/709] Minor fix on line 19 * minor fix on line 29 --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 6f591d9b4..455493781 100644 --- a/README.md +++ b/README.md @@ -16,7 +16,7 @@ This __C++ 14__ library provides a framework to create BehaviorTrees. It was designed to be flexible, easy to use, reactive and fast. 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. +__AI for games__, or to replace Finite State Machines in your application. There are few features that make __BehaviorTree.CPP__ unique, when compared to other implementations: @@ -26,7 +26,7 @@ There are few features that make __BehaviorTree.CPP__ unique, when compared to o - Trees are defined using a Domain Specific Scripting __scripting language__ (based on XML), and can be loaded at run-time; in other words, even if written in C++, Trees are _not_ hard-coded. -- You can staticaly link your custom TreeNodes or convert them into __plugins__ +- You can statically link your custom TreeNodes or convert them into __plugins__ which can be loaded at run-time. - It provides a type-safe and flexible mechanism to do __Dataflow__ between From ea0ffd2f4e2bcb8a52e95f688ac510e3d1eef1a8 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 11 Jun 2020 19:36:15 +0200 Subject: [PATCH 042/709] trying to fix compilation in eloquent --- CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 58722a816..75dea11d6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -72,7 +72,6 @@ endif() find_package(ament_cmake QUIET) if ( ament_cmake_FOUND ) - find_package(ament_cmake_gtest REQUIRED) # Not adding -DUSING_ROS since xml_parsing.cpp hasn't been ported to ROS2 From fd3e20fcbc068872583fa4989f1c9fad889112c1 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 11 Jun 2020 21:10:20 +0200 Subject: [PATCH 043/709] preparing release --- CHANGELOG.rst | 108 ++++++++------------------------------------------ 1 file changed, 16 insertions(+), 92 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index c761ad888..3384d9596 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,99 +2,23 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -3.2.0 (2020-03-22) ------------------- -* root_node removed in favour of a method. tickRoot() added -* Moving to c++14 -* fixed compilation on ROS2 and ubuntu 18.94 -* fix compilation and unit tests -* Boost coroutine (`#164 `_) - Remove the faulty coroutine that created significant problems in favour of boost::coroutine2 (use older boost::coroutine as a fallback). -* doc fix -* Fix issue `#140 `_ -* Merge branch 'master' of github.com:BehaviorTree/BehaviorTree.CPP -* (issue `#163 `_) fix ded code -* Merge pull request `#162 `_ from unvestigate/master - Tree is declared as a struct, so it needs to be forward-declared as a… -* Tree is declared as a struct, so it needs to be forward-declared as a struct too. -* Merge pull request `#161 `_ from unvestigate/master - A couple of small changes needed to build on MSVC2015 -* The __cplusplus macro does not work properly prior to MSVC2017 15.7 Preview 3: https://devblogs.microsoft.com/cppblog/msvc-now-correctly-reports-__cplusplus/ -* MSVC2015 seems to need an explicit operator== for comparing against literal strings. -* [Breaking API change] make TreeNode::setStatus() protected - Users are not supposed to set the status of a node manually from the - outside. This might be a source of hard to debug errors as seen in - Navigation2 of ROS2. - If this change breaks your code, there is an high probability that your - code was already broken. -* fix warning -* comments -* Update action_node.h -* Fix bug in default port values -* fix issue `#141 `_ -* fix unit tests -* cosmetic: names changed -* change API of haltChildren() -* fix unittest switch should halt -* halt the SwitchNode correctly -* add unittest switch_node -* Merge pull request `#155 `_ from BehaviorTree/imgbot - [ImgBot] Optimize images -* Merge pull request `#156 `_ from HansRobo/patch-1 - Fix error message -* Modify documentation images. - SequenceNode: - AimTo -> AimAt - "Aim at a target" might sound more appropriate in this example than "aim to reach a goal". - SequenceStar: - Sequence -> ReactiveSequence - The text says "On the other hand, isBatteryOK must be checked at every tick, - for this reason its parent must be a ReactiveSequence." - Modify the image to match the text. -* Fix bug `#149 `_ -* Merge pull request `#152 `_ from happykeyboard/add_unix_BUILD_SHARED - Added BUILD_SHARED_LIBS option to cmake. If set to "OFF", static libr… -* Added BUILD_SHARED_LIBS option to cmake. If set to "OFF", static library will be generated - for a UNIX build - If BUILD_UNIT_TESTS is off, do not search for gtest library, and do not include tests subdirectory -* experimental integration of Switch ControlNode -* bug fix -* Added SubTtreeWrapper -* Merge pull request `#150 `_ from seanyen/patch-1 - Install library to portable locations -* Install library to portable locations -* Merge pull request `#126 `_ from Jesus05/patch-1 - (3dparty coroutine) ifdef MSV_VER to WIN32 -* Merge pull request `#135 `_ from 3wnbr1/master - Add macOS support -* Merge pull request `#138 `_ from HansRobo/fix/remerge\_`#53 `_ - Add `#53 `_ content -* Merge pull request `#142 `_ from RavenX8/patch-1 - Fixed VS2017/2019 compile error -* Merge pull request `#145 `_ from renan028/fix_retry_node_negative_tries - fix RetryNode loop that should be an infinity loop if max_attempts\_ =… -* Update t11_runtime_ports.cpp -* make easier to create ports at run-time -* fix RetryNode loop that should be an infinity loop if max_attempts\_ == -1 - As documentation said: - "Use -1 to create an infinite loop." -* Update basic_types.cpp - Added missing include for std::setlocale. This fixes the following error in Visual Studio: - https://ci.appveyor.com/project/facontidavide59577/behaviortree-cpp/build/job/d1ttd2w84nvnqo2e#L52 -* Merge pull request `#139 `_ from scgroot/master - Fixed compiling for c++17 -* Fixed compiling for c++17 -* Add `#53 `_ content -* Merge pull request `#136 `_ from msadowski/msadowski-readme-fix - Fix some typos in readme -* Fix some typos in readme -* Add macOS support -* fix issue `#120 `_ -* update flatbuffers and avoid ambiguities +Forthcoming +----------- +* trying to fix compilation in eloquent Minor fix on line 19 * Update README.md -* (3dparty coroutine) ifdef MSV_VER to WIN32 - On Windows not only MSVC compilator. -* Contributors: 3wnbr1, Christopher Torres, Davide Faconti, HansRobo, ImgBotApp, Jesus, Kotaro Yoshimoto, Mateusz Sadowski, Peter Polidoro, Sean Yen, Sebastian Ahlman, Steffen Groot, Vadim Linevich, renan028 +* more badges +* readme updated +* fix ros2 compilation? +* move to github actions +* replace dot by zero in boost version (`#197 `_) +* Always use nonstd::string_view for binary compatibility (fix issue `#200 `_) +* Adding ForceRunningNode Decorator (`#192 `_) +* updated doc +* Add XML parsing support for custom Control Nodes (`#194 `_) +* Fix typo +* [Windows] Compare `std::type_info` objects to check type. (`#181 `_) +* Fix pseudocode for ReactiveFallback. (`#191 `_) +* Contributors: Aayush Naik, Darío Hereñú, Davide Faconti, Francisco Martín Rico, G.Doisy, Sarathkrishnan Ramesh, Sean Yen, Ting Chang 3.5.0 (2020-05-14) ------------------ From 84ca8cf9ea9ecd42c45cba90d546182f58a1a03a Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 11 Jun 2020 21:10:30 +0200 Subject: [PATCH 044/709] 3.5.1 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 3384d9596..c277178c0 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.5.1 (2020-06-11) +------------------ * trying to fix compilation in eloquent Minor fix on line 19 * Update README.md * more badges diff --git a/package.xml b/package.xml index 2016dd1fb..e71f2e954 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.5.0 + 3.5.1 This package provides the Behavior Trees core library. From b17641c1eb44bddac46d0ba3b98866016b2f8797 Mon Sep 17 00:00:00 2001 From: Aayush Naik Date: Mon, 6 Jul 2020 16:32:00 -0700 Subject: [PATCH 045/709] Update tutorial_05_subtrees.md I believe that the API has been updated. Reflecting the same in this tutorial. --- docs/tutorial_05_subtrees.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/tutorial_05_subtrees.md b/docs/tutorial_05_subtrees.md index 766a38787..fd7d532f5 100644 --- a/docs/tutorial_05_subtrees.md +++ b/docs/tutorial_05_subtrees.md @@ -88,13 +88,13 @@ int main() auto tree = factory.createTreeFromText(xml_text); // This logger prints state changes on console - StdCoutLogger logger_cout(tree.rootNode()); + StdCoutLogger logger_cout(tree); // This logger saves state changes on file - FileLogger logger_file(tree.rootNode(), "bt_trace.fbl"); + FileLogger logger_file(tree, "bt_trace.fbl"); // This logger stores the execution time of each node - MinitraceLogger logger_minitrace(tree.rootNode(), "bt_trace.json"); + MinitraceLogger logger_minitrace(tree, "bt_trace.json"); #ifdef ZMQ_FOUND // This logger publish status changes using ZeroMQ. Used by Groot From d17a07895c4cc297ff591fbb0b3d95174fe85ad9 Mon Sep 17 00:00:00 2001 From: Renan Salles Date: Fri, 7 Aug 2020 03:43:07 -0300 Subject: [PATCH 046/709] add failure threshold to parallel node with tests (#216) --- .../controls/parallel_node.h | 14 +++-- src/controls/parallel_node.cpp | 53 ++++++++++++++----- tests/gtest_parallel.cpp | 49 ++++++++++++++++- 3 files changed, 98 insertions(+), 18 deletions(-) diff --git a/include/behaviortree_cpp_v3/controls/parallel_node.h b/include/behaviortree_cpp_v3/controls/parallel_node.h index 0c6c959fe..e49d176ec 100644 --- a/include/behaviortree_cpp_v3/controls/parallel_node.h +++ b/include/behaviortree_cpp_v3/controls/parallel_node.h @@ -24,13 +24,15 @@ class ParallelNode : public ControlNode { public: - ParallelNode(const std::string& name, unsigned threshold); + ParallelNode(const std::string& name, unsigned success_threshold, + unsigned failure_threshold = 1); ParallelNode(const std::string& name, const NodeConfiguration& config); static PortsList providedPorts() { - return { InputPort(THRESHOLD_KEY) }; + return { InputPort(THRESHOLD_SUCCESS), + InputPort(THRESHOLD_FAILURE) }; } ~ParallelNode() = default; @@ -38,15 +40,19 @@ class ParallelNode : public ControlNode virtual void halt() override; unsigned int thresholdM(); + unsigned int thresholdFM(); void setThresholdM(unsigned int threshold_M); + void setThresholdFM(unsigned int threshold_M); private: - unsigned int threshold_; + unsigned int success_threshold_; + unsigned int failure_threshold_; std::set skip_list_; bool read_parameter_from_ports_; - static constexpr const char* THRESHOLD_KEY = "threshold"; + static constexpr const char* THRESHOLD_SUCCESS = "success_threshold"; + static constexpr const char* THRESHOLD_FAILURE = "failure_threshold"; virtual BT::NodeStatus tick() override; }; diff --git a/src/controls/parallel_node.cpp b/src/controls/parallel_node.cpp index 0ab8cb29a..18ff9e7f6 100644 --- a/src/controls/parallel_node.cpp +++ b/src/controls/parallel_node.cpp @@ -16,11 +16,14 @@ namespace BT { -constexpr const char* ParallelNode::THRESHOLD_KEY; +constexpr const char* ParallelNode::THRESHOLD_FAILURE; +constexpr const char* ParallelNode::THRESHOLD_SUCCESS; -ParallelNode::ParallelNode(const std::string& name, unsigned threshold) +ParallelNode::ParallelNode(const std::string& name, unsigned success_threshold, + unsigned failure_threshold) : ControlNode::ControlNode(name, {} ), - threshold_(threshold), + success_threshold_(success_threshold), + failure_threshold_(failure_threshold), read_parameter_from_ports_(false) { setRegistrationID("Parallel"); @@ -29,7 +32,8 @@ ParallelNode::ParallelNode(const std::string& name, unsigned threshold) ParallelNode::ParallelNode(const std::string &name, const NodeConfiguration& config) : ControlNode::ControlNode(name, config), - threshold_(0), + success_threshold_(1), + failure_threshold_(1), read_parameter_from_ports_(true) { } @@ -38,9 +42,14 @@ NodeStatus ParallelNode::tick() { if(read_parameter_from_ports_) { - if( !getInput(THRESHOLD_KEY, threshold_) ) + if( !getInput(THRESHOLD_SUCCESS, success_threshold_) ) { - throw RuntimeError("Missing parameter [", THRESHOLD_KEY, "] in ParallelNode"); + throw RuntimeError("Missing parameter [", THRESHOLD_SUCCESS, "] in ParallelNode"); + } + + if( !getInput(THRESHOLD_FAILURE, failure_threshold_) ) + { + throw RuntimeError("Missing parameter [", THRESHOLD_FAILURE, "] in ParallelNode"); } } @@ -49,9 +58,14 @@ NodeStatus ParallelNode::tick() const size_t children_count = children_nodes_.size(); - if( children_count < threshold_) + if( children_count < success_threshold_) { - throw LogicError("Number of children is less than threshold. Can never suceed."); + throw LogicError("Number of children is less than threshold. Can never succeed."); + } + + if( children_count < failure_threshold_) + { + throw LogicError("Number of children is less than threshold. Can never fail."); } // Routing the tree according to the sequence node's logic: @@ -80,7 +94,7 @@ NodeStatus ParallelNode::tick() } success_childred_num++; - if (success_childred_num == threshold_) + if (success_childred_num == success_threshold_) { skip_list_.clear(); haltChildren(); @@ -95,8 +109,11 @@ NodeStatus ParallelNode::tick() skip_list_.insert(i); } failure_childred_num++; - - if (failure_childred_num > children_count - threshold_) + + // It fails if it is not possible to succeed anymore or if + // number of failures are equal to failure_threshold_ + if ((failure_childred_num > children_count - success_threshold_) + || (failure_childred_num == failure_threshold_)) { skip_list_.clear(); haltChildren(); @@ -127,12 +144,22 @@ void ParallelNode::halt() unsigned int ParallelNode::thresholdM() { - return threshold_; + return success_threshold_; +} + +unsigned int ParallelNode::thresholdFM() +{ + return failure_threshold_; } void ParallelNode::setThresholdM(unsigned int threshold_M) { - threshold_ = threshold_M; + success_threshold_ = threshold_M; +} + +void ParallelNode::setThresholdFM(unsigned int threshold_M) +{ + failure_threshold_ = threshold_M; } } diff --git a/tests/gtest_parallel.cpp b/tests/gtest_parallel.cpp index 16d2f5140..08f79f8fe 100644 --- a/tests/gtest_parallel.cpp +++ b/tests/gtest_parallel.cpp @@ -145,7 +145,7 @@ TEST_F(SimpleParallelTest, Threshold_3) ASSERT_EQ(NodeStatus::SUCCESS, state); } -TEST_F(SimpleParallelTest, Threshold_1) +TEST_F(SimpleParallelTest, Threshold_2) { root.setThresholdM(2); BT::NodeStatus state = root.executeTick(); @@ -189,11 +189,57 @@ TEST_F(ComplexParallelTest, ConditionsTrue) ASSERT_EQ(NodeStatus::SUCCESS, state); } +TEST_F(ComplexParallelTest, ConditionsLeftFalse) +{ + parallel_left.setThresholdFM(3); + parallel_left.setThresholdM(3); + condition_L1.setExpectedResult(NodeStatus::FAILURE); + condition_L2.setExpectedResult(NodeStatus::FAILURE); + BT::NodeStatus state = parallel_root.executeTick(); + + // It fails because Parallel Left it will never succeed (two already fail) + // even though threshold_failure == 3 + + ASSERT_EQ(NodeStatus::IDLE, parallel_left.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_L1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_L2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_L1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_L2.status()); + + ASSERT_EQ(NodeStatus::IDLE, parallel_right.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_R.status()); + ASSERT_EQ(NodeStatus::IDLE, action_R.status()); + + ASSERT_EQ(NodeStatus::FAILURE, state); +} + TEST_F(ComplexParallelTest, ConditionRightFalse) { condition_R.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = parallel_root.executeTick(); + // It fails because threshold_failure is 1 for parallel right and + // condition_R fails + + ASSERT_EQ(NodeStatus::IDLE, parallel_left.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_L1.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_L2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_L1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_L2.status()); + + ASSERT_EQ(NodeStatus::IDLE, parallel_right.status()); + ASSERT_EQ(NodeStatus::IDLE, condition_R.status()); + ASSERT_EQ(NodeStatus::IDLE, action_R.status()); + + ASSERT_EQ(NodeStatus::FAILURE, state); +} + +TEST_F(ComplexParallelTest, ConditionRightFalse_thresholdF_2) +{ + parallel_right.setThresholdFM(2); + condition_R.setExpectedResult(NodeStatus::FAILURE); + BT::NodeStatus state = parallel_root.executeTick(); + // All the actions are running ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status()); @@ -229,6 +275,7 @@ TEST_F(ComplexParallelTest, ConditionRightFalseAction1Done) { condition_R.setExpectedResult(NodeStatus::FAILURE); + parallel_right.setThresholdFM(2); parallel_left.setThresholdM(4); BT::NodeStatus state = parallel_root.executeTick(); From beb11cb3cf178aff8eaa847ca6d279527bb0fe87 Mon Sep 17 00:00:00 2001 From: Wuqiqi123 <37368540+Wuqiqi123@users.noreply.github.com> Date: Tue, 1 Sep 2020 15:41:33 +0800 Subject: [PATCH 047/709] Update SequenceNode.md (#211) --- docs/SequenceNode.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/SequenceNode.md b/docs/SequenceNode.md index 302669b88..3f4e5eec1 100644 --- a/docs/SequenceNode.md +++ b/docs/SequenceNode.md @@ -45,9 +45,9 @@ This tree represents the behavior of a sniper in a computer game. status = RUNNING; // _index is a private member - while( index < number_of_children) + while(_index < number_of_children) { - child_status = child[index]->tick(); + child_status = child[_index]->tick(); if( child_status == SUCCESS ) { _index++; From 8f1c491df50fe6680cdb6126cbed8b41114e27ba Mon Sep 17 00:00:00 2001 From: Indraneel Patil <38927559+indraneelpatil@users.noreply.github.com> Date: Tue, 1 Sep 2020 13:12:13 +0530 Subject: [PATCH 048/709] Added delay node and wait for enter keypress node (#182) * Added delay node and wait for enter press node * Fixed unsigned int to int conversion bug * Added a new timer to keep a track of delay timeout and return RUNNING in the meanwhile * Removed wait for keypress node * Review changes suggested by gramss Co-authored-by: Indraneel Patil --- CMakeLists.txt | 1 + include/behaviortree_cpp_v3/behavior_tree.h | 1 + .../decorators/delay_node.h | 62 +++++++++++++ src/bt_factory.cpp | 1 + src/decorators/delay_node.cpp | 87 +++++++++++++++++++ src/decorators/retry_node.cpp | 1 - 6 files changed, 152 insertions(+), 1 deletion(-) create mode 100644 include/behaviortree_cpp_v3/decorators/delay_node.h create mode 100644 src/decorators/delay_node.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 75dea11d6..6cb7e5679 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -162,6 +162,7 @@ list(APPEND BT_SOURCE src/decorators/retry_node.cpp src/decorators/subtree_node.cpp src/decorators/timeout_node.cpp + src/decorators/delay_node.cpp src/controls/if_then_else_node.cpp src/controls/fallback_node.cpp diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index 92394aab2..0e702143d 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -42,6 +42,7 @@ #include "behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h" #include "behaviortree_cpp_v3/decorators/blackboard_precondition.h" #include "behaviortree_cpp_v3/decorators/timeout_node.h" +#include "behaviortree_cpp_v3/decorators/delay_node.h" namespace BT diff --git a/include/behaviortree_cpp_v3/decorators/delay_node.h b/include/behaviortree_cpp_v3/decorators/delay_node.h new file mode 100644 index 000000000..4a68c9440 --- /dev/null +++ b/include/behaviortree_cpp_v3/decorators/delay_node.h @@ -0,0 +1,62 @@ +#ifndef DECORATOR_DELAY_NODE_H +#define DECORATOR_DELAY_NODE_H + +#include "behaviortree_cpp_v3/decorator_node.h" +#include +#include "timer_queue.h" + +namespace BT +{ +/** + * @brief The delay node will introduce a delay of a few milliseconds + * and then tick the child returning the status of the child as it is + * upon completion + * The delay is in milliseconds and it is passed using the port "delay_msec". + * + * During the delay the node changes status to RUNNING + * + * Example: + * + * + * + * + */ +class DelayNode : public DecoratorNode +{ + public: + DelayNode(const std::string& name, unsigned milliseconds); + + DelayNode(const std::string& name, const NodeConfiguration& config); + + ~DelayNode() override + { + halt(); + } + + static PortsList providedPorts() + { + return {InputPort("delay_msec", "Tick the child after a few milliseconds")}; + } + void halt() override + { + timer_.cancelAll(); + DecoratorNode::halt(); + } + + private: + TimerQueue timer_; + uint64_t timer_id_; + + virtual BT::NodeStatus tick() override; + + bool delay_aborted; + bool delay_complete; + unsigned msec_; + bool read_parameter_from_ports_; + bool delay_started_; + std::mutex delay_mutex; +}; + +} // namespace BT + +#endif // DELAY_NODE_H diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 9f01e206f..e0b3f8f40 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -37,6 +37,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("KeepRunningUntilFailure"); registerNodeType("Repeat"); registerNodeType("Timeout"); + registerNodeType("Delay"); registerNodeType("ForceSuccess"); registerNodeType("ForceFailure"); diff --git a/src/decorators/delay_node.cpp b/src/decorators/delay_node.cpp new file mode 100644 index 000000000..4a91514eb --- /dev/null +++ b/src/decorators/delay_node.cpp @@ -0,0 +1,87 @@ +/* Contributed by Indraneel on 26/04/2020 +*/ +#include "behaviortree_cpp_v3/decorators/delay_node.h" +#include "behaviortree_cpp_v3/action_node.h" + +namespace BT +{ +DelayNode::DelayNode(const std::string& name, unsigned milliseconds) + : DecoratorNode(name, {}) + , msec_(milliseconds) + , read_parameter_from_ports_(false) + , delay_started_(false) + , delay_aborted(false) +{ + setRegistrationID("Delay"); +} + +DelayNode::DelayNode(const std::string& name, const NodeConfiguration& config) + : DecoratorNode(name, config) + , msec_(0) + , read_parameter_from_ports_(true) + , delay_started_(false) + , delay_aborted(false) +{ +} + +NodeStatus DelayNode::tick() +{ + if (read_parameter_from_ports_) + { + if (!getInput("delay_msec", msec_)) + { + throw RuntimeError("Missing parameter [delay_msec] in DelayNode"); + } + } + + if (!delay_started_) + { + delay_complete = false; + delay_started_ = true; + setStatus(NodeStatus::RUNNING); + if (msec_ >= 0) + { + timer_id_ = timer_.add(std::chrono::milliseconds(msec_), + [this](bool aborted) + { + std::unique_lock lk(delay_mutex); + if (!aborted) + { + delay_complete = true; + } + else + { + delay_aborted = true; + } + }); + } + else + { + throw RuntimeError("Parameter [delay_msec] in DelayNode cannot be negative (Time once lost is lost forever)! "); + } + + } + + std::unique_lock lk(delay_mutex); + + if (delay_aborted) + { + delay_aborted = false; + delay_started_ = false; + return NodeStatus::FAILURE; + } + + else if (delay_complete) + { + delay_started_ = false; + delay_aborted = false; + auto child_status = child()->executeTick(); + return child_status; + } + else + { + return NodeStatus::RUNNING; + } +} + +} // namespace BT diff --git a/src/decorators/retry_node.cpp b/src/decorators/retry_node.cpp index eec561fc6..93b52d5df 100644 --- a/src/decorators/retry_node.cpp +++ b/src/decorators/retry_node.cpp @@ -55,7 +55,6 @@ NodeStatus RetryNode::tick() while (try_index_ < max_attempts_ || max_attempts_ == -1) { NodeStatus child_state = child_node_->executeTick(); - switch (child_state) { case NodeStatus::SUCCESS: From 63d6fd42a1c4794c81aa7adfb5fba3e42aace8b8 Mon Sep 17 00:00:00 2001 From: fultoncjb Date: Tue, 1 Sep 2020 03:50:45 -0400 Subject: [PATCH 049/709] Allow BT factory to define clock source for TimerQueue/TimerNode (#215) * Allow BT factory to define clock source for TimerQueue/TimerNode * Fix unit tests Co-authored-by: Cam Fulton Co-authored-by: Davide Faconti --- CMakeLists.txt | 1 - .../decorators/timeout_node.h | 78 +++++++++++++++- .../decorators/timer_queue.h | 16 ++-- src/bt_factory.cpp | 2 +- src/decorators/timeout_node.cpp | 91 ------------------- tests/gtest_coroutines.cpp | 4 +- tests/gtest_decorator.cpp | 4 +- 7 files changed, 86 insertions(+), 110 deletions(-) delete mode 100644 src/decorators/timeout_node.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 6cb7e5679..6224bc965 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -161,7 +161,6 @@ list(APPEND BT_SOURCE src/decorators/repeat_node.cpp src/decorators/retry_node.cpp src/decorators/subtree_node.cpp - src/decorators/timeout_node.cpp src/decorators/delay_node.cpp src/controls/if_then_else_node.cpp diff --git a/include/behaviortree_cpp_v3/decorators/timeout_node.h b/include/behaviortree_cpp_v3/decorators/timeout_node.h index ca1197433..ac345795c 100644 --- a/include/behaviortree_cpp_v3/decorators/timeout_node.h +++ b/include/behaviortree_cpp_v3/decorators/timeout_node.h @@ -10,7 +10,7 @@ namespace BT /** * @brief The TimeoutNode will halt() a running child if * the latter has been RUNNING for more than a give time. - * The timeout is in millisecons and it is passed using the port "msec". + * The timeout is in milliseconds and it is passed using the port "msec". * * If timeout is reached it returns FAILURE. * @@ -20,12 +20,30 @@ namespace BT * * */ +template class TimeoutNode : public DecoratorNode { public: - TimeoutNode(const std::string& name, unsigned milliseconds); + TimeoutNode(const std::string& name, unsigned milliseconds) + : DecoratorNode(name, {} ), + child_halted_(false), + timer_id_(0), + msec_(milliseconds), + read_parameter_from_ports_(false), + timeout_started_(false) + { + setRegistrationID("Timeout"); + } - TimeoutNode(const std::string& name, const NodeConfiguration& config); + TimeoutNode(const std::string& name, const NodeConfiguration& config) + : DecoratorNode(name, config), + child_halted_(false), + timer_id_(0), + msec_(0), + read_parameter_from_ports_(true), + timeout_started_(false) + { + } ~TimeoutNode() override { @@ -39,9 +57,59 @@ class TimeoutNode : public DecoratorNode } private: - TimerQueue timer_ ; + TimerQueue<_Clock, _Duration> timer_ ; + + virtual BT::NodeStatus tick() override + { + if( read_parameter_from_ports_ ) + { + if( !getInput("msec", msec_) ) + { + throw RuntimeError("Missing parameter [msec] in TimeoutNode"); + } + } + + if ( !timeout_started_ ) + { + timeout_started_ = true; + setStatus(NodeStatus::RUNNING); + child_halted_ = false; + + if (msec_ > 0) + { + timer_id_ = timer_.add(std::chrono::milliseconds(msec_), + [this](bool aborted) + { + std::unique_lock lk( timeout_mutex_ ); + if (!aborted && child()->status() == NodeStatus::RUNNING) + { + child_halted_ = true; + haltChild(); + } + }); + } + } - virtual BT::NodeStatus tick() override; + std::unique_lock lk( timeout_mutex_ ); + + if (child_halted_) + { + timeout_started_ = false; + return NodeStatus::FAILURE; + } + else + { + auto child_status = child()->executeTick(); + if (child_status != NodeStatus::RUNNING) + { + timeout_started_ = false; + timeout_mutex_.unlock(); + timer_.cancel(timer_id_); + timeout_mutex_.lock(); + } + return child_status; + } + } std::atomic child_halted_; uint64_t timer_id_; diff --git a/include/behaviortree_cpp_v3/decorators/timer_queue.h b/include/behaviortree_cpp_v3/decorators/timer_queue.h index abc9ab19d..5c1fc4ed6 100644 --- a/include/behaviortree_cpp_v3/decorators/timer_queue.h +++ b/include/behaviortree_cpp_v3/decorators/timer_queue.h @@ -62,6 +62,7 @@ class Semaphore // - Handlers are ALWAYS executed in the Timer Queue worker thread. // - Handlers execution order is NOT guaranteed // +template class TimerQueue { public: @@ -85,7 +86,7 @@ class TimerQueue uint64_t add(std::chrono::milliseconds milliseconds, std::function handler) { WorkItem item; - item.end = Clock::now() + milliseconds; + item.end = _Clock::now() + milliseconds; item.handler = std::move(handler); std::unique_lock lk(m_mtx); @@ -118,7 +119,7 @@ class TimerQueue { WorkItem newItem; // Zero time, so it stays at the top for immediate execution - newItem.end = Clock::time_point(); + newItem.end = std::chrono::time_point<_Clock, _Duration>(); 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 @@ -150,7 +151,7 @@ class TimerQueue { if (item.id) { - item.end = Clock::time_point(); + item.end = std::chrono::time_point<_Clock, _Duration>(); item.id = 0; } } @@ -162,7 +163,6 @@ class TimerQueue } private: - using Clock = std::chrono::steady_clock; TimerQueue(const TimerQueue&) = delete; TimerQueue& operator=(const TimerQueue&) = delete; @@ -193,7 +193,7 @@ class TimerQueue assert(m_items.size() == 0); } - std::pair calcWaitTime() + std::pair> calcWaitTime() { std::lock_guard lk(m_mtx); while (m_items.size()) @@ -212,13 +212,13 @@ class TimerQueue // No items found, so return no wait time (causes the thread to wait // indefinitely) - return std::make_pair(false, Clock::time_point()); + return std::make_pair(false, std::chrono::time_point<_Clock, _Duration>()); } void checkWork() { std::unique_lock lk(m_mtx); - while (m_items.size() && m_items.top().end <= Clock::now()) + while (m_items.size() && m_items.top().end <= _Clock::now()) { WorkItem item(std::move(m_items.top())); m_items.pop(); @@ -237,7 +237,7 @@ class TimerQueue struct WorkItem { - Clock::time_point end; + std::chrono::time_point<_Clock, _Duration> end; uint64_t id; // id==0 means it was cancelled std::function handler; bool operator>(const WorkItem& other) const diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index e0b3f8f40..704bdfc73 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -36,7 +36,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("RetryUntilSuccesful"); registerNodeType("KeepRunningUntilFailure"); registerNodeType("Repeat"); - registerNodeType("Timeout"); + registerNodeType>("Timeout"); registerNodeType("Delay"); registerNodeType("ForceSuccess"); diff --git a/src/decorators/timeout_node.cpp b/src/decorators/timeout_node.cpp deleted file mode 100644 index 69905a980..000000000 --- a/src/decorators/timeout_node.cpp +++ /dev/null @@ -1,91 +0,0 @@ -/* Copyright (C) 2018-2020 Davide Faconti, Eurecat - 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 "behaviortree_cpp_v3/decorators/timeout_node.h" -#include "behaviortree_cpp_v3/action_node.h" - -namespace BT -{ - -TimeoutNode::TimeoutNode(const std::string& name, unsigned milliseconds) - : DecoratorNode(name, {} ), - child_halted_(false), - timer_id_(0), - msec_(milliseconds), - read_parameter_from_ports_(false), - timeout_started_(false) -{ - setRegistrationID("Timeout"); -} - -TimeoutNode::TimeoutNode(const std::string& name, const NodeConfiguration& config) - : DecoratorNode(name, config), - child_halted_(false), - timer_id_(0), - msec_(0), - read_parameter_from_ports_(true), - timeout_started_(false) -{ -} - -NodeStatus TimeoutNode::tick() -{ - if( read_parameter_from_ports_ ) - { - if( !getInput("msec", msec_) ) - { - throw RuntimeError("Missing parameter [msec] in TimeoutNode"); - } - } - - if ( !timeout_started_ ) - { - timeout_started_ = true; - setStatus(NodeStatus::RUNNING); - child_halted_ = false; - - if (msec_ > 0) - { - timer_id_ = timer_.add(std::chrono::milliseconds(msec_), - [this](bool aborted) - { - std::unique_lock lk( timeout_mutex_ ); - if (!aborted && child()->status() == NodeStatus::RUNNING) - { - child_halted_ = true; - haltChild(); - } - }); - } - } - - std::unique_lock lk( timeout_mutex_ ); - - if (child_halted_) - { - timeout_started_ = false; - return NodeStatus::FAILURE; - } - else - { - auto child_status = child()->executeTick(); - if (child_status != NodeStatus::RUNNING) - { - timeout_started_ = false; - timeout_mutex_.unlock(); - timer_.cancel(timer_id_); - timeout_mutex_.lock(); - } - return child_status; - } -} - -} diff --git a/tests/gtest_coroutines.cpp b/tests/gtest_coroutines.cpp index 77364856f..d006582c8 100644 --- a/tests/gtest_coroutines.cpp +++ b/tests/gtest_coroutines.cpp @@ -116,7 +116,7 @@ TEST(CoroTest, do_action_timeout) BT::assignDefaultRemapping(node_config_); SimpleCoroAction node( milliseconds(300), false, "Action", node_config_); - BT::TimeoutNode timeout("TimeoutAction", 200); + BT::TimeoutNode<> timeout("TimeoutAction", 200); timeout.setChild(&node); @@ -137,7 +137,7 @@ TEST(CoroTest, sequence_child) SimpleCoroAction actionA( milliseconds(200), false, "action_A", node_config_); SimpleCoroAction actionB( milliseconds(200), false, "action_B", node_config_); - BT::TimeoutNode timeout("timeout", 300); + BT::TimeoutNode<> timeout("timeout", 300); BT::SequenceNode sequence("sequence"); timeout.setChild(&sequence); diff --git a/tests/gtest_decorator.cpp b/tests/gtest_decorator.cpp index b8eaf3cbf..e07470b9d 100644 --- a/tests/gtest_decorator.cpp +++ b/tests/gtest_decorator.cpp @@ -20,7 +20,7 @@ using std::chrono::milliseconds; struct DeadlineTest : testing::Test { - BT::TimeoutNode root; + BT::TimeoutNode<> root; BT::AsyncActionTest action; DeadlineTest() : root("deadline", 300) @@ -66,7 +66,7 @@ struct RetryTest : testing::Test struct TimeoutAndRetry : testing::Test { - BT::TimeoutNode timeout_root; + BT::TimeoutNode<> timeout_root; BT::RetryNode retry; BT::SyncActionTest action; From 1e5a84a97a2954282506a2f0bf58b7b394547534 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 1 Sep 2020 10:02:15 +0200 Subject: [PATCH 050/709] fix compilation --- include/behaviortree_cpp_v3/decorators/delay_node.h | 2 +- include/behaviortree_cpp_v3/decorators/timer_queue.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/delay_node.h b/include/behaviortree_cpp_v3/decorators/delay_node.h index 4a68c9440..715f49581 100644 --- a/include/behaviortree_cpp_v3/decorators/delay_node.h +++ b/include/behaviortree_cpp_v3/decorators/delay_node.h @@ -44,7 +44,7 @@ class DelayNode : public DecoratorNode } private: - TimerQueue timer_; + TimerQueue<> timer_; uint64_t timer_id_; virtual BT::NodeStatus tick() override; diff --git a/include/behaviortree_cpp_v3/decorators/timer_queue.h b/include/behaviortree_cpp_v3/decorators/timer_queue.h index 5c1fc4ed6..2715dff54 100644 --- a/include/behaviortree_cpp_v3/decorators/timer_queue.h +++ b/include/behaviortree_cpp_v3/decorators/timer_queue.h @@ -62,7 +62,7 @@ class Semaphore // - Handlers are ALWAYS executed in the Timer Queue worker thread. // - Handlers execution order is NOT guaranteed // -template +template class TimerQueue { public: From 55c982bfaeb2b414e3f08481d311fcac7139ea4c Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 1 Sep 2020 10:11:28 +0200 Subject: [PATCH 051/709] decreasing warning level to fix issue #220 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6224bc965..66d8ccac3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -229,7 +229,7 @@ if( ZMQ_FOUND ) endif() if(MSVC) - target_compile_options(${BEHAVIOR_TREE_LIBRARY} PRIVATE /W4 /WX) + target_compile_options(${BEHAVIOR_TREE_LIBRARY} PRIVATE /W3 /WX) else() target_compile_options(${BEHAVIOR_TREE_LIBRARY} PRIVATE -Wall -Wextra -Werror=return-type) From fba8d96697f89d9b65b18011a2e256b2c74b4ece Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 1 Sep 2020 10:22:50 +0200 Subject: [PATCH 052/709] tutorial 1 fixed --- docs/tutorial_01_first_tree.md | 2 +- examples/t01_build_your_first_tree.cpp | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/docs/tutorial_01_first_tree.md b/docs/tutorial_01_first_tree.md index a73c379fe..6a5b93464 100644 --- a/docs/tutorial_01_first_tree.md +++ b/docs/tutorial_01_first_tree.md @@ -107,7 +107,7 @@ Let's consider the following XML file named __my_tree.xml__: - + diff --git a/examples/t01_build_your_first_tree.cpp b/examples/t01_build_your_first_tree.cpp index 00269358b..4ffe0c621 100644 --- a/examples/t01_build_your_first_tree.cpp +++ b/examples/t01_build_your_first_tree.cpp @@ -24,7 +24,6 @@ static const char* xml_text = R"( - From 479813b098337654616f438bcb2eb80e249dfe7a Mon Sep 17 00:00:00 2001 From: Valerio Magnago Date: Tue, 1 Sep 2020 15:37:17 +0200 Subject: [PATCH 053/709] docs: Small changes to tutorial 02 (#225) * docs: fix to my_tree.xml Before my_tree.xml was containing an `SayHello` Action that was not registered inside the BehaviourTreeFactory contained in the simple_bt.cpp * docs: tutorial 1 my_tree.xml editable in Groot Add to the xml tree definition the node declaration needed to edit the behavior xml file with groot * docs: clearer code for first tutorial Now at the end of the tutorial the entire code that can be copied and pasted directy to test the demo is provided. In particular the needed include files are added which are not mentioned along the tutorial and this spare a little time for new users to figure them out. * docs: remove blank lines * docs: little addition to tutorial_02 docs - Provide a default implementation of `SaySomething2` - Add Groot support in the xml file * docs: Add missing SaySimple2 * docs: removed not useful stuff Co-authored-by: Valerio Magnago --- docs/tutorial_02_basic_ports.md | 60 ++++++++++++++++++++++++--------- 1 file changed, 45 insertions(+), 15 deletions(-) diff --git a/docs/tutorial_02_basic_ports.md b/docs/tutorial_02_basic_ports.md index 2d841b541..d5d9aee29 100644 --- a/docs/tutorial_02_basic_ports.md +++ b/docs/tutorial_02_basic_ports.md @@ -93,6 +93,27 @@ class SaySomething : public SyncActionNode ``` +Alternatively the same functionality can be implemented in a simple function. This function takes an instance of `BT:TreeNode` as input in order to access the "message" Input Port: + +```c++ +// Simple function that return a NodeStatus +BT::NodeStatus SaySomethingSimple(BT::TreeNode& self) +{ + Optional msg = self.getInput("message"); + // Check if optional is valid. If not, throw its error + if (!msg) + { + throw BT::RuntimeError("missing required input [message]: ", msg.error()); + } + + // use the method value() to extract the valid message. + std::cout << "Robot says: " << msg.value() << std::endl; + return NodeStatus::SUCCESS; +} +``` + + + When a custom TreeNode has input and/or output ports, these ports must be declared in the __static__ method: @@ -109,7 +130,7 @@ check the validity of the returned value and to decide what to do: - Return `NodeStatus::FAILURE`? - Throw an exception? - Use a different default value? - + !!! Warning "Important" It is __always__ recommended to call the method `getInput()` inside the `tick()`, and __not__ in the constructor of the class. @@ -118,11 +139,11 @@ check the validity of the returned value and to decide what to do: the nature of the input, which could be either static or dynamic. A dynamic input can change at run-time, for this reason it should be read periodically. - + ## Output ports An input port pointing to the entry of the blackboard will be valid only -if another node have already wrritten "something" inside that same entry. +if another node have already written "something" inside that same entry. `ThinkWhatToSay` is an example of Node that uses an __output port__ to write a string into an entry. @@ -172,24 +193,31 @@ In this example, a Sequence of 5 Actions is executed: `SaySomething2` is a SimpleActionNode. ```XML - - - - - - - - - - - + + + + + + + + + + + ``` The C++ code: ```C++ +#include "behaviortree_cpp_v3/bt_factory.h" + +// file that contains the custom nodes definitions +#include "dummy_nodes.h" + int main() { + using namespace DummyNodes; + BehaviorTreeFactory factory; factory.registerNodeType("SaySomething"); @@ -202,7 +230,7 @@ int main() factory.registerSimpleAction("SaySomething2", SaySomethingSimple, say_something_ports ); - auto tree = factory.createTreeFromText(xml_text); + auto tree = factory.createTreeFromFile("./my_tree.xml"); tree.tickRoot(); @@ -223,3 +251,5 @@ this means that they "point" to the same entry of the blackboard. These ports can be connected to each other because their type is the same, i.e. `std::string`. + + From bef80cd7cbf06f8d15d50b7d90e7630d929af0dc Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 2 Sep 2020 14:24:20 +0200 Subject: [PATCH 054/709] fix warnings --- src/loggers/bt_zmq_publisher.cpp | 6 +++--- tools/bt_recorder.cpp | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/loggers/bt_zmq_publisher.cpp b/src/loggers/bt_zmq_publisher.cpp index 872f11d04..6b9baf122 100644 --- a/src/loggers/bt_zmq_publisher.cpp +++ b/src/loggers/bt_zmq_publisher.cpp @@ -65,12 +65,12 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, zmq::message_t req; try { - bool received = zmq_->server.recv(&req); + bool received = zmq_->server.recv(&req, 0); if (received) { zmq::message_t reply(tree_buffer_.size()); memcpy(reply.data(), tree_buffer_.data(), tree_buffer_.size()); - zmq_->server.send(reply); + zmq_->server.send(reply, 0); } } catch (zmq::error_t& err) @@ -162,7 +162,7 @@ void PublisherZMQ::flush() createStatusBuffer(); } - zmq_->publisher.send(message); + zmq_->publisher.send(message, 0); send_pending_ = false; // printf("%.3f zmq send\n", std::chrono::duration( std::chrono::high_resolution_clock::now().time_since_epoch() ).count()); } diff --git a/tools/bt_recorder.cpp b/tools/bt_recorder.cpp index 6175312f8..3aa67402e 100644 --- a/tools/bt_recorder.cpp +++ b/tools/bt_recorder.cpp @@ -57,7 +57,7 @@ int main(int argc, char* argv[]) zmq::message_t msg; try { - subscriber.recv(&update); + subscriber.recv(&update, 0); } catch (zmq::error_t& e) { From aa86d7873368c3ce75f06a846b9987f0dc176b6c Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 2 Sep 2020 14:33:16 +0200 Subject: [PATCH 055/709] fix warning and follow coding standard --- .../decorators/delay_node.h | 8 +-- src/decorators/delay_node.cpp | 52 ++++++++----------- 2 files changed, 26 insertions(+), 34 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/delay_node.h b/include/behaviortree_cpp_v3/decorators/delay_node.h index 715f49581..cf5392a5f 100644 --- a/include/behaviortree_cpp_v3/decorators/delay_node.h +++ b/include/behaviortree_cpp_v3/decorators/delay_node.h @@ -49,12 +49,12 @@ class DelayNode : public DecoratorNode virtual BT::NodeStatus tick() override; - bool delay_aborted; - bool delay_complete; + bool delay_started_; + bool delay_complete_; + bool delay_aborted_; unsigned msec_; bool read_parameter_from_ports_; - bool delay_started_; - std::mutex delay_mutex; + std::mutex delay_mutex_; }; } // namespace BT diff --git a/src/decorators/delay_node.cpp b/src/decorators/delay_node.cpp index 4a91514eb..47b88d5c5 100644 --- a/src/decorators/delay_node.cpp +++ b/src/decorators/delay_node.cpp @@ -7,20 +7,20 @@ namespace BT { DelayNode::DelayNode(const std::string& name, unsigned milliseconds) : DecoratorNode(name, {}) + , delay_started_(false) + , delay_aborted_(false) , msec_(milliseconds) , read_parameter_from_ports_(false) - , delay_started_(false) - , delay_aborted(false) { setRegistrationID("Delay"); } DelayNode::DelayNode(const std::string& name, const NodeConfiguration& config) : DecoratorNode(name, config) + , delay_started_(false) + , delay_aborted_(false) , msec_(0) , read_parameter_from_ports_(true) - , delay_started_(false) - , delay_aborted(false) { } @@ -36,45 +36,37 @@ NodeStatus DelayNode::tick() if (!delay_started_) { - delay_complete = false; + delay_complete_ = false; delay_started_ = true; setStatus(NodeStatus::RUNNING); - if (msec_ >= 0) + + timer_id_ = timer_.add(std::chrono::milliseconds(msec_), + [this](bool aborted) { - timer_id_ = timer_.add(std::chrono::milliseconds(msec_), - [this](bool aborted) + std::unique_lock lk(delay_mutex_); + if (!aborted) { - std::unique_lock lk(delay_mutex); - if (!aborted) - { - delay_complete = true; - } - else - { - delay_aborted = true; - } - }); - } - else - { - throw RuntimeError("Parameter [delay_msec] in DelayNode cannot be negative (Time once lost is lost forever)! "); - } - + delay_complete_ = true; + } + else + { + delay_aborted_ = true; + } + }); } - std::unique_lock lk(delay_mutex); + std::unique_lock lk(delay_mutex_); - if (delay_aborted) + if (delay_aborted_) { - delay_aborted = false; + delay_aborted_ = false; delay_started_ = false; return NodeStatus::FAILURE; } - - else if (delay_complete) + else if (delay_complete_) { delay_started_ = false; - delay_aborted = false; + delay_aborted_ = false; auto child_status = child()->executeTick(); return child_status; } From 0464966ac0df61d233c09d630017278932f2dc5f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 2 Sep 2020 14:57:42 +0200 Subject: [PATCH 056/709] version bump --- CHANGELOG.rst | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index c277178c0..16c875dce 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* fix warning and follow coding standard +* docs: Small changes to tutorial 02 (`#225 `_) + Co-authored-by: Valerio Magnago +* Merge branch 'master' of https://github.com/BehaviorTree/BehaviorTree.CPP +* tutorial 1 fixed +* decreasing warning level to fix issue `#220 `_ +* fix compilation +* Allow BT factory to define clock source for TimerQueue/TimerNode (`#215 `_) + * Allow BT factory to define clock source for TimerQueue/TimerNode + * Fix unit tests + Co-authored-by: Cam Fulton + Co-authored-by: Davide Faconti +* Added delay node and wait for enter keypress node (`#182 `_) + * Added delay node and wait for enter press node + * Fixed unsigned int to int conversion bug + * Added a new timer to keep a track of delay timeout and return RUNNING in the meanwhile + * Removed wait for keypress node + * Review changes suggested by gramss + Co-authored-by: Indraneel Patil +* Update SequenceNode.md (`#211 `_) +* add failure threshold to parallel node with tests (`#216 `_) +* Update tutorial_05_subtrees.md + I believe that the API has been updated. Reflecting the same in this tutorial. +* Contributors: Aayush Naik, Davide Faconti, Indraneel Patil, Renan Salles, Valerio Magnago, Wuqiqi123, fultoncjb + 3.5.1 (2020-06-11) ------------------ * trying to fix compilation in eloquent Minor fix on line 19 From 2761d3c4ca1ac1ca44933f24885dcbc874203c05 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 2 Sep 2020 14:57:58 +0200 Subject: [PATCH 057/709] 3.5.2 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 16c875dce..d4f390434 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.5.2 (2020-09-02) +------------------ * fix warning and follow coding standard * docs: Small changes to tutorial 02 (`#225 `_) Co-authored-by: Valerio Magnago diff --git a/package.xml b/package.xml index e71f2e954..09635ec03 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.5.1 + 3.5.2 This package provides the Behavior Trees core library. From 5d752e10446203cb0545d3428845fde84a44dba9 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 7 Sep 2020 17:33:17 +0200 Subject: [PATCH 058/709] better tutorial --- docs/tutorial_08_additional_args.md | 146 ++++++++++++++-------------- mkdocs.yml | 2 +- 2 files changed, 72 insertions(+), 76 deletions(-) diff --git a/docs/tutorial_08_additional_args.md b/docs/tutorial_08_additional_args.md index 367f9a4fd..ce2aef333 100644 --- a/docs/tutorial_08_additional_args.md +++ b/docs/tutorial_08_additional_args.md @@ -1,4 +1,4 @@ -# Custom initialization and/or construction +# Pass additional arguments during initialization and/or construction In every single example we explored so far we were "forced" to provide a constructor with the following signature @@ -11,21 +11,25 @@ constructor with the following signature In same cases, it is desirable to pass to the constructor of our class additional arguments, parameters, pointers, references, etc. -We will just use the word _"parameter"_ for the rest of the tutorial. +**Many people use blackboards to do that: this is not recomendable.** -Even if, theoretically, these parameters can be passed using Input Ports, +We will just use the word _"arguments"_ for the rest of the tutorial. + +Even if, theoretically, these arguments **could** be passed using Input Ports, that would be the wrong way to do it if: -- The parameters are known at _deployment-time_. -- The parameters don't change at _run-time_. -- The parameters don't need to be from the _XML_. +- The arguments are known at _deployment-time_. +- The arguments don't change at _run-time_. +- The arguments don't need to be set from the _XML_. + +If all these conditions are met, using ports or the blackboard is cumbersome and highly discouraged. -If all these conditions are met, using ports is just cumbersome and highly discouraged. +## Method 1: register a custom builder -## The C++ example +Consider the following custom node called **Action_A**. -Next, we can see two alternative ways to pass parameters to a class: -either as arguments of the constructor of the class or in an `init()` method. +We want to pass three additional arguments; they can be arbitrarily complex objects, +you are not limited to built-in types. ```C++ // Action_A has a different constructor than the default one. @@ -41,47 +45,71 @@ public: _arg2(arg2), _arg3(arg3) {} - NodeStatus tick() override - { - std::cout << "Action_A: " << _arg1 << " / " << _arg2 << " / " - << _arg3 << std::endl; - return NodeStatus::SUCCESS; - } // this example doesn't require any port static PortsList providedPorts() { return {}; } + // tick() can access the private members + NodeStatus tick() override; + private: int _arg1; double _arg2; std::string _arg3; }; +``` + +This node should be registered as shown further: + +```C++ +BehaviorTreeFactory factory; + +// A node builder is a functor that creates a std::unique_ptr. +// Using lambdas or std::bind, we can easily "inject" additional arguments. +NodeBuilder builder_A = + [](const std::string& name, const NodeConfiguration& config) +{ + return std::make_unique( name, config, 42, 3.14, "hello world" ); +}; + +// BehaviorTreeFactory::registerBuilder is a more general way to +// register a custom node. +factory.registerBuilder( "Action_A", builder_A); + +// Register more custom nodes, if needed. +// .... + +// The rest of your code, where you create and tick the tree, goes here. +// .... +``` + +## Method 2: use an init method + +Alternatively, you may call an init method before ticking the tree. + +```C++ -// Action_B implements an init(...) method that must be called once -// before the first tick() class Action_B: public SyncActionNode { public: + // The constructor looks as usual. Action_B(const std::string& name, const NodeConfiguration& config): SyncActionNode(name, config) {} - // we want this method to be called ONCE and BEFORE the first tick() - void init( int arg1, double arg2, std::string arg3 ) + // We want this method to be called ONCE and BEFORE the first tick() + void init( int arg1, double arg2, const std::string& arg3 ) { _arg1 = (arg1); _arg2 = (arg2); _arg3 = (arg3); } - NodeStatus tick() override - { - std::cout << "Action_B: " << _arg1 << " / " << _arg2 << " / " - << _arg3 << std::endl; - return NodeStatus::SUCCESS; - } // this example doesn't require any port static PortsList providedPorts() { return {}; } + // tick() can access the private members + NodeStatus tick() override; + private: int _arg1; double _arg2; @@ -89,66 +117,34 @@ private: }; ``` -The way we register and initialize them in our `main` is slightly different. - +The way we register and initialize Action_B is slightly different: ```C++ -static const char* xml_text = R"( - - - - - - - - - - )"; - -int main() -{ - BehaviorTreeFactory factory; - // A node builder is nothing more than a function pointer to create a - // std::unique_ptr. - // Using lambdas or std::bind, we can easily "inject" additional arguments. - NodeBuilder builder_A = - [](const std::string& name, const NodeConfiguration& config) - { - return std::make_unique( name, config, 42, 3.14, "hello world" ); - }; +BehaviorTreeFactory factory; - // BehaviorTreeFactory::registerBuilder is a more general way to - // register a custom node. - factory.registerBuilder( "Action_A", builder_A); +// The regitration of Action_B is done as usual, but remember +// that we still need to call Action_B::init() +factory.registerNodeType( "Action_B" ); - // The regitration of Action_B is done as usual, but remember - // that we still need to call Action_B::init() - factory.registerNodeType( "Action_B" ); +// Register more custom nodes, if needed. +// .... - auto tree = factory.createTreeFromText(xml_text); +// Create the whole tree +auto tree = factory.createTreeFromText(xml_text); - // Iterate through all the nodes and call init() if it is an Action_B - for( auto& node: tree.nodes ) +// Iterate through all the nodes and call init() if it is an Action_B +for( auto& node: tree.nodes ) +{ + // Not a typo: it is "=", not "==" + if( auto action_B = dynamic_cast( node.get() )) { - if( auto action_B_node = dynamic_cast( node.get() )) - { - action_B_node->init( 69, 9.99, "interesting_value" ); - } + action_B->init( 42, 3.14, "hello world"); } - - tree.tickRoot(); - - return 0; } - -/* Expected output: - - Action_A: 42 / 3.14 / hello world - Action_B: 69 / 9.99 / interesting_value -*/ - +// The rest of your code, where you tick the tree, goes here. +// .... ``` diff --git a/mkdocs.yml b/mkdocs.yml index f52752d45..a76d768fc 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -49,7 +49,7 @@ nav: - "Tutorial 5: Subtrees and Loggers": tutorial_05_subtrees.md - "Tutorial 6: Ports remapping": tutorial_06_subtree_ports.md - "Tutorial 7: Wrap legacy code": tutorial_07_legacy.md - - "Tutorial 8: Class parameters": tutorial_08_additional_args.md + - "Tutorial 8: Additional arguments": tutorial_08_additional_args.md - "Tutorial 9: Coroutines": tutorial_09_coroutines.md - Migration Guide: From da1cb44943309e64a18ac4b6668420526d7167ea Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 10 Sep 2020 12:46:18 +0200 Subject: [PATCH 059/709] fix issue #228 . Retry and Repeat node need to halt the child --- CMakeLists.txt | 8 +---- src/decorators/repeat_node.cpp | 2 ++ src/decorators/retry_node.cpp | 2 ++ tests/gtest_decorator.cpp | 55 ++++++++++++++++++++++++++------ tests/include/action_test_node.h | 18 ++++++++--- tests/src/action_test_node.cpp | 13 ++++++-- 6 files changed, 75 insertions(+), 23 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 66d8ccac3..70041b00a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -102,13 +102,7 @@ elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) set(BUILD_TOOL_INCLUDE_DIRS ${catkin_INCLUDE_DIRS}) elseif(BUILD_UNIT_TESTS) - find_package(GTest) - - if(NOT GTEST_FOUND) - message(WARNING " GTest missing! You may want to follow these instructions:") - message(WARNING " https://gist.github.com/Cartexius/4c437c084d6e388288201aadf9c8cdd5") - endif() - + find_package(GTest REQUIRED) endif() diff --git a/src/decorators/repeat_node.cpp b/src/decorators/repeat_node.cpp index 3c7493ad7..7a4509a56 100644 --- a/src/decorators/repeat_node.cpp +++ b/src/decorators/repeat_node.cpp @@ -56,12 +56,14 @@ NodeStatus RepeatNode::tick() case NodeStatus::SUCCESS: { try_index_++; + haltChild(); } break; case NodeStatus::FAILURE: { try_index_ = 0; + haltChild(); return (NodeStatus::FAILURE); } diff --git a/src/decorators/retry_node.cpp b/src/decorators/retry_node.cpp index 93b52d5df..3b9f5c8c8 100644 --- a/src/decorators/retry_node.cpp +++ b/src/decorators/retry_node.cpp @@ -60,12 +60,14 @@ NodeStatus RetryNode::tick() case NodeStatus::SUCCESS: { try_index_ = 0; + haltChild(); return (NodeStatus::SUCCESS); } case NodeStatus::FAILURE: { try_index_++; + haltChild(); } break; diff --git a/tests/gtest_decorator.cpp b/tests/gtest_decorator.cpp index e07470b9d..7ed19d93c 100644 --- a/tests/gtest_decorator.cpp +++ b/tests/gtest_decorator.cpp @@ -28,10 +28,7 @@ struct DeadlineTest : testing::Test { root.setChild(&action); } - ~DeadlineTest() - { - - } + ~DeadlineTest() = default; }; struct RepeatTest : testing::Test @@ -43,10 +40,19 @@ struct RepeatTest : testing::Test { root.setChild(&action); } - ~RepeatTest() + ~RepeatTest() = default; +}; + +struct RepeatTestAsync : testing::Test +{ + BT::RepeatNode root; + BT::AsyncActionTest action; + + RepeatTestAsync() : root("repeat", 3), action("action", milliseconds(100)) { - + root.setChild(&action); } + ~RepeatTestAsync() = default; }; struct RetryTest : testing::Test @@ -58,10 +64,7 @@ struct RetryTest : testing::Test { root.setChild(&action); } - ~RetryTest() - { - - } + ~RetryTest() = default; }; struct TimeoutAndRetry : testing::Test @@ -128,6 +131,38 @@ TEST_F(RetryTest, RetryTestA) ASSERT_EQ(1, action.tickCount() ); } + +TEST_F(RepeatTestAsync, RepeatTestAsync) +{ + action.setExpectedResult(NodeStatus::SUCCESS); + + auto res = root.executeTick(); + + while(res == NodeStatus::RUNNING){ + std::this_thread::sleep_for(std::chrono::milliseconds(20)); + res = root.executeTick(); + } + + ASSERT_EQ(NodeStatus::SUCCESS, root.status()); + ASSERT_EQ(3, action.successCount() ); + ASSERT_EQ(0, action.failureCount() ); + + //------------------- + action.setExpectedResult(NodeStatus::FAILURE); + action.resetCounters(); + + res = root.executeTick(); + while(res == NodeStatus::RUNNING){ + std::this_thread::sleep_for(std::chrono::milliseconds(20)); + res = root.executeTick(); + } + + ASSERT_EQ(NodeStatus::FAILURE, root.status()); + ASSERT_EQ(0, action.successCount() ); + ASSERT_EQ(1, action.failureCount() ); + +} + TEST_F(RepeatTest, RepeatTestA) { action.setExpectedResult(NodeStatus::FAILURE); diff --git a/tests/include/action_test_node.h b/tests/include/action_test_node.h index 495b31d8a..0815210e5 100644 --- a/tests/include/action_test_node.h +++ b/tests/include/action_test_node.h @@ -49,13 +49,21 @@ class AsyncActionTest : public AsyncActionNode void setExpectedResult(NodeStatus res); - int tickCount() const - { + int tickCount() const { return tick_count_; } - void resetTicks() - { + int successCount() const { + return success_count_; + } + + int failureCount() const { + return failure_count_; + } + + void resetCounters() { + success_count_ = 0; + failure_count_ = 0; tick_count_ = 0; } @@ -64,6 +72,8 @@ class AsyncActionTest : public AsyncActionNode BT::Duration time_; std::atomic expected_result_; std::atomic tick_count_; + int success_count_; + int failure_count_; }; } diff --git a/tests/src/action_test_node.cpp b/tests/src/action_test_node.cpp index 77b0042e2..d18c8ca9b 100644 --- a/tests/src/action_test_node.cpp +++ b/tests/src/action_test_node.cpp @@ -15,7 +15,9 @@ #include BT::AsyncActionTest::AsyncActionTest(const std::string& name, BT::Duration deadline_ms) : - AsyncActionNode(name, {}) + AsyncActionNode(name, {}), + success_count_(0), + failure_count_(0) { expected_result_ = NodeStatus::SUCCESS; time_ = deadline_ms; @@ -40,12 +42,19 @@ BT::NodeStatus BT::AsyncActionTest::tick() return NodeStatus::IDLE; } + if( expected_result_ == NodeStatus::SUCCESS){ + success_count_++; + } + else if( expected_result_ == NodeStatus::FAILURE){ + failure_count_++; + } + return expected_result_; } void BT::AsyncActionTest::halt() { - // do more cleanup here is necessary + // do more cleanup here if necessary AsyncActionNode::halt(); } From 5d9d2d4fa5ee8444ab0b3417c75cc4d74a2086ce Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 10 Sep 2020 12:52:49 +0200 Subject: [PATCH 060/709] prepare release --- CHANGELOG.rst | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index d4f390434..aa9526783 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* fix issue `#228 `_ . Retry and Repeat node need to halt the child +* better tutorial +* Contributors: Davide Faconti + 3.5.2 (2020-09-02) ------------------ * fix warning and follow coding standard From 63d970917bdfb63f27ace69aa1ffadda0eee0f57 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 10 Sep 2020 12:53:07 +0200 Subject: [PATCH 061/709] 3.5.3 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index aa9526783..9c2412957 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.5.3 (2020-09-10) +------------------ * fix issue `#228 `_ . Retry and Repeat node need to halt the child * better tutorial * Contributors: Davide Faconti diff --git a/package.xml b/package.xml index 09635ec03..74c7bd30d 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.5.2 + 3.5.3 This package provides the Behavior Trees core library. From 2e9dccfc5257773b641151d1be8b5a432ee58dd3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 16 Sep 2020 11:34:37 +0200 Subject: [PATCH 062/709] fix issue #230 --- include/behaviortree_cpp_v3/controls/parallel_node.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/behaviortree_cpp_v3/controls/parallel_node.h b/include/behaviortree_cpp_v3/controls/parallel_node.h index e49d176ec..5e52d41bd 100644 --- a/include/behaviortree_cpp_v3/controls/parallel_node.h +++ b/include/behaviortree_cpp_v3/controls/parallel_node.h @@ -31,8 +31,8 @@ class ParallelNode : public ControlNode static PortsList providedPorts() { - return { InputPort(THRESHOLD_SUCCESS), - InputPort(THRESHOLD_FAILURE) }; + return { InputPort(THRESHOLD_SUCCESS, "number of childen which need to succeed to trigger a SUCCESS )), + InputPort(THRESHOLD_FAILURE, 1, "number of childen which need to fail to trigger a FAILURE ) }; } ~ParallelNode() = default; From 3b30d6a4552e7dc6fd58d8f67dfc1228ddcf7f91 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 16 Sep 2020 12:09:38 +0200 Subject: [PATCH 063/709] fix --- include/behaviortree_cpp_v3/controls/parallel_node.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/behaviortree_cpp_v3/controls/parallel_node.h b/include/behaviortree_cpp_v3/controls/parallel_node.h index 5e52d41bd..b5a5ffb72 100644 --- a/include/behaviortree_cpp_v3/controls/parallel_node.h +++ b/include/behaviortree_cpp_v3/controls/parallel_node.h @@ -31,8 +31,8 @@ class ParallelNode : public ControlNode static PortsList providedPorts() { - return { InputPort(THRESHOLD_SUCCESS, "number of childen which need to succeed to trigger a SUCCESS )), - InputPort(THRESHOLD_FAILURE, 1, "number of childen which need to fail to trigger a FAILURE ) }; + return { InputPort(THRESHOLD_SUCCESS, "number of childen which need to succeed to trigger a SUCCESS" ), + InputPort(THRESHOLD_FAILURE, 1, "number of childen which need to fail to trigger a FAILURE" ) }; } ~ParallelNode() = default; From f54f6d83e5c06f44eae2b4d9700f5178dbdb4159 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 8 Oct 2020 23:02:27 +0200 Subject: [PATCH 064/709] Update retry_node.cpp --- src/decorators/retry_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/decorators/retry_node.cpp b/src/decorators/retry_node.cpp index 3b9f5c8c8..6f8386ddc 100644 --- a/src/decorators/retry_node.cpp +++ b/src/decorators/retry_node.cpp @@ -23,7 +23,7 @@ RetryNode::RetryNode(const std::string& name, int NTries) try_index_(0), read_parameter_from_ports_(false) { - setRegistrationID("RetryUntilSuccesful"); + setRegistrationID("RetryUntilSuccessful"); } RetryNode::RetryNode(const std::string& name, const NodeConfiguration& config) From 5a629b2869b08780c042d5996fd0f1bc817e8833 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Florian=20Gram=C3=9F?= <6034322+gramss@users.noreply.github.com> Date: Wed, 2 Dec 2020 13:26:23 +0100 Subject: [PATCH 065/709] Improved switching BTs with active Groot monitoring (ZMQ logger destruction) (#244) * Skip 100ms (max) wait for detached thread * add {} to single line if statements --- src/loggers/bt_zmq_publisher.cpp | 21 +++++++++++++++++++-- 1 file changed, 19 insertions(+), 2 deletions(-) diff --git a/src/loggers/bt_zmq_publisher.cpp b/src/loggers/bt_zmq_publisher.cpp index 6b9baf122..9b7ecc323 100644 --- a/src/loggers/bt_zmq_publisher.cpp +++ b/src/loggers/bt_zmq_publisher.cpp @@ -75,6 +75,10 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, } catch (zmq::error_t& err) { + if (err.num() == ETERM) + { + std::cout << "[PublisherZMQ] Server quitting." << std::endl; + } std::cout << "[PublisherZMQ] just died. Exeption " << err.what() << std::endl; active_server_ = false; } @@ -87,6 +91,7 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, PublisherZMQ::~PublisherZMQ() { active_server_ = false; + zmq_->context.shutdown(); if (thread_.joinable()) { thread_.join(); @@ -161,8 +166,20 @@ void PublisherZMQ::flush() transition_buffer_.clear(); createStatusBuffer(); } - - zmq_->publisher.send(message, 0); + try + { + zmq_->publisher.send(message, 0); + } + catch (zmq::error_t& err) + { + if (err.num() == ETERM) + { + std::cout << "[PublisherZMQ] Publisher quitting." << std::endl; + } + std::cout << "[PublisherZMQ] just died. Exeption " << err.what() << std::endl; + } + + send_pending_ = false; // printf("%.3f zmq send\n", std::chrono::duration( std::chrono::high_resolution_clock::now().time_since_epoch() ).count()); } From f09ab36063615b12ab992858252ad4d8d0f942b3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 2 Dec 2020 22:27:22 +0100 Subject: [PATCH 066/709] Use the latest version of zmq.hpp --- src/loggers/bt_zmq_publisher.cpp | 15 +- src/loggers/zmq.hpp | 2688 ++++++++++++++++++++++++++++++ 2 files changed, 2695 insertions(+), 8 deletions(-) create mode 100644 src/loggers/zmq.hpp diff --git a/src/loggers/bt_zmq_publisher.cpp b/src/loggers/bt_zmq_publisher.cpp index 9b7ecc323..9f04223c3 100644 --- a/src/loggers/bt_zmq_publisher.cpp +++ b/src/loggers/bt_zmq_publisher.cpp @@ -1,7 +1,7 @@ #include "behaviortree_cpp_v3/loggers/bt_zmq_publisher.h" #include "behaviortree_cpp_v3/flatbuffers/bt_flatbuffer_helper.h" #include -#include +#include "zmq.hpp" namespace BT { @@ -55,7 +55,7 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, zmq_->server.bind(str); int timeout_ms = 100; - zmq_->server.setsockopt(ZMQ_RCVTIMEO, &timeout_ms, sizeof(int)); + zmq_->server.set(zmq::sockopt::rcvtimeo, timeout_ms); active_server_ = true; @@ -65,12 +65,12 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, zmq::message_t req; try { - bool received = zmq_->server.recv(&req, 0); + zmq::recv_result_t 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, 0); + zmq_->server.send(reply, zmq::send_flags::none); } } catch (zmq::error_t& err) @@ -148,14 +148,14 @@ void PublisherZMQ::flush() 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, static_cast(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()); + flatbuffers::WriteScalar(data_ptr, static_cast(transition_buffer_.size())); data_ptr += sizeof(uint32_t); for (auto& transition : transition_buffer_) @@ -168,7 +168,7 @@ void PublisherZMQ::flush() } try { - zmq_->publisher.send(message, 0); + zmq_->publisher.send(message, zmq::send_flags::none); } catch (zmq::error_t& err) { @@ -179,7 +179,6 @@ void PublisherZMQ::flush() std::cout << "[PublisherZMQ] just died. Exeption " << err.what() << std::endl; } - 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/loggers/zmq.hpp b/src/loggers/zmq.hpp new file mode 100644 index 000000000..d02a208f9 --- /dev/null +++ b/src/loggers/zmq.hpp @@ -0,0 +1,2688 @@ +/* + Copyright (c) 2016-2017 ZeroMQ community + Copyright (c) 2009-2011 250bpm s.r.o. + Copyright (c) 2011 Botond Ballo + Copyright (c) 2007-2009 iMatix Corporation + + 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 __ZMQ_HPP_INCLUDED__ +#define __ZMQ_HPP_INCLUDED__ + +#ifdef _WIN32 +#ifndef NOMINMAX +#define NOMINMAX +#endif +#endif + +// included here for _HAS_CXX* macros +#include + +#if defined(_MSVC_LANG) +#define CPPZMQ_LANG _MSVC_LANG +#else +#define CPPZMQ_LANG __cplusplus +#endif +// overwrite if specific language macros indicate higher version +#if defined(_HAS_CXX14) && _HAS_CXX14 && CPPZMQ_LANG < 201402L +#undef CPPZMQ_LANG +#define CPPZMQ_LANG 201402L +#endif +#if defined(_HAS_CXX17) && _HAS_CXX17 && CPPZMQ_LANG < 201703L +#undef CPPZMQ_LANG +#define CPPZMQ_LANG 201703L +#endif + +// macros defined if has a specific standard or greater +#if CPPZMQ_LANG >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1900) +#define ZMQ_CPP11 +#endif +#if CPPZMQ_LANG >= 201402L +#define ZMQ_CPP14 +#endif +#if CPPZMQ_LANG >= 201703L +#define ZMQ_CPP17 +#endif + +#if defined(ZMQ_CPP14) && !defined(_MSC_VER) +#define ZMQ_DEPRECATED(msg) [[deprecated(msg)]] +#elif defined(_MSC_VER) +#define ZMQ_DEPRECATED(msg) __declspec(deprecated(msg)) +#elif defined(__GNUC__) +#define ZMQ_DEPRECATED(msg) __attribute__((deprecated(msg))) +#endif + +#if defined(ZMQ_CPP17) +#define ZMQ_NODISCARD [[nodiscard]] +#else +#define ZMQ_NODISCARD +#endif + +#if defined(ZMQ_CPP11) +#define ZMQ_NOTHROW noexcept +#define ZMQ_EXPLICIT explicit +#define ZMQ_OVERRIDE override +#define ZMQ_NULLPTR nullptr +#define ZMQ_CONSTEXPR_FN constexpr +#define ZMQ_CONSTEXPR_VAR constexpr +#define ZMQ_CPP11_DEPRECATED(msg) ZMQ_DEPRECATED(msg) +#else +#define ZMQ_NOTHROW throw() +#define ZMQ_EXPLICIT +#define ZMQ_OVERRIDE +#define ZMQ_NULLPTR 0 +#define ZMQ_CONSTEXPR_FN +#define ZMQ_CONSTEXPR_VAR const +#define ZMQ_CPP11_DEPRECATED(msg) +#endif +#if defined(ZMQ_CPP14) && (!defined(_MSC_VER) || _MSC_VER > 1900) +#define ZMQ_EXTENDED_CONSTEXPR +#endif +#if defined(ZMQ_CPP17) +#define ZMQ_INLINE_VAR inline +#else +#define ZMQ_INLINE_VAR +#endif + +#include +#include + +#include +#include +#include +#include +#include +#include +#ifdef ZMQ_CPP11 +#include +#include +#include +#include +#endif + +#if defined(__has_include) && defined(ZMQ_CPP17) +#define CPPZMQ_HAS_INCLUDE_CPP17(X) __has_include(X) +#else +#define CPPZMQ_HAS_INCLUDE_CPP17(X) 0 +#endif + +#if CPPZMQ_HAS_INCLUDE_CPP17() && !defined(CPPZMQ_HAS_OPTIONAL) +#define CPPZMQ_HAS_OPTIONAL 1 +#endif +#ifndef CPPZMQ_HAS_OPTIONAL +#define CPPZMQ_HAS_OPTIONAL 0 +#elif CPPZMQ_HAS_OPTIONAL +#include +#endif + +#if CPPZMQ_HAS_INCLUDE_CPP17() && !defined(CPPZMQ_HAS_STRING_VIEW) +#define CPPZMQ_HAS_STRING_VIEW 1 +#endif +#ifndef CPPZMQ_HAS_STRING_VIEW +#define CPPZMQ_HAS_STRING_VIEW 0 +#elif CPPZMQ_HAS_STRING_VIEW +#include +#endif + +/* Version macros for compile-time API version detection */ +#define CPPZMQ_VERSION_MAJOR 4 +#define CPPZMQ_VERSION_MINOR 7 +#define CPPZMQ_VERSION_PATCH 1 + +#define CPPZMQ_VERSION \ + ZMQ_MAKE_VERSION(CPPZMQ_VERSION_MAJOR, CPPZMQ_VERSION_MINOR, \ + CPPZMQ_VERSION_PATCH) + +// Detect whether the compiler supports C++11 rvalue references. +#if (defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ > 2)) \ + && defined(__GXX_EXPERIMENTAL_CXX0X__)) +#define ZMQ_HAS_RVALUE_REFS +#define ZMQ_DELETED_FUNCTION = delete +#elif defined(__clang__) +#if __has_feature(cxx_rvalue_references) +#define ZMQ_HAS_RVALUE_REFS +#endif + +#if __has_feature(cxx_deleted_functions) +#define ZMQ_DELETED_FUNCTION = delete +#else +#define ZMQ_DELETED_FUNCTION +#endif +#elif defined(_MSC_VER) && (_MSC_VER >= 1900) +#define ZMQ_HAS_RVALUE_REFS +#define ZMQ_DELETED_FUNCTION = delete +#elif defined(_MSC_VER) && (_MSC_VER >= 1600) +#define ZMQ_HAS_RVALUE_REFS +#define ZMQ_DELETED_FUNCTION +#else +#define ZMQ_DELETED_FUNCTION +#endif + +#if defined(ZMQ_CPP11) && !defined(__llvm__) && !defined(__INTEL_COMPILER) \ + && defined(__GNUC__) && __GNUC__ < 5 +#define ZMQ_CPP11_PARTIAL +#elif defined(__GLIBCXX__) && __GLIBCXX__ < 20160805 +//the date here is the last date of gcc 4.9.4, which +// effectively means libstdc++ from gcc 5.5 and higher won't trigger this branch +#define ZMQ_CPP11_PARTIAL +#endif + +#ifdef ZMQ_CPP11 +#ifdef ZMQ_CPP11_PARTIAL +#define ZMQ_IS_TRIVIALLY_COPYABLE(T) __has_trivial_copy(T) +#else +#include +#define ZMQ_IS_TRIVIALLY_COPYABLE(T) std::is_trivially_copyable::value +#endif +#endif + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(3, 3, 0) +#define ZMQ_NEW_MONITOR_EVENT_LAYOUT +#endif + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 1, 0) +#define ZMQ_HAS_PROXY_STEERABLE +/* Socket event data */ +typedef struct +{ + uint16_t event; // id of the event as bitfield + int32_t value; // value is either error code, fd or reconnect interval +} zmq_event_t; +#endif + +// Avoid using deprecated message receive function when possible +#if ZMQ_VERSION < ZMQ_MAKE_VERSION(3, 2, 0) +#define zmq_msg_recv(msg, socket, flags) zmq_recvmsg(socket, msg, flags) +#endif + + +// In order to prevent unused variable warnings when building in non-debug +// mode use this macro to make assertions. +#ifndef NDEBUG +#define ZMQ_ASSERT(expression) assert(expression) +#else +#define ZMQ_ASSERT(expression) (void) (expression) +#endif + +namespace zmq +{ +#ifdef ZMQ_CPP11 +namespace detail +{ +namespace ranges +{ +using std::begin; +using std::end; +template auto begin(T &&r) -> decltype(begin(std::forward(r))) +{ + return begin(std::forward(r)); +} +template auto end(T &&r) -> decltype(end(std::forward(r))) +{ + return end(std::forward(r)); +} +} // namespace ranges + +template using void_t = void; + +template +using iter_value_t = typename std::iterator_traits::value_type; + +template +using range_iter_t = decltype( + ranges::begin(std::declval::type &>())); + +template using range_value_t = iter_value_t>; + +template struct is_range : std::false_type +{ +}; + +template +struct is_range< + T, + void_t::type &>()) + == ranges::end(std::declval::type &>()))>> + : std::true_type +{ +}; + +} // namespace detail +#endif + +typedef zmq_free_fn free_fn; +typedef zmq_pollitem_t pollitem_t; + +class error_t : public std::exception +{ + public: + error_t() ZMQ_NOTHROW : errnum(zmq_errno()) {} + explicit error_t(int err) ZMQ_NOTHROW : errnum(err) {} + virtual const char *what() const ZMQ_NOTHROW ZMQ_OVERRIDE + { + return zmq_strerror(errnum); + } + int num() const ZMQ_NOTHROW { return errnum; } + + private: + int errnum; +}; + +inline int poll(zmq_pollitem_t *items_, size_t nitems_, long timeout_ = -1) +{ + int rc = zmq_poll(items_, static_cast(nitems_), timeout_); + if (rc < 0) + throw error_t(); + return rc; +} + +ZMQ_DEPRECATED("from 4.3.1, use poll taking non-const items") +inline int poll(zmq_pollitem_t const *items_, size_t nitems_, long timeout_ = -1) +{ + return poll(const_cast(items_), nitems_, timeout_); +} + +#ifdef ZMQ_CPP11 +ZMQ_DEPRECATED("from 4.3.1, use poll taking non-const items") +inline int +poll(zmq_pollitem_t const *items, size_t nitems, std::chrono::milliseconds timeout) +{ + return poll(const_cast(items), nitems, + static_cast(timeout.count())); +} + +ZMQ_DEPRECATED("from 4.3.1, use poll taking non-const items") +inline int poll(std::vector const &items, + std::chrono::milliseconds timeout) +{ + return poll(const_cast(items.data()), items.size(), + static_cast(timeout.count())); +} + +ZMQ_DEPRECATED("from 4.3.1, use poll taking non-const items") +inline int poll(std::vector const &items, long timeout_ = -1) +{ + return poll(const_cast(items.data()), items.size(), timeout_); +} + +inline int +poll(zmq_pollitem_t *items, size_t nitems, std::chrono::milliseconds timeout) +{ + return poll(items, nitems, static_cast(timeout.count())); +} + +inline int poll(std::vector &items, + std::chrono::milliseconds timeout) +{ + return poll(items.data(), items.size(), static_cast(timeout.count())); +} + +ZMQ_DEPRECATED("from 4.3.1, use poll taking std::chrono instead of long") +inline int poll(std::vector &items, long timeout_ = -1) +{ + return poll(items.data(), items.size(), timeout_); +} + +template +inline int poll(std::array &items, + std::chrono::milliseconds timeout) +{ + return poll(items.data(), items.size(), static_cast(timeout.count())); +} +#endif + + +inline void version(int *major_, int *minor_, int *patch_) +{ + zmq_version(major_, minor_, patch_); +} + +#ifdef ZMQ_CPP11 +inline std::tuple version() +{ + std::tuple v; + zmq_version(&std::get<0>(v), &std::get<1>(v), &std::get<2>(v)); + return v; +} + +#if !defined(ZMQ_CPP11_PARTIAL) +namespace detail +{ +template struct is_char_type +{ + // true if character type for string literals in C++11 + static constexpr bool value = + std::is_same::value || std::is_same::value + || std::is_same::value || std::is_same::value; +}; +} +#endif + +#endif + +class message_t +{ + public: + message_t() ZMQ_NOTHROW + { + int rc = zmq_msg_init(&msg); + ZMQ_ASSERT(rc == 0); + } + + explicit message_t(size_t size_) + { + int rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + } + + template message_t(ForwardIter first, ForwardIter last) + { + typedef typename std::iterator_traits::value_type value_t; + + assert(std::distance(first, last) >= 0); + size_t const size_ = + static_cast(std::distance(first, last)) * sizeof(value_t); + int const rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + std::copy(first, last, data()); + } + + message_t(const void *data_, size_t size_) + { + int rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + if (size_) { + // this constructor allows (nullptr, 0), + // memcpy with a null pointer is UB + memcpy(data(), data_, size_); + } + } + + message_t(void *data_, size_t size_, free_fn *ffn_, void *hint_ = ZMQ_NULLPTR) + { + int rc = zmq_msg_init_data(&msg, data_, size_, ffn_, hint_); + if (rc != 0) + throw error_t(); + } + + // overload set of string-like types and generic containers +#if defined(ZMQ_CPP11) && !defined(ZMQ_CPP11_PARTIAL) + // NOTE this constructor will include the null terminator + // when called with a string literal. + // An overload taking const char* can not be added because + // it would be preferred over this function and break compatiblity. + template< + class Char, + size_t N, + typename = typename std::enable_if::value>::type> + ZMQ_DEPRECATED("from 4.7.0, use constructors taking iterators, (pointer, size) " + "or strings instead") + explicit message_t(const Char (&data)[N]) : + message_t(detail::ranges::begin(data), detail::ranges::end(data)) + { + } + + template::value + && ZMQ_IS_TRIVIALLY_COPYABLE(detail::range_value_t) + && !detail::is_char_type>::value + && !std::is_same::value>::type> + explicit message_t(const Range &rng) : + message_t(detail::ranges::begin(rng), detail::ranges::end(rng)) + { + } + + explicit message_t(const std::string &str) : message_t(str.data(), str.size()) {} + +#if CPPZMQ_HAS_STRING_VIEW + explicit message_t(std::string_view str) : message_t(str.data(), str.size()) {} +#endif + +#endif + +#ifdef ZMQ_HAS_RVALUE_REFS + message_t(message_t &&rhs) ZMQ_NOTHROW : msg(rhs.msg) + { + int rc = zmq_msg_init(&rhs.msg); + ZMQ_ASSERT(rc == 0); + } + + message_t &operator=(message_t &&rhs) ZMQ_NOTHROW + { + std::swap(msg, rhs.msg); + return *this; + } +#endif + + ~message_t() ZMQ_NOTHROW + { + int rc = zmq_msg_close(&msg); + ZMQ_ASSERT(rc == 0); + } + + void rebuild() + { + int rc = zmq_msg_close(&msg); + if (rc != 0) + throw error_t(); + rc = zmq_msg_init(&msg); + ZMQ_ASSERT(rc == 0); + } + + void rebuild(size_t size_) + { + int rc = zmq_msg_close(&msg); + if (rc != 0) + throw error_t(); + rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + } + + void rebuild(const void *data_, size_t size_) + { + int rc = zmq_msg_close(&msg); + if (rc != 0) + throw error_t(); + rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + memcpy(data(), data_, size_); + } + + void rebuild(void *data_, size_t size_, free_fn *ffn_, void *hint_ = ZMQ_NULLPTR) + { + int rc = zmq_msg_close(&msg); + if (rc != 0) + throw error_t(); + rc = zmq_msg_init_data(&msg, data_, size_, ffn_, hint_); + if (rc != 0) + throw error_t(); + } + + ZMQ_DEPRECATED("from 4.3.1, use move taking non-const reference instead") + void move(message_t const *msg_) + { + int rc = zmq_msg_move(&msg, const_cast(msg_->handle())); + if (rc != 0) + throw error_t(); + } + + void move(message_t &msg_) + { + int rc = zmq_msg_move(&msg, msg_.handle()); + if (rc != 0) + throw error_t(); + } + + ZMQ_DEPRECATED("from 4.3.1, use copy taking non-const reference instead") + void copy(message_t const *msg_) + { + int rc = zmq_msg_copy(&msg, const_cast(msg_->handle())); + if (rc != 0) + throw error_t(); + } + + void copy(message_t &msg_) + { + int rc = zmq_msg_copy(&msg, msg_.handle()); + if (rc != 0) + throw error_t(); + } + + bool more() const ZMQ_NOTHROW + { + int rc = zmq_msg_more(const_cast(&msg)); + return rc != 0; + } + + void *data() ZMQ_NOTHROW { return zmq_msg_data(&msg); } + + const void *data() const ZMQ_NOTHROW + { + return zmq_msg_data(const_cast(&msg)); + } + + size_t size() const ZMQ_NOTHROW + { + return zmq_msg_size(const_cast(&msg)); + } + + ZMQ_NODISCARD bool empty() const ZMQ_NOTHROW { return size() == 0u; } + + template T *data() ZMQ_NOTHROW { return static_cast(data()); } + + template T const *data() const ZMQ_NOTHROW + { + return static_cast(data()); + } + + ZMQ_DEPRECATED("from 4.3.0, use operator== instead") + bool equal(const message_t *other) const ZMQ_NOTHROW { return *this == *other; } + + bool operator==(const message_t &other) const ZMQ_NOTHROW + { + const size_t my_size = size(); + return my_size == other.size() && 0 == memcmp(data(), other.data(), my_size); + } + + bool operator!=(const message_t &other) const ZMQ_NOTHROW + { + return !(*this == other); + } + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(3, 2, 0) + int get(int property_) + { + int value = zmq_msg_get(&msg, property_); + if (value == -1) + throw error_t(); + return value; + } +#endif + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 1, 0) + const char *gets(const char *property_) + { + const char *value = zmq_msg_gets(&msg, property_); + if (value == ZMQ_NULLPTR) + throw error_t(); + return value; + } +#endif + +#if defined(ZMQ_BUILD_DRAFT_API) && ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 0) + uint32_t routing_id() const + { + return zmq_msg_routing_id(const_cast(&msg)); + } + + void set_routing_id(uint32_t routing_id) + { + int rc = zmq_msg_set_routing_id(&msg, routing_id); + if (rc != 0) + throw error_t(); + } + + const char *group() const + { + return zmq_msg_group(const_cast(&msg)); + } + + void set_group(const char *group) + { + int rc = zmq_msg_set_group(&msg, group); + if (rc != 0) + throw error_t(); + } +#endif + + // interpret message content as a string + std::string to_string() const + { + return std::string(static_cast(data()), size()); + } +#if CPPZMQ_HAS_STRING_VIEW + // interpret message content as a string + std::string_view to_string_view() const noexcept + { + return std::string_view(static_cast(data()), size()); + } +#endif + + /** Dump content to string for debugging. + * Ascii chars are readable, the rest is printed as hex. + * Probably ridiculously slow. + * Use to_string() or to_string_view() for + * interpreting the message as a string. + */ + std::string str() const + { + // Partly mutuated from the same method in zmq::multipart_t + std::stringstream os; + + const unsigned char *msg_data = this->data(); + unsigned char byte; + size_t size = this->size(); + int is_ascii[2] = {0, 0}; + + os << "zmq::message_t [size " << std::dec << std::setw(3) + << std::setfill('0') << size << "] ("; + // Totally arbitrary + if (size >= 1000) { + os << "... too big to print)"; + } else { + while (size--) { + byte = *msg_data++; + + is_ascii[1] = (byte >= 32 && byte < 127); + if (is_ascii[1] != is_ascii[0]) + os << " "; // Separate text/non text + + if (is_ascii[1]) { + os << byte; + } else { + os << std::hex << std::uppercase << std::setw(2) + << std::setfill('0') << static_cast(byte); + } + is_ascii[0] = is_ascii[1]; + } + os << ")"; + } + return os.str(); + } + + void swap(message_t &other) ZMQ_NOTHROW + { + // this assumes zmq::msg_t from libzmq is trivially relocatable + std::swap(msg, other.msg); + } + + ZMQ_NODISCARD zmq_msg_t *handle() ZMQ_NOTHROW { return &msg; } + ZMQ_NODISCARD const zmq_msg_t *handle() const ZMQ_NOTHROW { return &msg; } + + private: + // The underlying message + zmq_msg_t msg; + + // Disable implicit message copying, so that users won't use shared + // messages (less efficient) without being aware of the fact. + message_t(const message_t &) ZMQ_DELETED_FUNCTION; + void operator=(const message_t &) ZMQ_DELETED_FUNCTION; +}; + +inline void swap(message_t &a, message_t &b) ZMQ_NOTHROW +{ + a.swap(b); +} + +#ifdef ZMQ_CPP11 +enum class ctxopt +{ +#ifdef ZMQ_BLOCKY + blocky = ZMQ_BLOCKY, +#endif +#ifdef ZMQ_IO_THREADS + io_threads = ZMQ_IO_THREADS, +#endif +#ifdef ZMQ_THREAD_SCHED_POLICY + thread_sched_policy = ZMQ_THREAD_SCHED_POLICY, +#endif +#ifdef ZMQ_THREAD_PRIORITY + thread_priority = ZMQ_THREAD_PRIORITY, +#endif +#ifdef ZMQ_THREAD_AFFINITY_CPU_ADD + thread_affinity_cpu_add = ZMQ_THREAD_AFFINITY_CPU_ADD, +#endif +#ifdef ZMQ_THREAD_AFFINITY_CPU_REMOVE + thread_affinity_cpu_remove = ZMQ_THREAD_AFFINITY_CPU_REMOVE, +#endif +#ifdef ZMQ_THREAD_NAME_PREFIX + thread_name_prefix = ZMQ_THREAD_NAME_PREFIX, +#endif +#ifdef ZMQ_MAX_MSGSZ + max_msgsz = ZMQ_MAX_MSGSZ, +#endif +#ifdef ZMQ_ZERO_COPY_RECV + zero_copy_recv = ZMQ_ZERO_COPY_RECV, +#endif +#ifdef ZMQ_MAX_SOCKETS + max_sockets = ZMQ_MAX_SOCKETS, +#endif +#ifdef ZMQ_SOCKET_LIMIT + socket_limit = ZMQ_SOCKET_LIMIT, +#endif +#ifdef ZMQ_IPV6 + ipv6 = ZMQ_IPV6, +#endif +#ifdef ZMQ_MSG_T_SIZE + msg_t_size = ZMQ_MSG_T_SIZE +#endif +}; +#endif + +class context_t +{ + public: + context_t() + { + ptr = zmq_ctx_new(); + if (ptr == ZMQ_NULLPTR) + throw error_t(); + } + + + explicit context_t(int io_threads_, int max_sockets_ = ZMQ_MAX_SOCKETS_DFLT) + { + ptr = zmq_ctx_new(); + if (ptr == ZMQ_NULLPTR) + throw error_t(); + + int rc = zmq_ctx_set(ptr, ZMQ_IO_THREADS, io_threads_); + ZMQ_ASSERT(rc == 0); + + rc = zmq_ctx_set(ptr, ZMQ_MAX_SOCKETS, max_sockets_); + ZMQ_ASSERT(rc == 0); + } + +#ifdef ZMQ_HAS_RVALUE_REFS + context_t(context_t &&rhs) ZMQ_NOTHROW : ptr(rhs.ptr) { rhs.ptr = ZMQ_NULLPTR; } + context_t &operator=(context_t &&rhs) ZMQ_NOTHROW + { + close(); + std::swap(ptr, rhs.ptr); + return *this; + } +#endif + + ~context_t() ZMQ_NOTHROW { close(); } + + ZMQ_CPP11_DEPRECATED("from 4.7.0, use set taking zmq::ctxopt instead") + int setctxopt(int option_, int optval_) + { + int rc = zmq_ctx_set(ptr, option_, optval_); + ZMQ_ASSERT(rc == 0); + return rc; + } + + ZMQ_CPP11_DEPRECATED("from 4.7.0, use get taking zmq::ctxopt instead") + int getctxopt(int option_) { return zmq_ctx_get(ptr, option_); } + +#ifdef ZMQ_CPP11 + void set(ctxopt option, int optval) + { + int rc = zmq_ctx_set(ptr, static_cast(option), optval); + if (rc == -1) + throw error_t(); + } + + ZMQ_NODISCARD int get(ctxopt option) + { + int rc = zmq_ctx_get(ptr, static_cast(option)); + // some options have a default value of -1 + // which is unfortunate, and may result in errors + // that don't make sense + if (rc == -1) + throw error_t(); + return rc; + } +#endif + + // Terminates context (see also shutdown()). + void close() ZMQ_NOTHROW + { + if (ptr == ZMQ_NULLPTR) + return; + + int rc; + do { + rc = zmq_ctx_destroy(ptr); + } while (rc == -1 && errno == EINTR); + + ZMQ_ASSERT(rc == 0); + ptr = ZMQ_NULLPTR; + } + + // Shutdown context in preparation for termination (close()). + // Causes all blocking socket operations and any further + // socket operations to return with ETERM. + void shutdown() ZMQ_NOTHROW + { + if (ptr == ZMQ_NULLPTR) + return; + int rc = zmq_ctx_shutdown(ptr); + ZMQ_ASSERT(rc == 0); + } + + // Be careful with this, it's probably only useful for + // using the C api together with an existing C++ api. + // Normally you should never need to use this. + ZMQ_EXPLICIT operator void *() ZMQ_NOTHROW { return ptr; } + + ZMQ_EXPLICIT operator void const *() const ZMQ_NOTHROW { return ptr; } + + ZMQ_NODISCARD void *handle() ZMQ_NOTHROW { return ptr; } + + ZMQ_DEPRECATED("from 4.7.0, use handle() != nullptr instead") + operator bool() const ZMQ_NOTHROW { return ptr != ZMQ_NULLPTR; } + + void swap(context_t &other) ZMQ_NOTHROW { std::swap(ptr, other.ptr); } + + private: + void *ptr; + + context_t(const context_t &) ZMQ_DELETED_FUNCTION; + void operator=(const context_t &) ZMQ_DELETED_FUNCTION; +}; + +inline void swap(context_t &a, context_t &b) ZMQ_NOTHROW +{ + a.swap(b); +} + +#ifdef ZMQ_CPP11 + +struct recv_buffer_size +{ + size_t size; // number of bytes written to buffer + size_t untruncated_size; // untruncated message size in bytes + + ZMQ_NODISCARD bool truncated() const noexcept + { + return size != untruncated_size; + } +}; + +#if CPPZMQ_HAS_OPTIONAL + +using send_result_t = std::optional; +using recv_result_t = std::optional; +using recv_buffer_result_t = std::optional; + +#else + +namespace detail +{ +// A C++11 type emulating the most basic +// operations of std::optional for trivial types +template class trivial_optional +{ + public: + static_assert(std::is_trivial::value, "T must be trivial"); + using value_type = T; + + trivial_optional() = default; + trivial_optional(T value) noexcept : _value(value), _has_value(true) {} + + const T *operator->() const noexcept + { + assert(_has_value); + return &_value; + } + T *operator->() noexcept + { + assert(_has_value); + return &_value; + } + + const T &operator*() const noexcept + { + assert(_has_value); + return _value; + } + T &operator*() noexcept + { + assert(_has_value); + return _value; + } + + T &value() + { + if (!_has_value) + throw std::exception(); + return _value; + } + const T &value() const + { + if (!_has_value) + throw std::exception(); + return _value; + } + + explicit operator bool() const noexcept { return _has_value; } + bool has_value() const noexcept { return _has_value; } + + private: + T _value{}; + bool _has_value{false}; +}; +} // namespace detail + +using send_result_t = detail::trivial_optional; +using recv_result_t = detail::trivial_optional; +using recv_buffer_result_t = detail::trivial_optional; + +#endif + +namespace detail +{ +template constexpr T enum_bit_or(T a, T b) noexcept +{ + static_assert(std::is_enum::value, "must be enum"); + using U = typename std::underlying_type::type; + return static_cast(static_cast(a) | static_cast(b)); +} +template constexpr T enum_bit_and(T a, T b) noexcept +{ + static_assert(std::is_enum::value, "must be enum"); + using U = typename std::underlying_type::type; + return static_cast(static_cast(a) & static_cast(b)); +} +template constexpr T enum_bit_xor(T a, T b) noexcept +{ + static_assert(std::is_enum::value, "must be enum"); + using U = typename std::underlying_type::type; + return static_cast(static_cast(a) ^ static_cast(b)); +} +template constexpr T enum_bit_not(T a) noexcept +{ + static_assert(std::is_enum::value, "must be enum"); + using U = typename std::underlying_type::type; + return static_cast(~static_cast(a)); +} +} // namespace detail + +// partially satisfies named requirement BitmaskType +enum class send_flags : int +{ + none = 0, + dontwait = ZMQ_DONTWAIT, + sndmore = ZMQ_SNDMORE +}; + +constexpr send_flags operator|(send_flags a, send_flags b) noexcept +{ + return detail::enum_bit_or(a, b); +} +constexpr send_flags operator&(send_flags a, send_flags b) noexcept +{ + return detail::enum_bit_and(a, b); +} +constexpr send_flags operator^(send_flags a, send_flags b) noexcept +{ + return detail::enum_bit_xor(a, b); +} +constexpr send_flags operator~(send_flags a) noexcept +{ + return detail::enum_bit_not(a); +} + +// partially satisfies named requirement BitmaskType +enum class recv_flags : int +{ + none = 0, + dontwait = ZMQ_DONTWAIT +}; + +constexpr recv_flags operator|(recv_flags a, recv_flags b) noexcept +{ + return detail::enum_bit_or(a, b); +} +constexpr recv_flags operator&(recv_flags a, recv_flags b) noexcept +{ + return detail::enum_bit_and(a, b); +} +constexpr recv_flags operator^(recv_flags a, recv_flags b) noexcept +{ + return detail::enum_bit_xor(a, b); +} +constexpr recv_flags operator~(recv_flags a) noexcept +{ + return detail::enum_bit_not(a); +} + + +// mutable_buffer, const_buffer and buffer are based on +// the Networking TS specification, draft: +// http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2018/n4771.pdf + +class mutable_buffer +{ + public: + constexpr mutable_buffer() noexcept : _data(nullptr), _size(0) {} + constexpr mutable_buffer(void *p, size_t n) noexcept : _data(p), _size(n) + { +#ifdef ZMQ_EXTENDED_CONSTEXPR + assert(p != nullptr || n == 0); +#endif + } + + constexpr void *data() const noexcept { return _data; } + constexpr size_t size() const noexcept { return _size; } + mutable_buffer &operator+=(size_t n) noexcept + { + // (std::min) is a workaround for when a min macro is defined + const auto shift = (std::min)(n, _size); + _data = static_cast(_data) + shift; + _size -= shift; + return *this; + } + + private: + void *_data; + size_t _size; +}; + +inline mutable_buffer operator+(const mutable_buffer &mb, size_t n) noexcept +{ + return mutable_buffer(static_cast(mb.data()) + (std::min)(n, mb.size()), + mb.size() - (std::min)(n, mb.size())); +} +inline mutable_buffer operator+(size_t n, const mutable_buffer &mb) noexcept +{ + return mb + n; +} + +class const_buffer +{ + public: + constexpr const_buffer() noexcept : _data(nullptr), _size(0) {} + constexpr const_buffer(const void *p, size_t n) noexcept : _data(p), _size(n) + { +#ifdef ZMQ_EXTENDED_CONSTEXPR + assert(p != nullptr || n == 0); +#endif + } + constexpr const_buffer(const mutable_buffer &mb) noexcept : + _data(mb.data()), + _size(mb.size()) + { + } + + constexpr const void *data() const noexcept { return _data; } + constexpr size_t size() const noexcept { return _size; } + const_buffer &operator+=(size_t n) noexcept + { + const auto shift = (std::min)(n, _size); + _data = static_cast(_data) + shift; + _size -= shift; + return *this; + } + + private: + const void *_data; + size_t _size; +}; + +inline const_buffer operator+(const const_buffer &cb, size_t n) noexcept +{ + return const_buffer(static_cast(cb.data()) + + (std::min)(n, cb.size()), + cb.size() - (std::min)(n, cb.size())); +} +inline const_buffer operator+(size_t n, const const_buffer &cb) noexcept +{ + return cb + n; +} + +// buffer creation + +constexpr mutable_buffer buffer(void *p, size_t n) noexcept +{ + return mutable_buffer(p, n); +} +constexpr const_buffer buffer(const void *p, size_t n) noexcept +{ + return const_buffer(p, n); +} +constexpr mutable_buffer buffer(const mutable_buffer &mb) noexcept +{ + return mb; +} +inline mutable_buffer buffer(const mutable_buffer &mb, size_t n) noexcept +{ + return mutable_buffer(mb.data(), (std::min)(mb.size(), n)); +} +constexpr const_buffer buffer(const const_buffer &cb) noexcept +{ + return cb; +} +inline const_buffer buffer(const const_buffer &cb, size_t n) noexcept +{ + return const_buffer(cb.data(), (std::min)(cb.size(), n)); +} + +namespace detail +{ +template struct is_buffer +{ + static constexpr bool value = + std::is_same::value || std::is_same::value; +}; + +template struct is_pod_like +{ + // NOTE: The networking draft N4771 section 16.11 requires + // T in the buffer functions below to be + // trivially copyable OR standard layout. + // Here we decide to be conservative and require both. + static constexpr bool value = + ZMQ_IS_TRIVIALLY_COPYABLE(T) && std::is_standard_layout::value; +}; + +template constexpr auto seq_size(const C &c) noexcept -> decltype(c.size()) +{ + return c.size(); +} +template +constexpr size_t seq_size(const T (&/*array*/)[N]) noexcept +{ + return N; +} + +template +auto buffer_contiguous_sequence(Seq &&seq) noexcept + -> decltype(buffer(std::addressof(*std::begin(seq)), size_t{})) +{ + using T = typename std::remove_cv< + typename std::remove_reference::type>::type; + static_assert(detail::is_pod_like::value, "T must be POD"); + + const auto size = seq_size(seq); + return buffer(size != 0u ? std::addressof(*std::begin(seq)) : nullptr, + size * sizeof(T)); +} +template +auto buffer_contiguous_sequence(Seq &&seq, size_t n_bytes) noexcept + -> decltype(buffer_contiguous_sequence(seq)) +{ + using T = typename std::remove_cv< + typename std::remove_reference::type>::type; + static_assert(detail::is_pod_like::value, "T must be POD"); + + const auto size = seq_size(seq); + return buffer(size != 0u ? std::addressof(*std::begin(seq)) : nullptr, + (std::min)(size * sizeof(T), n_bytes)); +} + +} // namespace detail + +// C array +template mutable_buffer buffer(T (&data)[N]) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +mutable_buffer buffer(T (&data)[N], size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template const_buffer buffer(const T (&data)[N]) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(const T (&data)[N], size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +// std::array +template mutable_buffer buffer(std::array &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +mutable_buffer buffer(std::array &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template +const_buffer buffer(std::array &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(std::array &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template +const_buffer buffer(const std::array &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(const std::array &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +// std::vector +template +mutable_buffer buffer(std::vector &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +mutable_buffer buffer(std::vector &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template +const_buffer buffer(const std::vector &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(const std::vector &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +// std::basic_string +template +mutable_buffer buffer(std::basic_string &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +mutable_buffer buffer(std::basic_string &data, + size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template +const_buffer buffer(const std::basic_string &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(const std::basic_string &data, + size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} + +#if CPPZMQ_HAS_STRING_VIEW +// std::basic_string_view +template +const_buffer buffer(std::basic_string_view data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(std::basic_string_view data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +#endif + +// Buffer for a string literal (null terminated) +// where the buffer size excludes the terminating character. +// Equivalent to zmq::buffer(std::string_view("...")). +template +constexpr const_buffer str_buffer(const Char (&data)[N]) noexcept +{ + static_assert(detail::is_pod_like::value, "Char must be POD"); +#ifdef ZMQ_EXTENDED_CONSTEXPR + assert(data[N - 1] == Char{0}); +#endif + return const_buffer(static_cast(data), (N - 1) * sizeof(Char)); +} + +namespace literals +{ +constexpr const_buffer operator"" _zbuf(const char *str, size_t len) noexcept +{ + return const_buffer(str, len * sizeof(char)); +} +constexpr const_buffer operator"" _zbuf(const wchar_t *str, size_t len) noexcept +{ + return const_buffer(str, len * sizeof(wchar_t)); +} +constexpr const_buffer operator"" _zbuf(const char16_t *str, size_t len) noexcept +{ + return const_buffer(str, len * sizeof(char16_t)); +} +constexpr const_buffer operator"" _zbuf(const char32_t *str, size_t len) noexcept +{ + return const_buffer(str, len * sizeof(char32_t)); +} +} + +#endif // ZMQ_CPP11 + + +#ifdef ZMQ_CPP11 +namespace sockopt +{ +// There are two types of options, +// integral type with known compiler time size (int, bool, int64_t, uint64_t) +// and arrays with dynamic size (strings, binary data). + +// BoolUnit: if true accepts values of type bool (but passed as T into libzmq) +template struct integral_option +{ +}; + +// NullTerm: +// 0: binary data +// 1: null-terminated string (`getsockopt` size includes null) +// 2: binary (size 32) or Z85 encoder string of size 41 (null included) +template struct array_option +{ +}; + +#define ZMQ_DEFINE_INTEGRAL_OPT(OPT, NAME, TYPE) \ + using NAME##_t = integral_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} +#define ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(OPT, NAME, TYPE) \ + using NAME##_t = integral_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} +#define ZMQ_DEFINE_ARRAY_OPT(OPT, NAME) \ + using NAME##_t = array_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} +#define ZMQ_DEFINE_ARRAY_OPT_BINARY(OPT, NAME) \ + using NAME##_t = array_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} +#define ZMQ_DEFINE_ARRAY_OPT_BIN_OR_Z85(OPT, NAME) \ + using NAME##_t = array_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} + +// duplicate definition from libzmq 4.3.3 +#if defined _WIN32 +#if defined _WIN64 +typedef unsigned __int64 cppzmq_fd_t; +#else +typedef unsigned int cppzmq_fd_t; +#endif +#else +typedef int cppzmq_fd_t; +#endif + +#ifdef ZMQ_AFFINITY +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_AFFINITY, affinity, uint64_t); +#endif +#ifdef ZMQ_BACKLOG +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_BACKLOG, backlog, int); +#endif +#ifdef ZMQ_BINDTODEVICE +ZMQ_DEFINE_ARRAY_OPT_BINARY(ZMQ_BINDTODEVICE, bindtodevice); +#endif +#ifdef ZMQ_CONFLATE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_CONFLATE, conflate, int); +#endif +#ifdef ZMQ_CONNECT_ROUTING_ID +ZMQ_DEFINE_ARRAY_OPT(ZMQ_CONNECT_ROUTING_ID, connect_routing_id); +#endif +#ifdef ZMQ_CONNECT_TIMEOUT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_CONNECT_TIMEOUT, connect_timeout, int); +#endif +#ifdef ZMQ_CURVE_PUBLICKEY +ZMQ_DEFINE_ARRAY_OPT_BIN_OR_Z85(ZMQ_CURVE_PUBLICKEY, curve_publickey); +#endif +#ifdef ZMQ_CURVE_SECRETKEY +ZMQ_DEFINE_ARRAY_OPT_BIN_OR_Z85(ZMQ_CURVE_SECRETKEY, curve_secretkey); +#endif +#ifdef ZMQ_CURVE_SERVER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_CURVE_SERVER, curve_server, int); +#endif +#ifdef ZMQ_CURVE_SERVERKEY +ZMQ_DEFINE_ARRAY_OPT_BIN_OR_Z85(ZMQ_CURVE_SERVERKEY, curve_serverkey); +#endif +#ifdef ZMQ_EVENTS +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_EVENTS, events, int); +#endif +#ifdef ZMQ_FD +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_FD, fd, cppzmq_fd_t); +#endif +#ifdef ZMQ_GSSAPI_PLAINTEXT +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_GSSAPI_PLAINTEXT, gssapi_plaintext, int); +#endif +#ifdef ZMQ_GSSAPI_SERVER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_GSSAPI_SERVER, gssapi_server, int); +#endif +#ifdef ZMQ_GSSAPI_SERVICE_PRINCIPAL +ZMQ_DEFINE_ARRAY_OPT(ZMQ_GSSAPI_SERVICE_PRINCIPAL, gssapi_service_principal); +#endif +#ifdef ZMQ_GSSAPI_SERVICE_PRINCIPAL_NAMETYPE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_GSSAPI_SERVICE_PRINCIPAL_NAMETYPE, + gssapi_service_principal_nametype, + int); +#endif +#ifdef ZMQ_GSSAPI_PRINCIPAL +ZMQ_DEFINE_ARRAY_OPT(ZMQ_GSSAPI_PRINCIPAL, gssapi_principal); +#endif +#ifdef ZMQ_GSSAPI_PRINCIPAL_NAMETYPE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_GSSAPI_PRINCIPAL_NAMETYPE, + gssapi_principal_nametype, + int); +#endif +#ifdef ZMQ_HANDSHAKE_IVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_HANDSHAKE_IVL, handshake_ivl, int); +#endif +#ifdef ZMQ_HEARTBEAT_IVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_HEARTBEAT_IVL, heartbeat_ivl, int); +#endif +#ifdef ZMQ_HEARTBEAT_TIMEOUT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_HEARTBEAT_TIMEOUT, heartbeat_timeout, int); +#endif +#ifdef ZMQ_HEARTBEAT_TTL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_HEARTBEAT_TTL, heartbeat_ttl, int); +#endif +#ifdef ZMQ_IMMEDIATE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_IMMEDIATE, immediate, int); +#endif +#ifdef ZMQ_INVERT_MATCHING +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_INVERT_MATCHING, invert_matching, int); +#endif +#ifdef ZMQ_IPV6 +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_IPV6, ipv6, int); +#endif +#ifdef ZMQ_LAST_ENDPOINT +ZMQ_DEFINE_ARRAY_OPT(ZMQ_LAST_ENDPOINT, last_endpoint); +#endif +#ifdef ZMQ_LINGER +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_LINGER, linger, int); +#endif +#ifdef ZMQ_MAXMSGSIZE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_MAXMSGSIZE, maxmsgsize, int64_t); +#endif +#ifdef ZMQ_MECHANISM +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_MECHANISM, mechanism, int); +#endif +#ifdef ZMQ_METADATA +ZMQ_DEFINE_ARRAY_OPT(ZMQ_METADATA, metadata); +#endif +#ifdef ZMQ_MULTICAST_HOPS +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_MULTICAST_HOPS, multicast_hops, int); +#endif +#ifdef ZMQ_MULTICAST_LOOP +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_MULTICAST_LOOP, multicast_loop, int); +#endif +#ifdef ZMQ_MULTICAST_MAXTPDU +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_MULTICAST_MAXTPDU, multicast_maxtpdu, int); +#endif +#ifdef ZMQ_PLAIN_SERVER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_PLAIN_SERVER, plain_server, int); +#endif +#ifdef ZMQ_PLAIN_PASSWORD +ZMQ_DEFINE_ARRAY_OPT(ZMQ_PLAIN_PASSWORD, plain_password); +#endif +#ifdef ZMQ_PLAIN_USERNAME +ZMQ_DEFINE_ARRAY_OPT(ZMQ_PLAIN_USERNAME, plain_username); +#endif +#ifdef ZMQ_USE_FD +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_USE_FD, use_fd, int); +#endif +#ifdef ZMQ_PROBE_ROUTER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_PROBE_ROUTER, probe_router, int); +#endif +#ifdef ZMQ_RATE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RATE, rate, int); +#endif +#ifdef ZMQ_RCVBUF +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RCVBUF, rcvbuf, int); +#endif +#ifdef ZMQ_RCVHWM +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RCVHWM, rcvhwm, int); +#endif +#ifdef ZMQ_RCVMORE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_RCVMORE, rcvmore, int); +#endif +#ifdef ZMQ_RCVTIMEO +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RCVTIMEO, rcvtimeo, int); +#endif +#ifdef ZMQ_RECONNECT_IVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RECONNECT_IVL, reconnect_ivl, int); +#endif +#ifdef ZMQ_RECONNECT_IVL_MAX +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RECONNECT_IVL_MAX, reconnect_ivl_max, int); +#endif +#ifdef ZMQ_RECOVERY_IVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RECOVERY_IVL, recovery_ivl, int); +#endif +#ifdef ZMQ_REQ_CORRELATE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_REQ_CORRELATE, req_correlate, int); +#endif +#ifdef ZMQ_REQ_RELAXED +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_REQ_RELAXED, req_relaxed, int); +#endif +#ifdef ZMQ_ROUTER_HANDOVER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_ROUTER_HANDOVER, router_handover, int); +#endif +#ifdef ZMQ_ROUTER_MANDATORY +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_ROUTER_MANDATORY, router_mandatory, int); +#endif +#ifdef ZMQ_ROUTER_NOTIFY +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_ROUTER_NOTIFY, router_notify, int); +#endif +#ifdef ZMQ_ROUTING_ID +ZMQ_DEFINE_ARRAY_OPT_BINARY(ZMQ_ROUTING_ID, routing_id); +#endif +#ifdef ZMQ_SNDBUF +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_SNDBUF, sndbuf, int); +#endif +#ifdef ZMQ_SNDHWM +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_SNDHWM, sndhwm, int); +#endif +#ifdef ZMQ_SNDTIMEO +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_SNDTIMEO, sndtimeo, int); +#endif +#ifdef ZMQ_SOCKS_PROXY +ZMQ_DEFINE_ARRAY_OPT(ZMQ_SOCKS_PROXY, socks_proxy); +#endif +#ifdef ZMQ_STREAM_NOTIFY +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_STREAM_NOTIFY, stream_notify, int); +#endif +#ifdef ZMQ_SUBSCRIBE +ZMQ_DEFINE_ARRAY_OPT(ZMQ_SUBSCRIBE, subscribe); +#endif +#ifdef ZMQ_TCP_KEEPALIVE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_KEEPALIVE, tcp_keepalive, int); +#endif +#ifdef ZMQ_TCP_KEEPALIVE_CNT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_KEEPALIVE_CNT, tcp_keepalive_cnt, int); +#endif +#ifdef ZMQ_TCP_KEEPALIVE_IDLE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_KEEPALIVE_IDLE, tcp_keepalive_idle, int); +#endif +#ifdef ZMQ_TCP_KEEPALIVE_INTVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_KEEPALIVE_INTVL, tcp_keepalive_intvl, int); +#endif +#ifdef ZMQ_TCP_MAXRT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_MAXRT, tcp_maxrt, int); +#endif +#ifdef ZMQ_THREAD_SAFE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_THREAD_SAFE, thread_safe, int); +#endif +#ifdef ZMQ_TOS +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TOS, tos, int); +#endif +#ifdef ZMQ_TYPE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TYPE, type, int); +#endif +#ifdef ZMQ_UNSUBSCRIBE +ZMQ_DEFINE_ARRAY_OPT(ZMQ_UNSUBSCRIBE, unsubscribe); +#endif +#ifdef ZMQ_VMCI_BUFFER_SIZE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_VMCI_BUFFER_SIZE, vmci_buffer_size, uint64_t); +#endif +#ifdef ZMQ_VMCI_BUFFER_MIN_SIZE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_VMCI_BUFFER_MIN_SIZE, vmci_buffer_min_size, uint64_t); +#endif +#ifdef ZMQ_VMCI_BUFFER_MAX_SIZE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_VMCI_BUFFER_MAX_SIZE, vmci_buffer_max_size, uint64_t); +#endif +#ifdef ZMQ_VMCI_CONNECT_TIMEOUT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_VMCI_CONNECT_TIMEOUT, vmci_connect_timeout, int); +#endif +#ifdef ZMQ_XPUB_VERBOSE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_XPUB_VERBOSE, xpub_verbose, int); +#endif +#ifdef ZMQ_XPUB_VERBOSER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_XPUB_VERBOSER, xpub_verboser, int); +#endif +#ifdef ZMQ_XPUB_MANUAL +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_XPUB_MANUAL, xpub_manual, int); +#endif +#ifdef ZMQ_XPUB_NODROP +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_XPUB_NODROP, xpub_nodrop, int); +#endif +#ifdef ZMQ_XPUB_WELCOME_MSG +ZMQ_DEFINE_ARRAY_OPT(ZMQ_XPUB_WELCOME_MSG, xpub_welcome_msg); +#endif +#ifdef ZMQ_ZAP_ENFORCE_DOMAIN +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_ZAP_ENFORCE_DOMAIN, zap_enforce_domain, int); +#endif +#ifdef ZMQ_ZAP_DOMAIN +ZMQ_DEFINE_ARRAY_OPT(ZMQ_ZAP_DOMAIN, zap_domain); +#endif + +} // namespace sockopt +#endif // ZMQ_CPP11 + + +namespace detail +{ +class socket_base +{ + public: + socket_base() ZMQ_NOTHROW : _handle(ZMQ_NULLPTR) {} + ZMQ_EXPLICIT socket_base(void *handle) ZMQ_NOTHROW : _handle(handle) {} + + template + ZMQ_CPP11_DEPRECATED("from 4.7.0, use `set` taking option from zmq::sockopt") + void setsockopt(int option_, T const &optval) + { + setsockopt(option_, &optval, sizeof(T)); + } + + ZMQ_CPP11_DEPRECATED("from 4.7.0, use `set` taking option from zmq::sockopt") + void setsockopt(int option_, const void *optval_, size_t optvallen_) + { + int rc = zmq_setsockopt(_handle, option_, optval_, optvallen_); + if (rc != 0) + throw error_t(); + } + + ZMQ_CPP11_DEPRECATED("from 4.7.0, use `get` taking option from zmq::sockopt") + void getsockopt(int option_, void *optval_, size_t *optvallen_) const + { + int rc = zmq_getsockopt(_handle, option_, optval_, optvallen_); + if (rc != 0) + throw error_t(); + } + + template + ZMQ_CPP11_DEPRECATED("from 4.7.0, use `get` taking option from zmq::sockopt") + T getsockopt(int option_) const + { + T optval; + size_t optlen = sizeof(T); + getsockopt(option_, &optval, &optlen); + return optval; + } + +#ifdef ZMQ_CPP11 + // Set integral socket option, e.g. + // `socket.set(zmq::sockopt::linger, 0)` + template + void set(sockopt::integral_option, const T &val) + { + static_assert(std::is_integral::value, "T must be integral"); + set_option(Opt, &val, sizeof val); + } + + // Set integral socket option from boolean, e.g. + // `socket.set(zmq::sockopt::immediate, false)` + template + void set(sockopt::integral_option, bool val) + { + static_assert(std::is_integral::value, "T must be integral"); + T rep_val = val; + set_option(Opt, &rep_val, sizeof rep_val); + } + + // Set array socket option, e.g. + // `socket.set(zmq::sockopt::plain_username, "foo123")` + template + void set(sockopt::array_option, const char *buf) + { + set_option(Opt, buf, std::strlen(buf)); + } + + // Set array socket option, e.g. + // `socket.set(zmq::sockopt::routing_id, zmq::buffer(id))` + template + void set(sockopt::array_option, const_buffer buf) + { + set_option(Opt, buf.data(), buf.size()); + } + + // Set array socket option, e.g. + // `socket.set(zmq::sockopt::routing_id, id_str)` + template + void set(sockopt::array_option, const std::string &buf) + { + set_option(Opt, buf.data(), buf.size()); + } + +#if CPPZMQ_HAS_STRING_VIEW + // Set array socket option, e.g. + // `socket.set(zmq::sockopt::routing_id, id_str)` + template + void set(sockopt::array_option, std::string_view buf) + { + set_option(Opt, buf.data(), buf.size()); + } +#endif + + // Get scalar socket option, e.g. + // `auto opt = socket.get(zmq::sockopt::linger)` + template + ZMQ_NODISCARD T get(sockopt::integral_option) const + { + static_assert(std::is_integral::value, "T must be integral"); + T val; + size_t size = sizeof val; + get_option(Opt, &val, &size); + assert(size == sizeof val); + return val; + } + + // Get array socket option, writes to buf, returns option size in bytes, e.g. + // `size_t optsize = socket.get(zmq::sockopt::routing_id, zmq::buffer(id))` + template + ZMQ_NODISCARD size_t get(sockopt::array_option, + mutable_buffer buf) const + { + size_t size = buf.size(); + get_option(Opt, buf.data(), &size); + return size; + } + + // Get array socket option as string (initializes the string buffer size to init_size) e.g. + // `auto s = socket.get(zmq::sockopt::routing_id)` + // Note: removes the null character from null-terminated string options, + // i.e. the string size excludes the null character. + template + ZMQ_NODISCARD std::string get(sockopt::array_option, + size_t init_size = 1024) const + { + if (NullTerm == 2 && init_size == 1024) { + init_size = 41; // get as Z85 string + } + std::string str(init_size, '\0'); + size_t size = get(sockopt::array_option{}, buffer(str)); + if (NullTerm == 1) { + if (size > 0) { + assert(str[size - 1] == '\0'); + --size; + } + } else if (NullTerm == 2) { + assert(size == 32 || size == 41); + if (size == 41) { + assert(str[size - 1] == '\0'); + --size; + } + } + str.resize(size); + return str; + } +#endif + + void bind(std::string const &addr) { bind(addr.c_str()); } + + void bind(const char *addr_) + { + int rc = zmq_bind(_handle, addr_); + if (rc != 0) + throw error_t(); + } + + void unbind(std::string const &addr) { unbind(addr.c_str()); } + + void unbind(const char *addr_) + { + int rc = zmq_unbind(_handle, addr_); + if (rc != 0) + throw error_t(); + } + + void connect(std::string const &addr) { connect(addr.c_str()); } + + void connect(const char *addr_) + { + int rc = zmq_connect(_handle, addr_); + if (rc != 0) + throw error_t(); + } + + void disconnect(std::string const &addr) { disconnect(addr.c_str()); } + + void disconnect(const char *addr_) + { + int rc = zmq_disconnect(_handle, addr_); + if (rc != 0) + throw error_t(); + } + + bool connected() const ZMQ_NOTHROW { return (_handle != ZMQ_NULLPTR); } + + ZMQ_CPP11_DEPRECATED("from 4.3.1, use send taking a const_buffer and send_flags") + size_t send(const void *buf_, size_t len_, int flags_ = 0) + { + int nbytes = zmq_send(_handle, buf_, len_, flags_); + if (nbytes >= 0) + return static_cast(nbytes); + if (zmq_errno() == EAGAIN) + return 0; + throw error_t(); + } + + ZMQ_CPP11_DEPRECATED("from 4.3.1, use send taking message_t and send_flags") + bool send(message_t &msg_, + int flags_ = 0) // default until removed + { + int nbytes = zmq_msg_send(msg_.handle(), _handle, flags_); + if (nbytes >= 0) + return true; + if (zmq_errno() == EAGAIN) + return false; + throw error_t(); + } + + template + ZMQ_CPP11_DEPRECATED( + "from 4.4.1, use send taking message_t or buffer (for contiguous " + "ranges), and send_flags") + bool send(T first, T last, int flags_ = 0) + { + zmq::message_t msg(first, last); + int nbytes = zmq_msg_send(msg.handle(), _handle, flags_); + if (nbytes >= 0) + return true; + if (zmq_errno() == EAGAIN) + return false; + throw error_t(); + } + +#ifdef ZMQ_HAS_RVALUE_REFS + ZMQ_CPP11_DEPRECATED("from 4.3.1, use send taking message_t and send_flags") + bool send(message_t &&msg_, + int flags_ = 0) // default until removed + { +#ifdef ZMQ_CPP11 + return send(msg_, static_cast(flags_)).has_value(); +#else + return send(msg_, flags_); +#endif + } +#endif + +#ifdef ZMQ_CPP11 + send_result_t send(const_buffer buf, send_flags flags = send_flags::none) + { + const int nbytes = + zmq_send(_handle, buf.data(), buf.size(), static_cast(flags)); + if (nbytes >= 0) + return static_cast(nbytes); + if (zmq_errno() == EAGAIN) + return {}; + throw error_t(); + } + + send_result_t send(message_t &msg, send_flags flags) + { + int nbytes = zmq_msg_send(msg.handle(), _handle, static_cast(flags)); + if (nbytes >= 0) + return static_cast(nbytes); + if (zmq_errno() == EAGAIN) + return {}; + throw error_t(); + } + + send_result_t send(message_t &&msg, send_flags flags) + { + return send(msg, flags); + } +#endif + + ZMQ_CPP11_DEPRECATED( + "from 4.3.1, use recv taking a mutable_buffer and recv_flags") + size_t recv(void *buf_, size_t len_, int flags_ = 0) + { + int nbytes = zmq_recv(_handle, buf_, len_, flags_); + if (nbytes >= 0) + return static_cast(nbytes); + if (zmq_errno() == EAGAIN) + return 0; + throw error_t(); + } + + ZMQ_CPP11_DEPRECATED( + "from 4.3.1, use recv taking a reference to message_t and recv_flags") + bool recv(message_t *msg_, int flags_ = 0) + { + int nbytes = zmq_msg_recv(msg_->handle(), _handle, flags_); + if (nbytes >= 0) + return true; + if (zmq_errno() == EAGAIN) + return false; + throw error_t(); + } + +#ifdef ZMQ_CPP11 + ZMQ_NODISCARD + recv_buffer_result_t recv(mutable_buffer buf, + recv_flags flags = recv_flags::none) + { + const int nbytes = + zmq_recv(_handle, buf.data(), buf.size(), static_cast(flags)); + if (nbytes >= 0) { + return recv_buffer_size{ + (std::min)(static_cast(nbytes), buf.size()), + static_cast(nbytes)}; + } + if (zmq_errno() == EAGAIN) + return {}; + throw error_t(); + } + + ZMQ_NODISCARD + recv_result_t recv(message_t &msg, recv_flags flags = recv_flags::none) + { + const int nbytes = + zmq_msg_recv(msg.handle(), _handle, static_cast(flags)); + if (nbytes >= 0) { + assert(msg.size() == static_cast(nbytes)); + return static_cast(nbytes); + } + if (zmq_errno() == EAGAIN) + return {}; + throw error_t(); + } +#endif + +#if defined(ZMQ_BUILD_DRAFT_API) && ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 0) + void join(const char *group) + { + int rc = zmq_join(_handle, group); + if (rc != 0) + throw error_t(); + } + + void leave(const char *group) + { + int rc = zmq_leave(_handle, group); + if (rc != 0) + throw error_t(); + } +#endif + + ZMQ_NODISCARD void *handle() ZMQ_NOTHROW { return _handle; } + ZMQ_NODISCARD const void *handle() const ZMQ_NOTHROW { return _handle; } + + ZMQ_EXPLICIT operator bool() const ZMQ_NOTHROW { return _handle != ZMQ_NULLPTR; } + // note: non-const operator bool can be removed once + // operator void* is removed from socket_t + ZMQ_EXPLICIT operator bool() ZMQ_NOTHROW { return _handle != ZMQ_NULLPTR; } + + protected: + void *_handle; + + private: + void set_option(int option_, const void *optval_, size_t optvallen_) + { + int rc = zmq_setsockopt(_handle, option_, optval_, optvallen_); + if (rc != 0) + throw error_t(); + } + + void get_option(int option_, void *optval_, size_t *optvallen_) const + { + int rc = zmq_getsockopt(_handle, option_, optval_, optvallen_); + if (rc != 0) + throw error_t(); + } +}; +} // namespace detail + +#ifdef ZMQ_CPP11 +enum class socket_type : int +{ + req = ZMQ_REQ, + rep = ZMQ_REP, + dealer = ZMQ_DEALER, + router = ZMQ_ROUTER, + pub = ZMQ_PUB, + sub = ZMQ_SUB, + xpub = ZMQ_XPUB, + xsub = ZMQ_XSUB, + push = ZMQ_PUSH, + pull = ZMQ_PULL, +#if defined(ZMQ_BUILD_DRAFT_API) && ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 0) + server = ZMQ_SERVER, + client = ZMQ_CLIENT, + radio = ZMQ_RADIO, + dish = ZMQ_DISH, +#endif +#if ZMQ_VERSION_MAJOR >= 4 + stream = ZMQ_STREAM, +#endif + pair = ZMQ_PAIR +}; +#endif + +struct from_handle_t +{ + struct _private + { + }; // disabling use other than with from_handle + ZMQ_CONSTEXPR_FN ZMQ_EXPLICIT from_handle_t(_private /*p*/) ZMQ_NOTHROW {} +}; + +ZMQ_CONSTEXPR_VAR from_handle_t from_handle = + from_handle_t(from_handle_t::_private()); + +// A non-owning nullable reference to a socket. +// The reference is invalidated on socket close or destruction. +class socket_ref : public detail::socket_base +{ + public: + socket_ref() ZMQ_NOTHROW : detail::socket_base() {} +#ifdef ZMQ_CPP11 + socket_ref(std::nullptr_t) ZMQ_NOTHROW : detail::socket_base() {} +#endif + socket_ref(from_handle_t /*fh*/, void *handle) ZMQ_NOTHROW + : detail::socket_base(handle) + { + } +}; + +#ifdef ZMQ_CPP11 +inline bool operator==(socket_ref sr, std::nullptr_t /*p*/) ZMQ_NOTHROW +{ + return sr.handle() == nullptr; +} +inline bool operator==(std::nullptr_t /*p*/, socket_ref sr) ZMQ_NOTHROW +{ + return sr.handle() == nullptr; +} +inline bool operator!=(socket_ref sr, std::nullptr_t /*p*/) ZMQ_NOTHROW +{ + return !(sr == nullptr); +} +inline bool operator!=(std::nullptr_t /*p*/, socket_ref sr) ZMQ_NOTHROW +{ + return !(sr == nullptr); +} +#endif + +inline bool operator==(socket_ref a, socket_ref b) ZMQ_NOTHROW +{ + return std::equal_to()(a.handle(), b.handle()); +} +inline bool operator!=(socket_ref a, socket_ref b) ZMQ_NOTHROW +{ + return !(a == b); +} +inline bool operator<(socket_ref a, socket_ref b) ZMQ_NOTHROW +{ + return std::less()(a.handle(), b.handle()); +} +inline bool operator>(socket_ref a, socket_ref b) ZMQ_NOTHROW +{ + return b < a; +} +inline bool operator<=(socket_ref a, socket_ref b) ZMQ_NOTHROW +{ + return !(a > b); +} +inline bool operator>=(socket_ref a, socket_ref b) ZMQ_NOTHROW +{ + return !(a < b); +} + +} // namespace zmq + +#ifdef ZMQ_CPP11 +namespace std +{ +template<> struct hash +{ + size_t operator()(zmq::socket_ref sr) const ZMQ_NOTHROW + { + return hash()(sr.handle()); + } +}; +} // namespace std +#endif + +namespace zmq +{ +class socket_t : public detail::socket_base +{ + friend class monitor_t; + + public: + socket_t() ZMQ_NOTHROW : detail::socket_base(ZMQ_NULLPTR), ctxptr(ZMQ_NULLPTR) {} + + socket_t(context_t &context_, int type_) : + detail::socket_base(zmq_socket(context_.handle(), type_)), + ctxptr(context_.handle()) + { + if (_handle == ZMQ_NULLPTR) + throw error_t(); + } + +#ifdef ZMQ_CPP11 + socket_t(context_t &context_, socket_type type_) : + socket_t(context_, static_cast(type_)) + { + } +#endif + +#ifdef ZMQ_HAS_RVALUE_REFS + socket_t(socket_t &&rhs) ZMQ_NOTHROW : detail::socket_base(rhs._handle), + ctxptr(rhs.ctxptr) + { + rhs._handle = ZMQ_NULLPTR; + rhs.ctxptr = ZMQ_NULLPTR; + } + socket_t &operator=(socket_t &&rhs) ZMQ_NOTHROW + { + close(); + std::swap(_handle, rhs._handle); + std::swap(ctxptr, rhs.ctxptr); + return *this; + } +#endif + + ~socket_t() ZMQ_NOTHROW { close(); } + + operator void *() ZMQ_NOTHROW { return _handle; } + + operator void const *() const ZMQ_NOTHROW { return _handle; } + + void close() ZMQ_NOTHROW + { + if (_handle == ZMQ_NULLPTR) + // already closed + return; + int rc = zmq_close(_handle); + ZMQ_ASSERT(rc == 0); + _handle = ZMQ_NULLPTR; + ctxptr = ZMQ_NULLPTR; + } + + void swap(socket_t &other) ZMQ_NOTHROW + { + std::swap(_handle, other._handle); + std::swap(ctxptr, other.ctxptr); + } + + operator socket_ref() ZMQ_NOTHROW { return socket_ref(from_handle, _handle); } + + private: + void *ctxptr; + + socket_t(const socket_t &) ZMQ_DELETED_FUNCTION; + void operator=(const socket_t &) ZMQ_DELETED_FUNCTION; + + // used by monitor_t + socket_t(void *context_, int type_) : + detail::socket_base(zmq_socket(context_, type_)), + ctxptr(context_) + { + if (_handle == ZMQ_NULLPTR) + throw error_t(); + if (ctxptr == ZMQ_NULLPTR) + throw error_t(); + } +}; + +inline void swap(socket_t &a, socket_t &b) ZMQ_NOTHROW +{ + a.swap(b); +} + +ZMQ_DEPRECATED("from 4.3.1, use proxy taking socket_t objects") +inline void proxy(void *frontend, void *backend, void *capture) +{ + int rc = zmq_proxy(frontend, backend, capture); + if (rc != 0) + throw error_t(); +} + +inline void +proxy(socket_ref frontend, socket_ref backend, socket_ref capture = socket_ref()) +{ + int rc = zmq_proxy(frontend.handle(), backend.handle(), capture.handle()); + if (rc != 0) + throw error_t(); +} + +#ifdef ZMQ_HAS_PROXY_STEERABLE +ZMQ_DEPRECATED("from 4.3.1, use proxy_steerable taking socket_t objects") +inline void +proxy_steerable(void *frontend, void *backend, void *capture, void *control) +{ + int rc = zmq_proxy_steerable(frontend, backend, capture, control); + if (rc != 0) + throw error_t(); +} + +inline void proxy_steerable(socket_ref frontend, + socket_ref backend, + socket_ref capture, + socket_ref control) +{ + int rc = zmq_proxy_steerable(frontend.handle(), backend.handle(), + capture.handle(), control.handle()); + if (rc != 0) + throw error_t(); +} +#endif + +class monitor_t +{ + public: + monitor_t() : _socket(), _monitor_socket() {} + + virtual ~monitor_t() { close(); } + +#ifdef ZMQ_HAS_RVALUE_REFS + monitor_t(monitor_t &&rhs) ZMQ_NOTHROW : _socket(), _monitor_socket() + { + std::swap(_socket, rhs._socket); + std::swap(_monitor_socket, rhs._monitor_socket); + } + + monitor_t &operator=(monitor_t &&rhs) ZMQ_NOTHROW + { + close(); + _socket = socket_ref(); + std::swap(_socket, rhs._socket); + std::swap(_monitor_socket, rhs._monitor_socket); + return *this; + } +#endif + + + void + monitor(socket_t &socket, std::string const &addr, int events = ZMQ_EVENT_ALL) + { + monitor(socket, addr.c_str(), events); + } + + void monitor(socket_t &socket, const char *addr_, int events = ZMQ_EVENT_ALL) + { + init(socket, addr_, events); + while (true) { + check_event(-1); + } + } + + void init(socket_t &socket, std::string const &addr, int events = ZMQ_EVENT_ALL) + { + init(socket, addr.c_str(), events); + } + + void init(socket_t &socket, const char *addr_, int events = ZMQ_EVENT_ALL) + { + int rc = zmq_socket_monitor(socket.handle(), addr_, events); + if (rc != 0) + throw error_t(); + + _socket = socket; + _monitor_socket = socket_t(socket.ctxptr, ZMQ_PAIR); + _monitor_socket.connect(addr_); + + on_monitor_started(); + } + + bool check_event(int timeout = 0) + { + assert(_monitor_socket); + + zmq_msg_t eventMsg; + zmq_msg_init(&eventMsg); + + zmq::pollitem_t items[] = { + {_monitor_socket.handle(), 0, ZMQ_POLLIN, 0}, + }; + + zmq::poll(&items[0], 1, timeout); + + if (items[0].revents & ZMQ_POLLIN) { + int rc = zmq_msg_recv(&eventMsg, _monitor_socket.handle(), 0); + if (rc == -1 && zmq_errno() == ETERM) + return false; + assert(rc != -1); + + } else { + zmq_msg_close(&eventMsg); + return false; + } + +#if ZMQ_VERSION_MAJOR >= 4 + const char *data = static_cast(zmq_msg_data(&eventMsg)); + zmq_event_t msgEvent; + memcpy(&msgEvent.event, data, sizeof(uint16_t)); + data += sizeof(uint16_t); + memcpy(&msgEvent.value, data, sizeof(int32_t)); + zmq_event_t *event = &msgEvent; +#else + zmq_event_t *event = static_cast(zmq_msg_data(&eventMsg)); +#endif + +#ifdef ZMQ_NEW_MONITOR_EVENT_LAYOUT + zmq_msg_t addrMsg; + zmq_msg_init(&addrMsg); + int rc = zmq_msg_recv(&addrMsg, _monitor_socket.handle(), 0); + if (rc == -1 && zmq_errno() == ETERM) { + zmq_msg_close(&eventMsg); + return false; + } + + assert(rc != -1); + const char *str = static_cast(zmq_msg_data(&addrMsg)); + std::string address(str, str + zmq_msg_size(&addrMsg)); + zmq_msg_close(&addrMsg); +#else + // Bit of a hack, but all events in the zmq_event_t union have the same layout so this will work for all event types. + std::string address = event->data.connected.addr; +#endif + +#ifdef ZMQ_EVENT_MONITOR_STOPPED + if (event->event == ZMQ_EVENT_MONITOR_STOPPED) { + zmq_msg_close(&eventMsg); + return false; + } + +#endif + + switch (event->event) { + case ZMQ_EVENT_CONNECTED: + on_event_connected(*event, address.c_str()); + break; + case ZMQ_EVENT_CONNECT_DELAYED: + on_event_connect_delayed(*event, address.c_str()); + break; + case ZMQ_EVENT_CONNECT_RETRIED: + on_event_connect_retried(*event, address.c_str()); + break; + case ZMQ_EVENT_LISTENING: + on_event_listening(*event, address.c_str()); + break; + case ZMQ_EVENT_BIND_FAILED: + on_event_bind_failed(*event, address.c_str()); + break; + case ZMQ_EVENT_ACCEPTED: + on_event_accepted(*event, address.c_str()); + break; + case ZMQ_EVENT_ACCEPT_FAILED: + on_event_accept_failed(*event, address.c_str()); + break; + case ZMQ_EVENT_CLOSED: + on_event_closed(*event, address.c_str()); + break; + case ZMQ_EVENT_CLOSE_FAILED: + on_event_close_failed(*event, address.c_str()); + break; + case ZMQ_EVENT_DISCONNECTED: + on_event_disconnected(*event, address.c_str()); + break; +#ifdef ZMQ_BUILD_DRAFT_API +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 3) + case ZMQ_EVENT_HANDSHAKE_FAILED_NO_DETAIL: + on_event_handshake_failed_no_detail(*event, address.c_str()); + break; + case ZMQ_EVENT_HANDSHAKE_FAILED_PROTOCOL: + on_event_handshake_failed_protocol(*event, address.c_str()); + break; + case ZMQ_EVENT_HANDSHAKE_FAILED_AUTH: + on_event_handshake_failed_auth(*event, address.c_str()); + break; + case ZMQ_EVENT_HANDSHAKE_SUCCEEDED: + on_event_handshake_succeeded(*event, address.c_str()); + break; +#elif ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 1) + case ZMQ_EVENT_HANDSHAKE_FAILED: + on_event_handshake_failed(*event, address.c_str()); + break; + case ZMQ_EVENT_HANDSHAKE_SUCCEED: + on_event_handshake_succeed(*event, address.c_str()); + break; +#endif +#endif + default: + on_event_unknown(*event, address.c_str()); + break; + } + zmq_msg_close(&eventMsg); + + return true; + } + +#ifdef ZMQ_EVENT_MONITOR_STOPPED + void abort() + { + if (_socket) + zmq_socket_monitor(_socket.handle(), ZMQ_NULLPTR, 0); + + _socket = socket_ref(); + } +#endif + virtual void on_monitor_started() {} + virtual void on_event_connected(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_connect_delayed(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_connect_retried(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_listening(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_bind_failed(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_accepted(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_accept_failed(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_closed(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_close_failed(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_disconnected(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 3) + virtual void on_event_handshake_failed_no_detail(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_handshake_failed_protocol(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_handshake_failed_auth(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_handshake_succeeded(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } +#elif ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 1) + virtual void on_event_handshake_failed(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_handshake_succeed(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } +#endif + virtual void on_event_unknown(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + + private: + monitor_t(const monitor_t &) ZMQ_DELETED_FUNCTION; + void operator=(const monitor_t &) ZMQ_DELETED_FUNCTION; + + socket_ref _socket; + socket_t _monitor_socket; + + void close() ZMQ_NOTHROW + { + if (_socket) + zmq_socket_monitor(_socket.handle(), ZMQ_NULLPTR, 0); + _monitor_socket.close(); + } +}; + +#if defined(ZMQ_BUILD_DRAFT_API) && defined(ZMQ_CPP11) && defined(ZMQ_HAVE_POLLER) + +// polling events +enum class event_flags : short +{ + none = 0, + pollin = ZMQ_POLLIN, + pollout = ZMQ_POLLOUT, + pollerr = ZMQ_POLLERR, + pollpri = ZMQ_POLLPRI +}; + +constexpr event_flags operator|(event_flags a, event_flags b) noexcept +{ + return detail::enum_bit_or(a, b); +} +constexpr event_flags operator&(event_flags a, event_flags b) noexcept +{ + return detail::enum_bit_and(a, b); +} +constexpr event_flags operator^(event_flags a, event_flags b) noexcept +{ + return detail::enum_bit_xor(a, b); +} +constexpr event_flags operator~(event_flags a) noexcept +{ + return detail::enum_bit_not(a); +} + +struct no_user_data; + +// layout compatible with zmq_poller_event_t +template struct poller_event +{ + socket_ref socket; +#ifdef _WIN32 + SOCKET fd; +#else + int fd; +#endif + T *user_data; + event_flags events; +}; + +template class poller_t +{ + public: + using event_type = poller_event; + + poller_t() : poller_ptr(zmq_poller_new()) + { + if (!poller_ptr) + throw error_t(); + } + + template< + typename Dummy = void, + typename = + typename std::enable_if::value, Dummy>::type> + void add(zmq::socket_ref socket, event_flags events, T *user_data) + { + add_impl(socket, events, user_data); + } + + void add(zmq::socket_ref socket, event_flags events) + { + add_impl(socket, events, nullptr); + } + + void remove(zmq::socket_ref socket) + { + if (0 != zmq_poller_remove(poller_ptr.get(), socket.handle())) { + throw error_t(); + } + } + + void modify(zmq::socket_ref socket, event_flags events) + { + if (0 + != zmq_poller_modify(poller_ptr.get(), socket.handle(), + static_cast(events))) { + throw error_t(); + } + } + + size_t wait_all(std::vector &poller_events, + const std::chrono::milliseconds timeout) + { + int rc = zmq_poller_wait_all( + poller_ptr.get(), + reinterpret_cast(poller_events.data()), + static_cast(poller_events.size()), + static_cast(timeout.count())); + if (rc > 0) + return static_cast(rc); + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 3) + if (zmq_errno() == EAGAIN) +#else + if (zmq_errno() == ETIMEDOUT) +#endif + return 0; + + throw error_t(); + } + + private: + struct destroy_poller_t + { + void operator()(void *ptr) noexcept + { + int rc = zmq_poller_destroy(&ptr); + ZMQ_ASSERT(rc == 0); + } + }; + + std::unique_ptr poller_ptr; + + void add_impl(zmq::socket_ref socket, event_flags events, T *user_data) + { + if (0 + != zmq_poller_add(poller_ptr.get(), socket.handle(), user_data, + static_cast(events))) { + throw error_t(); + } + } +}; +#endif // defined(ZMQ_BUILD_DRAFT_API) && defined(ZMQ_CPP11) && defined(ZMQ_HAVE_POLLER) + +inline std::ostream &operator<<(std::ostream &os, const message_t &msg) +{ + return os << msg.str(); +} + +} // namespace zmq + +#endif // __ZMQ_HPP_INCLUDED__ From 9b766efbff5857928bef2595257fd18e243000e1 Mon Sep 17 00:00:00 2001 From: amangiat88 <69592241+amangiat88@users.noreply.github.com> Date: Thu, 3 Dec 2020 11:40:55 -0600 Subject: [PATCH 067/709] Update bt_factory.cpp (#245) --- src/bt_factory.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 704bdfc73..b8501297e 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -183,7 +183,7 @@ std::vector getCatkinLibraryPaths() void BehaviorTreeFactory::registerFromROSPlugins() { std::vector plugins; - ros::package::getPlugins("behaviortree_cpp", "bt_lib_plugin", plugins, true); + ros::package::getPlugins("behaviortree_cpp_v3", "bt_lib_plugin", plugins, true); std::vector catkin_lib_paths = getCatkinLibraryPaths(); for (const auto& plugin : plugins) From 739beee182dc389183e4aca7d5cdaf25769bb86a Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 10 Dec 2020 21:34:40 +0100 Subject: [PATCH 068/709] version bump --- CHANGELOG.rst | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 9c2412957..1f72a78a3 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Update bt_factory.cpp (`#245 `_) +* Use the latest version of zmq.hpp +* Improved switching BTs with active Groot monitoring (ZMQ logger destruction) (`#244 `_) + * Skip 100ms (max) wait for detached thread + * add {} to single line if statements +* Update retry_node.cpp +* fix +* fix issue `#230 `_ +* Contributors: Davide Faconti, Florian Gramß, amangiat88 + 3.5.3 (2020-09-10) ------------------ * fix issue `#228 `_ . Retry and Repeat node need to halt the child From a2634526a14a0e320f2ed4383d08fb6def2635ba Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 10 Dec 2020 21:34:54 +0100 Subject: [PATCH 069/709] 3.5.4 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 1f72a78a3..491e9a921 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.5.4 (2020-12-10) +------------------ * Update bt_factory.cpp (`#245 `_) * Use the latest version of zmq.hpp * Improved switching BTs with active Groot monitoring (ZMQ logger destruction) (`#244 `_) diff --git a/package.xml b/package.xml index 74c7bd30d..3156ad631 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.5.3 + 3.5.4 This package provides the Behavior Trees core library. From b7c2d9b3a10535158688189010ce42473045ef8d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 20 Jan 2021 23:02:53 +0100 Subject: [PATCH 070/709] fix issue #251 --- CMakeLists.txt | 26 ++++++++++++++++++-------- tools/CMakeLists.txt | 2 +- 2 files changed, 19 insertions(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 70041b00a..69cf90599 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,8 +15,8 @@ endif() #---- Include boost to add coroutines ---- find_package(Boost COMPONENTS coroutine QUIET) + if(Boost_FOUND) - include_directories(${Boost_INCLUDE_DIRS}) string(REPLACE "." "0" Boost_VERSION_NODOT ${Boost_VERSION}) if(NOT Boost_VERSION_NODOT VERSION_LESS 105900) message(STATUS "Found boost::coroutine2.") @@ -24,12 +24,13 @@ if(Boost_FOUND) set(BT_COROUTINES true) elseif(NOT Boost_VERSION_NODOT VERSION_LESS 105300) message(STATUS "Found boost::coroutine.") - include_directories(${Boost_INCLUDE_DIRS}) add_definitions(-DBT_BOOST_COROUTINE) set(BT_COROUTINES true) endif() endif() +include_directories(${Boost_INCLUDE_DIRS}) + if(NOT DEFINED BT_COROUTINES) message(STATUS "Coroutines disabled. Install Boost to enable them (version 1.59+ recommended).") add_definitions(-DBT_NO_COROUTINES) @@ -47,16 +48,15 @@ option(BUILD_SHARED_LIBS "Build shared libraries" ON) find_package(Threads) find_package(ZMQ) -list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES +list(APPEND BEHAVIOR_TREE_PUBLIC_LIBRARIES ${CMAKE_THREAD_LIBS_INIT} ${CMAKE_DL_LIBS} - ${Boost_LIBRARIES} ) +) if( ZMQ_FOUND ) message(STATUS "ZeroMQ found.") add_definitions( -DZMQ_FOUND ) list(APPEND BT_SOURCE src/loggers/bt_zmq_publisher.cpp) - list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${ZMQ_LIBRARIES}) else() message(WARNING "ZeroMQ NOT found. Skipping the build of [PublisherZMQ] and [bt_recorder].") endif() @@ -98,7 +98,7 @@ elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) CATKIN_DEPENDS roslib ) - list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${catkin_LIBRARIES}) + list(APPEND BEHAVIOR_TREE_PUBLIC_LIBRARIES ${catkin_LIBRARIES}) set(BUILD_TOOL_INCLUDE_DIRS ${catkin_INCLUDE_DIRS}) elseif(BUILD_UNIT_TESTS) @@ -181,7 +181,7 @@ if(CURSES_FOUND) list(APPEND BT_SOURCE src/controls/manual_node.cpp ) - list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${CURSES_LIBRARIES}) + list(APPEND BEHAVIOR_TREE_PUBLIC_LIBRARIES ${CURSES_LIBRARIES}) add_definitions(-DNCURSES_FOUND) endif() @@ -208,7 +208,17 @@ if( ZMQ_FOUND ) endif() target_link_libraries(${BEHAVIOR_TREE_LIBRARY} PUBLIC - ${BEHAVIOR_TREE_EXTERNAL_LIBRARIES}) + ${BEHAVIOR_TREE_PUBLIC_LIBRARIES}) + +target_link_libraries(${BEHAVIOR_TREE_LIBRARY} PRIVATE + ${Boost_LIBRARIES} + ${ZMQ_LIBRARIES}) + +#get_target_property(my_libs ${BEHAVIOR_TREE_LIBRARY} INTERFACE_LINK_LIBRARIES) +#list(REMOVE_ITEM _libs X) +#message("my_libs: ${my_libs}") + +#set_target_properties(${BEHAVIOR_TREE_LIBRARY} PROPERTIES INTERFACE_LINK_LIBRARIES "") target_compile_definitions(${BEHAVIOR_TREE_LIBRARY} PRIVATE $<$:TINYXML2_DEBUG>) diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt index c8e883868..08018507d 100644 --- a/tools/CMakeLists.txt +++ b/tools/CMakeLists.txt @@ -8,7 +8,7 @@ install(TARGETS bt3_log_cat if( ZMQ_FOUND ) add_executable(bt3_recorder bt_recorder.cpp ) - target_link_libraries(bt3_recorder ${BEHAVIOR_TREE_LIBRARY} ) + target_link_libraries(bt3_recorder ${BEHAVIOR_TREE_LIBRARY} ${ZMQ_LIBRARIES}) install(TARGETS bt3_recorder DESTINATION ${BEHAVIOR_TREE_BIN_DESTINATION} ) endif() From 5d6b6d9098137a271003c43428fad52135820140 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 27 Jan 2021 10:08:26 +0100 Subject: [PATCH 071/709] version bump --- CHANGELOG.rst | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 491e9a921..3ba4cac9c 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* fix issue `#251 `_ +* Contributors: Davide Faconti + 3.5.4 (2020-12-10) ------------------ * Update bt_factory.cpp (`#245 `_) From b63a6d0ebe45c574c6af0ce1f5c96f5a08c86d04 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 27 Jan 2021 10:08:30 +0100 Subject: [PATCH 072/709] 3.5.5 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 3ba4cac9c..26216d3f6 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.5.5 (2021-01-27) +------------------ * fix issue `#251 `_ * Contributors: Davide Faconti diff --git a/package.xml b/package.xml index 3156ad631..cdcdee949 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.5.4 + 3.5.5 This package provides the Behavior Trees core library. From bfc8bbdceb5d85848a375714a878fc0858f6861e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 27 Jan 2021 10:14:12 +0100 Subject: [PATCH 073/709] fix cmake warning --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 69cf90599..a390aed9b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -27,9 +27,9 @@ if(Boost_FOUND) add_definitions(-DBT_BOOST_COROUTINE) set(BT_COROUTINES true) endif() + include_directories(${Boost_INCLUDE_DIRS}) endif() -include_directories(${Boost_INCLUDE_DIRS}) if(NOT DEFINED BT_COROUTINES) message(STATUS "Coroutines disabled. Install Boost to enable them (version 1.59+ recommended).") From 8ff9c496c275c1612c8552f0556f20ac95ed90da Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 27 Jan 2021 10:15:26 +0100 Subject: [PATCH 074/709] revert 3.5.5 --- package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package.xml b/package.xml index cdcdee949..3156ad631 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.5.5 + 3.5.4 This package provides the Behavior Trees core library. From 821ba34fd9c6cce7c2f1248636a7a00d6f0ea102 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 27 Jan 2021 10:15:36 +0100 Subject: [PATCH 075/709] 3.5.5 --- package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package.xml b/package.xml index 3156ad631..cdcdee949 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.5.4 + 3.5.5 This package provides the Behavior Trees core library. From 582092f84519efac298f6b2094a831b3b17fbc0d Mon Sep 17 00:00:00 2001 From: LucasNolasco Date: Thu, 28 Jan 2021 09:35:08 -0300 Subject: [PATCH 076/709] Fixed typos on SequenceNode.md (#254) --- docs/SequenceNode.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/SequenceNode.md b/docs/SequenceNode.md index 3f4e5eec1..7b42c5164 100644 --- a/docs/SequenceNode.md +++ b/docs/SequenceNode.md @@ -72,7 +72,7 @@ This tree represents the behavior of a sniper in a computer game. This node is particularly useful to continuously check Conditions; but the user should also be careful when using asynchronous children, to be -sure that thy are not ticked more often that expected. +sure that they are not ticked more often that expected. Let's take a look at another example: From 95b8c7c959645c9ceeb26112bf89d4de39c4742e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 3 Feb 2021 22:30:38 +0100 Subject: [PATCH 077/709] fix issue #250 --- src/basic_types.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/basic_types.cpp b/src/basic_types.cpp index 38e7e6db7..0a2e7a541 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -125,10 +125,10 @@ double convertFromString(StringView str) // see issue #120 // http://quick-bench.com/DWaXRWnxtxvwIMvZy2DxVPEKJnE - const auto old_locale = setlocale(LC_NUMERIC,nullptr); + std::string old_locale = setlocale(LC_NUMERIC,nullptr); setlocale(LC_NUMERIC,"C"); double val = std::stod(str.data()); - setlocale(LC_NUMERIC,old_locale); + setlocale(LC_NUMERIC, old_locale.c_str()); return val; } From bde7fc551e0a55163b8e1528bc1bb08d74cb85e0 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 3 Feb 2021 22:45:33 +0100 Subject: [PATCH 078/709] fix issue #256 --- include/behaviortree_cpp_v3/basic_types.h | 6 ++++++ src/basic_types.cpp | 16 ++++++++++++++++ 2 files changed, 22 insertions(+) diff --git a/include/behaviortree_cpp_v3/basic_types.h b/include/behaviortree_cpp_v3/basic_types.h index a9392ccf9..0f301bd9a 100644 --- a/include/behaviortree_cpp_v3/basic_types.h +++ b/include/behaviortree_cpp_v3/basic_types.h @@ -84,6 +84,12 @@ unsigned convertFromString(StringView str); template <> long convertFromString(StringView str); +template <> +unsigned long convertFromString(StringView str); + +template <> +float convertFromString(StringView str); + template <> double convertFromString(StringView str); diff --git a/src/basic_types.cpp b/src/basic_types.cpp index 0a2e7a541..894ad4802 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -119,6 +119,12 @@ unsigned convertFromString(StringView str) return unsigned(std::stoul(str.data())); } +template <> +unsigned long convertFromString(StringView str) +{ + return std::stoul(str.data()); +} + template <> double convertFromString(StringView str) { @@ -132,6 +138,16 @@ double convertFromString(StringView str) return val; } +template <> +float convertFromString(StringView str) +{ + std::string old_locale = setlocale(LC_NUMERIC,nullptr); + setlocale(LC_NUMERIC,"C"); + float val = std::stof(str.data()); + setlocale(LC_NUMERIC, old_locale.c_str()); + return val; +} + template <> std::vector convertFromString>(StringView str) { From 4428f00ec6315a71b53fdf2cfc9c596bfa7a04c3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 3 Feb 2021 22:56:12 +0100 Subject: [PATCH 079/709] fix issue #227 --- include/behaviortree_cpp_v3/blackboard.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/behaviortree_cpp_v3/blackboard.h b/include/behaviortree_cpp_v3/blackboard.h index 63bfc8edb..c248f4994 100644 --- a/include/behaviortree_cpp_v3/blackboard.h +++ b/include/behaviortree_cpp_v3/blackboard.h @@ -149,7 +149,7 @@ class Blackboard Any temp(value); - if( locked_type && locked_type != &typeid(T) && locked_type != &temp.type() ) + if( locked_type && *locked_type != typeid(T) && *locked_type != temp.type() ) { bool mismatching = true; if( std::is_constructible::value ) From b737b5131a67b287d5f18445e4c33f36a5712c91 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 3 Feb 2021 23:05:43 +0100 Subject: [PATCH 080/709] Update README.md --- README.md | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 455493781..968893a05 100644 --- a/README.md +++ b/README.md @@ -43,6 +43,11 @@ You can learn about the main concepts, the API and the tutorials here: https://w To find more details about the conceptual ideas that make this implementation different from others, you can read the [final deliverable of the project MOOD2Be](https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/MOOD2Be_final_report.pdf). +# Does your company use BehaviorTree.CPP? + +No company, institution or public/private funding is currently supporting the development of BehaviorTree.CPP and Groot. + +Consider becoming a **sponsor** to support bug fixing and development of new features. You can find contact details in [package.xml](package.xml). # Design principles @@ -124,7 +129,7 @@ to your catkin workspace. # Acknowledgement -This library was developed at **Eurecat - https://eurecat.org/en/** (main author, Davide Faconti) in a joint effort +This library was initially developed at **Eurecat - https://eurecat.org/en/** (main author, Davide Faconti) in a joint effort with the **Italian Institute of Technology** (Michele Colledanchise). This software is one of the main components of [MOOD2Be](https://eurecat.org/en/portfolio-items/mood2be/), @@ -153,7 +158,7 @@ The Preprint version (free) is available here: https://arxiv.org/abs/1709.00084 The MIT License (MIT) Copyright (c) 2014-2018 Michele Colledanchise -Copyright (c) 2018-2020 Davide Faconti +Copyright (c) 2018-2021 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 From 72757477496318779a66731570d3d679d9ff9117 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 3 Feb 2021 23:06:52 +0100 Subject: [PATCH 081/709] changelog updated --- CHANGELOG.rst | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 26216d3f6..87bbdcdbe 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* fix issue `#227 `_ +* fix issue `#256 `_ +* Merge branch 'master' of https://github.com/BehaviorTree/BehaviorTree.CPP +* fix issue `#250 `_ +* Fixed typos on SequenceNode.md (`#254 `_) +* Contributors: Davide Faconti, LucasNolasco + 3.5.5 (2021-01-27) ------------------ * fix issue `#251 `_ From eb9ff2e63d713c94106f57dd91565a1840223a70 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 3 Feb 2021 23:07:09 +0100 Subject: [PATCH 082/709] 3.5.6 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 87bbdcdbe..270ee83d3 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.5.6 (2021-02-03) +------------------ * fix issue `#227 `_ * fix issue `#256 `_ * Merge branch 'master' of https://github.com/BehaviorTree/BehaviorTree.CPP diff --git a/package.xml b/package.xml index cdcdee949..4bb978033 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.5.5 + 3.5.6 This package provides the Behavior Trees core library. From 332dd520b5d69ebc9ca0e7e6db2848c1328eb53c Mon Sep 17 00:00:00 2001 From: Cong Liu Date: Thu, 4 Feb 2021 14:41:14 +0800 Subject: [PATCH 083/709] abstract_logger.h: fixed a typo (#257) --- include/behaviortree_cpp_v3/loggers/abstract_logger.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/behaviortree_cpp_v3/loggers/abstract_logger.h b/include/behaviortree_cpp_v3/loggers/abstract_logger.h index f8aaec802..80d3f19f7 100644 --- a/include/behaviortree_cpp_v3/loggers/abstract_logger.h +++ b/include/behaviortree_cpp_v3/loggers/abstract_logger.h @@ -30,7 +30,7 @@ class StatusChangeLogger enabled_ = enabled; } - void seTimestampType(TimestampType type) + void setTimestampType(TimestampType type) { type_ = type; } From d6dc3277a91bb8c45abbfc970f02da39d4ee1ecc Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 13 Feb 2021 17:30:24 +0100 Subject: [PATCH 084/709] Update README.md --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 968893a05..1116d52be 100644 --- a/README.md +++ b/README.md @@ -45,9 +45,9 @@ To find more details about the conceptual ideas that make this implementation di # Does your company use BehaviorTree.CPP? -No company, institution or public/private funding is currently supporting the development of BehaviorTree.CPP and Groot. +No company, institution or public/private funding is currently supporting the development of BehaviorTree.CPP and Groot. As a consequence, my time to support this library is very small and my intention to support Groot is close to zero. -Consider becoming a **sponsor** to support bug fixing and development of new features. You can find contact details in [package.xml](package.xml). +If your company use this software, consider becoming a **sponsor** to support bug fixing and development of new features. You can find contact details in [package.xml](package.xml). # Design principles From 6983ace9f722d31776ab4c5de857858cba5c052c Mon Sep 17 00:00:00 2001 From: Francesco Vigni Date: Tue, 16 Feb 2021 21:20:04 +0100 Subject: [PATCH 085/709] Fix typo (#260) Co-authored-by: Francesco Vigni --- docs/xml_format.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/xml_format.md b/docs/xml_format.md index d4ff9fcdf..62a49ff77 100644 --- a/docs/xml_format.md +++ b/docs/xml_format.md @@ -143,7 +143,7 @@ Let's say that we want to incapsulate few action into the behaviorTree "__GraspO - + @@ -183,7 +183,7 @@ using the previous example, we may split the two behavior trees into two files: - + From b5c6d8dd8f5d5d1fdcbe2e52807ccf401a7d28c7 Mon Sep 17 00:00:00 2001 From: Adam Sasine Date: Fri, 5 Mar 2021 03:51:56 -0500 Subject: [PATCH 086/709] Added printTreeRecursively overload with ostream parameter (#264) * Added overload to printTreeRecursively * Changed include to iosfwd * Added test to verify function writes to stream * Added call to overload without stream parameter * Fixed conversion error * Removed overload in favor of default argument --- include/behaviortree_cpp_v3/behavior_tree.h | 5 ++- src/behavior_tree.cpp | 14 +++---- tests/gtest_tree.cpp | 42 +++++++++++++++++++++ 3 files changed, 52 insertions(+), 9 deletions(-) diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index 0e702143d..d3052f7e0 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -44,6 +44,7 @@ #include "behaviortree_cpp_v3/decorators/timeout_node.h" #include "behaviortree_cpp_v3/decorators/delay_node.h" +#include namespace BT { @@ -56,9 +57,9 @@ void applyRecursiveVisitor(const TreeNode* root_node, void applyRecursiveVisitor(TreeNode* root_node, const std::function& visitor); /** - * Debug function to print on screen the hierarchy of the tree. + * Debug function to print the hierarchy of the tree. Prints to std::cout by default. */ -void printTreeRecursively(const TreeNode* root_node); +void printTreeRecursively(const TreeNode* root_node, std::ostream& stream = std::cout); typedef std::vector> SerializedTreeStatus; diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index f50b23eaf..b6da165b7 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -60,21 +60,21 @@ void applyRecursiveVisitor(TreeNode* node, const std::function& } } -void printTreeRecursively(const TreeNode* root_node) +void printTreeRecursively(const TreeNode* root_node, std::ostream& stream) { std::function recursivePrint; - recursivePrint = [&recursivePrint](unsigned indent, const BT::TreeNode* node) { + recursivePrint = [&recursivePrint, &stream](unsigned indent, const BT::TreeNode* node) { for (unsigned i = 0; i < indent; i++) { - std::cout << " "; + stream << " "; } if (!node) { - std::cout << "!nullptr!" << std::endl; + stream << "!nullptr!" << std::endl; return; } - std::cout << node->name() << std::endl; + stream << node->name() << std::endl; indent++; if (auto control = dynamic_cast(node)) @@ -90,9 +90,9 @@ void printTreeRecursively(const TreeNode* root_node) } }; - std::cout << "----------------" << std::endl; + stream << "----------------" << std::endl; recursivePrint(0, root_node); - std::cout << "----------------" << std::endl; + stream << "----------------" << std::endl; } void buildSerializedStatusSnapshot(TreeNode* root_node, SerializedTreeStatus& serialized_buffer) diff --git a/tests/gtest_tree.cpp b/tests/gtest_tree.cpp index ab07d0530..0a963047c 100644 --- a/tests/gtest_tree.cpp +++ b/tests/gtest_tree.cpp @@ -15,6 +15,9 @@ #include "condition_test_node.h" #include "behaviortree_cpp_v3/behavior_tree.h" +#include +#include + using BT::NodeStatus; using std::chrono::milliseconds; @@ -76,6 +79,45 @@ TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); } +TEST_F(BehaviorTreeTest, PrintWithStream) +{ + // no stream parameter should go to default stream (std::cout) + BT::printTreeRecursively(&root); + + // verify value for with custom stream parameter + std::stringstream stream; + BT::printTreeRecursively(&root, stream); + const auto string = stream.str(); + std::string line; + + // first line is all dashes + ASSERT_FALSE(std::getline(stream, line, '\n').fail()); + ASSERT_STREQ("----------------", line.c_str()); + + // each line is the name of the node, indented by depth * 3 spaces + ASSERT_FALSE(std::getline(stream, line, '\n').fail()); + ASSERT_STREQ(root.name().c_str(), line.c_str()); + + ASSERT_FALSE(std::getline(stream, line, '\n').fail()); + ASSERT_STREQ((" " + fal_conditions.name()).c_str(), line.c_str()); + + ASSERT_FALSE(std::getline(stream, line, '\n').fail()); + ASSERT_STREQ((" " + condition_1.name()).c_str(), line.c_str()); + + ASSERT_FALSE(std::getline(stream, line, '\n').fail()); + ASSERT_STREQ((" " + condition_2.name()).c_str(), line.c_str()); + + ASSERT_FALSE(std::getline(stream, line, '\n').fail()); + ASSERT_STREQ((" " + action_1.name()).c_str(), line.c_str()); + + // last line is all dashes + ASSERT_FALSE(std::getline(stream, line, '\n').fail()); + ASSERT_STREQ("----------------", line.c_str()); + + // no more lines + ASSERT_TRUE(std::getline(stream, line, '\n').fail()); +} + int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); From 5ac88ffd56c041bf1d2ca8366808d29ef86cdae7 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 1 Apr 2021 01:25:52 -0700 Subject: [PATCH 087/709] Clear all of blackboard's content (#269) --- include/behaviortree_cpp_v3/blackboard.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/include/behaviortree_cpp_v3/blackboard.h b/include/behaviortree_cpp_v3/blackboard.h index c248f4994..818bd39a3 100644 --- a/include/behaviortree_cpp_v3/blackboard.h +++ b/include/behaviortree_cpp_v3/blackboard.h @@ -189,6 +189,13 @@ class Blackboard std::vector getKeys() const; + void clear() + { + std::unique_lock lock(mutex_); + storage_.clear(); + internal_to_external_.clear(); + } + private: struct Entry{ From c17f216082564eff44b5e9be9c83510c45bfb2ea Mon Sep 17 00:00:00 2001 From: Heben Date: Thu, 1 Apr 2021 17:28:15 +0900 Subject: [PATCH 088/709] Fix bug on halt of delay node (#272) - When DelayNode is halted and ticked again, it always returned FAILURE since the state of DelayNode was not properly reset. - This commit fixes unexpected behavior of DelayNode when it is halted. Co-authored-by: Jinwoo Choi --- include/behaviortree_cpp_v3/decorators/delay_node.h | 1 + src/decorators/delay_node.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/include/behaviortree_cpp_v3/decorators/delay_node.h b/include/behaviortree_cpp_v3/decorators/delay_node.h index cf5392a5f..39cd1fd51 100644 --- a/include/behaviortree_cpp_v3/decorators/delay_node.h +++ b/include/behaviortree_cpp_v3/decorators/delay_node.h @@ -39,6 +39,7 @@ class DelayNode : public DecoratorNode } void halt() override { + delay_started_ = false; timer_.cancelAll(); DecoratorNode::halt(); } diff --git a/src/decorators/delay_node.cpp b/src/decorators/delay_node.cpp index 47b88d5c5..fb418a116 100644 --- a/src/decorators/delay_node.cpp +++ b/src/decorators/delay_node.cpp @@ -37,6 +37,7 @@ NodeStatus DelayNode::tick() if (!delay_started_) { delay_complete_ = false; + delay_aborted_ = false; delay_started_ = true; setStatus(NodeStatus::RUNNING); From 5b9c25075129d95b59ea9d31f27a1ccaa898795a Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 1 Apr 2021 11:14:28 +0200 Subject: [PATCH 089/709] fix some warnings --- tools/bt_log_cat.cpp | 4 ++-- tools/bt_recorder.cpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/tools/bt_log_cat.cpp b/tools/bt_log_cat.cpp index 8822d44ce..51537459c 100644 --- a/tools/bt_log_cat.cpp +++ b/tools/bt_log_cat.cpp @@ -21,13 +21,13 @@ int main(int argc, char* argv[]) } fseek(file, 0L, SEEK_END); - const size_t length = ftell(file); + const size_t length = static_cast(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]); + const auto bt_header_size = flatbuffers::ReadScalar(&buffer[0]); auto behavior_tree = Serialization::GetBehaviorTree(&buffer[4]); diff --git a/tools/bt_recorder.cpp b/tools/bt_recorder.cpp index 3aa67402e..27947fd34 100644 --- a/tools/bt_recorder.cpp +++ b/tools/bt_recorder.cpp @@ -20,8 +20,8 @@ static void CatchSignals(void) action.sa_handler = s_signal_handler; action.sa_flags = 0; sigemptyset(&action.sa_mask); - sigaction(SIGINT, &action, NULL); - sigaction(SIGTERM, &action, NULL); + sigaction(SIGINT, &action, nullptr); + sigaction(SIGTERM, &action, nullptr); } int main(int argc, char* argv[]) @@ -57,7 +57,7 @@ int main(int argc, char* argv[]) zmq::message_t msg; try { - subscriber.recv(&update, 0); + subscriber.recv(update, zmq::recv_flags::none); } catch (zmq::error_t& e) { From 798e4175603ba2f93575612434eb221cb6a1e604 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 1 Apr 2021 11:14:36 +0200 Subject: [PATCH 090/709] add test --- tests/gtest_ports.cpp | 75 +++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 75 insertions(+) diff --git a/tests/gtest_ports.cpp b/tests/gtest_ports.cpp index 1e654cdef..c0a86acfd 100644 --- a/tests/gtest_ports.cpp +++ b/tests/gtest_ports.cpp @@ -48,6 +48,81 @@ TEST(PortTest, DefaultPorts) NodeStatus status = tree.tickRoot(); ASSERT_EQ( status, NodeStatus::SUCCESS ); +} + +struct MyType +{ + std::string value; +}; + + +class NodeInPorts : public SyncActionNode +{ + public: + NodeInPorts(const std::string &name, const NodeConfiguration &config) + : SyncActionNode(name, config) + {} + + + NodeStatus tick() + { + int val_A = 0; + MyType val_B; + if( getInput("int_port", val_A) && + getInput("any_port", val_B) ) + { + return NodeStatus::SUCCESS; + } + return NodeStatus::FAILURE; + } + + static PortsList providedPorts() + { + return { BT::InputPort("int_port"), + BT::InputPort("any_port") }; + } +}; + +class NodeOutPorts : public SyncActionNode +{ + public: + NodeOutPorts(const std::string &name, const NodeConfiguration &config) + : SyncActionNode(name, config) + {} + + + NodeStatus tick() + { + return NodeStatus::SUCCESS; + } + + static PortsList providedPorts() + { + return { BT::OutputPort("int_port"), + BT::OutputPort("any_port") }; + } +}; + +TEST(PortTest, EmptyPort) +{ + std::string xml_txt = R"( + + + + + + + + )"; + + BehaviorTreeFactory factory; + factory.registerNodeType("NodeOutPorts"); + factory.registerNodeType("NodeInPorts"); + + auto tree = factory.createTreeFromText(xml_txt); + NodeStatus status = tree.tickRoot(); + // expect failure because port is not set yet + ASSERT_EQ( status, NodeStatus::FAILURE ); } From 725eba7e0abbc704284dec393706e5404f1472e3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 1 Apr 2021 11:31:51 +0200 Subject: [PATCH 091/709] add zmq.hpp in 3rdparty dirfectory --- 3rdparty/cppzmq/zmq.hpp | 2688 ++++++++++++++++++++++++++++++ src/loggers/bt_zmq_publisher.cpp | 4 +- tools/bt_recorder.cpp | 4 +- 3 files changed, 2692 insertions(+), 4 deletions(-) create mode 100644 3rdparty/cppzmq/zmq.hpp diff --git a/3rdparty/cppzmq/zmq.hpp b/3rdparty/cppzmq/zmq.hpp new file mode 100644 index 000000000..d59eb55e5 --- /dev/null +++ b/3rdparty/cppzmq/zmq.hpp @@ -0,0 +1,2688 @@ +/* + Copyright (c) 2016-2017 ZeroMQ community + Copyright (c) 2009-2011 250bpm s.r.o. + Copyright (c) 2011 Botond Ballo + Copyright (c) 2007-2009 iMatix Corporation + + 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 __ZMQ_HPP_INCLUDED__ +#define __ZMQ_HPP_INCLUDED__ + +#ifdef _WIN32 +#ifndef NOMINMAX +#define NOMINMAX +#endif +#endif + +// included here for _HAS_CXX* macros +#include + +#if defined(_MSVC_LANG) +#define CPPZMQ_LANG _MSVC_LANG +#else +#define CPPZMQ_LANG __cplusplus +#endif +// overwrite if specific language macros indicate higher version +#if defined(_HAS_CXX14) && _HAS_CXX14 && CPPZMQ_LANG < 201402L +#undef CPPZMQ_LANG +#define CPPZMQ_LANG 201402L +#endif +#if defined(_HAS_CXX17) && _HAS_CXX17 && CPPZMQ_LANG < 201703L +#undef CPPZMQ_LANG +#define CPPZMQ_LANG 201703L +#endif + +// macros defined if has a specific standard or greater +#if CPPZMQ_LANG >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1900) +#define ZMQ_CPP11 +#endif +#if CPPZMQ_LANG >= 201402L +#define ZMQ_CPP14 +#endif +#if CPPZMQ_LANG >= 201703L +#define ZMQ_CPP17 +#endif + +#if defined(ZMQ_CPP14) && !defined(_MSC_VER) +#define ZMQ_DEPRECATED(msg) [[deprecated(msg)]] +#elif defined(_MSC_VER) +#define ZMQ_DEPRECATED(msg) __declspec(deprecated(msg)) +#elif defined(__GNUC__) +#define ZMQ_DEPRECATED(msg) __attribute__((deprecated(msg))) +#endif + +#if defined(ZMQ_CPP17) +#define ZMQ_NODISCARD [[nodiscard]] +#else +#define ZMQ_NODISCARD +#endif + +#if defined(ZMQ_CPP11) +#define ZMQ_NOTHROW noexcept +#define ZMQ_EXPLICIT explicit +#define ZMQ_OVERRIDE override +#define ZMQ_NULLPTR nullptr +#define ZMQ_CONSTEXPR_FN constexpr +#define ZMQ_CONSTEXPR_VAR constexpr +#define ZMQ_CPP11_DEPRECATED(msg) ZMQ_DEPRECATED(msg) +#else +#define ZMQ_NOTHROW throw() +#define ZMQ_EXPLICIT +#define ZMQ_OVERRIDE +#define ZMQ_NULLPTR 0 +#define ZMQ_CONSTEXPR_FN +#define ZMQ_CONSTEXPR_VAR const +#define ZMQ_CPP11_DEPRECATED(msg) +#endif +#if defined(ZMQ_CPP14) && (!defined(_MSC_VER) || _MSC_VER > 1900) +#define ZMQ_EXTENDED_CONSTEXPR +#endif +#if defined(ZMQ_CPP17) +#define ZMQ_INLINE_VAR inline +#define ZMQ_CONSTEXPR_IF constexpr +#else +#define ZMQ_INLINE_VAR +#define ZMQ_CONSTEXPR_IF +#endif + +#include +#include + +#include +#include +#include +#include +#include +#include +#ifdef ZMQ_CPP11 +#include +#include +#include +#include +#endif + +#if defined(__has_include) && defined(ZMQ_CPP17) +#define CPPZMQ_HAS_INCLUDE_CPP17(X) __has_include(X) +#else +#define CPPZMQ_HAS_INCLUDE_CPP17(X) 0 +#endif + +#if CPPZMQ_HAS_INCLUDE_CPP17() && !defined(CPPZMQ_HAS_OPTIONAL) +#define CPPZMQ_HAS_OPTIONAL 1 +#endif +#ifndef CPPZMQ_HAS_OPTIONAL +#define CPPZMQ_HAS_OPTIONAL 0 +#elif CPPZMQ_HAS_OPTIONAL +#include +#endif + +#if CPPZMQ_HAS_INCLUDE_CPP17() && !defined(CPPZMQ_HAS_STRING_VIEW) +#define CPPZMQ_HAS_STRING_VIEW 1 +#endif +#ifndef CPPZMQ_HAS_STRING_VIEW +#define CPPZMQ_HAS_STRING_VIEW 0 +#elif CPPZMQ_HAS_STRING_VIEW +#include +#endif + +/* Version macros for compile-time API version detection */ +#define CPPZMQ_VERSION_MAJOR 4 +#define CPPZMQ_VERSION_MINOR 8 +#define CPPZMQ_VERSION_PATCH 0 + +#define CPPZMQ_VERSION \ + ZMQ_MAKE_VERSION(CPPZMQ_VERSION_MAJOR, CPPZMQ_VERSION_MINOR, \ + CPPZMQ_VERSION_PATCH) + +// Detect whether the compiler supports C++11 rvalue references. +#if (defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ > 2)) \ + && defined(__GXX_EXPERIMENTAL_CXX0X__)) +#define ZMQ_HAS_RVALUE_REFS +#define ZMQ_DELETED_FUNCTION = delete +#elif defined(__clang__) +#if __has_feature(cxx_rvalue_references) +#define ZMQ_HAS_RVALUE_REFS +#endif + +#if __has_feature(cxx_deleted_functions) +#define ZMQ_DELETED_FUNCTION = delete +#else +#define ZMQ_DELETED_FUNCTION +#endif +#elif defined(_MSC_VER) && (_MSC_VER >= 1900) +#define ZMQ_HAS_RVALUE_REFS +#define ZMQ_DELETED_FUNCTION = delete +#elif defined(_MSC_VER) && (_MSC_VER >= 1600) +#define ZMQ_HAS_RVALUE_REFS +#define ZMQ_DELETED_FUNCTION +#else +#define ZMQ_DELETED_FUNCTION +#endif + +#if defined(ZMQ_CPP11) && !defined(__llvm__) && !defined(__INTEL_COMPILER) \ + && defined(__GNUC__) && __GNUC__ < 5 +#define ZMQ_CPP11_PARTIAL +#elif defined(__GLIBCXX__) && __GLIBCXX__ < 20160805 +//the date here is the last date of gcc 4.9.4, which +// effectively means libstdc++ from gcc 5.5 and higher won't trigger this branch +#define ZMQ_CPP11_PARTIAL +#endif + +#ifdef ZMQ_CPP11 +#ifdef ZMQ_CPP11_PARTIAL +#define ZMQ_IS_TRIVIALLY_COPYABLE(T) __has_trivial_copy(T) +#else +#include +#define ZMQ_IS_TRIVIALLY_COPYABLE(T) std::is_trivially_copyable::value +#endif +#endif + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(3, 3, 0) +#define ZMQ_NEW_MONITOR_EVENT_LAYOUT +#endif + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 1, 0) +#define ZMQ_HAS_PROXY_STEERABLE +/* Socket event data */ +typedef struct +{ + uint16_t event; // id of the event as bitfield + int32_t value; // value is either error code, fd or reconnect interval +} zmq_event_t; +#endif + +// Avoid using deprecated message receive function when possible +#if ZMQ_VERSION < ZMQ_MAKE_VERSION(3, 2, 0) +#define zmq_msg_recv(msg, socket, flags) zmq_recvmsg(socket, msg, flags) +#endif + + +// In order to prevent unused variable warnings when building in non-debug +// mode use this macro to make assertions. +#ifndef NDEBUG +#define ZMQ_ASSERT(expression) assert(expression) +#else +#define ZMQ_ASSERT(expression) (void) (expression) +#endif + +namespace zmq +{ +#ifdef ZMQ_CPP11 +namespace detail +{ +namespace ranges +{ +using std::begin; +using std::end; +template auto begin(T &&r) -> decltype(begin(std::forward(r))) +{ + return begin(std::forward(r)); +} +template auto end(T &&r) -> decltype(end(std::forward(r))) +{ + return end(std::forward(r)); +} +} // namespace ranges + +template using void_t = void; + +template +using iter_value_t = typename std::iterator_traits::value_type; + +template +using range_iter_t = decltype( + ranges::begin(std::declval::type &>())); + +template using range_value_t = iter_value_t>; + +template struct is_range : std::false_type +{ +}; + +template +struct is_range< + T, + void_t::type &>()) + == ranges::end(std::declval::type &>()))>> + : std::true_type +{ +}; + +} // namespace detail +#endif + +typedef zmq_free_fn free_fn; +typedef zmq_pollitem_t pollitem_t; + +// duplicate definition from libzmq 4.3.3 +#if defined _WIN32 +#if defined _WIN64 +typedef unsigned __int64 fd_t; +#else +typedef unsigned int fd_t; +#endif +#else +typedef int fd_t; +#endif + +class error_t : public std::exception +{ + public: + error_t() ZMQ_NOTHROW : errnum(zmq_errno()) {} + explicit error_t(int err) ZMQ_NOTHROW : errnum(err) {} + virtual const char *what() const ZMQ_NOTHROW ZMQ_OVERRIDE + { + return zmq_strerror(errnum); + } + int num() const ZMQ_NOTHROW { return errnum; } + + private: + int errnum; +}; + +inline int poll(zmq_pollitem_t *items_, size_t nitems_, long timeout_ = -1) +{ + int rc = zmq_poll(items_, static_cast(nitems_), timeout_); + if (rc < 0) + throw error_t(); + return rc; +} + +ZMQ_DEPRECATED("from 4.3.1, use poll taking non-const items") +inline int poll(zmq_pollitem_t const *items_, size_t nitems_, long timeout_ = -1) +{ + return poll(const_cast(items_), nitems_, timeout_); +} + +#ifdef ZMQ_CPP11 +ZMQ_DEPRECATED("from 4.3.1, use poll taking non-const items") +inline int +poll(zmq_pollitem_t const *items, size_t nitems, std::chrono::milliseconds timeout) +{ + return poll(const_cast(items), nitems, + static_cast(timeout.count())); +} + +ZMQ_DEPRECATED("from 4.3.1, use poll taking non-const items") +inline int poll(std::vector const &items, + std::chrono::milliseconds timeout) +{ + return poll(const_cast(items.data()), items.size(), + static_cast(timeout.count())); +} + +ZMQ_DEPRECATED("from 4.3.1, use poll taking non-const items") +inline int poll(std::vector const &items, long timeout_ = -1) +{ + return poll(const_cast(items.data()), items.size(), timeout_); +} + +inline int +poll(zmq_pollitem_t *items, size_t nitems, std::chrono::milliseconds timeout) +{ + return poll(items, nitems, static_cast(timeout.count())); +} + +inline int poll(std::vector &items, + std::chrono::milliseconds timeout) +{ + return poll(items.data(), items.size(), static_cast(timeout.count())); +} + +ZMQ_DEPRECATED("from 4.3.1, use poll taking std::chrono instead of long") +inline int poll(std::vector &items, long timeout_ = -1) +{ + return poll(items.data(), items.size(), timeout_); +} + +template +inline int poll(std::array &items, + std::chrono::milliseconds timeout) +{ + return poll(items.data(), items.size(), static_cast(timeout.count())); +} +#endif + + +inline void version(int *major_, int *minor_, int *patch_) +{ + zmq_version(major_, minor_, patch_); +} + +#ifdef ZMQ_CPP11 +inline std::tuple version() +{ + std::tuple v; + zmq_version(&std::get<0>(v), &std::get<1>(v), &std::get<2>(v)); + return v; +} + +#if !defined(ZMQ_CPP11_PARTIAL) +namespace detail +{ +template struct is_char_type +{ + // true if character type for string literals in C++11 + static constexpr bool value = + std::is_same::value || std::is_same::value + || std::is_same::value || std::is_same::value; +}; +} +#endif + +#endif + +class message_t +{ + public: + message_t() ZMQ_NOTHROW + { + int rc = zmq_msg_init(&msg); + ZMQ_ASSERT(rc == 0); + } + + explicit message_t(size_t size_) + { + int rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + } + + template message_t(ForwardIter first, ForwardIter last) + { + typedef typename std::iterator_traits::value_type value_t; + + assert(std::distance(first, last) >= 0); + size_t const size_ = + static_cast(std::distance(first, last)) * sizeof(value_t); + int const rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + std::copy(first, last, data()); + } + + message_t(const void *data_, size_t size_) + { + int rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + if (size_) { + // this constructor allows (nullptr, 0), + // memcpy with a null pointer is UB + memcpy(data(), data_, size_); + } + } + + message_t(void *data_, size_t size_, free_fn *ffn_, void *hint_ = ZMQ_NULLPTR) + { + int rc = zmq_msg_init_data(&msg, data_, size_, ffn_, hint_); + if (rc != 0) + throw error_t(); + } + + // overload set of string-like types and generic containers +#if defined(ZMQ_CPP11) && !defined(ZMQ_CPP11_PARTIAL) + // NOTE this constructor will include the null terminator + // when called with a string literal. + // An overload taking const char* can not be added because + // it would be preferred over this function and break compatiblity. + template< + class Char, + size_t N, + typename = typename std::enable_if::value>::type> + ZMQ_DEPRECATED("from 4.7.0, use constructors taking iterators, (pointer, size) " + "or strings instead") + explicit message_t(const Char (&data)[N]) : + message_t(detail::ranges::begin(data), detail::ranges::end(data)) + { + } + + template::value + && ZMQ_IS_TRIVIALLY_COPYABLE(detail::range_value_t) + && !detail::is_char_type>::value + && !std::is_same::value>::type> + explicit message_t(const Range &rng) : + message_t(detail::ranges::begin(rng), detail::ranges::end(rng)) + { + } + + explicit message_t(const std::string &str) : message_t(str.data(), str.size()) {} + +#if CPPZMQ_HAS_STRING_VIEW + explicit message_t(std::string_view str) : message_t(str.data(), str.size()) {} +#endif + +#endif + +#ifdef ZMQ_HAS_RVALUE_REFS + message_t(message_t &&rhs) ZMQ_NOTHROW : msg(rhs.msg) + { + int rc = zmq_msg_init(&rhs.msg); + ZMQ_ASSERT(rc == 0); + } + + message_t &operator=(message_t &&rhs) ZMQ_NOTHROW + { + std::swap(msg, rhs.msg); + return *this; + } +#endif + + ~message_t() ZMQ_NOTHROW + { + int rc = zmq_msg_close(&msg); + ZMQ_ASSERT(rc == 0); + } + + void rebuild() + { + int rc = zmq_msg_close(&msg); + if (rc != 0) + throw error_t(); + rc = zmq_msg_init(&msg); + ZMQ_ASSERT(rc == 0); + } + + void rebuild(size_t size_) + { + int rc = zmq_msg_close(&msg); + if (rc != 0) + throw error_t(); + rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + } + + void rebuild(const void *data_, size_t size_) + { + int rc = zmq_msg_close(&msg); + if (rc != 0) + throw error_t(); + rc = zmq_msg_init_size(&msg, size_); + if (rc != 0) + throw error_t(); + memcpy(data(), data_, size_); + } + + void rebuild(void *data_, size_t size_, free_fn *ffn_, void *hint_ = ZMQ_NULLPTR) + { + int rc = zmq_msg_close(&msg); + if (rc != 0) + throw error_t(); + rc = zmq_msg_init_data(&msg, data_, size_, ffn_, hint_); + if (rc != 0) + throw error_t(); + } + + ZMQ_DEPRECATED("from 4.3.1, use move taking non-const reference instead") + void move(message_t const *msg_) + { + int rc = zmq_msg_move(&msg, const_cast(msg_->handle())); + if (rc != 0) + throw error_t(); + } + + void move(message_t &msg_) + { + int rc = zmq_msg_move(&msg, msg_.handle()); + if (rc != 0) + throw error_t(); + } + + ZMQ_DEPRECATED("from 4.3.1, use copy taking non-const reference instead") + void copy(message_t const *msg_) + { + int rc = zmq_msg_copy(&msg, const_cast(msg_->handle())); + if (rc != 0) + throw error_t(); + } + + void copy(message_t &msg_) + { + int rc = zmq_msg_copy(&msg, msg_.handle()); + if (rc != 0) + throw error_t(); + } + + bool more() const ZMQ_NOTHROW + { + int rc = zmq_msg_more(const_cast(&msg)); + return rc != 0; + } + + void *data() ZMQ_NOTHROW { return zmq_msg_data(&msg); } + + const void *data() const ZMQ_NOTHROW + { + return zmq_msg_data(const_cast(&msg)); + } + + size_t size() const ZMQ_NOTHROW + { + return zmq_msg_size(const_cast(&msg)); + } + + ZMQ_NODISCARD bool empty() const ZMQ_NOTHROW { return size() == 0u; } + + template T *data() ZMQ_NOTHROW { return static_cast(data()); } + + template T const *data() const ZMQ_NOTHROW + { + return static_cast(data()); + } + + ZMQ_DEPRECATED("from 4.3.0, use operator== instead") + bool equal(const message_t *other) const ZMQ_NOTHROW { return *this == *other; } + + bool operator==(const message_t &other) const ZMQ_NOTHROW + { + const size_t my_size = size(); + return my_size == other.size() && 0 == memcmp(data(), other.data(), my_size); + } + + bool operator!=(const message_t &other) const ZMQ_NOTHROW + { + return !(*this == other); + } + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(3, 2, 0) + int get(int property_) + { + int value = zmq_msg_get(&msg, property_); + if (value == -1) + throw error_t(); + return value; + } +#endif + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 1, 0) + const char *gets(const char *property_) + { + const char *value = zmq_msg_gets(&msg, property_); + if (value == ZMQ_NULLPTR) + throw error_t(); + return value; + } +#endif + +#if defined(ZMQ_BUILD_DRAFT_API) && ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 0) + uint32_t routing_id() const + { + return zmq_msg_routing_id(const_cast(&msg)); + } + + void set_routing_id(uint32_t routing_id) + { + int rc = zmq_msg_set_routing_id(&msg, routing_id); + if (rc != 0) + throw error_t(); + } + + const char *group() const + { + return zmq_msg_group(const_cast(&msg)); + } + + void set_group(const char *group) + { + int rc = zmq_msg_set_group(&msg, group); + if (rc != 0) + throw error_t(); + } +#endif + + // interpret message content as a string + std::string to_string() const + { + return std::string(static_cast(data()), size()); + } +#if CPPZMQ_HAS_STRING_VIEW + // interpret message content as a string + std::string_view to_string_view() const noexcept + { + return std::string_view(static_cast(data()), size()); + } +#endif + + /** Dump content to string for debugging. + * Ascii chars are readable, the rest is printed as hex. + * Probably ridiculously slow. + * Use to_string() or to_string_view() for + * interpreting the message as a string. + */ + std::string str() const + { + // Partly mutuated from the same method in zmq::multipart_t + std::stringstream os; + + const unsigned char *msg_data = this->data(); + unsigned char byte; + size_t size = this->size(); + int is_ascii[2] = {0, 0}; + + os << "zmq::message_t [size " << std::dec << std::setw(3) + << std::setfill('0') << size << "] ("; + // Totally arbitrary + if (size >= 1000) { + os << "... too big to print)"; + } else { + while (size--) { + byte = *msg_data++; + + is_ascii[1] = (byte >= 32 && byte < 127); + if (is_ascii[1] != is_ascii[0]) + os << " "; // Separate text/non text + + if (is_ascii[1]) { + os << byte; + } else { + os << std::hex << std::uppercase << std::setw(2) + << std::setfill('0') << static_cast(byte); + } + is_ascii[0] = is_ascii[1]; + } + os << ")"; + } + return os.str(); + } + + void swap(message_t &other) ZMQ_NOTHROW + { + // this assumes zmq::msg_t from libzmq is trivially relocatable + std::swap(msg, other.msg); + } + + ZMQ_NODISCARD zmq_msg_t *handle() ZMQ_NOTHROW { return &msg; } + ZMQ_NODISCARD const zmq_msg_t *handle() const ZMQ_NOTHROW { return &msg; } + + private: + // The underlying message + zmq_msg_t msg; + + // Disable implicit message copying, so that users won't use shared + // messages (less efficient) without being aware of the fact. + message_t(const message_t &) ZMQ_DELETED_FUNCTION; + void operator=(const message_t &) ZMQ_DELETED_FUNCTION; +}; + +inline void swap(message_t &a, message_t &b) ZMQ_NOTHROW +{ + a.swap(b); +} + +#ifdef ZMQ_CPP11 +enum class ctxopt +{ +#ifdef ZMQ_BLOCKY + blocky = ZMQ_BLOCKY, +#endif +#ifdef ZMQ_IO_THREADS + io_threads = ZMQ_IO_THREADS, +#endif +#ifdef ZMQ_THREAD_SCHED_POLICY + thread_sched_policy = ZMQ_THREAD_SCHED_POLICY, +#endif +#ifdef ZMQ_THREAD_PRIORITY + thread_priority = ZMQ_THREAD_PRIORITY, +#endif +#ifdef ZMQ_THREAD_AFFINITY_CPU_ADD + thread_affinity_cpu_add = ZMQ_THREAD_AFFINITY_CPU_ADD, +#endif +#ifdef ZMQ_THREAD_AFFINITY_CPU_REMOVE + thread_affinity_cpu_remove = ZMQ_THREAD_AFFINITY_CPU_REMOVE, +#endif +#ifdef ZMQ_THREAD_NAME_PREFIX + thread_name_prefix = ZMQ_THREAD_NAME_PREFIX, +#endif +#ifdef ZMQ_MAX_MSGSZ + max_msgsz = ZMQ_MAX_MSGSZ, +#endif +#ifdef ZMQ_ZERO_COPY_RECV + zero_copy_recv = ZMQ_ZERO_COPY_RECV, +#endif +#ifdef ZMQ_MAX_SOCKETS + max_sockets = ZMQ_MAX_SOCKETS, +#endif +#ifdef ZMQ_SOCKET_LIMIT + socket_limit = ZMQ_SOCKET_LIMIT, +#endif +#ifdef ZMQ_IPV6 + ipv6 = ZMQ_IPV6, +#endif +#ifdef ZMQ_MSG_T_SIZE + msg_t_size = ZMQ_MSG_T_SIZE +#endif +}; +#endif + +class context_t +{ + public: + context_t() + { + ptr = zmq_ctx_new(); + if (ptr == ZMQ_NULLPTR) + throw error_t(); + } + + + explicit context_t(int io_threads_, int max_sockets_ = ZMQ_MAX_SOCKETS_DFLT) + { + ptr = zmq_ctx_new(); + if (ptr == ZMQ_NULLPTR) + throw error_t(); + + int rc = zmq_ctx_set(ptr, ZMQ_IO_THREADS, io_threads_); + ZMQ_ASSERT(rc == 0); + + rc = zmq_ctx_set(ptr, ZMQ_MAX_SOCKETS, max_sockets_); + ZMQ_ASSERT(rc == 0); + } + +#ifdef ZMQ_HAS_RVALUE_REFS + context_t(context_t &&rhs) ZMQ_NOTHROW : ptr(rhs.ptr) { rhs.ptr = ZMQ_NULLPTR; } + context_t &operator=(context_t &&rhs) ZMQ_NOTHROW + { + close(); + std::swap(ptr, rhs.ptr); + return *this; + } +#endif + + ~context_t() ZMQ_NOTHROW { close(); } + + ZMQ_CPP11_DEPRECATED("from 4.7.0, use set taking zmq::ctxopt instead") + int setctxopt(int option_, int optval_) + { + int rc = zmq_ctx_set(ptr, option_, optval_); + ZMQ_ASSERT(rc == 0); + return rc; + } + + ZMQ_CPP11_DEPRECATED("from 4.7.0, use get taking zmq::ctxopt instead") + int getctxopt(int option_) { return zmq_ctx_get(ptr, option_); } + +#ifdef ZMQ_CPP11 + void set(ctxopt option, int optval) + { + int rc = zmq_ctx_set(ptr, static_cast(option), optval); + if (rc == -1) + throw error_t(); + } + + ZMQ_NODISCARD int get(ctxopt option) + { + int rc = zmq_ctx_get(ptr, static_cast(option)); + // some options have a default value of -1 + // which is unfortunate, and may result in errors + // that don't make sense + if (rc == -1) + throw error_t(); + return rc; + } +#endif + + // Terminates context (see also shutdown()). + void close() ZMQ_NOTHROW + { + if (ptr == ZMQ_NULLPTR) + return; + + int rc; + do { + rc = zmq_ctx_destroy(ptr); + } while (rc == -1 && errno == EINTR); + + ZMQ_ASSERT(rc == 0); + ptr = ZMQ_NULLPTR; + } + + // Shutdown context in preparation for termination (close()). + // Causes all blocking socket operations and any further + // socket operations to return with ETERM. + void shutdown() ZMQ_NOTHROW + { + if (ptr == ZMQ_NULLPTR) + return; + int rc = zmq_ctx_shutdown(ptr); + ZMQ_ASSERT(rc == 0); + } + + // Be careful with this, it's probably only useful for + // using the C api together with an existing C++ api. + // Normally you should never need to use this. + ZMQ_EXPLICIT operator void *() ZMQ_NOTHROW { return ptr; } + + ZMQ_EXPLICIT operator void const *() const ZMQ_NOTHROW { return ptr; } + + ZMQ_NODISCARD void *handle() ZMQ_NOTHROW { return ptr; } + + ZMQ_DEPRECATED("from 4.7.0, use handle() != nullptr instead") + operator bool() const ZMQ_NOTHROW { return ptr != ZMQ_NULLPTR; } + + void swap(context_t &other) ZMQ_NOTHROW { std::swap(ptr, other.ptr); } + + private: + void *ptr; + + context_t(const context_t &) ZMQ_DELETED_FUNCTION; + void operator=(const context_t &) ZMQ_DELETED_FUNCTION; +}; + +inline void swap(context_t &a, context_t &b) ZMQ_NOTHROW +{ + a.swap(b); +} + +#ifdef ZMQ_CPP11 + +struct recv_buffer_size +{ + size_t size; // number of bytes written to buffer + size_t untruncated_size; // untruncated message size in bytes + + ZMQ_NODISCARD bool truncated() const noexcept + { + return size != untruncated_size; + } +}; + +#if CPPZMQ_HAS_OPTIONAL + +using send_result_t = std::optional; +using recv_result_t = std::optional; +using recv_buffer_result_t = std::optional; + +#else + +namespace detail +{ +// A C++11 type emulating the most basic +// operations of std::optional for trivial types +template class trivial_optional +{ + public: + static_assert(std::is_trivial::value, "T must be trivial"); + using value_type = T; + + trivial_optional() = default; + trivial_optional(T value) noexcept : _value(value), _has_value(true) {} + + const T *operator->() const noexcept + { + assert(_has_value); + return &_value; + } + T *operator->() noexcept + { + assert(_has_value); + return &_value; + } + + const T &operator*() const noexcept + { + assert(_has_value); + return _value; + } + T &operator*() noexcept + { + assert(_has_value); + return _value; + } + + T &value() + { + if (!_has_value) + throw std::exception(); + return _value; + } + const T &value() const + { + if (!_has_value) + throw std::exception(); + return _value; + } + + explicit operator bool() const noexcept { return _has_value; } + bool has_value() const noexcept { return _has_value; } + + private: + T _value{}; + bool _has_value{false}; +}; +} // namespace detail + +using send_result_t = detail::trivial_optional; +using recv_result_t = detail::trivial_optional; +using recv_buffer_result_t = detail::trivial_optional; + +#endif + +namespace detail +{ +template constexpr T enum_bit_or(T a, T b) noexcept +{ + static_assert(std::is_enum::value, "must be enum"); + using U = typename std::underlying_type::type; + return static_cast(static_cast(a) | static_cast(b)); +} +template constexpr T enum_bit_and(T a, T b) noexcept +{ + static_assert(std::is_enum::value, "must be enum"); + using U = typename std::underlying_type::type; + return static_cast(static_cast(a) & static_cast(b)); +} +template constexpr T enum_bit_xor(T a, T b) noexcept +{ + static_assert(std::is_enum::value, "must be enum"); + using U = typename std::underlying_type::type; + return static_cast(static_cast(a) ^ static_cast(b)); +} +template constexpr T enum_bit_not(T a) noexcept +{ + static_assert(std::is_enum::value, "must be enum"); + using U = typename std::underlying_type::type; + return static_cast(~static_cast(a)); +} +} // namespace detail + +// partially satisfies named requirement BitmaskType +enum class send_flags : int +{ + none = 0, + dontwait = ZMQ_DONTWAIT, + sndmore = ZMQ_SNDMORE +}; + +constexpr send_flags operator|(send_flags a, send_flags b) noexcept +{ + return detail::enum_bit_or(a, b); +} +constexpr send_flags operator&(send_flags a, send_flags b) noexcept +{ + return detail::enum_bit_and(a, b); +} +constexpr send_flags operator^(send_flags a, send_flags b) noexcept +{ + return detail::enum_bit_xor(a, b); +} +constexpr send_flags operator~(send_flags a) noexcept +{ + return detail::enum_bit_not(a); +} + +// partially satisfies named requirement BitmaskType +enum class recv_flags : int +{ + none = 0, + dontwait = ZMQ_DONTWAIT +}; + +constexpr recv_flags operator|(recv_flags a, recv_flags b) noexcept +{ + return detail::enum_bit_or(a, b); +} +constexpr recv_flags operator&(recv_flags a, recv_flags b) noexcept +{ + return detail::enum_bit_and(a, b); +} +constexpr recv_flags operator^(recv_flags a, recv_flags b) noexcept +{ + return detail::enum_bit_xor(a, b); +} +constexpr recv_flags operator~(recv_flags a) noexcept +{ + return detail::enum_bit_not(a); +} + + +// mutable_buffer, const_buffer and buffer are based on +// the Networking TS specification, draft: +// http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2018/n4771.pdf + +class mutable_buffer +{ + public: + constexpr mutable_buffer() noexcept : _data(nullptr), _size(0) {} + constexpr mutable_buffer(void *p, size_t n) noexcept : _data(p), _size(n) + { +#ifdef ZMQ_EXTENDED_CONSTEXPR + assert(p != nullptr || n == 0); +#endif + } + + constexpr void *data() const noexcept { return _data; } + constexpr size_t size() const noexcept { return _size; } + mutable_buffer &operator+=(size_t n) noexcept + { + // (std::min) is a workaround for when a min macro is defined + const auto shift = (std::min)(n, _size); + _data = static_cast(_data) + shift; + _size -= shift; + return *this; + } + + private: + void *_data; + size_t _size; +}; + +inline mutable_buffer operator+(const mutable_buffer &mb, size_t n) noexcept +{ + return mutable_buffer(static_cast(mb.data()) + (std::min)(n, mb.size()), + mb.size() - (std::min)(n, mb.size())); +} +inline mutable_buffer operator+(size_t n, const mutable_buffer &mb) noexcept +{ + return mb + n; +} + +class const_buffer +{ + public: + constexpr const_buffer() noexcept : _data(nullptr), _size(0) {} + constexpr const_buffer(const void *p, size_t n) noexcept : _data(p), _size(n) + { +#ifdef ZMQ_EXTENDED_CONSTEXPR + assert(p != nullptr || n == 0); +#endif + } + constexpr const_buffer(const mutable_buffer &mb) noexcept : + _data(mb.data()), _size(mb.size()) + { + } + + constexpr const void *data() const noexcept { return _data; } + constexpr size_t size() const noexcept { return _size; } + const_buffer &operator+=(size_t n) noexcept + { + const auto shift = (std::min)(n, _size); + _data = static_cast(_data) + shift; + _size -= shift; + return *this; + } + + private: + const void *_data; + size_t _size; +}; + +inline const_buffer operator+(const const_buffer &cb, size_t n) noexcept +{ + return const_buffer(static_cast(cb.data()) + + (std::min)(n, cb.size()), + cb.size() - (std::min)(n, cb.size())); +} +inline const_buffer operator+(size_t n, const const_buffer &cb) noexcept +{ + return cb + n; +} + +// buffer creation + +constexpr mutable_buffer buffer(void *p, size_t n) noexcept +{ + return mutable_buffer(p, n); +} +constexpr const_buffer buffer(const void *p, size_t n) noexcept +{ + return const_buffer(p, n); +} +constexpr mutable_buffer buffer(const mutable_buffer &mb) noexcept +{ + return mb; +} +inline mutable_buffer buffer(const mutable_buffer &mb, size_t n) noexcept +{ + return mutable_buffer(mb.data(), (std::min)(mb.size(), n)); +} +constexpr const_buffer buffer(const const_buffer &cb) noexcept +{ + return cb; +} +inline const_buffer buffer(const const_buffer &cb, size_t n) noexcept +{ + return const_buffer(cb.data(), (std::min)(cb.size(), n)); +} + +namespace detail +{ +template struct is_buffer +{ + static constexpr bool value = + std::is_same::value || std::is_same::value; +}; + +template struct is_pod_like +{ + // NOTE: The networking draft N4771 section 16.11 requires + // T in the buffer functions below to be + // trivially copyable OR standard layout. + // Here we decide to be conservative and require both. + static constexpr bool value = + ZMQ_IS_TRIVIALLY_COPYABLE(T) && std::is_standard_layout::value; +}; + +template constexpr auto seq_size(const C &c) noexcept -> decltype(c.size()) +{ + return c.size(); +} +template +constexpr size_t seq_size(const T (&/*array*/)[N]) noexcept +{ + return N; +} + +template +auto buffer_contiguous_sequence(Seq &&seq) noexcept + -> decltype(buffer(std::addressof(*std::begin(seq)), size_t{})) +{ + using T = typename std::remove_cv< + typename std::remove_reference::type>::type; + static_assert(detail::is_pod_like::value, "T must be POD"); + + const auto size = seq_size(seq); + return buffer(size != 0u ? std::addressof(*std::begin(seq)) : nullptr, + size * sizeof(T)); +} +template +auto buffer_contiguous_sequence(Seq &&seq, size_t n_bytes) noexcept + -> decltype(buffer_contiguous_sequence(seq)) +{ + using T = typename std::remove_cv< + typename std::remove_reference::type>::type; + static_assert(detail::is_pod_like::value, "T must be POD"); + + const auto size = seq_size(seq); + return buffer(size != 0u ? std::addressof(*std::begin(seq)) : nullptr, + (std::min)(size * sizeof(T), n_bytes)); +} + +} // namespace detail + +// C array +template mutable_buffer buffer(T (&data)[N]) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +mutable_buffer buffer(T (&data)[N], size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template const_buffer buffer(const T (&data)[N]) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(const T (&data)[N], size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +// std::array +template mutable_buffer buffer(std::array &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +mutable_buffer buffer(std::array &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template +const_buffer buffer(std::array &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(std::array &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template +const_buffer buffer(const std::array &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(const std::array &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +// std::vector +template +mutable_buffer buffer(std::vector &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +mutable_buffer buffer(std::vector &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template +const_buffer buffer(const std::vector &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(const std::vector &data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +// std::basic_string +template +mutable_buffer buffer(std::basic_string &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +mutable_buffer buffer(std::basic_string &data, + size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +template +const_buffer buffer(const std::basic_string &data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(const std::basic_string &data, + size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} + +#if CPPZMQ_HAS_STRING_VIEW +// std::basic_string_view +template +const_buffer buffer(std::basic_string_view data) noexcept +{ + return detail::buffer_contiguous_sequence(data); +} +template +const_buffer buffer(std::basic_string_view data, size_t n_bytes) noexcept +{ + return detail::buffer_contiguous_sequence(data, n_bytes); +} +#endif + +// Buffer for a string literal (null terminated) +// where the buffer size excludes the terminating character. +// Equivalent to zmq::buffer(std::string_view("...")). +template +constexpr const_buffer str_buffer(const Char (&data)[N]) noexcept +{ + static_assert(detail::is_pod_like::value, "Char must be POD"); +#ifdef ZMQ_EXTENDED_CONSTEXPR + assert(data[N - 1] == Char{0}); +#endif + return const_buffer(static_cast(data), (N - 1) * sizeof(Char)); +} + +namespace literals +{ +constexpr const_buffer operator"" _zbuf(const char *str, size_t len) noexcept +{ + return const_buffer(str, len * sizeof(char)); +} +constexpr const_buffer operator"" _zbuf(const wchar_t *str, size_t len) noexcept +{ + return const_buffer(str, len * sizeof(wchar_t)); +} +constexpr const_buffer operator"" _zbuf(const char16_t *str, size_t len) noexcept +{ + return const_buffer(str, len * sizeof(char16_t)); +} +constexpr const_buffer operator"" _zbuf(const char32_t *str, size_t len) noexcept +{ + return const_buffer(str, len * sizeof(char32_t)); +} +} + +namespace sockopt +{ +// There are two types of options, +// integral type with known compiler time size (int, bool, int64_t, uint64_t) +// and arrays with dynamic size (strings, binary data). + +// BoolUnit: if true accepts values of type bool (but passed as T into libzmq) +template struct integral_option +{ +}; + +// NullTerm: +// 0: binary data +// 1: null-terminated string (`getsockopt` size includes null) +// 2: binary (size 32) or Z85 encoder string of size 41 (null included) +template struct array_option +{ +}; + +#define ZMQ_DEFINE_INTEGRAL_OPT(OPT, NAME, TYPE) \ + using NAME##_t = integral_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} +#define ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(OPT, NAME, TYPE) \ + using NAME##_t = integral_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} +#define ZMQ_DEFINE_ARRAY_OPT(OPT, NAME) \ + using NAME##_t = array_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} +#define ZMQ_DEFINE_ARRAY_OPT_BINARY(OPT, NAME) \ + using NAME##_t = array_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} +#define ZMQ_DEFINE_ARRAY_OPT_BIN_OR_Z85(OPT, NAME) \ + using NAME##_t = array_option; \ + ZMQ_INLINE_VAR ZMQ_CONSTEXPR_VAR NAME##_t NAME {} + +// deprecated, use zmq::fd_t +using cppzmq_fd_t = ::zmq::fd_t; + +#ifdef ZMQ_AFFINITY +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_AFFINITY, affinity, uint64_t); +#endif +#ifdef ZMQ_BACKLOG +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_BACKLOG, backlog, int); +#endif +#ifdef ZMQ_BINDTODEVICE +ZMQ_DEFINE_ARRAY_OPT_BINARY(ZMQ_BINDTODEVICE, bindtodevice); +#endif +#ifdef ZMQ_CONFLATE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_CONFLATE, conflate, int); +#endif +#ifdef ZMQ_CONNECT_ROUTING_ID +ZMQ_DEFINE_ARRAY_OPT(ZMQ_CONNECT_ROUTING_ID, connect_routing_id); +#endif +#ifdef ZMQ_CONNECT_TIMEOUT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_CONNECT_TIMEOUT, connect_timeout, int); +#endif +#ifdef ZMQ_CURVE_PUBLICKEY +ZMQ_DEFINE_ARRAY_OPT_BIN_OR_Z85(ZMQ_CURVE_PUBLICKEY, curve_publickey); +#endif +#ifdef ZMQ_CURVE_SECRETKEY +ZMQ_DEFINE_ARRAY_OPT_BIN_OR_Z85(ZMQ_CURVE_SECRETKEY, curve_secretkey); +#endif +#ifdef ZMQ_CURVE_SERVER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_CURVE_SERVER, curve_server, int); +#endif +#ifdef ZMQ_CURVE_SERVERKEY +ZMQ_DEFINE_ARRAY_OPT_BIN_OR_Z85(ZMQ_CURVE_SERVERKEY, curve_serverkey); +#endif +#ifdef ZMQ_EVENTS +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_EVENTS, events, int); +#endif +#ifdef ZMQ_FD +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_FD, fd, ::zmq::fd_t); +#endif +#ifdef ZMQ_GSSAPI_PLAINTEXT +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_GSSAPI_PLAINTEXT, gssapi_plaintext, int); +#endif +#ifdef ZMQ_GSSAPI_SERVER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_GSSAPI_SERVER, gssapi_server, int); +#endif +#ifdef ZMQ_GSSAPI_SERVICE_PRINCIPAL +ZMQ_DEFINE_ARRAY_OPT(ZMQ_GSSAPI_SERVICE_PRINCIPAL, gssapi_service_principal); +#endif +#ifdef ZMQ_GSSAPI_SERVICE_PRINCIPAL_NAMETYPE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_GSSAPI_SERVICE_PRINCIPAL_NAMETYPE, + gssapi_service_principal_nametype, + int); +#endif +#ifdef ZMQ_GSSAPI_PRINCIPAL +ZMQ_DEFINE_ARRAY_OPT(ZMQ_GSSAPI_PRINCIPAL, gssapi_principal); +#endif +#ifdef ZMQ_GSSAPI_PRINCIPAL_NAMETYPE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_GSSAPI_PRINCIPAL_NAMETYPE, + gssapi_principal_nametype, + int); +#endif +#ifdef ZMQ_HANDSHAKE_IVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_HANDSHAKE_IVL, handshake_ivl, int); +#endif +#ifdef ZMQ_HEARTBEAT_IVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_HEARTBEAT_IVL, heartbeat_ivl, int); +#endif +#ifdef ZMQ_HEARTBEAT_TIMEOUT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_HEARTBEAT_TIMEOUT, heartbeat_timeout, int); +#endif +#ifdef ZMQ_HEARTBEAT_TTL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_HEARTBEAT_TTL, heartbeat_ttl, int); +#endif +#ifdef ZMQ_IMMEDIATE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_IMMEDIATE, immediate, int); +#endif +#ifdef ZMQ_INVERT_MATCHING +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_INVERT_MATCHING, invert_matching, int); +#endif +#ifdef ZMQ_IPV6 +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_IPV6, ipv6, int); +#endif +#ifdef ZMQ_LAST_ENDPOINT +ZMQ_DEFINE_ARRAY_OPT(ZMQ_LAST_ENDPOINT, last_endpoint); +#endif +#ifdef ZMQ_LINGER +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_LINGER, linger, int); +#endif +#ifdef ZMQ_MAXMSGSIZE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_MAXMSGSIZE, maxmsgsize, int64_t); +#endif +#ifdef ZMQ_MECHANISM +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_MECHANISM, mechanism, int); +#endif +#ifdef ZMQ_METADATA +ZMQ_DEFINE_ARRAY_OPT(ZMQ_METADATA, metadata); +#endif +#ifdef ZMQ_MULTICAST_HOPS +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_MULTICAST_HOPS, multicast_hops, int); +#endif +#ifdef ZMQ_MULTICAST_LOOP +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_MULTICAST_LOOP, multicast_loop, int); +#endif +#ifdef ZMQ_MULTICAST_MAXTPDU +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_MULTICAST_MAXTPDU, multicast_maxtpdu, int); +#endif +#ifdef ZMQ_PLAIN_SERVER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_PLAIN_SERVER, plain_server, int); +#endif +#ifdef ZMQ_PLAIN_PASSWORD +ZMQ_DEFINE_ARRAY_OPT(ZMQ_PLAIN_PASSWORD, plain_password); +#endif +#ifdef ZMQ_PLAIN_USERNAME +ZMQ_DEFINE_ARRAY_OPT(ZMQ_PLAIN_USERNAME, plain_username); +#endif +#ifdef ZMQ_USE_FD +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_USE_FD, use_fd, int); +#endif +#ifdef ZMQ_PROBE_ROUTER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_PROBE_ROUTER, probe_router, int); +#endif +#ifdef ZMQ_RATE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RATE, rate, int); +#endif +#ifdef ZMQ_RCVBUF +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RCVBUF, rcvbuf, int); +#endif +#ifdef ZMQ_RCVHWM +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RCVHWM, rcvhwm, int); +#endif +#ifdef ZMQ_RCVMORE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_RCVMORE, rcvmore, int); +#endif +#ifdef ZMQ_RCVTIMEO +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RCVTIMEO, rcvtimeo, int); +#endif +#ifdef ZMQ_RECONNECT_IVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RECONNECT_IVL, reconnect_ivl, int); +#endif +#ifdef ZMQ_RECONNECT_IVL_MAX +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RECONNECT_IVL_MAX, reconnect_ivl_max, int); +#endif +#ifdef ZMQ_RECOVERY_IVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_RECOVERY_IVL, recovery_ivl, int); +#endif +#ifdef ZMQ_REQ_CORRELATE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_REQ_CORRELATE, req_correlate, int); +#endif +#ifdef ZMQ_REQ_RELAXED +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_REQ_RELAXED, req_relaxed, int); +#endif +#ifdef ZMQ_ROUTER_HANDOVER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_ROUTER_HANDOVER, router_handover, int); +#endif +#ifdef ZMQ_ROUTER_MANDATORY +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_ROUTER_MANDATORY, router_mandatory, int); +#endif +#ifdef ZMQ_ROUTER_NOTIFY +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_ROUTER_NOTIFY, router_notify, int); +#endif +#ifdef ZMQ_ROUTING_ID +ZMQ_DEFINE_ARRAY_OPT_BINARY(ZMQ_ROUTING_ID, routing_id); +#endif +#ifdef ZMQ_SNDBUF +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_SNDBUF, sndbuf, int); +#endif +#ifdef ZMQ_SNDHWM +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_SNDHWM, sndhwm, int); +#endif +#ifdef ZMQ_SNDTIMEO +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_SNDTIMEO, sndtimeo, int); +#endif +#ifdef ZMQ_SOCKS_PROXY +ZMQ_DEFINE_ARRAY_OPT(ZMQ_SOCKS_PROXY, socks_proxy); +#endif +#ifdef ZMQ_STREAM_NOTIFY +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_STREAM_NOTIFY, stream_notify, int); +#endif +#ifdef ZMQ_SUBSCRIBE +ZMQ_DEFINE_ARRAY_OPT(ZMQ_SUBSCRIBE, subscribe); +#endif +#ifdef ZMQ_TCP_KEEPALIVE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_KEEPALIVE, tcp_keepalive, int); +#endif +#ifdef ZMQ_TCP_KEEPALIVE_CNT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_KEEPALIVE_CNT, tcp_keepalive_cnt, int); +#endif +#ifdef ZMQ_TCP_KEEPALIVE_IDLE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_KEEPALIVE_IDLE, tcp_keepalive_idle, int); +#endif +#ifdef ZMQ_TCP_KEEPALIVE_INTVL +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_KEEPALIVE_INTVL, tcp_keepalive_intvl, int); +#endif +#ifdef ZMQ_TCP_MAXRT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TCP_MAXRT, tcp_maxrt, int); +#endif +#ifdef ZMQ_THREAD_SAFE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_THREAD_SAFE, thread_safe, int); +#endif +#ifdef ZMQ_TOS +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TOS, tos, int); +#endif +#ifdef ZMQ_TYPE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_TYPE, type, int); +#endif +#ifdef ZMQ_UNSUBSCRIBE +ZMQ_DEFINE_ARRAY_OPT(ZMQ_UNSUBSCRIBE, unsubscribe); +#endif +#ifdef ZMQ_VMCI_BUFFER_SIZE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_VMCI_BUFFER_SIZE, vmci_buffer_size, uint64_t); +#endif +#ifdef ZMQ_VMCI_BUFFER_MIN_SIZE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_VMCI_BUFFER_MIN_SIZE, vmci_buffer_min_size, uint64_t); +#endif +#ifdef ZMQ_VMCI_BUFFER_MAX_SIZE +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_VMCI_BUFFER_MAX_SIZE, vmci_buffer_max_size, uint64_t); +#endif +#ifdef ZMQ_VMCI_CONNECT_TIMEOUT +ZMQ_DEFINE_INTEGRAL_OPT(ZMQ_VMCI_CONNECT_TIMEOUT, vmci_connect_timeout, int); +#endif +#ifdef ZMQ_XPUB_VERBOSE +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_XPUB_VERBOSE, xpub_verbose, int); +#endif +#ifdef ZMQ_XPUB_VERBOSER +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_XPUB_VERBOSER, xpub_verboser, int); +#endif +#ifdef ZMQ_XPUB_MANUAL +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_XPUB_MANUAL, xpub_manual, int); +#endif +#ifdef ZMQ_XPUB_NODROP +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_XPUB_NODROP, xpub_nodrop, int); +#endif +#ifdef ZMQ_XPUB_WELCOME_MSG +ZMQ_DEFINE_ARRAY_OPT(ZMQ_XPUB_WELCOME_MSG, xpub_welcome_msg); +#endif +#ifdef ZMQ_ZAP_ENFORCE_DOMAIN +ZMQ_DEFINE_INTEGRAL_BOOL_UNIT_OPT(ZMQ_ZAP_ENFORCE_DOMAIN, zap_enforce_domain, int); +#endif +#ifdef ZMQ_ZAP_DOMAIN +ZMQ_DEFINE_ARRAY_OPT(ZMQ_ZAP_DOMAIN, zap_domain); +#endif + +} // namespace sockopt +#endif // ZMQ_CPP11 + + +namespace detail +{ +class socket_base +{ + public: + socket_base() ZMQ_NOTHROW : _handle(ZMQ_NULLPTR) {} + ZMQ_EXPLICIT socket_base(void *handle) ZMQ_NOTHROW : _handle(handle) {} + + template + ZMQ_CPP11_DEPRECATED("from 4.7.0, use `set` taking option from zmq::sockopt") + void setsockopt(int option_, T const &optval) + { + setsockopt(option_, &optval, sizeof(T)); + } + + ZMQ_CPP11_DEPRECATED("from 4.7.0, use `set` taking option from zmq::sockopt") + void setsockopt(int option_, const void *optval_, size_t optvallen_) + { + int rc = zmq_setsockopt(_handle, option_, optval_, optvallen_); + if (rc != 0) + throw error_t(); + } + + ZMQ_CPP11_DEPRECATED("from 4.7.0, use `get` taking option from zmq::sockopt") + void getsockopt(int option_, void *optval_, size_t *optvallen_) const + { + int rc = zmq_getsockopt(_handle, option_, optval_, optvallen_); + if (rc != 0) + throw error_t(); + } + + template + ZMQ_CPP11_DEPRECATED("from 4.7.0, use `get` taking option from zmq::sockopt") + T getsockopt(int option_) const + { + T optval; + size_t optlen = sizeof(T); + getsockopt(option_, &optval, &optlen); + return optval; + } + +#ifdef ZMQ_CPP11 + // Set integral socket option, e.g. + // `socket.set(zmq::sockopt::linger, 0)` + template + void set(sockopt::integral_option, const T &val) + { + static_assert(std::is_integral::value, "T must be integral"); + set_option(Opt, &val, sizeof val); + } + + // Set integral socket option from boolean, e.g. + // `socket.set(zmq::sockopt::immediate, false)` + template + void set(sockopt::integral_option, bool val) + { + static_assert(std::is_integral::value, "T must be integral"); + T rep_val = val; + set_option(Opt, &rep_val, sizeof rep_val); + } + + // Set array socket option, e.g. + // `socket.set(zmq::sockopt::plain_username, "foo123")` + template + void set(sockopt::array_option, const char *buf) + { + set_option(Opt, buf, std::strlen(buf)); + } + + // Set array socket option, e.g. + // `socket.set(zmq::sockopt::routing_id, zmq::buffer(id))` + template + void set(sockopt::array_option, const_buffer buf) + { + set_option(Opt, buf.data(), buf.size()); + } + + // Set array socket option, e.g. + // `socket.set(zmq::sockopt::routing_id, id_str)` + template + void set(sockopt::array_option, const std::string &buf) + { + set_option(Opt, buf.data(), buf.size()); + } + +#if CPPZMQ_HAS_STRING_VIEW + // Set array socket option, e.g. + // `socket.set(zmq::sockopt::routing_id, id_str)` + template + void set(sockopt::array_option, std::string_view buf) + { + set_option(Opt, buf.data(), buf.size()); + } +#endif + + // Get scalar socket option, e.g. + // `auto opt = socket.get(zmq::sockopt::linger)` + template + ZMQ_NODISCARD T get(sockopt::integral_option) const + { + static_assert(std::is_integral::value, "T must be integral"); + T val; + size_t size = sizeof val; + get_option(Opt, &val, &size); + assert(size == sizeof val); + return val; + } + + // Get array socket option, writes to buf, returns option size in bytes, e.g. + // `size_t optsize = socket.get(zmq::sockopt::routing_id, zmq::buffer(id))` + template + ZMQ_NODISCARD size_t get(sockopt::array_option, + mutable_buffer buf) const + { + size_t size = buf.size(); + get_option(Opt, buf.data(), &size); + return size; + } + + // Get array socket option as string (initializes the string buffer size to init_size) e.g. + // `auto s = socket.get(zmq::sockopt::routing_id)` + // Note: removes the null character from null-terminated string options, + // i.e. the string size excludes the null character. + template + ZMQ_NODISCARD std::string get(sockopt::array_option, + size_t init_size = 1024) const + { + if ZMQ_CONSTEXPR_IF (NullTerm == 2) { + if (init_size == 1024) { + init_size = 41; // get as Z85 string + } + } + std::string str(init_size, '\0'); + size_t size = get(sockopt::array_option{}, buffer(str)); + if ZMQ_CONSTEXPR_IF (NullTerm == 1) { + if (size > 0) { + assert(str[size - 1] == '\0'); + --size; + } + } else if ZMQ_CONSTEXPR_IF (NullTerm == 2) { + assert(size == 32 || size == 41); + if (size == 41) { + assert(str[size - 1] == '\0'); + --size; + } + } + str.resize(size); + return str; + } +#endif + + void bind(std::string const &addr) { bind(addr.c_str()); } + + void bind(const char *addr_) + { + int rc = zmq_bind(_handle, addr_); + if (rc != 0) + throw error_t(); + } + + void unbind(std::string const &addr) { unbind(addr.c_str()); } + + void unbind(const char *addr_) + { + int rc = zmq_unbind(_handle, addr_); + if (rc != 0) + throw error_t(); + } + + void connect(std::string const &addr) { connect(addr.c_str()); } + + void connect(const char *addr_) + { + int rc = zmq_connect(_handle, addr_); + if (rc != 0) + throw error_t(); + } + + void disconnect(std::string const &addr) { disconnect(addr.c_str()); } + + void disconnect(const char *addr_) + { + int rc = zmq_disconnect(_handle, addr_); + if (rc != 0) + throw error_t(); + } + + ZMQ_DEPRECATED("from 4.7.1, use handle() != nullptr or operator bool") + bool connected() const ZMQ_NOTHROW { return (_handle != ZMQ_NULLPTR); } + + ZMQ_CPP11_DEPRECATED("from 4.3.1, use send taking a const_buffer and send_flags") + size_t send(const void *buf_, size_t len_, int flags_ = 0) + { + int nbytes = zmq_send(_handle, buf_, len_, flags_); + if (nbytes >= 0) + return static_cast(nbytes); + if (zmq_errno() == EAGAIN) + return 0; + throw error_t(); + } + + ZMQ_CPP11_DEPRECATED("from 4.3.1, use send taking message_t and send_flags") + bool send(message_t &msg_, + int flags_ = 0) // default until removed + { + int nbytes = zmq_msg_send(msg_.handle(), _handle, flags_); + if (nbytes >= 0) + return true; + if (zmq_errno() == EAGAIN) + return false; + throw error_t(); + } + + template + ZMQ_CPP11_DEPRECATED( + "from 4.4.1, use send taking message_t or buffer (for contiguous " + "ranges), and send_flags") + bool send(T first, T last, int flags_ = 0) + { + zmq::message_t msg(first, last); + int nbytes = zmq_msg_send(msg.handle(), _handle, flags_); + if (nbytes >= 0) + return true; + if (zmq_errno() == EAGAIN) + return false; + throw error_t(); + } + +#ifdef ZMQ_HAS_RVALUE_REFS + ZMQ_CPP11_DEPRECATED("from 4.3.1, use send taking message_t and send_flags") + bool send(message_t &&msg_, + int flags_ = 0) // default until removed + { +#ifdef ZMQ_CPP11 + return send(msg_, static_cast(flags_)).has_value(); +#else + return send(msg_, flags_); +#endif + } +#endif + +#ifdef ZMQ_CPP11 + send_result_t send(const_buffer buf, send_flags flags = send_flags::none) + { + const int nbytes = + zmq_send(_handle, buf.data(), buf.size(), static_cast(flags)); + if (nbytes >= 0) + return static_cast(nbytes); + if (zmq_errno() == EAGAIN) + return {}; + throw error_t(); + } + + send_result_t send(message_t &msg, send_flags flags) + { + int nbytes = zmq_msg_send(msg.handle(), _handle, static_cast(flags)); + if (nbytes >= 0) + return static_cast(nbytes); + if (zmq_errno() == EAGAIN) + return {}; + throw error_t(); + } + + send_result_t send(message_t &&msg, send_flags flags) + { + return send(msg, flags); + } +#endif + + ZMQ_CPP11_DEPRECATED( + "from 4.3.1, use recv taking a mutable_buffer and recv_flags") + size_t recv(void *buf_, size_t len_, int flags_ = 0) + { + int nbytes = zmq_recv(_handle, buf_, len_, flags_); + if (nbytes >= 0) + return static_cast(nbytes); + if (zmq_errno() == EAGAIN) + return 0; + throw error_t(); + } + + ZMQ_CPP11_DEPRECATED( + "from 4.3.1, use recv taking a reference to message_t and recv_flags") + bool recv(message_t *msg_, int flags_ = 0) + { + int nbytes = zmq_msg_recv(msg_->handle(), _handle, flags_); + if (nbytes >= 0) + return true; + if (zmq_errno() == EAGAIN) + return false; + throw error_t(); + } + +#ifdef ZMQ_CPP11 + ZMQ_NODISCARD + recv_buffer_result_t recv(mutable_buffer buf, + recv_flags flags = recv_flags::none) + { + const int nbytes = + zmq_recv(_handle, buf.data(), buf.size(), static_cast(flags)); + if (nbytes >= 0) { + return recv_buffer_size{ + (std::min)(static_cast(nbytes), buf.size()), + static_cast(nbytes)}; + } + if (zmq_errno() == EAGAIN) + return {}; + throw error_t(); + } + + ZMQ_NODISCARD + recv_result_t recv(message_t &msg, recv_flags flags = recv_flags::none) + { + const int nbytes = + zmq_msg_recv(msg.handle(), _handle, static_cast(flags)); + if (nbytes >= 0) { + assert(msg.size() == static_cast(nbytes)); + return static_cast(nbytes); + } + if (zmq_errno() == EAGAIN) + return {}; + throw error_t(); + } +#endif + +#if defined(ZMQ_BUILD_DRAFT_API) && ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 0) + void join(const char *group) + { + int rc = zmq_join(_handle, group); + if (rc != 0) + throw error_t(); + } + + void leave(const char *group) + { + int rc = zmq_leave(_handle, group); + if (rc != 0) + throw error_t(); + } +#endif + + ZMQ_NODISCARD void *handle() ZMQ_NOTHROW { return _handle; } + ZMQ_NODISCARD const void *handle() const ZMQ_NOTHROW { return _handle; } + + ZMQ_EXPLICIT operator bool() const ZMQ_NOTHROW { return _handle != ZMQ_NULLPTR; } + // note: non-const operator bool can be removed once + // operator void* is removed from socket_t + ZMQ_EXPLICIT operator bool() ZMQ_NOTHROW { return _handle != ZMQ_NULLPTR; } + + protected: + void *_handle; + + private: + void set_option(int option_, const void *optval_, size_t optvallen_) + { + int rc = zmq_setsockopt(_handle, option_, optval_, optvallen_); + if (rc != 0) + throw error_t(); + } + + void get_option(int option_, void *optval_, size_t *optvallen_) const + { + int rc = zmq_getsockopt(_handle, option_, optval_, optvallen_); + if (rc != 0) + throw error_t(); + } +}; +} // namespace detail + +#ifdef ZMQ_CPP11 +enum class socket_type : int +{ + req = ZMQ_REQ, + rep = ZMQ_REP, + dealer = ZMQ_DEALER, + router = ZMQ_ROUTER, + pub = ZMQ_PUB, + sub = ZMQ_SUB, + xpub = ZMQ_XPUB, + xsub = ZMQ_XSUB, + push = ZMQ_PUSH, + pull = ZMQ_PULL, +#if defined(ZMQ_BUILD_DRAFT_API) && ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 0) + server = ZMQ_SERVER, + client = ZMQ_CLIENT, + radio = ZMQ_RADIO, + dish = ZMQ_DISH, +#endif +#if ZMQ_VERSION_MAJOR >= 4 + stream = ZMQ_STREAM, +#endif + pair = ZMQ_PAIR +}; +#endif + +struct from_handle_t +{ + struct _private + { + }; // disabling use other than with from_handle + ZMQ_CONSTEXPR_FN ZMQ_EXPLICIT from_handle_t(_private /*p*/) ZMQ_NOTHROW {} +}; + +ZMQ_CONSTEXPR_VAR from_handle_t from_handle = + from_handle_t(from_handle_t::_private()); + +// A non-owning nullable reference to a socket. +// The reference is invalidated on socket close or destruction. +class socket_ref : public detail::socket_base +{ + public: + socket_ref() ZMQ_NOTHROW : detail::socket_base() {} +#ifdef ZMQ_CPP11 + socket_ref(std::nullptr_t) ZMQ_NOTHROW : detail::socket_base() {} +#endif + socket_ref(from_handle_t /*fh*/, void *handle) ZMQ_NOTHROW + : detail::socket_base(handle) + { + } +}; + +#ifdef ZMQ_CPP11 +inline bool operator==(socket_ref sr, std::nullptr_t /*p*/) ZMQ_NOTHROW +{ + return sr.handle() == nullptr; +} +inline bool operator==(std::nullptr_t /*p*/, socket_ref sr) ZMQ_NOTHROW +{ + return sr.handle() == nullptr; +} +inline bool operator!=(socket_ref sr, std::nullptr_t /*p*/) ZMQ_NOTHROW +{ + return !(sr == nullptr); +} +inline bool operator!=(std::nullptr_t /*p*/, socket_ref sr) ZMQ_NOTHROW +{ + return !(sr == nullptr); +} +#endif + +inline bool operator==(const detail::socket_base& a, const detail::socket_base& b) ZMQ_NOTHROW +{ + return std::equal_to()(a.handle(), b.handle()); +} +inline bool operator!=(const detail::socket_base& a, const detail::socket_base& b) ZMQ_NOTHROW +{ + return !(a == b); +} +inline bool operator<(const detail::socket_base& a, const detail::socket_base& b) ZMQ_NOTHROW +{ + return std::less()(a.handle(), b.handle()); +} +inline bool operator>(const detail::socket_base& a, const detail::socket_base& b) ZMQ_NOTHROW +{ + return b < a; +} +inline bool operator<=(const detail::socket_base& a, const detail::socket_base& b) ZMQ_NOTHROW +{ + return !(a > b); +} +inline bool operator>=(const detail::socket_base& a, const detail::socket_base& b) ZMQ_NOTHROW +{ + return !(a < b); +} + +} // namespace zmq + +#ifdef ZMQ_CPP11 +namespace std +{ +template<> struct hash +{ + size_t operator()(zmq::socket_ref sr) const ZMQ_NOTHROW + { + return hash()(sr.handle()); + } +}; +} // namespace std +#endif + +namespace zmq +{ +class socket_t : public detail::socket_base +{ + friend class monitor_t; + + public: + socket_t() ZMQ_NOTHROW : detail::socket_base(ZMQ_NULLPTR), ctxptr(ZMQ_NULLPTR) {} + + socket_t(context_t &context_, int type_) : + detail::socket_base(zmq_socket(context_.handle(), type_)), + ctxptr(context_.handle()) + { + if (_handle == ZMQ_NULLPTR) + throw error_t(); + } + +#ifdef ZMQ_CPP11 + socket_t(context_t &context_, socket_type type_) : + socket_t(context_, static_cast(type_)) + { + } +#endif + +#ifdef ZMQ_HAS_RVALUE_REFS + socket_t(socket_t &&rhs) ZMQ_NOTHROW : detail::socket_base(rhs._handle), + ctxptr(rhs.ctxptr) + { + rhs._handle = ZMQ_NULLPTR; + rhs.ctxptr = ZMQ_NULLPTR; + } + socket_t &operator=(socket_t &&rhs) ZMQ_NOTHROW + { + close(); + std::swap(_handle, rhs._handle); + std::swap(ctxptr, rhs.ctxptr); + return *this; + } +#endif + + ~socket_t() ZMQ_NOTHROW { close(); } + + operator void *() ZMQ_NOTHROW { return _handle; } + + operator void const *() const ZMQ_NOTHROW { return _handle; } + + void close() ZMQ_NOTHROW + { + if (_handle == ZMQ_NULLPTR) + // already closed + return; + int rc = zmq_close(_handle); + ZMQ_ASSERT(rc == 0); + _handle = ZMQ_NULLPTR; + ctxptr = ZMQ_NULLPTR; + } + + void swap(socket_t &other) ZMQ_NOTHROW + { + std::swap(_handle, other._handle); + std::swap(ctxptr, other.ctxptr); + } + + operator socket_ref() ZMQ_NOTHROW { return socket_ref(from_handle, _handle); } + + private: + void *ctxptr; + + socket_t(const socket_t &) ZMQ_DELETED_FUNCTION; + void operator=(const socket_t &) ZMQ_DELETED_FUNCTION; + + // used by monitor_t + socket_t(void *context_, int type_) : + detail::socket_base(zmq_socket(context_, type_)), ctxptr(context_) + { + if (_handle == ZMQ_NULLPTR) + throw error_t(); + if (ctxptr == ZMQ_NULLPTR) + throw error_t(); + } +}; + +inline void swap(socket_t &a, socket_t &b) ZMQ_NOTHROW +{ + a.swap(b); +} + +ZMQ_DEPRECATED("from 4.3.1, use proxy taking socket_t objects") +inline void proxy(void *frontend, void *backend, void *capture) +{ + int rc = zmq_proxy(frontend, backend, capture); + if (rc != 0) + throw error_t(); +} + +inline void +proxy(socket_ref frontend, socket_ref backend, socket_ref capture = socket_ref()) +{ + int rc = zmq_proxy(frontend.handle(), backend.handle(), capture.handle()); + if (rc != 0) + throw error_t(); +} + +#ifdef ZMQ_HAS_PROXY_STEERABLE +ZMQ_DEPRECATED("from 4.3.1, use proxy_steerable taking socket_t objects") +inline void +proxy_steerable(void *frontend, void *backend, void *capture, void *control) +{ + int rc = zmq_proxy_steerable(frontend, backend, capture, control); + if (rc != 0) + throw error_t(); +} + +inline void proxy_steerable(socket_ref frontend, + socket_ref backend, + socket_ref capture, + socket_ref control) +{ + int rc = zmq_proxy_steerable(frontend.handle(), backend.handle(), + capture.handle(), control.handle()); + if (rc != 0) + throw error_t(); +} +#endif + +class monitor_t +{ + public: + monitor_t() : _socket(), _monitor_socket() {} + + virtual ~monitor_t() { close(); } + +#ifdef ZMQ_HAS_RVALUE_REFS + monitor_t(monitor_t &&rhs) ZMQ_NOTHROW : _socket(), _monitor_socket() + { + std::swap(_socket, rhs._socket); + std::swap(_monitor_socket, rhs._monitor_socket); + } + + monitor_t &operator=(monitor_t &&rhs) ZMQ_NOTHROW + { + close(); + _socket = socket_ref(); + std::swap(_socket, rhs._socket); + std::swap(_monitor_socket, rhs._monitor_socket); + return *this; + } +#endif + + + void + monitor(socket_t &socket, std::string const &addr, int events = ZMQ_EVENT_ALL) + { + monitor(socket, addr.c_str(), events); + } + + void monitor(socket_t &socket, const char *addr_, int events = ZMQ_EVENT_ALL) + { + init(socket, addr_, events); + while (true) { + check_event(-1); + } + } + + void init(socket_t &socket, std::string const &addr, int events = ZMQ_EVENT_ALL) + { + init(socket, addr.c_str(), events); + } + + void init(socket_t &socket, const char *addr_, int events = ZMQ_EVENT_ALL) + { + int rc = zmq_socket_monitor(socket.handle(), addr_, events); + if (rc != 0) + throw error_t(); + + _socket = socket; + _monitor_socket = socket_t(socket.ctxptr, ZMQ_PAIR); + _monitor_socket.connect(addr_); + + on_monitor_started(); + } + + bool check_event(int timeout = 0) + { + assert(_monitor_socket); + + zmq::message_t eventMsg; + + zmq::pollitem_t items[] = { + {_monitor_socket.handle(), 0, ZMQ_POLLIN, 0}, + }; + + zmq::poll(&items[0], 1, timeout); + + if (items[0].revents & ZMQ_POLLIN) { + int rc = zmq_msg_recv(eventMsg.handle(), _monitor_socket.handle(), 0); + if (rc == -1 && zmq_errno() == ETERM) + return false; + assert(rc != -1); + + } else { + return false; + } + +#if ZMQ_VERSION_MAJOR >= 4 + const char *data = static_cast(eventMsg.data()); + zmq_event_t msgEvent; + memcpy(&msgEvent.event, data, sizeof(uint16_t)); + data += sizeof(uint16_t); + memcpy(&msgEvent.value, data, sizeof(int32_t)); + zmq_event_t *event = &msgEvent; +#else + zmq_event_t *event = static_cast(eventMsg.data()); +#endif + +#ifdef ZMQ_NEW_MONITOR_EVENT_LAYOUT + zmq::message_t addrMsg; + int rc = zmq_msg_recv(addrMsg.handle(), _monitor_socket.handle(), 0); + if (rc == -1 && zmq_errno() == ETERM) { + return false; + } + + assert(rc != -1); + std::string address = addrMsg.to_string(); +#else + // Bit of a hack, but all events in the zmq_event_t union have the same layout so this will work for all event types. + std::string address = event->data.connected.addr; +#endif + +#ifdef ZMQ_EVENT_MONITOR_STOPPED + if (event->event == ZMQ_EVENT_MONITOR_STOPPED) { + return false; + } + +#endif + + switch (event->event) { + case ZMQ_EVENT_CONNECTED: + on_event_connected(*event, address.c_str()); + break; + case ZMQ_EVENT_CONNECT_DELAYED: + on_event_connect_delayed(*event, address.c_str()); + break; + case ZMQ_EVENT_CONNECT_RETRIED: + on_event_connect_retried(*event, address.c_str()); + break; + case ZMQ_EVENT_LISTENING: + on_event_listening(*event, address.c_str()); + break; + case ZMQ_EVENT_BIND_FAILED: + on_event_bind_failed(*event, address.c_str()); + break; + case ZMQ_EVENT_ACCEPTED: + on_event_accepted(*event, address.c_str()); + break; + case ZMQ_EVENT_ACCEPT_FAILED: + on_event_accept_failed(*event, address.c_str()); + break; + case ZMQ_EVENT_CLOSED: + on_event_closed(*event, address.c_str()); + break; + case ZMQ_EVENT_CLOSE_FAILED: + on_event_close_failed(*event, address.c_str()); + break; + case ZMQ_EVENT_DISCONNECTED: + on_event_disconnected(*event, address.c_str()); + break; +#ifdef ZMQ_BUILD_DRAFT_API +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 3) + case ZMQ_EVENT_HANDSHAKE_FAILED_NO_DETAIL: + on_event_handshake_failed_no_detail(*event, address.c_str()); + break; + case ZMQ_EVENT_HANDSHAKE_FAILED_PROTOCOL: + on_event_handshake_failed_protocol(*event, address.c_str()); + break; + case ZMQ_EVENT_HANDSHAKE_FAILED_AUTH: + on_event_handshake_failed_auth(*event, address.c_str()); + break; + case ZMQ_EVENT_HANDSHAKE_SUCCEEDED: + on_event_handshake_succeeded(*event, address.c_str()); + break; +#elif ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 1) + case ZMQ_EVENT_HANDSHAKE_FAILED: + on_event_handshake_failed(*event, address.c_str()); + break; + case ZMQ_EVENT_HANDSHAKE_SUCCEED: + on_event_handshake_succeed(*event, address.c_str()); + break; +#endif +#endif + default: + on_event_unknown(*event, address.c_str()); + break; + } + + return true; + } + +#ifdef ZMQ_EVENT_MONITOR_STOPPED + void abort() + { + if (_socket) + zmq_socket_monitor(_socket.handle(), ZMQ_NULLPTR, 0); + + _socket = socket_ref(); + } +#endif + virtual void on_monitor_started() {} + virtual void on_event_connected(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_connect_delayed(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_connect_retried(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_listening(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_bind_failed(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_accepted(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_accept_failed(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_closed(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_close_failed(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_disconnected(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 3) + virtual void on_event_handshake_failed_no_detail(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_handshake_failed_protocol(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_handshake_failed_auth(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_handshake_succeeded(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } +#elif ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 1) + virtual void on_event_handshake_failed(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } + virtual void on_event_handshake_succeed(const zmq_event_t &event_, + const char *addr_) + { + (void) event_; + (void) addr_; + } +#endif + virtual void on_event_unknown(const zmq_event_t &event_, const char *addr_) + { + (void) event_; + (void) addr_; + } + + private: + monitor_t(const monitor_t &) ZMQ_DELETED_FUNCTION; + void operator=(const monitor_t &) ZMQ_DELETED_FUNCTION; + + socket_ref _socket; + socket_t _monitor_socket; + + void close() ZMQ_NOTHROW + { + if (_socket) + zmq_socket_monitor(_socket.handle(), ZMQ_NULLPTR, 0); + _monitor_socket.close(); + } +}; + +#if defined(ZMQ_BUILD_DRAFT_API) && defined(ZMQ_CPP11) && defined(ZMQ_HAVE_POLLER) + +// polling events +enum class event_flags : short +{ + none = 0, + pollin = ZMQ_POLLIN, + pollout = ZMQ_POLLOUT, + pollerr = ZMQ_POLLERR, + pollpri = ZMQ_POLLPRI +}; + +constexpr event_flags operator|(event_flags a, event_flags b) noexcept +{ + return detail::enum_bit_or(a, b); +} +constexpr event_flags operator&(event_flags a, event_flags b) noexcept +{ + return detail::enum_bit_and(a, b); +} +constexpr event_flags operator^(event_flags a, event_flags b) noexcept +{ + return detail::enum_bit_xor(a, b); +} +constexpr event_flags operator~(event_flags a) noexcept +{ + return detail::enum_bit_not(a); +} + +struct no_user_data; + +// layout compatible with zmq_poller_event_t +template struct poller_event +{ + socket_ref socket; + ::zmq::fd_t fd; + T *user_data; + event_flags events; +}; + +template class poller_t +{ + public: + using event_type = poller_event; + + poller_t() : poller_ptr(zmq_poller_new()) + { + if (!poller_ptr) + throw error_t(); + } + + template< + typename Dummy = void, + typename = + typename std::enable_if::value, Dummy>::type> + void add(zmq::socket_ref socket, event_flags events, T *user_data) + { + add_impl(socket, events, user_data); + } + + void add(zmq::socket_ref socket, event_flags events) + { + add_impl(socket, events, nullptr); + } + + void remove(zmq::socket_ref socket) + { + if (0 != zmq_poller_remove(poller_ptr.get(), socket.handle())) { + throw error_t(); + } + } + + void modify(zmq::socket_ref socket, event_flags events) + { + if (0 + != zmq_poller_modify(poller_ptr.get(), socket.handle(), + static_cast(events))) { + throw error_t(); + } + } + + size_t wait_all(std::vector &poller_events, + const std::chrono::milliseconds timeout) + { + int rc = zmq_poller_wait_all( + poller_ptr.get(), + reinterpret_cast(poller_events.data()), + static_cast(poller_events.size()), + static_cast(timeout.count())); + if (rc > 0) + return static_cast(rc); + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 2, 3) + if (zmq_errno() == EAGAIN) +#else + if (zmq_errno() == ETIMEDOUT) +#endif + return 0; + + throw error_t(); + } + +#if ZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 3, 3) + size_t size() const noexcept + { + int rc = zmq_poller_size(const_cast(poller_ptr.get())); + ZMQ_ASSERT(rc >= 0); + return static_cast(std::max(rc, 0)); + } +#endif + + private: + struct destroy_poller_t + { + void operator()(void *ptr) noexcept + { + int rc = zmq_poller_destroy(&ptr); + ZMQ_ASSERT(rc == 0); + } + }; + + std::unique_ptr poller_ptr; + + void add_impl(zmq::socket_ref socket, event_flags events, T *user_data) + { + if (0 + != zmq_poller_add(poller_ptr.get(), socket.handle(), user_data, + static_cast(events))) { + throw error_t(); + } + } +}; +#endif // defined(ZMQ_BUILD_DRAFT_API) && defined(ZMQ_CPP11) && defined(ZMQ_HAVE_POLLER) + +inline std::ostream &operator<<(std::ostream &os, const message_t &msg) +{ + return os << msg.str(); +} + +} // namespace zmq + +#endif // __ZMQ_HPP_INCLUDED__ + diff --git a/src/loggers/bt_zmq_publisher.cpp b/src/loggers/bt_zmq_publisher.cpp index 9f04223c3..38914a673 100644 --- a/src/loggers/bt_zmq_publisher.cpp +++ b/src/loggers/bt_zmq_publisher.cpp @@ -1,7 +1,7 @@ +#include #include "behaviortree_cpp_v3/loggers/bt_zmq_publisher.h" #include "behaviortree_cpp_v3/flatbuffers/bt_flatbuffer_helper.h" -#include -#include "zmq.hpp" +#include "cppzmq/zmq.hpp" namespace BT { diff --git a/tools/bt_recorder.cpp b/tools/bt_recorder.cpp index 27947fd34..29511e49f 100644 --- a/tools/bt_recorder.cpp +++ b/tools/bt_recorder.cpp @@ -2,8 +2,8 @@ #include #include #include -#include #include +#include "cppzmq/zmq.hpp" #include "behaviortree_cpp_v3/flatbuffers/BT_logger_generated.h" // http://zguide.zeromq.org/cpp:interrupt @@ -44,7 +44,7 @@ int main(int argc, char* argv[]) subscriber.connect("tcp://localhost:1666"); // Subscribe to everything - subscriber.setsockopt(ZMQ_SUBSCRIBE, "", 0); + subscriber.set(zmq::sockopt::subscribe, ""); printf("----------- Started -----------------\n"); From bef30e526a81ac02fb2fcc9dccd5e03899814b99 Mon Sep 17 00:00:00 2001 From: Adam Sasine Date: Sun, 25 Apr 2021 04:15:39 -0400 Subject: [PATCH 092/709] Registered missing dummy nodes for examples (#275) * Added CheckTemperature dummy node * Added SayHello dummy node --- sample_nodes/dummy_nodes.cpp | 12 ++++++++++++ sample_nodes/dummy_nodes.h | 5 +++++ 2 files changed, 17 insertions(+) diff --git a/sample_nodes/dummy_nodes.cpp b/sample_nodes/dummy_nodes.cpp index e3c819319..9c0a228f5 100644 --- a/sample_nodes/dummy_nodes.cpp +++ b/sample_nodes/dummy_nodes.cpp @@ -16,6 +16,18 @@ BT::NodeStatus CheckBattery() return BT::NodeStatus::SUCCESS; } +BT::NodeStatus CheckTemperature() +{ + std::cout << "[ Temperature: OK ]" << std::endl; + return BT::NodeStatus::SUCCESS; +} + +BT::NodeStatus SayHello() +{ + std::cout << "Robot says: Hello World" << std::endl; + return BT::NodeStatus::SUCCESS; +} + BT::NodeStatus GripperInterface::open() { _opened = true; diff --git a/sample_nodes/dummy_nodes.h b/sample_nodes/dummy_nodes.h index 7a0d14e48..9fd7096c7 100644 --- a/sample_nodes/dummy_nodes.h +++ b/sample_nodes/dummy_nodes.h @@ -9,6 +9,9 @@ namespace DummyNodes BT::NodeStatus CheckBattery(); +BT::NodeStatus CheckTemperature(); +BT::NodeStatus SayHello(); + class GripperInterface { public: @@ -69,6 +72,8 @@ inline void RegisterNodes(BT::BehaviorTreeFactory& factory) static GripperInterface grip_singleton; factory.registerSimpleCondition("CheckBattery", std::bind(CheckBattery)); + factory.registerSimpleCondition("CheckTemperature", std::bind(CheckTemperature)); + factory.registerSimpleAction("SayHello", std::bind(SayHello)); factory.registerSimpleAction("OpenGripper", std::bind(&GripperInterface::open, &grip_singleton)); factory.registerSimpleAction("CloseGripper", std::bind(&GripperInterface::close, &grip_singleton)); factory.registerNodeType("ApproachObject"); From d73de953748a7be7c833ccd58383bcb950846d8f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 2 May 2021 17:06:04 +0200 Subject: [PATCH 093/709] add github workflow --- .github/workflows/build_ubuntu.yml | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) create mode 100644 .github/workflows/build_ubuntu.yml diff --git a/.github/workflows/build_ubuntu.yml b/.github/workflows/build_ubuntu.yml new file mode 100644 index 000000000..5124e10c0 --- /dev/null +++ b/.github/workflows/build_ubuntu.yml @@ -0,0 +1,27 @@ +name: build and run tests +on: + push: + branches: [ master ] + pull_request: + branches: [ master ] +jobs: + build: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + # install dependencies + - name: apt + run: sudo apt-get update && sudo apt-get install -yq libzmq3-dev libdw-dev libgtest-dev cmake + - name: Install gtest manually + run: cd /usr/src/gtest && sudo cmake CMakeLists.txt && sudo make && sudo cp *.a /usr/lib + # build project + - name: mkdir + run: mkdir build + - name: cmake build + run: cmake -Bbuild -H. + - name: cmake make + run: cmake --build build/ --target all + # run tests + - name: run test + run: build/test/behaviortree_cpp_v3_test + From 1b59cb026768c288b0f5dc8632c831d2742968e8 Mon Sep 17 00:00:00 2001 From: Uilian Ries Date: Sun, 2 May 2021 12:14:58 -0300 Subject: [PATCH 094/709] Remove native support for Conan (#280) Signed-off-by: Uilian Ries --- .travis.yml | 26 ---------- conan/build.py | 78 ----------------------------- conan/test_package/CMakeLists.txt | 9 ---- conan/test_package/conanfile.py | 19 ------- conan/test_package/test_package.cpp | 68 ------------------------- conan/travis/build.sh | 14 ------ conan/travis/install.sh | 21 -------- conanfile.py | 70 -------------------------- 8 files changed, 305 deletions(-) delete mode 100644 conan/build.py delete mode 100644 conan/test_package/CMakeLists.txt delete mode 100644 conan/test_package/conanfile.py delete mode 100644 conan/test_package/test_package.cpp delete mode 100755 conan/travis/build.sh delete mode 100755 conan/travis/install.sh delete mode 100644 conanfile.py diff --git a/.travis.yml b/.travis.yml index c0d1fdb3a..ae4fd354d 100644 --- a/.travis.yml +++ b/.travis.yml @@ -11,30 +11,6 @@ os: compiler: - gcc -conan-linux: &conan-linux - os: linux - dist: xenial - language: python - python: "3.7" - services: - - docker - before_install: - - true - install: - - ./conan/travis/install.sh - script: - - ./conan/travis/build.sh - -conan-osx: &conan-osx - os: osx - language: generic - before_install: - - true - install: - - ./conan/travis/install.sh - script: - - ./conan/travis/build.sh - matrix: include: - bare_linux: @@ -62,5 +38,3 @@ before_script: script: - if [ "$ROS_DISTRO" = "none" ]; then (cd build; cmake .. ; sudo cmake --build . --target install; ./bin/behaviortree_cpp_v3_test); fi - if [ "$ROS_DISTRO" != "none" ]; then (.ci_config/travis.sh); fi - - diff --git a/conan/build.py b/conan/build.py deleted file mode 100644 index e86a05685..000000000 --- a/conan/build.py +++ /dev/null @@ -1,78 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- - -import os -import re -from cpt.packager import ConanMultiPackager -from cpt.ci_manager import CIManager -from cpt.printer import Printer - - -class BuilderSettings(object): - - @property - def branch(self): - """ Get branch name - """ - printer = Printer(None) - ci_manager = CIManager(printer) - return ci_manager.get_branch() - - @property - def username(self): - """ Set BehaviorTree as package's owner - """ - return os.getenv("CONAN_USERNAME", "BehaviorTree") - - @property - def upload(self): - """ Set BehaviorTree repository to be used on upload. - The upload server address could be customized by env var - CONAN_UPLOAD. If not defined, the method will check the branch name. - Only master or CONAN_STABLE_BRANCH_PATTERN will be accepted. - The master branch will be pushed to testing channel, because it does - not match the stable pattern. Otherwise it will upload to stable - channel. - """ - if os.getenv("CONAN_UPLOAD", None) is not None: - return os.getenv("CONAN_UPLOAD") - - prog = re.compile(self.stable_branch_pattern) - if self.branch and prog.match(self.branch): - return "https://api.bintray.com/conan/BehaviorTree/conan" - - return None - - @property - def upload_only_when_stable(self): - """ Force to upload when match stable pattern branch - """ - return os.getenv("CONAN_UPLOAD_ONLY_WHEN_STABLE", True) - - @property - def stable_branch_pattern(self): - """ Only upload the package the branch name is like a tag - """ - return os.getenv("CONAN_STABLE_BRANCH_PATTERN", r"\d+\.\d+\.\d+") - - @property - def version(self): - return self.branch if re.match(self.stable_branch_pattern, self.branch) else "latest" - - @property - def reference(self): - """ Read project version from branch name to create Conan referece - """ - return os.getenv("CONAN_REFERENCE", "BehaviorTree.CPP/{}".format(self.version)) - -if __name__ == "__main__": - settings = BuilderSettings() - builder = ConanMultiPackager( - reference=settings.reference, - username=settings.username, - upload=settings.upload, - upload_only_when_stable=settings.upload_only_when_stable, - stable_branch_pattern=settings.stable_branch_pattern, - test_folder=os.path.join("conan", "test_package")) - builder.add_common_builds(pure_c=False) - builder.run() diff --git a/conan/test_package/CMakeLists.txt b/conan/test_package/CMakeLists.txt deleted file mode 100644 index 9c1c78c58..000000000 --- a/conan/test_package/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -project(test_package CXX) -cmake_minimum_required(VERSION 2.8.11) - -include(${CMAKE_BINARY_DIR}/conanbuildinfo.cmake) -conan_basic_setup() - -add_executable(${PROJECT_NAME} test_package.cpp) -target_link_libraries(${PROJECT_NAME} ${CONAN_LIBS}) -set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 11) diff --git a/conan/test_package/conanfile.py b/conan/test_package/conanfile.py deleted file mode 100644 index 95695b296..000000000 --- a/conan/test_package/conanfile.py +++ /dev/null @@ -1,19 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- -import os -from conans import ConanFile, CMake - - -class TestPackageConan(ConanFile): - settings = "os", "compiler", "build_type", "arch" - generators = "cmake" - - def build(self): - cmake = CMake(self) - cmake.configure() - cmake.build() - - def test(self): - assert os.path.isfile(os.path.join(self.deps_cpp_info["BehaviorTree.CPP"].rootpath, "licenses", "LICENSE")) - bin_path = os.path.join("bin", "test_package") - self.run(bin_path, run_environment=True) diff --git a/conan/test_package/test_package.cpp b/conan/test_package/test_package.cpp deleted file mode 100644 index 2602eac09..000000000 --- a/conan/test_package/test_package.cpp +++ /dev/null @@ -1,68 +0,0 @@ -#include "behaviortree_cpp_v3/behavior_tree.h" -#include "behaviortree_cpp_v3/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)); - } - - - - return 0; -} diff --git a/conan/travis/build.sh b/conan/travis/build.sh deleted file mode 100755 index 069ced202..000000000 --- a/conan/travis/build.sh +++ /dev/null @@ -1,14 +0,0 @@ -#!/bin/bash - -set -e -set -x - -if [[ "$(uname -s)" == 'Darwin' ]]; then - if which pyenv > /dev/null; then - eval "$(pyenv init -)" - fi - pyenv activate conan -fi - -conan user -python conan/build.py diff --git a/conan/travis/install.sh b/conan/travis/install.sh deleted file mode 100755 index f11590923..000000000 --- a/conan/travis/install.sh +++ /dev/null @@ -1,21 +0,0 @@ -#!/bin/bash - -set -ex - -if [[ "$(uname -s)" == 'Darwin' ]]; then - brew update || brew update - brew outdated pyenv || brew upgrade pyenv - brew install pyenv-virtualenv - brew install cmake || true - - if which pyenv > /dev/null; then - eval "$(pyenv init -)" - fi - - pyenv install 3.7.1 - pyenv virtualenv 3.7.1 conan - pyenv rehash - pyenv activate conan -fi - -pip install -U conan==1.10.2 conan_package_tools diff --git a/conanfile.py b/conanfile.py deleted file mode 100644 index 311dca7a9..000000000 --- a/conanfile.py +++ /dev/null @@ -1,70 +0,0 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- - -"""Conan recipe package for BehaviorTree.CPP -""" -from conans import ConanFile, CMake, tools -from conans.model.version import Version -from conans.errors import ConanInvalidConfiguration - - -class BehaviorTreeConan(ConanFile): - name = "BehaviorTree.CPP" - license = "MIT" - url = "https://github.com/BehaviorTree/BehaviorTree.CPP" - author = "Davide Faconti " - topics = ("conan", "behaviortree", "ai", "robotics", "games", "coordination") - description = "This C++ library provides a framework to create BehaviorTrees. It was designed to be flexible, easy to use and fast." - settings = "os", "compiler", "build_type", "arch" - options = {"shared": [True, False]} - default_options = {"shared": False} - generators = "cmake" - exports = "LICENSE" - exports_sources = ("cmake/*", "include/*", "src/*", "3rdparty/*", "CMakeLists.txt") - requires = "cppzmq/4.3.0@bincrafters/stable" - - def configure(self): - if self.settings.os == "Linux" and \ - self.settings.compiler == "gcc" and \ - Version(self.settings.compiler.version.value) < "5": - raise ConanInvalidConfiguration("BehaviorTree.CPP can not be built by GCC < 5") - if self.settings.os == "Windows": - raise ConanInvalidConfiguration("BehaviorTree.CPP is not prepared to be built on Windows yet") - - def _configure_cmake(self): - """Create CMake instance and execute configure step - """ - cmake = CMake(self) - cmake.definitions["BUILD_EXAMPLES"] = False - cmake.definitions["BUILD_UNIT_TESTS"] = False - cmake.configure() - return cmake - - def build(self): - """Configure, build and install BehaviorTree using CMake. - """ - tools.replace_in_file("CMakeLists.txt", - "project(behaviortree_cpp)", - """project(behaviortree_cpp) - include(${CMAKE_BINARY_DIR}/conanbuildinfo.cmake) - conan_basic_setup()""") - # INFO (uilian): zmq could require libsodium - tools.replace_in_file("CMakeLists.txt", - "BEHAVIOR_TREE_EXTERNAL_LIBRARIES zmq", - "BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${CONAN_LIBS}") - cmake = self._configure_cmake() - cmake.build() - - def package(self): - """Copy BehaviorTree artifacts to package folder - """ - self.copy(pattern="LICENSE", dst="licenses") - cmake = self._configure_cmake() - cmake.install() - - def package_info(self): - """Collect built libraries names and solve pthread path. - """ - self.cpp_info.libs = tools.collect_libs(self) - if self.settings.os == "Linux": - self.cpp_info.libs.append("pthread") From 34bd0112aae2d7e71e9cf9125d9ba4f97179aa06 Mon Sep 17 00:00:00 2001 From: Per-Arne Andersen Date: Sun, 2 May 2021 17:18:07 +0200 Subject: [PATCH 095/709] Fixes for compilation on windows. (#248) * Fix for detecting ZeroMQ on windows Naming convention is a bit different for ZeroMQ, specifically on Windows with vcpkg. While ZMQ and ZeroMQ are valid on linux, the ZMQ naming convention only works on linux. * Compilation on windows not working with /WX * Macro collision on Windows On windows, the macros defined in the abstract logger collides with other in windows.h. Made them lowercase to avoid collision --- CMakeLists.txt | 1 - cmake/FindZMQ.cmake | 10 +++++++++- include/behaviortree_cpp_v3/loggers/abstract_logger.h | 8 ++++---- 3 files changed, 13 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a390aed9b..13750e07c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -233,7 +233,6 @@ if( ZMQ_FOUND ) endif() if(MSVC) - target_compile_options(${BEHAVIOR_TREE_LIBRARY} PRIVATE /W3 /WX) else() target_compile_options(${BEHAVIOR_TREE_LIBRARY} PRIVATE -Wall -Wextra -Werror=return-type) diff --git a/cmake/FindZMQ.cmake b/cmake/FindZMQ.cmake index 2a6baf9a8..c4b8c23de 100644 --- a/cmake/FindZMQ.cmake +++ b/cmake/FindZMQ.cmake @@ -13,6 +13,14 @@ # For details see the accompanying COPYING-CMAKE-SCRIPTS file. # +if(ZeroMQ_FOUND) + set(ZMQ_FOUND ${ZeroMQ_FOUND}) + set(ZMQ_INCLUDE_DIRS ${ZeroMQ_INCLUDE_DIR}) + set(ZMQ_LIBRARIES ${ZeroMQ_LIBRARY}) +else() + + + if (ZMQ_LIBRARIES AND ZMQ_INCLUDE_DIRS) # in cache already set(ZMQ_FOUND TRUE) @@ -55,4 +63,4 @@ else (ZMQ_LIBRARIES AND ZMQ_INCLUDE_DIRS) mark_as_advanced(ZMQ_INCLUDE_DIRS ZMQ_LIBRARIES) endif (ZMQ_LIBRARIES AND ZMQ_INCLUDE_DIRS) - +endif(ZeroMQ_FOUND) \ No newline at end of file diff --git a/include/behaviortree_cpp_v3/loggers/abstract_logger.h b/include/behaviortree_cpp_v3/loggers/abstract_logger.h index 80d3f19f7..cfa966da8 100644 --- a/include/behaviortree_cpp_v3/loggers/abstract_logger.h +++ b/include/behaviortree_cpp_v3/loggers/abstract_logger.h @@ -8,8 +8,8 @@ namespace BT { enum class TimestampType { - ABSOLUTE, - RELATIVE + absolute, + relative }; typedef std::array SerializedTransition; @@ -62,7 +62,7 @@ class StatusChangeLogger //-------------------------------------------- inline StatusChangeLogger::StatusChangeLogger(TreeNode* root_node) - : enabled_(true), show_transition_to_idle_(true), type_(TimestampType::ABSOLUTE) + : enabled_(true), show_transition_to_idle_(true), type_(TimestampType::absolute) { first_timestamp_ = std::chrono::high_resolution_clock::now(); @@ -70,7 +70,7 @@ inline StatusChangeLogger::StatusChangeLogger(TreeNode* root_node) NodeStatus status) { if (enabled_ && (status != NodeStatus::IDLE || show_transition_to_idle_)) { - if (type_ == TimestampType::ABSOLUTE) + if (type_ == TimestampType::absolute) { this->callback(timestamp.time_since_epoch(), node, prev, status); } From 33c29e500b08c53c3c80caa139c0ff905b2ec18d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 2 May 2021 19:50:19 +0200 Subject: [PATCH 096/709] remove appveyor --- .appveyor.yml | 22 ---------------------- 1 file changed, 22 deletions(-) delete mode 100644 .appveyor.yml diff --git a/.appveyor.yml b/.appveyor.yml deleted file mode 100644 index 0bb8c1909..000000000 --- a/.appveyor.yml +++ /dev/null @@ -1,22 +0,0 @@ -clone_depth: 5 - -environment: - matrix: - - GENERATOR : "Visual Studio 15 2017 Win64" - APPVEYOR_BUILD_WORKER_IMAGE: Visual Studio 2017 - PLATFORM: x64 - - -configuration: - - Release - -install: - - set PATH=C:\MinGW\bin;C:\MinGW\msys\1.0;%PATH% - -before_build: - - mkdir build - - cd build - - cmake "-G%GENERATOR%" -DCMAKE_IGNORE_PATH="C:/Program Files/Git/usr/bin" .. - -build_script: -- cmake --build . From 8d3de631993aaa279c9319b42fee476f2e5316f3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 2 May 2021 19:51:12 +0200 Subject: [PATCH 097/709] remove potential crash when an unfinished tree throws an exception --- src/behavior_tree.cpp | 4 +++- src/decorator_node.cpp | 3 +++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index b6da165b7..4f25bc500 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -56,7 +56,9 @@ void applyRecursiveVisitor(TreeNode* node, const std::function& } else if (auto decorator = dynamic_cast(node)) { - applyRecursiveVisitor(decorator->child(), visitor); + if( decorator->child() ){ + applyRecursiveVisitor(decorator->child(), visitor); + } } } diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 6c9967625..d79da5d6d 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -48,6 +48,9 @@ TreeNode* DecoratorNode::child() void DecoratorNode::haltChild() { + if( !child_node_ ){ + return; + } if (child_node_->status() == NodeStatus::RUNNING) { child_node_->halt(); From 494b432e52a58f8eba476d71ad45983707722eb7 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 2 May 2021 19:51:46 +0200 Subject: [PATCH 098/709] Fix issue #273 --- src/xml_parsing.cpp | 184 ++++++++++++++++++++++++---------------- tests/gtest_subtree.cpp | 43 ++++++++++ 2 files changed, 152 insertions(+), 75 deletions(-) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 62d0e4562..7dedc941f 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -14,8 +14,8 @@ #include #if defined(__linux) || defined(__linux__) - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wattributes" +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wattributes" #endif #ifdef _MSC_VER @@ -37,6 +37,11 @@ namespace BT { using namespace BT_TinyXML2; +auto StrEqual = [](const char* str1, const char* str2) -> bool { + return strcmp(str1, str2) == 0; +}; + + struct XMLParser::Pimpl { TreeNode::Ptr createNodeFromXML(const XMLElement* element, @@ -48,6 +53,8 @@ struct XMLParser::Pimpl Blackboard::Ptr blackboard, const TreeNode::Ptr& root_parent); + void getPortsRecursively(const XMLElement* element, std::vector &output_ports); + void loadDocImpl(BT_TinyXML2::XMLDocument* doc); std::list > opened_documents; @@ -60,9 +67,9 @@ struct XMLParser::Pimpl int suffix_count; explicit Pimpl(const BehaviorTreeFactory &fact): - factory(fact), - current_path( filesystem::path::getcwd() ), - suffix_count(0) + factory(fact), + current_path( filesystem::path::getcwd() ), + suffix_count(0) {} void clear() @@ -80,7 +87,7 @@ struct XMLParser::Pimpl #endif XMLParser::XMLParser(const BehaviorTreeFactory &factory) : - _p( new Pimpl(factory) ) + _p( new Pimpl(factory) ) { } @@ -206,10 +213,6 @@ void VerifyXML(const std::string& xml_text, } //-------- Helper functions (lambdas) ----------------- - auto StrEqual = [](const char* str1, const char* str2) -> bool { - return strcmp(str1, str2) == 0; - }; - auto ThrowError = [&](int line_num, const std::string& text) { char buffer[256]; sprintf(buffer, "Error at line %d: -> %s", line_num, text.c_str()); @@ -239,8 +242,8 @@ void VerifyXML(const std::string& xml_text, if (meta_sibling) { - ThrowError(meta_sibling->GetLineNum(), - " Only a single node is supported"); + ThrowError(meta_sibling->GetLineNum(), + " Only a single node is supported"); } if (models_root) { @@ -251,13 +254,13 @@ void VerifyXML(const std::string& xml_text, { const char* name = node->Name(); if (StrEqual(name, "Action") || StrEqual(name, "Decorator") || - StrEqual(name, "SubTree") || StrEqual(name, "Condition") || StrEqual(name, "Control")) + StrEqual(name, "SubTree") || StrEqual(name, "Condition") || StrEqual(name, "Control")) { const char* ID = node->Attribute("ID"); if (!ID) { - ThrowError(node->GetLineNum(), - "Error at line %d: -> The attribute [ID] is mandatory"); + ThrowError(node->GetLineNum(), + "Error at line %d: -> The attribute [ID] is mandatory"); } } } @@ -274,52 +277,52 @@ void VerifyXML(const std::string& xml_text, { if (children_count != 1) { - ThrowError(node->GetLineNum(), - "The node must have exactly 1 child"); + ThrowError(node->GetLineNum(), + "The node must have exactly 1 child"); } if (!node->Attribute("ID")) { - ThrowError(node->GetLineNum(), - "The node must have the attribute [ID]"); + ThrowError(node->GetLineNum(), + "The node must have the attribute [ID]"); } } else if (StrEqual(name, "Action")) { if (children_count != 0) { - ThrowError(node->GetLineNum(), - "The node must not have any child"); + ThrowError(node->GetLineNum(), + "The node must not have any child"); } if (!node->Attribute("ID")) { - ThrowError(node->GetLineNum(), - "The node must have the attribute [ID]"); + ThrowError(node->GetLineNum(), + "The node must have the attribute [ID]"); } } else if (StrEqual(name, "Condition")) { if (children_count != 0) { - ThrowError(node->GetLineNum(), - "The node must not have any child"); + ThrowError(node->GetLineNum(), + "The node must not have any child"); } if (!node->Attribute("ID")) { - ThrowError(node->GetLineNum(), - "The node must have the attribute [ID]"); + ThrowError(node->GetLineNum(), + "The node must have the attribute [ID]"); } } else if (StrEqual(name, "Control")) { if (children_count == 0) { - ThrowError(node->GetLineNum(), - "The node must have at least 1 child"); + ThrowError(node->GetLineNum(), + "The node must have at least 1 child"); } if (!node->Attribute("ID")) { - ThrowError(node->GetLineNum(), - "The node must have the attribute [ID]"); + ThrowError(node->GetLineNum(), + "The node must have the attribute [ID]"); } } else if (StrEqual(name, "Sequence") || @@ -328,8 +331,8 @@ void VerifyXML(const std::string& xml_text, { if (children_count == 0) { - ThrowError(node->GetLineNum(), - "A Control node must have at least 1 child"); + ThrowError(node->GetLineNum(), + "A Control node must have at least 1 child"); } } else if (StrEqual(name, "SubTree")) @@ -349,8 +352,8 @@ void VerifyXML(const std::string& xml_text, if (!node->Attribute("ID")) { - ThrowError(node->GetLineNum(), - "The node must have the attribute [ID]"); + ThrowError(node->GetLineNum(), + "The node must have the attribute [ID]"); } } else @@ -359,8 +362,8 @@ void VerifyXML(const std::string& xml_text, bool found = ( registered_nodes.find(name) != registered_nodes.end() ); if (!found) { - ThrowError(node->GetLineNum(), - std::string("Node not recognized: ") + name); + ThrowError(node->GetLineNum(), + std::string("Node not recognized: ") + name); } } //recursion @@ -387,8 +390,8 @@ void VerifyXML(const std::string& xml_text, } if (ChildrenCount(bt_root) != 1) { - ThrowError(bt_root->GetLineNum(), - "The node must have exactly 1 child"); + ThrowError(bt_root->GetLineNum(), + "The node must have exactly 1 child"); } else { @@ -408,8 +411,8 @@ void VerifyXML(const std::string& xml_text, { if (tree_count != 1) { - throw RuntimeError("If you don't specify the attribute [main_tree_to_execute], " - "Your file must contain a single BehaviorTree"); + throw RuntimeError("If you don't specify the attribute [main_tree_to_execute], " + "Your file must contain a single BehaviorTree"); } } } @@ -572,10 +575,11 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, } } } + // use default value if available for empty ports. Only inputs for (const auto& port_it: manifest.ports) { - const std::string& port_name = port_it.first; + const std::string& port_name = port_it.first; const PortInfo& port_info = port_it.second; auto direction = port_info.direction(); @@ -586,6 +590,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, config.input_ports.insert( { port_name, port_info.defaultValue() } ); } } + child_node = factory.instantiateTreeNode(instance_name, ID, config); } else if( tree_roots.count(ID) != 0) { @@ -613,12 +618,13 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, Tree& output_tree, Blackboard::Ptr blackboard, const TreeNode::Ptr& root_parent) -{ +{ std::function recursiveStep; recursiveStep = [&](const TreeNode::Ptr& parent, const XMLElement* element) { + // create the node auto node = createNodeFromXML(element, blackboard, parent); output_tree.nodes.push_back(node); @@ -642,19 +648,19 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, recursivelyCreateTree( node->name(), output_tree, blackboard, node ); } else{ - // Creating an isolated - auto new_bb = Blackboard::create(blackboard); + // Creating an isolated + auto new_bb = Blackboard::create(blackboard); - for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) - { - if( strcmp(attr->Name(), "ID") == 0 ) + for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) { - continue; + if( strcmp(attr->Name(), "ID") == 0 ) + { + continue; + } + new_bb->addSubtreeRemapping( attr->Name(), attr->Value() ); } - new_bb->addSubtreeRemapping( attr->Name(), attr->Value() ); - } - output_tree.blackboard_stack.emplace_back(new_bb); - recursivelyCreateTree( node->name(), output_tree, new_bb, node ); + output_tree.blackboard_stack.emplace_back(new_bb); + recursivelyCreateTree( node->name(), output_tree, new_bb, node ); } } else if( dynamic_cast(node.get()) ) @@ -667,45 +673,50 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) { - if( strcmp(attr->Name(), "ID") == 0 ) + const char* attr_name = attr->Name(); + const char* attr_value = attr->Value(); + + if( StrEqual(attr_name, "ID") ) { continue; } - if( strcmp(attr->Name(), "__autoremap") == 0 ) + if( StrEqual(attr_name, "__autoremap") ) { - if( convertFromString(attr->Value()) ) - { - do_autoremap = true; - } + do_autoremap = convertFromString(attr_value); continue; } - StringView str = attr->Value(); - if( TreeNode::isBlackboardPointer(str)) + if( TreeNode::isBlackboardPointer(attr_value)) { - StringView port_name = TreeNode::stripBlackboardPointer(str); - new_bb->addSubtreeRemapping( attr->Name(), port_name); - mapped_keys.insert(attr->Name()); + // do remapping + StringView port_name = TreeNode::stripBlackboardPointer(attr_value); + new_bb->addSubtreeRemapping( attr_name, port_name ); + mapped_keys.insert(attr_name); } else{ - new_bb->set(attr->Name(), static_cast(str) ); - mapped_keys.insert(attr->Name()); + // constant string: just set that constant value into the BB + new_bb->set(attr_name, static_cast(attr_value) ); + mapped_keys.insert(attr_name); } } - recursivelyCreateTree( node->name(), output_tree, new_bb, node ); if( do_autoremap ) { - auto keys = new_bb->getKeys(); - for( StringView key: keys) + std::vector remapped_ports; + auto new_root_element = tree_roots[node->name()]->FirstChildElement(); + + getPortsRecursively( new_root_element, remapped_ports ); + for( const auto& port: remapped_ports) { - if( mapped_keys.count(key) == 0) + if( mapped_keys.count(port) == 0) { - new_bb->addSubtreeRemapping( key, key ); + new_bb->addSubtreeRemapping( port, port ); } } } - } + + recursivelyCreateTree( node->name(), output_tree, new_bb, node ); + } } else { @@ -723,6 +734,29 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, recursiveStep(root_parent, root_element); } +void XMLParser::Pimpl::getPortsRecursively(const XMLElement *element, + std::vector& output_ports) +{ + for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) + { + const char* attr_name = attr->Name(); + const char* attr_value = attr->Value(); + if( !StrEqual(attr_name, "ID") && + !StrEqual(attr_name, "name") && + TreeNode::isBlackboardPointer(attr_value) ) + { + auto port_name = TreeNode::stripBlackboardPointer(attr_value); + output_ports.push_back( static_cast(port_name) ); + } + } + + for (auto child_element = element->FirstChildElement(); child_element; + child_element = child_element->NextSiblingElement()) + { + getPortsRecursively(child_element, output_ports); + } +} + std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory) { @@ -761,9 +795,9 @@ std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory) XMLElement* port_element = nullptr; switch( port_info.direction() ) { - case PortDirection::INPUT: port_element = doc.NewElement("input_port"); break; - case PortDirection::OUTPUT: port_element = doc.NewElement("output_port"); break; - case PortDirection::INOUT: port_element = doc.NewElement("inout_port"); break; + case PortDirection::INPUT: port_element = doc.NewElement("input_port"); break; + case PortDirection::OUTPUT: port_element = doc.NewElement("output_port"); break; + case PortDirection::INOUT: port_element = doc.NewElement("inout_port"); break; } port_element->SetAttribute("name", port_name.c_str() ); diff --git a/tests/gtest_subtree.cpp b/tests/gtest_subtree.cpp index 10ee48660..c79fd8182 100644 --- a/tests/gtest_subtree.cpp +++ b/tests/gtest_subtree.cpp @@ -233,4 +233,47 @@ TEST(SubTree, SubtreePlusC) } +class ReadInConstructor : public BT::SyncActionNode +{ + public: + ReadInConstructor(const std::string& name, const BT::NodeConfiguration& config) + : BT::SyncActionNode(name, config) + { + auto msg = getInput("message"); + if (!msg) { + throw BT::RuntimeError("missing required input [message]: ", msg.error()); + } + } + + BT::NodeStatus tick() override { return BT::NodeStatus::SUCCESS; } + static BT::PortsList providedPorts() { return {BT::InputPort("message")}; } +}; + +TEST(SubTree, SubtreePlusD) +{ + BT::NodeConfiguration config; + config.blackboard = BT::Blackboard::create(); + static const char* xml_text = R"( + + + + + + + + + + + + )"; + + BT::BehaviorTreeFactory factory; + factory.registerNodeType("ReadInConstructor"); + config.blackboard->set("message", "hello"); + BT::Tree tree = factory.createTreeFromText(xml_text, config.blackboard); + auto ret = tree.tickRoot(); + ASSERT_EQ(ret, BT::NodeStatus::SUCCESS); +} + + From 5dd730a426000be5184dc76030cc0b20156f25fd Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 2 May 2021 19:52:38 +0200 Subject: [PATCH 099/709] readme update --- README.md | 1 - 1 file changed, 1 deletion(-) diff --git a/README.md b/README.md index 1116d52be..65a6b9349 100644 --- a/README.md +++ b/README.md @@ -3,7 +3,6 @@ [![Build Status](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP.svg?branch=master)](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP) [![ros1](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros1/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros1) [![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros2/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros2) -[![Build status](https://ci.appveyor.com/api/projects/status/8lawroklgnrkg38f?svg=true)](https://ci.appveyor.com/project/facontidavide59577/behaviortree-cpp) [![Codacy Badge](https://app.codacy.com/project/badge/Grade/f7489a1758ab47d49f62342f9649b62a)](https://www.codacy.com/manual/davide.faconti/BehaviorTree.CPP?utm_source=github.com&utm_medium=referral&utm_content=BehaviorTree/BehaviorTree.CPP&utm_campaign=Badge_Grade) [![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP)](https://lgtm.com/projects/g/BehaviorTree/BehaviorTree.CPP/context:cpp) [![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/BehaviorTree-ROS/Lobby?utm_source=badge&utm_medium=badge&utm_content=badge) From 4f3941bbb34100a54d521129c5bcbadfbb8aa692 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 2 May 2021 19:59:45 +0200 Subject: [PATCH 100/709] Update README.md --- README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 65a6b9349..c5f9dd540 100644 --- a/README.md +++ b/README.md @@ -44,7 +44,8 @@ To find more details about the conceptual ideas that make this implementation di # Does your company use BehaviorTree.CPP? -No company, institution or public/private funding is currently supporting the development of BehaviorTree.CPP and Groot. As a consequence, my time to support this library is very small and my intention to support Groot is close to zero. +No company, institution or public/private funding is currently supporting the development of BehaviorTree.CPP and Groot. As a consequence, my time to support **BehaviorTree.CPP** is very limited and I decided won't spend any time at all supporting **Groot**. +Pull Requests are welcome and will be reviewed, even if with some delay. If your company use this software, consider becoming a **sponsor** to support bug fixing and development of new features. You can find contact details in [package.xml](package.xml). From c46e29a8633b62aa7a4cb52c7704cd857b9a71c1 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 2 May 2021 20:18:00 +0200 Subject: [PATCH 101/709] updated to latest flatbuffers --- CMakeLists.txt | 2 + .../flatbuffers/BT_logger_generated.h | 169 +++---- .../behaviortree_cpp_v3/flatbuffers/base.h | 69 ++- .../flatbuffers/flatbuffers.h | 235 +++++++++- .../flatbuffers/stl_emulation.h | 414 +++++++++++++++++- 5 files changed, 768 insertions(+), 121 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 13750e07c..f0dc4d37d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -13,6 +13,8 @@ if(MSVC) add_definitions(-D_CRT_SECURE_NO_WARNINGS) endif() +add_definitions(-Wpedantic) + #---- Include boost to add coroutines ---- find_package(Boost COMPONENTS coroutine QUIET) diff --git a/include/behaviortree_cpp_v3/flatbuffers/BT_logger_generated.h b/include/behaviortree_cpp_v3/flatbuffers/BT_logger_generated.h index 70808c840..51ddcee29 100644 --- a/include/behaviortree_cpp_v3/flatbuffers/BT_logger_generated.h +++ b/include/behaviortree_cpp_v3/flatbuffers/BT_logger_generated.h @@ -9,20 +9,26 @@ namespace Serialization { struct PortModel; +struct PortModelBuilder; struct PortConfig; +struct PortConfigBuilder; struct TreeNode; +struct TreeNodeBuilder; struct NodeModel; +struct NodeModelBuilder; struct BehaviorTree; +struct BehaviorTreeBuilder; struct Timestamp; struct StatusChange; struct StatusChangeLog; +struct StatusChangeLogBuilder; enum class NodeStatus : int8_t { IDLE = 0, @@ -44,7 +50,7 @@ inline const NodeStatus (&EnumValuesNodeStatus())[4] { } inline const char * const *EnumNamesNodeStatus() { - static const char * const names[] = { + static const char * const names[5] = { "IDLE", "RUNNING", "SUCCESS", @@ -55,8 +61,8 @@ inline const char * const *EnumNamesNodeStatus() { } inline const char *EnumNameNodeStatus(NodeStatus e) { - if (e < NodeStatus::IDLE || e > NodeStatus::FAILURE) return ""; - const size_t index = static_cast(e); + if (flatbuffers::IsOutRange(e, NodeStatus::IDLE, NodeStatus::FAILURE)) return ""; + const size_t index = static_cast(e); return EnumNamesNodeStatus()[index]; } @@ -84,7 +90,7 @@ inline const NodeType (&EnumValuesNodeType())[6] { } inline const char * const *EnumNamesNodeType() { - static const char * const names[] = { + static const char * const names[7] = { "UNDEFINED", "ACTION", "CONDITION", @@ -97,8 +103,8 @@ inline const char * const *EnumNamesNodeType() { } inline const char *EnumNameNodeType(NodeType e) { - if (e < NodeType::UNDEFINED || e > NodeType::SUBTREE) return ""; - const size_t index = static_cast(e); + if (flatbuffers::IsOutRange(e, NodeType::UNDEFINED, NodeType::SUBTREE)) return ""; + const size_t index = static_cast(e); return EnumNamesNodeType()[index]; } @@ -120,7 +126,7 @@ inline const PortDirection (&EnumValuesPortDirection())[3] { } inline const char * const *EnumNamesPortDirection() { - static const char * const names[] = { + static const char * const names[4] = { "INPUT", "OUTPUT", "INOUT", @@ -130,8 +136,8 @@ inline const char * const *EnumNamesPortDirection() { } inline const char *EnumNamePortDirection(PortDirection e) { - if (e < PortDirection::INPUT || e > PortDirection::INOUT) return ""; - const size_t index = static_cast(e); + if (flatbuffers::IsOutRange(e, PortDirection::INPUT, PortDirection::INOUT)) return ""; + const size_t index = static_cast(e); return EnumNamesPortDirection()[index]; } @@ -140,8 +146,8 @@ FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) Timestamp FLATBUFFERS_FINAL_CLASS { uint64_t usec_since_epoch_; public: - Timestamp() { - memset(this, 0, sizeof(Timestamp)); + Timestamp() + : usec_since_epoch_(0) { } Timestamp(uint64_t _usec_since_epoch) : usec_since_epoch_(flatbuffers::EndianScalar(_usec_since_epoch)) { @@ -158,13 +164,18 @@ FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) StatusChange FLATBUFFERS_FINAL_CLASS { int8_t prev_status_; int8_t status_; int32_t padding0__; - Timestamp timestamp_; + Serialization::Timestamp timestamp_; public: - StatusChange() { - memset(this, 0, sizeof(StatusChange)); + StatusChange() + : uid_(0), + prev_status_(0), + status_(0), + padding0__(0), + timestamp_() { + (void)padding0__; } - StatusChange(uint16_t _uid, NodeStatus _prev_status, NodeStatus _status, const Timestamp &_timestamp) + StatusChange(uint16_t _uid, Serialization::NodeStatus _prev_status, Serialization::NodeStatus _status, const Serialization::Timestamp &_timestamp) : uid_(flatbuffers::EndianScalar(_uid)), prev_status_(flatbuffers::EndianScalar(static_cast(_prev_status))), status_(flatbuffers::EndianScalar(static_cast(_status))), @@ -175,19 +186,20 @@ FLATBUFFERS_MANUALLY_ALIGNED_STRUCT(8) StatusChange FLATBUFFERS_FINAL_CLASS { uint16_t uid() const { return flatbuffers::EndianScalar(uid_); } - NodeStatus prev_status() const { - return static_cast(flatbuffers::EndianScalar(prev_status_)); + Serialization::NodeStatus prev_status() const { + return static_cast(flatbuffers::EndianScalar(prev_status_)); } - NodeStatus status() const { - return static_cast(flatbuffers::EndianScalar(status_)); + Serialization::NodeStatus status() const { + return static_cast(flatbuffers::EndianScalar(status_)); } - const Timestamp ×tamp() const { + const Serialization::Timestamp ×tamp() const { return timestamp_; } }; FLATBUFFERS_STRUCT_END(StatusChange, 16); struct PortModel FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + typedef PortModelBuilder Builder; enum FlatBuffersVTableOffset FLATBUFFERS_VTABLE_UNDERLYING_TYPE { VT_PORT_NAME = 4, VT_DIRECTION = 6, @@ -197,8 +209,8 @@ struct PortModel FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { const flatbuffers::String *port_name() const { return GetPointer(VT_PORT_NAME); } - PortDirection direction() const { - return static_cast(GetField(VT_DIRECTION, 0)); + Serialization::PortDirection direction() const { + return static_cast(GetField(VT_DIRECTION, 0)); } const flatbuffers::String *type_info() const { return GetPointer(VT_TYPE_INFO); @@ -220,12 +232,13 @@ struct PortModel FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { }; struct PortModelBuilder { + typedef PortModel Table; flatbuffers::FlatBufferBuilder &fbb_; flatbuffers::uoffset_t start_; void add_port_name(flatbuffers::Offset port_name) { fbb_.AddOffset(PortModel::VT_PORT_NAME, port_name); } - void add_direction(PortDirection direction) { + void add_direction(Serialization::PortDirection direction) { fbb_.AddElement(PortModel::VT_DIRECTION, static_cast(direction), 0); } void add_type_info(flatbuffers::Offset type_info) { @@ -238,7 +251,6 @@ struct PortModelBuilder { : fbb_(_fbb) { start_ = fbb_.StartTable(); } - PortModelBuilder &operator=(const PortModelBuilder &); flatbuffers::Offset Finish() { const auto end = fbb_.EndTable(start_); auto o = flatbuffers::Offset(end); @@ -249,7 +261,7 @@ struct PortModelBuilder { inline flatbuffers::Offset CreatePortModel( flatbuffers::FlatBufferBuilder &_fbb, flatbuffers::Offset port_name = 0, - PortDirection direction = PortDirection::INPUT, + Serialization::PortDirection direction = Serialization::PortDirection::INPUT, flatbuffers::Offset type_info = 0, flatbuffers::Offset description = 0) { PortModelBuilder builder_(_fbb); @@ -263,7 +275,7 @@ inline flatbuffers::Offset CreatePortModel( inline flatbuffers::Offset CreatePortModelDirect( flatbuffers::FlatBufferBuilder &_fbb, const char *port_name = nullptr, - PortDirection direction = PortDirection::INPUT, + Serialization::PortDirection direction = Serialization::PortDirection::INPUT, const char *type_info = nullptr, const char *description = nullptr) { auto port_name__ = port_name ? _fbb.CreateString(port_name) : 0; @@ -278,6 +290,7 @@ inline flatbuffers::Offset CreatePortModelDirect( } struct PortConfig FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + typedef PortConfigBuilder Builder; enum FlatBuffersVTableOffset FLATBUFFERS_VTABLE_UNDERLYING_TYPE { VT_PORT_NAME = 4, VT_REMAP = 6 @@ -299,6 +312,7 @@ struct PortConfig FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { }; struct PortConfigBuilder { + typedef PortConfig Table; flatbuffers::FlatBufferBuilder &fbb_; flatbuffers::uoffset_t start_; void add_port_name(flatbuffers::Offset port_name) { @@ -311,7 +325,6 @@ struct PortConfigBuilder { : fbb_(_fbb) { start_ = fbb_.StartTable(); } - PortConfigBuilder &operator=(const PortConfigBuilder &); flatbuffers::Offset Finish() { const auto end = fbb_.EndTable(start_); auto o = flatbuffers::Offset(end); @@ -342,6 +355,7 @@ inline flatbuffers::Offset CreatePortConfigDirect( } struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + typedef TreeNodeBuilder Builder; enum FlatBuffersVTableOffset FLATBUFFERS_VTABLE_UNDERLYING_TYPE { VT_UID = 4, VT_CHILDREN_UID = 6, @@ -356,8 +370,8 @@ struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { const flatbuffers::Vector *children_uid() const { return GetPointer *>(VT_CHILDREN_UID); } - NodeStatus status() const { - return static_cast(GetField(VT_STATUS, 0)); + Serialization::NodeStatus status() const { + return static_cast(GetField(VT_STATUS, 0)); } const flatbuffers::String *instance_name() const { return GetPointer(VT_INSTANCE_NAME); @@ -365,8 +379,8 @@ struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { const flatbuffers::String *registration_name() const { return GetPointer(VT_REGISTRATION_NAME); } - const flatbuffers::Vector> *port_remaps() const { - return GetPointer> *>(VT_PORT_REMAPS); + const flatbuffers::Vector> *port_remaps() const { + return GetPointer> *>(VT_PORT_REMAPS); } bool Verify(flatbuffers::Verifier &verifier) const { return VerifyTableStart(verifier) && @@ -386,6 +400,7 @@ struct TreeNode FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { }; struct TreeNodeBuilder { + typedef TreeNode Table; flatbuffers::FlatBufferBuilder &fbb_; flatbuffers::uoffset_t start_; void add_uid(uint16_t uid) { @@ -394,7 +409,7 @@ struct TreeNodeBuilder { void add_children_uid(flatbuffers::Offset> children_uid) { fbb_.AddOffset(TreeNode::VT_CHILDREN_UID, children_uid); } - void add_status(NodeStatus status) { + void add_status(Serialization::NodeStatus status) { fbb_.AddElement(TreeNode::VT_STATUS, static_cast(status), 0); } void add_instance_name(flatbuffers::Offset instance_name) { @@ -403,14 +418,13 @@ struct TreeNodeBuilder { void add_registration_name(flatbuffers::Offset registration_name) { fbb_.AddOffset(TreeNode::VT_REGISTRATION_NAME, registration_name); } - void add_port_remaps(flatbuffers::Offset>> port_remaps) { + void add_port_remaps(flatbuffers::Offset>> port_remaps) { fbb_.AddOffset(TreeNode::VT_PORT_REMAPS, port_remaps); } 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); @@ -424,10 +438,10 @@ inline flatbuffers::Offset CreateTreeNode( flatbuffers::FlatBufferBuilder &_fbb, uint16_t uid = 0, flatbuffers::Offset> children_uid = 0, - NodeStatus status = NodeStatus::IDLE, + Serialization::NodeStatus status = Serialization::NodeStatus::IDLE, flatbuffers::Offset instance_name = 0, flatbuffers::Offset registration_name = 0, - flatbuffers::Offset>> port_remaps = 0) { + flatbuffers::Offset>> port_remaps = 0) { TreeNodeBuilder builder_(_fbb); builder_.add_port_remaps(port_remaps); builder_.add_registration_name(registration_name); @@ -442,14 +456,14 @@ inline flatbuffers::Offset CreateTreeNodeDirect( flatbuffers::FlatBufferBuilder &_fbb, uint16_t uid = 0, const std::vector *children_uid = nullptr, - NodeStatus status = NodeStatus::IDLE, + Serialization::NodeStatus status = Serialization::NodeStatus::IDLE, const char *instance_name = nullptr, const char *registration_name = nullptr, - const std::vector> *port_remaps = nullptr) { + const std::vector> *port_remaps = nullptr) { auto children_uid__ = children_uid ? _fbb.CreateVector(*children_uid) : 0; auto instance_name__ = instance_name ? _fbb.CreateString(instance_name) : 0; auto registration_name__ = registration_name ? _fbb.CreateString(registration_name) : 0; - auto port_remaps__ = port_remaps ? _fbb.CreateVector>(*port_remaps) : 0; + auto port_remaps__ = port_remaps ? _fbb.CreateVector>(*port_remaps) : 0; return Serialization::CreateTreeNode( _fbb, uid, @@ -461,6 +475,7 @@ inline flatbuffers::Offset CreateTreeNodeDirect( } struct NodeModel FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + typedef NodeModelBuilder Builder; enum FlatBuffersVTableOffset FLATBUFFERS_VTABLE_UNDERLYING_TYPE { VT_REGISTRATION_NAME = 4, VT_TYPE = 6, @@ -469,11 +484,11 @@ struct NodeModel FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { const flatbuffers::String *registration_name() const { return GetPointer(VT_REGISTRATION_NAME); } - NodeType type() const { - return static_cast(GetField(VT_TYPE, 0)); + Serialization::NodeType type() const { + return static_cast(GetField(VT_TYPE, 0)); } - const flatbuffers::Vector> *ports() const { - return GetPointer> *>(VT_PORTS); + const flatbuffers::Vector> *ports() const { + return GetPointer> *>(VT_PORTS); } bool Verify(flatbuffers::Verifier &verifier) const { return VerifyTableStart(verifier) && @@ -488,22 +503,22 @@ struct NodeModel FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { }; struct NodeModelBuilder { + typedef NodeModel Table; flatbuffers::FlatBufferBuilder &fbb_; flatbuffers::uoffset_t start_; void add_registration_name(flatbuffers::Offset registration_name) { fbb_.AddOffset(NodeModel::VT_REGISTRATION_NAME, registration_name); } - void add_type(NodeType type) { + void add_type(Serialization::NodeType type) { fbb_.AddElement(NodeModel::VT_TYPE, static_cast(type), 0); } - void add_ports(flatbuffers::Offset>> ports) { + void add_ports(flatbuffers::Offset>> ports) { fbb_.AddOffset(NodeModel::VT_PORTS, ports); } explicit NodeModelBuilder(flatbuffers::FlatBufferBuilder &_fbb) : fbb_(_fbb) { start_ = fbb_.StartTable(); } - NodeModelBuilder &operator=(const NodeModelBuilder &); flatbuffers::Offset Finish() { const auto end = fbb_.EndTable(start_); auto o = flatbuffers::Offset(end); @@ -515,8 +530,8 @@ struct NodeModelBuilder { inline flatbuffers::Offset CreateNodeModel( flatbuffers::FlatBufferBuilder &_fbb, flatbuffers::Offset registration_name = 0, - NodeType type = NodeType::UNDEFINED, - flatbuffers::Offset>> ports = 0) { + Serialization::NodeType type = Serialization::NodeType::UNDEFINED, + flatbuffers::Offset>> ports = 0) { NodeModelBuilder builder_(_fbb); builder_.add_ports(ports); builder_.add_registration_name(registration_name); @@ -527,10 +542,10 @@ inline flatbuffers::Offset CreateNodeModel( inline flatbuffers::Offset CreateNodeModelDirect( flatbuffers::FlatBufferBuilder &_fbb, const char *registration_name = nullptr, - NodeType type = NodeType::UNDEFINED, - const std::vector> *ports = nullptr) { + Serialization::NodeType type = Serialization::NodeType::UNDEFINED, + const std::vector> *ports = nullptr) { auto registration_name__ = registration_name ? _fbb.CreateString(registration_name) : 0; - auto ports__ = ports ? _fbb.CreateVector>(*ports) : 0; + auto ports__ = ports ? _fbb.CreateVector>(*ports) : 0; return Serialization::CreateNodeModel( _fbb, registration_name__, @@ -539,6 +554,7 @@ inline flatbuffers::Offset CreateNodeModelDirect( } struct BehaviorTree FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + typedef BehaviorTreeBuilder Builder; enum FlatBuffersVTableOffset FLATBUFFERS_VTABLE_UNDERLYING_TYPE { VT_ROOT_UID = 4, VT_NODES = 6, @@ -547,11 +563,11 @@ struct BehaviorTree FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { uint16_t root_uid() const { return GetField(VT_ROOT_UID, 0); } - const flatbuffers::Vector> *nodes() const { - return GetPointer> *>(VT_NODES); + const flatbuffers::Vector> *nodes() const { + return GetPointer> *>(VT_NODES); } - const flatbuffers::Vector> *node_models() const { - return GetPointer> *>(VT_NODE_MODELS); + const flatbuffers::Vector> *node_models() const { + return GetPointer> *>(VT_NODE_MODELS); } bool Verify(flatbuffers::Verifier &verifier) const { return VerifyTableStart(verifier) && @@ -567,22 +583,22 @@ struct BehaviorTree FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { }; struct BehaviorTreeBuilder { + typedef BehaviorTree Table; 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) { + void add_nodes(flatbuffers::Offset>> nodes) { fbb_.AddOffset(BehaviorTree::VT_NODES, nodes); } - void add_node_models(flatbuffers::Offset>> node_models) { + void add_node_models(flatbuffers::Offset>> node_models) { fbb_.AddOffset(BehaviorTree::VT_NODE_MODELS, node_models); } 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); @@ -593,8 +609,8 @@ struct BehaviorTreeBuilder { inline flatbuffers::Offset CreateBehaviorTree( flatbuffers::FlatBufferBuilder &_fbb, uint16_t root_uid = 0, - flatbuffers::Offset>> nodes = 0, - flatbuffers::Offset>> node_models = 0) { + flatbuffers::Offset>> nodes = 0, + flatbuffers::Offset>> node_models = 0) { BehaviorTreeBuilder builder_(_fbb); builder_.add_node_models(node_models); builder_.add_nodes(nodes); @@ -605,10 +621,10 @@ inline flatbuffers::Offset CreateBehaviorTree( inline flatbuffers::Offset CreateBehaviorTreeDirect( flatbuffers::FlatBufferBuilder &_fbb, uint16_t root_uid = 0, - const std::vector> *nodes = nullptr, - const std::vector> *node_models = nullptr) { - auto nodes__ = nodes ? _fbb.CreateVector>(*nodes) : 0; - auto node_models__ = node_models ? _fbb.CreateVector>(*node_models) : 0; + const std::vector> *nodes = nullptr, + const std::vector> *node_models = nullptr) { + auto nodes__ = nodes ? _fbb.CreateVector>(*nodes) : 0; + auto node_models__ = node_models ? _fbb.CreateVector>(*node_models) : 0; return Serialization::CreateBehaviorTree( _fbb, root_uid, @@ -617,15 +633,16 @@ inline flatbuffers::Offset CreateBehaviorTreeDirect( } struct StatusChangeLog FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { + typedef StatusChangeLogBuilder Builder; enum FlatBuffersVTableOffset FLATBUFFERS_VTABLE_UNDERLYING_TYPE { VT_BEHAVIOR_TREE = 4, VT_STATE_CHANGES = 6 }; - const BehaviorTree *behavior_tree() const { - return GetPointer(VT_BEHAVIOR_TREE); + const Serialization::BehaviorTree *behavior_tree() const { + return GetPointer(VT_BEHAVIOR_TREE); } - const flatbuffers::Vector *state_changes() const { - return GetPointer *>(VT_STATE_CHANGES); + const flatbuffers::Vector *state_changes() const { + return GetPointer *>(VT_STATE_CHANGES); } bool Verify(flatbuffers::Verifier &verifier) const { return VerifyTableStart(verifier) && @@ -638,19 +655,19 @@ struct StatusChangeLog FLATBUFFERS_FINAL_CLASS : private flatbuffers::Table { }; struct StatusChangeLogBuilder { + typedef StatusChangeLog Table; flatbuffers::FlatBufferBuilder &fbb_; flatbuffers::uoffset_t start_; - void add_behavior_tree(flatbuffers::Offset behavior_tree) { + void add_behavior_tree(flatbuffers::Offset behavior_tree) { fbb_.AddOffset(StatusChangeLog::VT_BEHAVIOR_TREE, behavior_tree); } - void add_state_changes(flatbuffers::Offset> state_changes) { + 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); @@ -660,8 +677,8 @@ struct StatusChangeLogBuilder { inline flatbuffers::Offset CreateStatusChangeLog( flatbuffers::FlatBufferBuilder &_fbb, - flatbuffers::Offset behavior_tree = 0, - flatbuffers::Offset> state_changes = 0) { + 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); @@ -670,9 +687,9 @@ inline flatbuffers::Offset CreateStatusChangeLog( inline flatbuffers::Offset CreateStatusChangeLogDirect( flatbuffers::FlatBufferBuilder &_fbb, - flatbuffers::Offset behavior_tree = 0, - const std::vector *state_changes = nullptr) { - auto state_changes__ = state_changes ? _fbb.CreateVectorOfStructs(*state_changes) : 0; + flatbuffers::Offset behavior_tree = 0, + const std::vector *state_changes = nullptr) { + auto state_changes__ = state_changes ? _fbb.CreateVectorOfStructs(*state_changes) : 0; return Serialization::CreateStatusChangeLog( _fbb, behavior_tree, diff --git a/include/behaviortree_cpp_v3/flatbuffers/base.h b/include/behaviortree_cpp_v3/flatbuffers/base.h index 1686dc680..54a51aacb 100644 --- a/include/behaviortree_cpp_v3/flatbuffers/base.h +++ b/include/behaviortree_cpp_v3/flatbuffers/base.h @@ -46,14 +46,17 @@ #include #include +#if defined(__unix__) && !defined(FLATBUFFERS_LOCALE_INDEPENDENT) + #include +#endif + #ifdef _STLPORT_VERSION #define FLATBUFFERS_CPP98_STL #endif -#ifndef FLATBUFFERS_CPP98_STL - #include -#endif -#include "behaviortree_cpp_v3/flatbuffers/stl_emulation.h" +#ifdef __ANDROID__ + #include +#endif #if defined(__ICCARM__) #include @@ -140,7 +143,7 @@ #endif // !defined(FLATBUFFERS_LITTLEENDIAN) #define FLATBUFFERS_VERSION_MAJOR 1 -#define FLATBUFFERS_VERSION_MINOR 11 +#define FLATBUFFERS_VERSION_MINOR 12 #define FLATBUFFERS_VERSION_REVISION 0 #define FLATBUFFERS_STRING_EXPAND(X) #X #define FLATBUFFERS_STRING(X) FLATBUFFERS_STRING_EXPAND(X) @@ -154,10 +157,12 @@ namespace flatbuffers { defined(__clang__) #define FLATBUFFERS_FINAL_CLASS final #define FLATBUFFERS_OVERRIDE override + #define FLATBUFFERS_EXPLICIT_CPP11 explicit #define FLATBUFFERS_VTABLE_UNDERLYING_TYPE : flatbuffers::voffset_t #else #define FLATBUFFERS_FINAL_CLASS #define FLATBUFFERS_OVERRIDE + #define FLATBUFFERS_EXPLICIT_CPP11 #define FLATBUFFERS_VTABLE_UNDERLYING_TYPE #endif @@ -165,13 +170,16 @@ namespace flatbuffers { (!defined(__GNUC__) || (__GNUC__ * 100 + __GNUC_MINOR__ >= 406)) || \ (defined(__cpp_constexpr) && __cpp_constexpr >= 200704) #define FLATBUFFERS_CONSTEXPR constexpr + #define FLATBUFFERS_CONSTEXPR_CPP11 constexpr + #define FLATBUFFERS_CONSTEXPR_DEFINED #else #define FLATBUFFERS_CONSTEXPR const + #define FLATBUFFERS_CONSTEXPR_CPP11 #endif #if (defined(__cplusplus) && __cplusplus >= 201402L) || \ (defined(__cpp_constexpr) && __cpp_constexpr >= 201304) - #define FLATBUFFERS_CONSTEXPR_CPP14 FLATBUFFERS_CONSTEXPR + #define FLATBUFFERS_CONSTEXPR_CPP14 FLATBUFFERS_CONSTEXPR_CPP11 #else #define FLATBUFFERS_CONSTEXPR_CPP14 #endif @@ -189,9 +197,25 @@ namespace flatbuffers { #if (!defined(_MSC_VER) || _MSC_FULL_VER >= 180020827) && \ (!defined(__GNUC__) || (__GNUC__ * 100 + __GNUC_MINOR__ >= 404)) || \ defined(__clang__) - #define FLATBUFFERS_DELETE_FUNC(func) func = delete; + #define FLATBUFFERS_DELETE_FUNC(func) func = delete #else - #define FLATBUFFERS_DELETE_FUNC(func) private: func; + #define FLATBUFFERS_DELETE_FUNC(func) private: func +#endif + +#if (!defined(_MSC_VER) || _MSC_VER >= 1900) && \ + (!defined(__GNUC__) || (__GNUC__ * 100 + __GNUC_MINOR__ >= 409)) || \ + defined(__clang__) + #define FLATBUFFERS_DEFAULT_DECLARATION +#endif + +// Check if we can use template aliases +// Not possible if Microsoft Compiler before 2012 +// Possible is the language feature __cpp_alias_templates is defined well +// Or possible if the C++ std is C+11 or newer +#if (defined(_MSC_VER) && _MSC_VER > 1700 /* MSVC2012 */) \ + || (defined(__cpp_alias_templates) && __cpp_alias_templates >= 200704) \ + || (defined(__cplusplus) && __cplusplus >= 201103L) + #define FLATBUFFERS_TEMPLATES_ALIASES #endif #ifndef FLATBUFFERS_HAS_STRING_VIEW @@ -212,6 +236,13 @@ namespace flatbuffers { typedef std::experimental::string_view string_view; } #define FLATBUFFERS_HAS_STRING_VIEW 1 + // Check for absl::string_view + #elif __has_include("absl/strings/string_view.h") + #include "absl/strings/string_view.h" + namespace flatbuffers { + typedef absl::string_view string_view; + } + #define FLATBUFFERS_HAS_STRING_VIEW 1 #endif #endif // __has_include #endif // !FLATBUFFERS_HAS_STRING_VIEW @@ -229,10 +260,8 @@ namespace flatbuffers { #ifndef FLATBUFFERS_LOCALE_INDEPENDENT // Enable locale independent functions {strtof_l, strtod_l,strtoll_l, strtoull_l}. - // They are part of the POSIX-2008 but not part of the C/C++ standard. - // GCC/Clang have definition (_XOPEN_SOURCE>=700) if POSIX-2008. #if ((defined(_MSC_VER) && _MSC_VER >= 1800) || \ - (defined(_XOPEN_SOURCE) && (_XOPEN_SOURCE>=700))) + (defined(_XOPEN_VERSION) && (_XOPEN_VERSION>=700)) && (!defined(__ANDROID_API__) || (defined(__ANDROID_API__) && (__ANDROID_API__>=21)))) #define FLATBUFFERS_LOCALE_INDEPENDENT 1 #else #define FLATBUFFERS_LOCALE_INDEPENDENT 0 @@ -301,7 +330,13 @@ typedef uintmax_t largest_scalar_t; // We support aligning the contents of buffers up to this size. #define FLATBUFFERS_MAX_ALIGNMENT 16 +inline bool VerifyAlignmentRequirements(size_t align, size_t min_align = 1) { + return (min_align <= align) && (align <= (FLATBUFFERS_MAX_ALIGNMENT)) && + (align & (align - 1)) == 0; // must be power of 2 +} + #if defined(_MSC_VER) + #pragma warning(disable: 4351) // C4351: new behavior: elements of array ... will be default initialized #pragma warning(push) #pragma warning(disable: 4127) // C4127: conditional expression is constant #endif @@ -367,6 +402,13 @@ T ReadScalar(const void *p) { return EndianScalar(*reinterpret_cast(p)); } +// See https://github.com/google/flatbuffers/issues/5950 + +#if (FLATBUFFERS_GCC >= 100000) && (FLATBUFFERS_GCC < 110000) + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstringop-overflow" +#endif + template // UBSAN: C++ aliasing type rules, see std::bit_cast<> for details. __supress_ubsan__("alignment") @@ -379,9 +421,14 @@ template __supress_ubsan__("alignment") void WriteScalar(void *p, Of *reinterpret_cast(p) = EndianScalar(t.o); } +#if (FLATBUFFERS_GCC >= 100000) && (FLATBUFFERS_GCC < 110000) + #pragma GCC diagnostic pop +#endif + // 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). +__supress_ubsan__("unsigned-integer-overflow") inline size_t PaddingBytes(size_t buf_size, size_t scalar_size) { return ((~buf_size) + 1) & (scalar_size - 1); } diff --git a/include/behaviortree_cpp_v3/flatbuffers/flatbuffers.h b/include/behaviortree_cpp_v3/flatbuffers/flatbuffers.h index 876285d79..de7875ff5 100644 --- a/include/behaviortree_cpp_v3/flatbuffers/flatbuffers.h +++ b/include/behaviortree_cpp_v3/flatbuffers/flatbuffers.h @@ -18,6 +18,11 @@ #define FLATBUFFERS_H_ #include "behaviortree_cpp_v3/flatbuffers/base.h" +#include "behaviortree_cpp_v3/flatbuffers/stl_emulation.h" + +#ifndef FLATBUFFERS_CPP98_STL +# include +#endif #if defined(FLATBUFFERS_NAN_DEFAULTS) # include @@ -43,6 +48,20 @@ template<> inline bool IsTheSameAs(double e, double def) { } #endif +// Check 'v' is out of closed range [low; high]. +// Workaround for GCC warning [-Werror=type-limits]: +// comparison is always true due to limited range of data type. +template +inline bool IsOutRange(const T &v, const T &low, const T &high) { + return (v < low) || (high < v); +} + +// Check 'v' is in closed range [low; high]. +template +inline bool IsInRange(const T &v, const T &low, const T &high) { + return !IsOutRange(v, low, high); +} + // 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 { @@ -238,6 +257,7 @@ template class Vector { typedef typename IndirectHelper::return_type return_type; typedef typename IndirectHelper::mutable_return_type mutable_return_type; + typedef return_type value_type; return_type Get(uoffset_t i) const { FLATBUFFERS_ASSERT(i < size()); @@ -351,6 +371,7 @@ template class Vector { // This class is a pointer. Copying will therefore create an invalid object. // Private and unimplemented copy constructor. Vector(const Vector &); + Vector &operator=(const Vector &); template static int KeyCompare(const void *ap, const void *bp) { const K *key = reinterpret_cast(ap); @@ -381,6 +402,7 @@ class VectorOfAny { private: VectorOfAny(const VectorOfAny &); + VectorOfAny &operator=(const VectorOfAny &); }; #ifndef FLATBUFFERS_CPP98_STL @@ -414,6 +436,7 @@ template class Array { IndirectHelperType; public: + typedef uint16_t size_type; typedef typename IndirectHelper::return_type return_type; typedef VectorIterator const_iterator; typedef VectorReverseIterator const_reverse_iterator; @@ -427,6 +450,13 @@ template class Array { 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)); + } + const_iterator begin() const { return const_iterator(Data(), 0); } const_iterator end() const { return const_iterator(Data(), size()); } @@ -464,6 +494,22 @@ template class Array { const T *data() const { return reinterpret_cast(Data()); } T *data() { return reinterpret_cast(Data()); } + // Copy data from a span with endian conversion. + // If this Array and the span overlap, the behavior is undefined. + void CopyFromSpan(flatbuffers::span src) { + const auto p1 = reinterpret_cast(src.data()); + const auto p2 = Data(); + FLATBUFFERS_ASSERT(!(p1 >= p2 && p1 < (p2 + length)) && + !(p2 >= p1 && p2 < (p1 + length))); + (void)p1; + (void)p2; + + CopyFromSpanImpl( + flatbuffers::integral_constant < bool, + !scalar_tag::value || sizeof(T) == 1 || FLATBUFFERS_LITTLEENDIAN > (), + src); + } + protected: void MutateImpl(flatbuffers::integral_constant, uoffset_t i, const T &val) { @@ -476,6 +522,20 @@ template class Array { *(GetMutablePointer(i)) = val; } + void CopyFromSpanImpl(flatbuffers::integral_constant, + flatbuffers::span src) { + // Use std::memcpy() instead of std::copy() to avoid preformance degradation + // due to aliasing if T is char or unsigned char. + // The size is known at compile time, so memcpy would be inlined. + std::memcpy(data(), src.data(), length * sizeof(T)); + } + + // Copy data from flatbuffers::span with endian conversion. + void CopyFromSpanImpl(flatbuffers::integral_constant, + flatbuffers::span src) { + for (size_type k = 0; k < length; k++) { Mutate(k, src[k]); } + } + // This class is only used to access pre-existing data. Don't ever // try to construct these manually. // 'constexpr' allows us to use 'size()' at compile time. @@ -502,10 +562,12 @@ template class Array, length> { static_assert(flatbuffers::is_same::value, "unexpected type T"); public: + typedef const void *return_type; + const uint8_t *Data() const { return data_; } // Make idl_gen_text.cpp::PrintContainer happy. - const void *operator[](uoffset_t) const { + return_type operator[](uoffset_t) const { FLATBUFFERS_ASSERT(false); return nullptr; } @@ -519,6 +581,30 @@ template class Array, length> { uint8_t data_[1]; }; +// Cast a raw T[length] to a raw flatbuffers::Array +// without endian conversion. Use with care. +template +Array &CastToArray(T (&arr)[length]) { + return *reinterpret_cast *>(arr); +} + +template +const Array &CastToArray(const T (&arr)[length]) { + return *reinterpret_cast *>(arr); +} + +template +Array &CastToArrayOfEnum(T (&arr)[length]) { + static_assert(sizeof(E) == sizeof(T), "invalid enum type E"); + return *reinterpret_cast *>(arr); +} + +template +const Array &CastToArrayOfEnum(const T (&arr)[length]) { + static_assert(sizeof(E) == sizeof(T), "invalid enum type E"); + return *reinterpret_cast *>(arr); +} + // Lexicographically compare two strings (possibly containing nulls), and // return true if the first is less than the second. static inline bool StringLessThan(const char *a_data, uoffset_t a_size, @@ -556,6 +642,14 @@ static inline const char *GetCstring(const String *str) { return str ? str->c_str() : ""; } +#ifdef FLATBUFFERS_HAS_STRING_VIEW +// Convenience function to get string_view from a String returning an empty +// string_view on null pointer. +static inline flatbuffers::string_view GetStringView(const String *str) { + return str ? str->string_view() : flatbuffers::string_view(); +} +#endif // FLATBUFFERS_HAS_STRING_VIEW + // Allocator interface. This is flatbuffers-specific and meant only for // `vector_downward` usage. class Allocator { @@ -728,9 +822,9 @@ class DetachedBuffer { #if !defined(FLATBUFFERS_CPP98_STL) // 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(const DetachedBuffer &other)); FLATBUFFERS_DELETE_FUNC( - DetachedBuffer &operator=(const DetachedBuffer &other)) + DetachedBuffer &operator=(const DetachedBuffer &other)); // clang-format off #endif // !defined(FLATBUFFERS_CPP98_STL) // clang-format on @@ -895,7 +989,7 @@ class vector_downward { Allocator *get_custom_allocator() { return allocator_; } uoffset_t size() const { - return static_cast(reserved_ - (cur_ - buf_)); + return static_cast(reserved_ - static_cast(cur_ - buf_)); } uoffset_t scratch_size() const { @@ -973,8 +1067,8 @@ class vector_downward { 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 &)) + FLATBUFFERS_DELETE_FUNC(vector_downward(const vector_downward &)); + FLATBUFFERS_DELETE_FUNC(vector_downward &operator=(const vector_downward &)); Allocator *allocator_; bool own_allocator_; @@ -1146,6 +1240,14 @@ class FlatBufferBuilder { return buf_.data(); } + /// @brief Get the serialized buffer (after you call `Finish()`) as a span. + /// @return Returns a constructed flatbuffers::span that is a view over the + /// FlatBuffer data inside the buffer. + flatbuffers::span GetBufferSpan() const { + Finished(); + return flatbuffers::span(buf_.data(), buf_.size()); + } + /// @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(); } @@ -1186,7 +1288,7 @@ class FlatBufferBuilder { /// 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() { + size_t GetBufferMinAlignment() const { Finished(); return minalign_; } @@ -1270,6 +1372,11 @@ class FlatBufferBuilder { TrackField(field, off); } + template void AddElement(voffset_t field, T e) { + 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)); @@ -1364,7 +1471,7 @@ class FlatBufferBuilder { 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; + auto vt2_size = ReadScalar(vt2); if (vt1_size != vt2_size || 0 != memcmp(vt2, vt1, vt1_size)) continue; vt_use = *vt_offset_ptr; buf_.pop(GetSize() - vtableoffsetloc); @@ -1505,6 +1612,16 @@ class FlatBufferBuilder { return off; } +#ifdef FLATBUFFERS_HAS_STRING_VIEW + /// @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 std::string_view to store in the buffer. + /// @return Returns the offset in the buffer where the string starts + Offset CreateSharedString(const flatbuffers::string_view str) { + return CreateSharedString(str.data(), str.size()); + } +#else /// @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. @@ -1522,6 +1639,7 @@ class FlatBufferBuilder { Offset CreateSharedString(const std::string &str) { return CreateSharedString(str.c_str(), str.length()); } +#endif /// @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, @@ -1552,11 +1670,13 @@ class FlatBufferBuilder { // 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) { + FLATBUFFERS_ASSERT(VerifyAlignmentRequirements(alignment)); PreAlign(len * elemsize, alignment); } // Similar to ForceVectorAlignment but for String fields. void ForceStringAlignment(size_t len, size_t alignment) { + FLATBUFFERS_ASSERT(VerifyAlignmentRequirements(alignment)); PreAlign((len + 1) * sizeof(char), alignment); } @@ -1574,6 +1694,7 @@ class FlatBufferBuilder { // causing the wrong overload to be selected, remove it. AssertScalarT(); StartVector(len, sizeof(T)); + if (len == 0) { return Offset>(EndVector(len)); } // clang-format off #if FLATBUFFERS_LITTLEENDIAN PushBytes(reinterpret_cast(v), len * sizeof(T)); @@ -1679,6 +1800,25 @@ class FlatBufferBuilder { 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. + /// @param[in] pack_func Pointer to a function to convert the native struct + /// to the FlatBuffer struct. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfNativeStructs( + const S *v, size_t len, T((*const pack_func)(const S &))) { + FLATBUFFERS_ASSERT(pack_func); + std::vector vv(len); + std::transform(v, v + len, vv.begin(), pack_func); + return CreateVectorOfStructs(data(vv), vv.size()); + } + /// @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. @@ -1691,9 +1831,7 @@ class FlatBufferBuilder { Offset> CreateVectorOfNativeStructs(const S *v, size_t len) { extern T Pack(const S &); - std::vector vv(len); - std::transform(v, v + len, vv.begin(), Pack); - return CreateVectorOfStructs(data(vv), vv.size()); + return CreateVectorOfNativeStructs(v, len, Pack); } // clang-format off @@ -1750,6 +1888,22 @@ class FlatBufferBuilder { 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`. + /// @param[in] pack_func Pointer to a function to convert the native struct + /// to the FlatBuffer struct. + /// @return Returns a typed `Offset` into the serialized data indicating + /// where the vector is stored. + template + Offset> CreateVectorOfNativeStructs( + const std::vector &v, T((*const pack_func)(const S &))) { + return CreateVectorOfNativeStructs(data(v), v.size(), pack_func); + } + /// @brief Serialize a `std::vector` of native structs into a FlatBuffer /// `vector`. /// @tparam T The data type of the `std::vector` struct elements. @@ -1770,8 +1924,8 @@ class FlatBufferBuilder { return a.KeyCompareLessThan(&b); } - private: - StructKeyComparator &operator=(const StructKeyComparator &); + FLATBUFFERS_DELETE_FUNC( + StructKeyComparator &operator=(const StructKeyComparator &)); }; /// @endcond @@ -1837,6 +1991,7 @@ class FlatBufferBuilder { /// @cond FLATBUFFERS_INTERNAL template struct TableKeyComparator { TableKeyComparator(vector_downward &buf) : buf_(buf) {} + TableKeyComparator(const TableKeyComparator &other) : buf_(other.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)); @@ -1845,7 +2000,8 @@ class FlatBufferBuilder { vector_downward &buf_; private: - TableKeyComparator &operator=(const TableKeyComparator &); + FLATBUFFERS_DELETE_FUNC( + TableKeyComparator &operator=(const TableKeyComparator &other)); }; /// @endcond @@ -2139,7 +2295,7 @@ class Verifier FLATBUFFERS_FINAL_CLASS { } template bool VerifyAlignment(size_t elem) const { - return (elem & (sizeof(T) - 1)) == 0 || !check_alignment_; + return Check((elem & (sizeof(T) - 1)) == 0 || !check_alignment_); } // Verify a range indicated by sizeof(T). @@ -2240,8 +2396,8 @@ class Verifier FLATBUFFERS_FINAL_CLASS { template bool VerifyBufferFromStart(const char *identifier, size_t start) { - if (identifier && (size_ < 2 * sizeof(flatbuffers::uoffset_t) || - !BufferHasIdentifier(buf_ + start, identifier))) { + if (identifier && !Check((size_ >= 2 * sizeof(flatbuffers::uoffset_t) && + BufferHasIdentifier(buf_ + start, identifier)))) { return false; } @@ -2373,6 +2529,12 @@ class Struct FLATBUFFERS_FINAL_CLASS { uint8_t *GetAddressOf(uoffset_t o) { return &data_[o]; } private: + // private constructor & copy constructor: you obtain instances of this + // class by pointing to existing data only + Struct(); + Struct(const Struct &); + Struct &operator=(const Struct &); + uint8_t data_[1]; }; @@ -2417,12 +2579,26 @@ class Table { return field_offset ? reinterpret_cast

(p) : nullptr; } + template + flatbuffers::Optional GetOptional(voffset_t field) const { + auto field_offset = GetOptionalFieldOffset(field); + auto p = data_ + field_offset; + return field_offset ? Optional(static_cast(ReadScalar(p))) + : Optional(); + } + template bool SetField(voffset_t field, T val, T def) { auto field_offset = GetOptionalFieldOffset(field); if (!field_offset) return IsTheSameAs(val, def); WriteScalar(data_ + field_offset, val); return true; } + template bool SetField(voffset_t field, T val) { + auto field_offset = GetOptionalFieldOffset(field); + if (!field_offset) return false; + WriteScalar(data_ + field_offset, val); + return true; + } bool SetPointer(voffset_t field, const uint8_t *val) { auto field_offset = GetOptionalFieldOffset(field); @@ -2485,10 +2661,22 @@ class Table { // class by pointing to existing data only Table(); Table(const Table &other); + Table &operator=(const Table &); uint8_t data_[1]; }; +// This specialization allows avoiding warnings like: +// MSVC C4800: type: forcing value to bool 'true' or 'false'. +template<> +inline flatbuffers::Optional Table::GetOptional( + voffset_t field) const { + auto field_offset = GetOptionalFieldOffset(field); + auto p = data_ + field_offset; + return field_offset ? Optional(ReadScalar(p) != 0) + : Optional(); +} + template void FlatBufferBuilder::Required(Offset table, voffset_t field) { auto table_ptr = reinterpret_cast(buf_.data_at(table.o)); @@ -2666,10 +2854,16 @@ inline const char * const *ElementaryTypeNames() { // clang-format on // Basic type info cost just 16bits per field! +// We're explicitly defining the signedness since the signedness of integer +// bitfields is otherwise implementation-defined and causes warnings on older +// GCC compilers. 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. + // ElementaryType + unsigned short base_type : 4; + // Either vector (in table) or array (in struct) + unsigned short is_repeating : 1; + // Index into type_refs below, or -1 for none. + signed short sequence_ref : 11; }; static_assert(sizeof(TypeCode) == 2, "TypeCode"); @@ -2684,6 +2878,7 @@ struct TypeTable { size_t num_elems; // of type_codes, values, names (but not type_refs). const TypeCode *type_codes; // num_elems count const TypeFunction *type_refs; // less than num_elems entries (see TypeCode). + const int16_t *array_sizes; // less than num_elems entries (see TypeCode). const int64_t *values; // Only set for non-consecutive enum/union or structs. const char *const *names; // Only set if compiled with --reflect-names. }; diff --git a/include/behaviortree_cpp_v3/flatbuffers/stl_emulation.h b/include/behaviortree_cpp_v3/flatbuffers/stl_emulation.h index e68089ff9..77e0f6610 100644 --- a/include/behaviortree_cpp_v3/flatbuffers/stl_emulation.h +++ b/include/behaviortree_cpp_v3/flatbuffers/stl_emulation.h @@ -18,6 +18,7 @@ #define FLATBUFFERS_STL_EMULATION_H_ // clang-format off +#include "behaviortree_cpp_v3/flatbuffers/base.h" #include #include @@ -33,15 +34,34 @@ #include #endif // defined(FLATBUFFERS_CPP98_STL) -// Check if we can use template aliases -// Not possible if Microsoft Compiler before 2012 -// Possible is the language feature __cpp_alias_templates is defined well -// Or possible if the C++ std is C+11 or newer -#if (defined(_MSC_VER) && _MSC_VER > 1700 /* MSVC2012 */) \ - || (defined(__cpp_alias_templates) && __cpp_alias_templates >= 200704) \ - || (defined(__cplusplus) && __cplusplus >= 201103L) - #define FLATBUFFERS_TEMPLATES_ALIASES -#endif +// Detect C++17 compatible compiler. +// __cplusplus >= 201703L - a compiler has support of 'static inline' variables. +#if defined(FLATBUFFERS_USE_STD_OPTIONAL) \ + || (defined(__cplusplus) && __cplusplus >= 201703L) \ + || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L)) + #include + #ifndef FLATBUFFERS_USE_STD_OPTIONAL + #define FLATBUFFERS_USE_STD_OPTIONAL + #endif +#endif // defined(FLATBUFFERS_USE_STD_OPTIONAL) ... + +// The __cpp_lib_span is the predefined feature macro. +#if defined(FLATBUFFERS_USE_STD_SPAN) + #include +#elif defined(__cpp_lib_span) && defined(__has_include) + #if __has_include() + #include + #define FLATBUFFERS_USE_STD_SPAN + #endif +#else + // Disable non-trivial ctors if FLATBUFFERS_SPAN_MINIMAL defined. + #if !defined(FLATBUFFERS_TEMPLATES_ALIASES) || defined(FLATBUFFERS_CPP98_STL) + #define FLATBUFFERS_SPAN_MINIMAL + #else + // Enable implicit construction of a span from a std::array. + #include + #endif +#endif // defined(FLATBUFFERS_USE_STD_SPAN) // This header provides backwards compatibility for C++98 STLs like stlport. namespace flatbuffers { @@ -96,13 +116,13 @@ inline void vector_emplace_back(std::vector *vector, V &&data) { } }; - template <> class numeric_limits : + template <> class numeric_limits : public std::numeric_limits { public: static float lowest() { return -FLT_MAX; } }; - template <> class numeric_limits : + template <> class numeric_limits : public std::numeric_limits { public: static double lowest() { return -DBL_MAX; } @@ -138,18 +158,22 @@ inline void vector_emplace_back(std::vector *vector, V &&data) { template using is_same = std::is_same; template using is_floating_point = std::is_floating_point; template using is_unsigned = std::is_unsigned; + template using is_enum = std::is_enum; template using make_unsigned = std::make_unsigned; template using conditional = std::conditional; template using integral_constant = std::integral_constant; -#else + template + using bool_constant = integral_constant; + #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; + template using is_enum = std::tr1::is_enum; // Android NDK doesn't have std::make_unsigned or std::tr1::make_unsigned. template struct make_unsigned { static_assert(is_unsigned::value, "Specialization not implemented!"); @@ -165,7 +189,9 @@ inline void vector_emplace_back(std::vector *vector, V &&data) { using conditional = std::tr1::conditional; template using integral_constant = std::tr1::integral_constant; -#endif // !FLATBUFFERS_CPP98_STL + template + using bool_constant = integral_constant; + #endif // !FLATBUFFERS_CPP98_STL #else // MSVC 2010 doesn't support C++11 aliases. template struct is_scalar : public std::is_scalar {}; @@ -173,11 +199,14 @@ inline void vector_emplace_back(std::vector *vector, V &&data) { template struct is_floating_point : public std::is_floating_point {}; template struct is_unsigned : public std::is_unsigned {}; + template struct is_enum : public std::is_enum {}; template struct make_unsigned : public std::make_unsigned {}; template struct conditional : public std::conditional {}; template struct integral_constant : public std::integral_constant {}; + template + struct bool_constant : public integral_constant {}; #endif // defined(FLATBUFFERS_TEMPLATES_ALIASES) #ifndef FLATBUFFERS_CPP98_STL @@ -187,7 +216,7 @@ inline void vector_emplace_back(std::vector *vector, V &&data) { // 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) + // namespace we have a completely independent implementation (see below) // for C++98 STL implementations. template class unique_ptr : public std::unique_ptr { public: @@ -280,8 +309,365 @@ inline void vector_emplace_back(std::vector *vector, V &&data) { template bool operator==(const unique_ptr& x, intptr_t y) { return reinterpret_cast(x.get()) == y; } + + template bool operator!=(const unique_ptr& x, decltype(nullptr)) { + return !!x; + } + + template bool operator!=(decltype(nullptr), const unique_ptr& x) { + return !!x; + } + + template bool operator==(const unique_ptr& x, decltype(nullptr)) { + return !x; + } + + template bool operator==(decltype(nullptr), const unique_ptr& x) { + return !x; + } + #endif // !FLATBUFFERS_CPP98_STL +#ifdef FLATBUFFERS_USE_STD_OPTIONAL +template +using Optional = std::optional; +using nullopt_t = std::nullopt_t; +inline constexpr nullopt_t nullopt = std::nullopt; + +#else +// Limited implementation of Optional type for a scalar T. +// This implementation limited by trivial types compatible with +// std::is_arithmetic or std::is_enum type traits. + +// A tag to indicate an empty flatbuffers::optional. +struct nullopt_t { + explicit FLATBUFFERS_CONSTEXPR_CPP11 nullopt_t(int) {} +}; + +#if defined(FLATBUFFERS_CONSTEXPR_DEFINED) + namespace internal { + template struct nullopt_holder { + static constexpr nullopt_t instance_ = nullopt_t(0); + }; + template + constexpr nullopt_t nullopt_holder::instance_; + } + static constexpr const nullopt_t &nullopt = internal::nullopt_holder::instance_; + +#else + namespace internal { + template struct nullopt_holder { + static const nullopt_t instance_; + }; + template + const nullopt_t nullopt_holder::instance_ = nullopt_t(0); + } + static const nullopt_t &nullopt = internal::nullopt_holder::instance_; + +#endif + +template +class Optional FLATBUFFERS_FINAL_CLASS { + // Non-scalar 'T' would extremely complicated Optional. + // Use is_scalar checking because flatbuffers flatbuffers::is_arithmetic + // isn't implemented. + static_assert(flatbuffers::is_scalar::value, "unexpected type T"); + + public: + ~Optional() {} + + FLATBUFFERS_CONSTEXPR_CPP11 Optional() FLATBUFFERS_NOEXCEPT + : value_(), has_value_(false) {} + + FLATBUFFERS_CONSTEXPR_CPP11 Optional(nullopt_t) FLATBUFFERS_NOEXCEPT + : value_(), has_value_(false) {} + + FLATBUFFERS_CONSTEXPR_CPP11 Optional(T val) FLATBUFFERS_NOEXCEPT + : value_(val), has_value_(true) {} + + FLATBUFFERS_CONSTEXPR_CPP11 Optional(const Optional &other) FLATBUFFERS_NOEXCEPT + : value_(other.value_), has_value_(other.has_value_) {} + + FLATBUFFERS_CONSTEXPR_CPP14 Optional &operator=(const Optional &other) FLATBUFFERS_NOEXCEPT { + value_ = other.value_; + has_value_ = other.has_value_; + return *this; + } + + FLATBUFFERS_CONSTEXPR_CPP14 Optional &operator=(nullopt_t) FLATBUFFERS_NOEXCEPT { + value_ = T(); + has_value_ = false; + return *this; + } + + FLATBUFFERS_CONSTEXPR_CPP14 Optional &operator=(T val) FLATBUFFERS_NOEXCEPT { + value_ = val; + has_value_ = true; + return *this; + } + + void reset() FLATBUFFERS_NOEXCEPT { + *this = nullopt; + } + + void swap(Optional &other) FLATBUFFERS_NOEXCEPT { + std::swap(value_, other.value_); + std::swap(has_value_, other.has_value_); + } + + FLATBUFFERS_CONSTEXPR_CPP11 FLATBUFFERS_EXPLICIT_CPP11 operator bool() const FLATBUFFERS_NOEXCEPT { + return has_value_; + } + + FLATBUFFERS_CONSTEXPR_CPP11 bool has_value() const FLATBUFFERS_NOEXCEPT { + return has_value_; + } + + FLATBUFFERS_CONSTEXPR_CPP11 const T& operator*() const FLATBUFFERS_NOEXCEPT { + return value_; + } + + const T& value() const { + FLATBUFFERS_ASSERT(has_value()); + return value_; + } + + T value_or(T default_value) const FLATBUFFERS_NOEXCEPT { + return has_value() ? value_ : default_value; + } + + private: + T value_; + bool has_value_; +}; + +template +FLATBUFFERS_CONSTEXPR_CPP11 bool operator==(const Optional& opt, nullopt_t) FLATBUFFERS_NOEXCEPT { + return !opt; +} +template +FLATBUFFERS_CONSTEXPR_CPP11 bool operator==(nullopt_t, const Optional& opt) FLATBUFFERS_NOEXCEPT { + return !opt; +} + +template +FLATBUFFERS_CONSTEXPR_CPP11 bool operator==(const Optional& lhs, const U& rhs) FLATBUFFERS_NOEXCEPT { + return static_cast(lhs) && (*lhs == rhs); +} + +template +FLATBUFFERS_CONSTEXPR_CPP11 bool operator==(const T& lhs, const Optional& rhs) FLATBUFFERS_NOEXCEPT { + return static_cast(rhs) && (lhs == *rhs); +} + +template +FLATBUFFERS_CONSTEXPR_CPP11 bool operator==(const Optional& lhs, const Optional& rhs) FLATBUFFERS_NOEXCEPT { + return static_cast(lhs) != static_cast(rhs) + ? false + : !static_cast(lhs) ? false : (*lhs == *rhs); +} +#endif // FLATBUFFERS_USE_STD_OPTIONAL + + +// Very limited and naive partial implementation of C++20 std::span. +#if defined(FLATBUFFERS_USE_STD_SPAN) + inline constexpr std::size_t dynamic_extent = std::dynamic_extent; + template + using span = std::span; + +#else // !defined(FLATBUFFERS_USE_STD_SPAN) +FLATBUFFERS_CONSTEXPR std::size_t dynamic_extent = static_cast(-1); + +// Exclude this code if MSVC2010 or non-STL Android is active. +// The non-STL Android doesn't have `std::is_convertible` required for SFINAE. +#if !defined(FLATBUFFERS_SPAN_MINIMAL) +namespace internal { + // This is SFINAE helper class for checking of a common condition: + // > This overload only participates in overload resolution + // > Check whether a pointer to an array of U can be converted + // > to a pointer to an array of E. + // This helper is used for checking of 'U -> const U'. + template + struct is_span_convertable { + using type = + typename std::conditional::value + && (Extent == dynamic_extent || N == Extent), + int, void>::type; + }; + +} // namespace internal +#endif // !defined(FLATBUFFERS_SPAN_MINIMAL) + +// T - element type; must be a complete type that is not an abstract +// class type. +// Extent - the number of elements in the sequence, or dynamic. +template +class span FLATBUFFERS_FINAL_CLASS { + public: + typedef T element_type; + typedef T& reference; + typedef const T& const_reference; + typedef T* pointer; + typedef const T* const_pointer; + typedef std::size_t size_type; + + static FLATBUFFERS_CONSTEXPR size_type extent = Extent; + + // Returns the number of elements in the span. + FLATBUFFERS_CONSTEXPR_CPP11 size_type size() const FLATBUFFERS_NOEXCEPT { + return count_; + } + + // Returns the size of the sequence in bytes. + FLATBUFFERS_CONSTEXPR_CPP11 + size_type size_bytes() const FLATBUFFERS_NOEXCEPT { + return size() * sizeof(element_type); + } + + // Checks if the span is empty. + FLATBUFFERS_CONSTEXPR_CPP11 bool empty() const FLATBUFFERS_NOEXCEPT { + return size() == 0; + } + + // Returns a pointer to the beginning of the sequence. + FLATBUFFERS_CONSTEXPR_CPP11 pointer data() const FLATBUFFERS_NOEXCEPT { + return data_; + } + + // Returns a reference to the idx-th element of the sequence. + // The behavior is undefined if the idx is greater than or equal to size(). + FLATBUFFERS_CONSTEXPR_CPP11 reference operator[](size_type idx) const { + return data()[idx]; + } + + FLATBUFFERS_CONSTEXPR_CPP11 span(const span &other) FLATBUFFERS_NOEXCEPT + : data_(other.data_), count_(other.count_) {} + + FLATBUFFERS_CONSTEXPR_CPP14 span &operator=(const span &other) + FLATBUFFERS_NOEXCEPT { + data_ = other.data_; + count_ = other.count_; + } + + // Limited implementation of + // `template constexpr std::span(It first, size_type count);`. + // + // Constructs a span that is a view over the range [first, first + count); + // the resulting span has: data() == first and size() == count. + // The behavior is undefined if [first, first + count) is not a valid range, + // or if (extent != flatbuffers::dynamic_extent && count != extent). + FLATBUFFERS_CONSTEXPR_CPP11 + explicit span(pointer first, size_type count) FLATBUFFERS_NOEXCEPT + : data_ (Extent == dynamic_extent ? first : (Extent == count ? first : nullptr)), + count_(Extent == dynamic_extent ? count : (Extent == count ? Extent : 0)) { + // Make span empty if the count argument is incompatible with span. + } + + // Exclude this code if MSVC2010 is active. The MSVC2010 isn't C++11 + // compliant, it doesn't support default template arguments for functions. + #if defined(FLATBUFFERS_SPAN_MINIMAL) + FLATBUFFERS_CONSTEXPR_CPP11 span() FLATBUFFERS_NOEXCEPT : data_(nullptr), + count_(0) { + static_assert(extent == 0 || extent == dynamic_extent, "invalid span"); + } + + #else + // Constructs an empty span whose data() == nullptr and size() == 0. + // This overload only participates in overload resolution if + // extent == 0 || extent == flatbuffers::dynamic_extent. + // A dummy template argument N is need dependency for SFINAE. + template::type = 0> + FLATBUFFERS_CONSTEXPR_CPP11 span() FLATBUFFERS_NOEXCEPT : data_(nullptr), + count_(0) { + static_assert(extent == 0 || extent == dynamic_extent, "invalid span"); + } + + // Constructs a span that is a view over the array arr; the resulting span + // has size() == N and data() == std::data(arr). These overloads only + // participate in overload resolution if + // extent == std::dynamic_extent || N == extent is true and + // std::remove_pointer_t(*)[] + // is convertible to element_type (*)[]. + template::type = 0> + FLATBUFFERS_CONSTEXPR_CPP11 span(element_type (&arr)[N]) FLATBUFFERS_NOEXCEPT + : data_(arr), count_(N) {} + + template::type = 0> + FLATBUFFERS_CONSTEXPR_CPP11 span(std::array &arr) FLATBUFFERS_NOEXCEPT + : data_(arr.data()), count_(N) {} + + //template + //FLATBUFFERS_CONSTEXPR_CPP11 span(std::array &arr) FLATBUFFERS_NOEXCEPT + // : data_(arr.data()), count_(N) {} + + template::type = 0> + FLATBUFFERS_CONSTEXPR_CPP11 span(const std::array &arr) FLATBUFFERS_NOEXCEPT + : data_(arr.data()), count_(N) {} + + // Converting constructor from another span s; + // the resulting span has size() == s.size() and data() == s.data(). + // This overload only participates in overload resolution + // if extent == std::dynamic_extent || N == extent is true and U (*)[] + // is convertible to element_type (*)[]. + template::type = 0> + FLATBUFFERS_CONSTEXPR_CPP11 span(const flatbuffers::span &s) FLATBUFFERS_NOEXCEPT + : span(s.data(), s.size()) { + } + + #endif // !defined(FLATBUFFERS_SPAN_MINIMAL) + + private: + // This is a naive implementation with 'count_' member even if (Extent != dynamic_extent). + pointer const data_; + const size_type count_; +}; + + #if !defined(FLATBUFFERS_SPAN_MINIMAL) + template + FLATBUFFERS_CONSTEXPR_CPP11 + flatbuffers::span make_span(U(&arr)[N]) FLATBUFFERS_NOEXCEPT { + return span(arr); + } + + template + FLATBUFFERS_CONSTEXPR_CPP11 + flatbuffers::span make_span(const U(&arr)[N]) FLATBUFFERS_NOEXCEPT { + return span(arr); + } + + template + FLATBUFFERS_CONSTEXPR_CPP11 + flatbuffers::span make_span(std::array &arr) FLATBUFFERS_NOEXCEPT { + return span(arr); + } + + template + FLATBUFFERS_CONSTEXPR_CPP11 + flatbuffers::span make_span(const std::array &arr) FLATBUFFERS_NOEXCEPT { + return span(arr); + } + + template + FLATBUFFERS_CONSTEXPR_CPP11 + flatbuffers::span make_span(U *first, std::size_t count) FLATBUFFERS_NOEXCEPT { + return span(first, count); + } + + template + FLATBUFFERS_CONSTEXPR_CPP11 + flatbuffers::span make_span(const U *first, std::size_t count) FLATBUFFERS_NOEXCEPT { + return span(first, count); + } +#endif + +#endif // defined(FLATBUFFERS_USE_STD_SPAN) + } // namespace flatbuffers #endif // FLATBUFFERS_STL_EMULATION_H_ From d769f5908ffed710fa426b7693dae49b69c1b79e Mon Sep 17 00:00:00 2001 From: Ross Weir <29697678+ross-weir@users.noreply.github.com> Date: Sun, 11 Jul 2021 18:12:39 +1000 Subject: [PATCH 102/709] Use pedantic for non MSVC builds (#289) --- CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f0dc4d37d..428b06f29 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,10 +11,10 @@ set(CMAKE_CXX_STANDARD_REQUIRED ON) if(MSVC) add_definitions(-D_CRT_SECURE_NO_WARNINGS) +else() + add_definitions(-Wpedantic) endif() -add_definitions(-Wpedantic) - #---- Include boost to add coroutines ---- find_package(Boost COMPONENTS coroutine QUIET) From 1ea02048ad3b934f06504a00e5628ead42d19375 Mon Sep 17 00:00:00 2001 From: "Affonso, Guilherme" Date: Sun, 11 Jul 2021 17:13:45 +0900 Subject: [PATCH 103/709] Update fallback documentation to V3 (#288) * Update FallbackNode.md description to V3 * Fix typo --- docs/BT_basics.md | 2 +- docs/FallbackNode.md | 24 +++++++++++++++++------- docs/index.md | 2 +- 3 files changed, 19 insertions(+), 9 deletions(-) diff --git a/docs/BT_basics.md b/docs/BT_basics.md index 14044e6af..827ac85af 100644 --- a/docs/BT_basics.md +++ b/docs/BT_basics.md @@ -39,7 +39,7 @@ The first two, as their names suggests, inform their parent that their operation was a success or a failure. RUNNING is returned by __asynchronous__ nodes when their execution is not -completed and they needs more time to return a valid result. +completed and they need more time to return a valid result. __Asynchronous nodes can be halted__. diff --git a/docs/FallbackNode.md b/docs/FallbackNode.md index 3d6789ad3..c0f1c83e4 100644 --- a/docs/FallbackNode.md +++ b/docs/FallbackNode.md @@ -5,6 +5,11 @@ in other frameworks. Their purpose is to try different strategies, until we find one that "works". +Currently the framework provides two kinds of nodes: + +- Fallback +- ReactiveFallback + They share the following rules: - Before ticking the first child, the node status becomes __RUNNING__. @@ -17,14 +22,19 @@ They share the following rules: - If a child returns __SUCCESS__, it stops and returns __SUCCESS__. All the children are halted. -The two versions of Fallback differ in the way they react when a child returns -RUNNING: +To understand how the two ControlNodes differ, refer to the following table: -- FallbackStar will return RUNNING and the next time it is ticked, - it will tick the same child where it left off before. - -- Plain old Fallback will return RUNNING and the index of the next child to - execute is reset after each execution. +| Type of ControlNode | Child returns RUNNING | +|---|:---:| +| Fallback | Tick again | +| ReactiveFallback | Restart | + +- "__Restart__" means that the entire fallback is restarted from the first + child of the list. + +- "__Tick again__" means that the next time the fallback is ticked, the + same child is ticked again. Previous sibling, which returned FAILURE already, + are not ticked again. ## Fallback diff --git a/docs/index.md b/docs/index.md index c5da1893b..fd34eb7f3 100644 --- a/docs/index.md +++ b/docs/index.md @@ -13,7 +13,7 @@ __BehaviorTree.CPP__ has many interesting features, when compared to other imple - 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 +- You can link staticaly your 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. From b422cc9de3738e13ea57d32822c3731890a87845 Mon Sep 17 00:00:00 2001 From: Yuwei Liang Date: Sun, 11 Jul 2021 16:14:42 +0800 Subject: [PATCH 104/709] Update FallbackNode.md (#287) Fix the pseudocode in the documentation of 'Reactive Fallback' according to its source code. --- docs/FallbackNode.md | 16 +++++++--------- 1 file changed, 7 insertions(+), 9 deletions(-) diff --git a/docs/FallbackNode.md b/docs/FallbackNode.md index c0f1c83e4..7c517b45c 100644 --- a/docs/FallbackNode.md +++ b/docs/FallbackNode.md @@ -88,7 +88,6 @@ if he/she is fully rested. ??? example "See the pseudocode" ``` c++ - // index is initialized to 0 in the constructor status = RUNNING; for (int index=0; index < number_of_children; index++) @@ -96,21 +95,20 @@ if he/she is fully rested. child_status = child[index]->tick(); if( child_status == RUNNING ) { + // Suspend all subsequent siblings and return RUNNING. + HaltSubsequentSiblings(); return RUNNING; } - else if( child_status == FAILURE ) { - // continue the while loop - index++; - } - else if( child_status == SUCCESS ) { + + // if child_status == FAILURE, continue to tick next sibling + + if( child_status == SUCCESS ) { // Suspend execution and return SUCCESS. - // At the next tick, index will be the same. - HaltAllChildren(); + HaltAllChildren(); return SUCCESS; } } // all the children returned FAILURE. Return FAILURE too. - index = 0; HaltAllChildren(); return FAILURE; ``` From bd6e227bb4931d8a34a4ba299e27cb20d983745d Mon Sep 17 00:00:00 2001 From: matthews-jca Date: Sun, 11 Jul 2021 03:15:29 -0500 Subject: [PATCH 105/709] Update documentation for reactive sequence (#286) --- include/behaviortree_cpp_v3/controls/reactive_sequence.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/behaviortree_cpp_v3/controls/reactive_sequence.h b/include/behaviortree_cpp_v3/controls/reactive_sequence.h index d621f977b..aa0aa3b1b 100644 --- a/include/behaviortree_cpp_v3/controls/reactive_sequence.h +++ b/include/behaviortree_cpp_v3/controls/reactive_sequence.h @@ -21,7 +21,7 @@ namespace BT * @brief The ReactiveSequence is similar to a ParallelNode. * All the children are ticked from first to last: * - * - If a child returns RUNNING, tick the next sibling. + * - If a child returns RUNNING, halt the remaining siblings in the sequence and return RUNNING. * - If a child returns SUCCESS, tick the next sibling. * - If a child returns FAILURE, stop and return FAILURE. * From 9dbfeaf799a95148dad4c85dd23b7f9fee586dbc Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 11 Jul 2021 10:26:07 +0200 Subject: [PATCH 106/709] file renamed and documentation fixed --- ...utorial_04_sequence_star.md => tutorial_04_sequence.md} | 0 examples/t04_reactive_sequence.cpp | 7 +++---- mkdocs.yml | 2 +- src/bt_factory.cpp | 3 ++- 4 files changed, 6 insertions(+), 6 deletions(-) rename docs/{tutorial_04_sequence_star.md => tutorial_04_sequence.md} (100%) diff --git a/docs/tutorial_04_sequence_star.md b/docs/tutorial_04_sequence.md similarity index 100% rename from docs/tutorial_04_sequence_star.md rename to docs/tutorial_04_sequence.md diff --git a/examples/t04_reactive_sequence.cpp b/examples/t04_reactive_sequence.cpp index cec330a5a..6e241973a 100644 --- a/examples/t04_reactive_sequence.cpp +++ b/examples/t04_reactive_sequence.cpp @@ -7,7 +7,7 @@ using namespace BT; /** This tutorial will teach you: * - * - The difference between Sequence and SequenceStar + * - The difference between Sequence and ReactiveSequence * * - How to create an asynchronous ActionNode (an action that is execute in * its own thread). @@ -111,14 +111,11 @@ Robot says: "mission started..." [ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.00 --- 2nd executeTick() --- -[ Battery: OK ] [ MoveBase: FINISHED ] --- 3rd executeTick() --- -[ Battery: OK ] Robot says: "mission completed!" - ------------ BUILDING A NEW TREE ------------ --- 1st executeTick() --- @@ -127,9 +124,11 @@ Robot says: "mission started..." [ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.00 --- 2nd executeTick() --- +[ Battery: OK ] [ MoveBase: FINISHED ] --- 3rd executeTick() --- +[ Battery: OK ] Robot says: "mission completed!" */ diff --git a/mkdocs.yml b/mkdocs.yml index a76d768fc..c781ebcc2 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -45,7 +45,7 @@ nav: - "Tutorial 1: Create a Tree": tutorial_01_first_tree.md - "Tutorial 2: Basic Ports": tutorial_02_basic_ports.md - "Tutorial 3: Generic ports": tutorial_03_generic_ports.md - - "Tutorial 4: Sequences": tutorial_04_sequence_star.md + - "Tutorial 4: Sequences": tutorial_04_sequence.md - "Tutorial 5: Subtrees and Loggers": tutorial_05_subtrees.md - "Tutorial 6: Ports remapping": tutorial_06_subtree_ports.md - "Tutorial 7: Wrap legacy code": tutorial_07_legacy.md diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index b8501297e..c25e73ef8 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -33,7 +33,8 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("WhileDoElse"); registerNodeType("Inverter"); - registerNodeType("RetryUntilSuccesful"); + registerNodeType("RetryUntilSuccesful"); //typo but back compatibility + registerNodeType("RetryUntilSuccessful"); // correct one registerNodeType("KeepRunningUntilFailure"); registerNodeType("Repeat"); registerNodeType>("Timeout"); From 278e60e8d26ce4a2484419e9f58ee342c9cb24bd Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 11 Jul 2021 10:26:24 +0200 Subject: [PATCH 107/709] fix --- src/bt_factory.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index c25e73ef8..dbf3e2333 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -33,7 +33,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("WhileDoElse"); registerNodeType("Inverter"); - registerNodeType("RetryUntilSuccesful"); //typo but back compatibility + registerNodeType("RetryUntilSuccesful"); //typo but back compatibility registerNodeType("RetryUntilSuccessful"); // correct one registerNodeType("KeepRunningUntilFailure"); registerNodeType("Repeat"); From 9d9fc1342c0dcfe023120be1686a7ccdb9ad1f75 Mon Sep 17 00:00:00 2001 From: Akash Date: Wed, 13 Oct 2021 02:39:13 -0500 Subject: [PATCH 108/709] Add signal handler for Windows (#307) --- tools/bt_recorder.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/tools/bt_recorder.cpp b/tools/bt_recorder.cpp index 29511e49f..e50152863 100644 --- a/tools/bt_recorder.cpp +++ b/tools/bt_recorder.cpp @@ -16,12 +16,17 @@ static void s_signal_handler(int) static void CatchSignals(void) { +#ifdef _WIN32 + signal(SIGINT, s_signal_handler); + signal(SIGTERM, s_signal_handler); +#else struct sigaction action; action.sa_handler = s_signal_handler; action.sa_flags = 0; sigemptyset(&action.sa_mask); sigaction(SIGINT, &action, nullptr); sigaction(SIGTERM, &action, nullptr); +#endif } int main(int argc, char* argv[]) From f60afbd55b9cae98ed87bd79b404cb1530533174 Mon Sep 17 00:00:00 2001 From: Taehyeon <45509381+plmoknijb15@users.noreply.github.com> Date: Wed, 13 Oct 2021 16:39:32 +0900 Subject: [PATCH 109/709] Update FallbackNode.md (#306) typo correction. --- docs/FallbackNode.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/FallbackNode.md b/docs/FallbackNode.md index 7c517b45c..773bb15d2 100644 --- a/docs/FallbackNode.md +++ b/docs/FallbackNode.md @@ -17,7 +17,7 @@ They share the following rules: - If a child returns __FAILURE__, the fallback ticks the next child. - If the __last__ child returns __FAILURE__ too, all the children are halted and - the sequence returns __FAILURE__. + the fallback returns __FAILURE__. - If a child returns __SUCCESS__, it stops and returns __SUCCESS__. All the children are halted. From bd14adcfae9792509da12295f437dc19fe3e0faf Mon Sep 17 00:00:00 2001 From: swarajpeppermint <85288063+swarajpeppermint@users.noreply.github.com> Date: Wed, 13 Oct 2021 13:09:52 +0530 Subject: [PATCH 110/709] Minor spelling correction (#305) Corrected `the_aswer` to `the_answer` --- docs/tutorial_02_basic_ports.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/tutorial_02_basic_ports.md b/docs/tutorial_02_basic_ports.md index d5d9aee29..1aa179b3a 100644 --- a/docs/tutorial_02_basic_ports.md +++ b/docs/tutorial_02_basic_ports.md @@ -245,7 +245,7 @@ int main() } ``` -We "connect" output ports to input ports using the same key (`the_aswer`); +We "connect" output ports to input ports using the same key (`the_answer`); this means that they "point" to the same entry of the blackboard. These ports can be connected to each other because their type is the same, From d7ce6f59760038f10c1ffbe29509907fd11784f7 Mon Sep 17 00:00:00 2001 From: Jake Keller Date: Wed, 13 Oct 2021 03:40:24 -0400 Subject: [PATCH 111/709] Fix github action (#302) --- .github/workflows/build_ubuntu.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build_ubuntu.yml b/.github/workflows/build_ubuntu.yml index 5124e10c0..0deadca32 100644 --- a/.github/workflows/build_ubuntu.yml +++ b/.github/workflows/build_ubuntu.yml @@ -13,7 +13,7 @@ jobs: - name: apt run: sudo apt-get update && sudo apt-get install -yq libzmq3-dev libdw-dev libgtest-dev cmake - name: Install gtest manually - run: cd /usr/src/gtest && sudo cmake CMakeLists.txt && sudo make && sudo cp *.a /usr/lib + run: cd /usr/src/gtest && sudo cmake CMakeLists.txt && sudo make && sudo cp lib/*.a /usr/lib # build project - name: mkdir run: mkdir build @@ -23,5 +23,5 @@ jobs: run: cmake --build build/ --target all # run tests - name: run test - run: build/test/behaviortree_cpp_v3_test + run: build/bin/behaviortree_cpp_v3_test From 4c9807ac9550116602f7c32cc3da5f1763f15fdb Mon Sep 17 00:00:00 2001 From: SubaruArai <78188579+SubaruArai@users.noreply.github.com> Date: Wed, 13 Oct 2021 16:41:56 +0900 Subject: [PATCH 112/709] added subclass RetryNodeTypo (#295) Co-authored-by: Subaru Arai --- .../decorators/retry_node.h | 20 +++++++++++++++++-- src/bt_factory.cpp | 2 +- 2 files changed, 19 insertions(+), 3 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/retry_node.h b/include/behaviortree_cpp_v3/decorators/retry_node.h index 60c4e2409..392f207e1 100644 --- a/include/behaviortree_cpp_v3/decorators/retry_node.h +++ b/include/behaviortree_cpp_v3/decorators/retry_node.h @@ -29,9 +29,9 @@ namespace BT * * Example: * - * + * * - * + * */ class RetryNode : public DecoratorNode { @@ -61,6 +61,22 @@ class RetryNode : public DecoratorNode virtual BT::NodeStatus tick() override; }; + +class +[[deprecated("RetryUntilSuccesful was a typo and deprecated, use RetryUntilSuccessful instead.")]] +RetryNodeTypo : RetryNode{ + public: + RetryNodeTypo(const std::string& name, int NTries) + : RetryNode(name, NTries) + { }; + + RetryNodeTypo(const std::string& name, const NodeConfiguration& config) + : RetryNode(name, config) + { }; + + virtual ~RetryNodeTypo() override = default; +}; + } #endif diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index dbf3e2333..c25e73ef8 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -33,7 +33,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("WhileDoElse"); registerNodeType("Inverter"); - registerNodeType("RetryUntilSuccesful"); //typo but back compatibility + registerNodeType("RetryUntilSuccesful"); //typo but back compatibility registerNodeType("RetryUntilSuccessful"); // correct one registerNodeType("KeepRunningUntilFailure"); registerNodeType("Repeat"); From 3c7bea1de428e648cdf728223ed9ad94c6021cbe Mon Sep 17 00:00:00 2001 From: Jake Keller Date: Wed, 13 Oct 2021 11:56:09 -0400 Subject: [PATCH 113/709] Fix references to RetryUntilSuccesful (#308) * Fix github action * Fix references to RetryUntilSuccesful --- docs/tutorial_05_subtrees.md | 4 ++-- docs/uml/CrossDoorSubtree.uxf | 2 +- docs/uml/ReadTheDocs.uxf | 2 +- examples/t05_crossdoor.cpp | 4 ++-- include/behaviortree_cpp_v3/decorators/retry_node.h | 6 +++++- 5 files changed, 11 insertions(+), 7 deletions(-) diff --git a/docs/tutorial_05_subtrees.md b/docs/tutorial_05_subtrees.md index fd7d532f5..553494beb 100644 --- a/docs/tutorial_05_subtrees.md +++ b/docs/tutorial_05_subtrees.md @@ -23,9 +23,9 @@ It is also the first practical example that uses `Decorators` and `Fallback`. - + - + diff --git a/docs/uml/CrossDoorSubtree.uxf b/docs/uml/CrossDoorSubtree.uxf index 8961c8b5b..b5a5e10ad 100644 --- a/docs/uml/CrossDoorSubtree.uxf +++ b/docs/uml/CrossDoorSubtree.uxf @@ -53,7 +53,7 @@ 150 40 - RetryUntilSuccesful + RetryUntilSuccesfful (num_attempts=4) diff --git a/docs/uml/ReadTheDocs.uxf b/docs/uml/ReadTheDocs.uxf index 363b8b169..7b1a773fe 100644 --- a/docs/uml/ReadTheDocs.uxf +++ b/docs/uml/ReadTheDocs.uxf @@ -43,7 +43,7 @@ Robot Behaviors 150 40 - RetryUntilSuccesful + RetryUntilSuccessful diff --git a/examples/t05_crossdoor.cpp b/examples/t05_crossdoor.cpp index 53de346dd..3539e0f4b 100644 --- a/examples/t05_crossdoor.cpp +++ b/examples/t05_crossdoor.cpp @@ -29,9 +29,9 @@ static const char* xml_text = R"( - + - + diff --git a/include/behaviortree_cpp_v3/decorators/retry_node.h b/include/behaviortree_cpp_v3/decorators/retry_node.h index 392f207e1..61d329348 100644 --- a/include/behaviortree_cpp_v3/decorators/retry_node.h +++ b/include/behaviortree_cpp_v3/decorators/retry_node.h @@ -32,6 +32,10 @@ namespace BT * * * + * + * Note: + * RetryNodeTypo is only included to support the depricated typo + * "RetryUntilSuccesful" (note the single 's' in Succesful) */ class RetryNode : public DecoratorNode { @@ -64,7 +68,7 @@ class RetryNode : public DecoratorNode class [[deprecated("RetryUntilSuccesful was a typo and deprecated, use RetryUntilSuccessful instead.")]] -RetryNodeTypo : RetryNode{ +RetryNodeTypo : public RetryNode{ public: RetryNodeTypo(const std::string& name, int NTries) : RetryNode(name, NTries) From 7312ad64c2aa73e0efaa5b54d28b56d432a44194 Mon Sep 17 00:00:00 2001 From: Billy Date: Tue, 19 Oct 2021 00:54:06 -0500 Subject: [PATCH 114/709] Fix doc statement (#309) Fix sentence --- docs/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/index.md b/docs/index.md index fd34eb7f3..5baa7c24d 100644 --- a/docs/index.md +++ b/docs/index.md @@ -52,7 +52,7 @@ make possible to express more complex control flows. The user can extend the ## "Ok, but WHY do we need BehaviorTrees (or FSM)?" -Many software systems, being robotics a notable example, are inherently +Many software systems, robotics being a notable example, are inherently complex. The usual approach to manage complexity, heterogeneity and scalability is to From e125ae7dd65ebc7b98023f76b9f611470fa98464 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 10 Nov 2021 17:40:19 +0900 Subject: [PATCH 115/709] Fix dependency in package.xml (#313) Signed-off-by: wep21 --- package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/package.xml b/package.xml index 4bb978033..3e92a189b 100644 --- a/package.xml +++ b/package.xml @@ -19,6 +19,7 @@ ament_cmake rclcpp + boost libzmq3-dev libncurses-dev From 69384df1582cee1dc60fb86a8f910a609461951f Mon Sep 17 00:00:00 2001 From: Yadu Date: Wed, 10 Nov 2021 16:41:04 +0800 Subject: [PATCH 116/709] Build samples independently of examples (#315) Signed-off-by: Yadunund --- CMakeLists.txt | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 428b06f29..83a4e21fb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -240,9 +240,15 @@ else() -Wall -Wextra -Werror=return-type) endif() +###################################################### +# Samples +if (BUILD_SAMPLES) + add_subdirectory(sample_nodes) +endif() + ###################################################### # Test -if (BUILD_UNIT_TESTS) +if (BUILD_UNIT_TESTS AND BUILD_SAMPLES) add_subdirectory(tests) endif() @@ -276,7 +282,6 @@ if(BUILD_TOOLS) add_subdirectory(tools) endif() -if( BUILD_EXAMPLES ) - add_subdirectory(sample_nodes) +if(BUILD_EXAMPLES AND BUILD_SAMPLES) add_subdirectory(examples) endif() From 6f9d241a3c83d58ab77f7bfb69958481afb6979e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 10 Nov 2021 10:15:15 +0100 Subject: [PATCH 117/709] prepare release --- CHANGELOG.rst | 65 ++++++++++++++++++++++++++++++++++ examples/CMakeLists.txt | 4 +++ examples/t11_runtime_ports.cpp | 2 +- 3 files changed, 70 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 270ee83d3..fc60b6ad5 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,71 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Build samples independently of examples (`#315 `_) +* Fix dependency in package.xml (`#313 `_) +* Fix doc statement (`#309 `_) + Fix sentence +* Fix references to RetryUntilSuccesful (`#308 `_) + * Fix github action + * Fix references to RetryUntilSuccesful +* added subclass RetryNodeTypo (`#295 `_) + Co-authored-by: Subaru Arai +* Fix github action (`#302 `_) +* Minor spelling correction (`#305 `_) + Corrected `the_aswer` to `the_answer` +* Update FallbackNode.md (`#306 `_) + typo correction. +* Add signal handler for Windows (`#307 `_) +* fix +* file renamed and documentation fixed +* Update documentation for reactive sequence (`#286 `_) +* Update FallbackNode.md (`#287 `_) + Fix the pseudocode in the documentation of 'Reactive Fallback' according to its source code. +* Update fallback documentation to V3 (`#288 `_) + * Update FallbackNode.md description to V3 + * Fix typo +* Use pedantic for non MSVC builds (`#289 `_) +* Merge branch 'master' of https://github.com/BehaviorTree/BehaviorTree.CPP +* updated to latest flatbuffers +* Update README.md +* Fix issue `#273 `_ +* remove potential crash when an unfinished tree throws an exception +* remove appveyor +* Merge branch 'git_actions' +* Fixes for compilation on windows. (`#248 `_) + * Fix for detecting ZeroMQ on windows + Naming convention is a bit different for ZeroMQ, specifically on Windows with vcpkg. While ZMQ and ZeroMQ are valid on linux, the ZMQ naming convention only works on linux. + * Compilation on windows not working with /WX + * Macro collision on Windows + On windows, the macros defined in the abstract logger collides with other in windows.h. Made them lowercase to avoid collision +* Remove native support for Conan (`#280 `_) +* add github workflow +* Registered missing dummy nodes for examples (`#275 `_) + * Added CheckTemperature dummy node + * Added SayHello dummy node +* add zmq.hpp in 3rdparty dirfectory +* add test +* fix some warnings +* Fix bug on halt of delay node (`#272 `_) + - When DelayNode is halted and ticked again, it always returned FAILURE since the state of DelayNode was not properly reset. + - This commit fixes unexpected behavior of DelayNode when it is halted. + Co-authored-by: Jinwoo Choi +* Clear all of blackboard's content (`#269 `_) +* Added printTreeRecursively overload with ostream parameter (`#264 `_) + * Added overload to printTreeRecursively + * Changed include to iosfwd + * Added test to verify function writes to stream + * Added call to overload without stream parameter + * Fixed conversion error + * Removed overload in favor of default argument +* Fix typo (`#260 `_) + Co-authored-by: Francesco Vigni +* Update README.md +* abstract_logger.h: fixed a typo (`#257 `_) +* Contributors: Adam Sasine, Affonso, Guilherme, Akash, Billy, Cong Liu, Daisuke Nishimatsu, Davide Faconti, Francesco Vigni, Heben, Jake Keller, Per-Arne Andersen, Ross Weir, Steve Macenski, SubaruArai, Taehyeon, Uilian Ries, Yadu, Yuwei Liang, matthews-jca, swarajpeppermint + 3.5.6 (2021-02-03) ------------------ * fix issue `#227 `_ diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 2ba4fa288..423b8b4e3 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -51,3 +51,7 @@ if(CURSES_FOUND) add_executable(t12_ncurses_manual_selector t12_ncurses_manual_selector.cpp ) target_link_libraries(t12_ncurses_manual_selector ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) endif() + + +add_executable(increment increment.cpp ) +target_link_libraries(increment ${BEHAVIOR_TREE_LIBRARY} ) diff --git a/examples/t11_runtime_ports.cpp b/examples/t11_runtime_ports.cpp index 96a725a05..817c8ad7c 100644 --- a/examples/t11_runtime_ports.cpp +++ b/examples/t11_runtime_ports.cpp @@ -58,7 +58,7 @@ int main() // more verbose way PortsList think_ports = {BT::OutputPort("text")}; factory.registerBuilder(CreateManifest("ThinkRuntimePort", think_ports), - CreateBuilder()); + CreateBuilder()); // less verbose way PortsList say_ports = {BT::InputPort("message")}; factory.registerNodeType("SayRuntimePort", say_ports); From f24e5357b1beead34d5c25f057954982b50871cc Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 10 Nov 2021 10:15:36 +0100 Subject: [PATCH 118/709] 3.6.0 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index fc60b6ad5..bebd4a073 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.6.0 (2021-11-10) +------------------ * Build samples independently of examples (`#315 `_) * Fix dependency in package.xml (`#313 `_) * Fix doc statement (`#309 `_) diff --git a/package.xml b/package.xml index 3e92a189b..067d1117c 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.5.6 + 3.6.0 This package provides the Behavior Trees core library. From d7e861f7b8295f224afb0677767f4e5d28670731 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 3 Jan 2022 01:31:28 -0800 Subject: [PATCH 119/709] fix #325 --- examples/CMakeLists.txt | 3 --- 1 file changed, 3 deletions(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 423b8b4e3..59b059cdd 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -52,6 +52,3 @@ if(CURSES_FOUND) target_link_libraries(t12_ncurses_manual_selector ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) endif() - -add_executable(increment increment.cpp ) -target_link_libraries(increment ${BEHAVIOR_TREE_LIBRARY} ) From 27c1a92de468acba43934c0a4b1f4c538906e3ba Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 15 Jan 2022 00:56:33 +0100 Subject: [PATCH 120/709] WIP --- docs/BT_basics.md | 105 ++-- docs/SequenceNode.md | 6 +- docs/images/DecoratorEnterRoom.svg | 578 +++++++++++++++++++++ docs/images/FallbackBasic.svg | 507 ++++++++++++++++++ docs/images/FetchBeer.svg | 642 +++++++++++++++++++++++ docs/images/FetchBeer2.svg | 3 + docs/images/FetchBeerFails.svg | 4 + docs/images/ReactiveSequence.svg | 208 ++++++++ docs/images/SequenceBasic.svg | 4 + docs/images/SequenceNode.svg | 318 ++++++++++++ docs/images/SequenceStar.svg | 314 +++++++++++ docs/images/Tutorial1.svg | 3 + docs/images/Tutorial2.svg | 804 +++++++++++++++++++++++++++++ docs/images/bt_intro_01.gif | Bin 0 -> 145274 bytes docs/index.md | 10 +- docs/tutorial_01_first_tree.md | 1 + docs/tutorial_02_basic_ports.md | 22 +- 17 files changed, 3463 insertions(+), 66 deletions(-) create mode 100644 docs/images/DecoratorEnterRoom.svg create mode 100644 docs/images/FallbackBasic.svg create mode 100644 docs/images/FetchBeer.svg create mode 100644 docs/images/FetchBeer2.svg create mode 100644 docs/images/FetchBeerFails.svg create mode 100644 docs/images/ReactiveSequence.svg create mode 100644 docs/images/SequenceBasic.svg create mode 100644 docs/images/SequenceNode.svg create mode 100644 docs/images/SequenceStar.svg create mode 100644 docs/images/Tutorial1.svg create mode 100644 docs/images/Tutorial2.svg create mode 100644 docs/images/bt_intro_01.gif diff --git a/docs/BT_basics.md b/docs/BT_basics.md index 827ac85af..bd593a7ae 100644 --- a/docs/BT_basics.md +++ b/docs/BT_basics.md @@ -1,73 +1,81 @@ # Introduction to BTs Unlike a Finite State Machine, a Behaviour Tree is a __tree of hierarchical nodes__ -that controls the flow of decision and the execution of "tasks" or, as we -will call them further, "__Actions__". +that controls the flow of execution of "tasks". -The __leaves__ of the tree are the actual commands, i.e. the place where -our coordinating component interacts with the rest of the system. +## Basic Concepts -For instance, in a service-oriented architecture, the leaves would contain -the "client" code that communicates with the "server" that performs the -operation. +- A signal called "__tick__" is sent to the root of the tree +and propagates through the tree until it reaches a leaf node. -In the following example, we can see two Actions executed in a sequence, -`DetectObject` and `GraspObject`. +- A TreeNode that receives a __tick__ signal executes it's callback. + This callback must return either -![Leaf To Component Communication](images/LeafToComponentCommunication.png) + - SUCCESS, + - FAILURE or + - RUNNING, if the action is asynchronous and it needs more time + to complete. -The other nodes of the tree, those which are __not leaves__, control the -"flow of execution". +- If a TreeNode has one or more children, it is in charge for ticking + them, based on its state, external parameters or the resulkt of the + previous sibling. -To better understand how this control flow takes place, imagine a signal -called "__tick__"; it is executed at the __root__ of the tree and it propagates -through the branches until it reaches one or multiple leaves. + - The __LeafNodes__, those TreeNodes which don't have any children, + are the actual commands, i.e. the place where the behavior tree + interacts with the rest of the system. + __Actions__ nodes are the most commond type of LeafNodes. !!! Note The word __tick__ will be often used as a *verb* (to tick / to be ticked) and it means "To invoke the callback `tick()` of a `TreeNode`". -When a `TreeNode` is ticked, it returns a `NodeStatus` that can be either: +In a service-oriented architecture, the leaves would contain +the "client" code that communicates with the "server", +that performs the actual operation. -- __SUCCESS__ -- __FAILURE__ -- __RUNNING__ +## How tick works +To mentally visualize how ticking the tree works, consider the example below. -The first two, as their names suggests, inform their parent that their operation - was a success or a failure. +![basic sequence](images/bt_intro_01.gif) -RUNNING is returned by __asynchronous__ nodes when their execution is not -completed and they need more time to return a valid result. +A __Sequence__ is the simplest __ControlNode__: it execute +its children one after the other and, if they all Succeed, +it returns SUCCESS (green) too. -__Asynchronous nodes can be halted__. +1. The first tick set the Sequence node to RUNNING (orange). +2. Sequence tick the first child, "DetectObject", that eventually returns SUCCESS. +3. As a result, the second child "GraspObject" is ticked and the entire Sequence switch from RUNNING to SUCCESS. -The result of a node is propagated back to its parent, that will decide -which child should be ticked next or may 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__ are similar to the ControlNode, but can only have a single child. +![UML hierarchy](images/TypeHierarchy.png) -__ActionNodes__ are leaves and do not have any children. The user should -implement their own ActionNodes to perform the actual tasks. +| Type of TreeNode | Children Count | Notes | +| ----------- | ------------------ | ------------------ | +| ControlNode | 1...N | Usually, ticks a child based on the result of its siblings or/and its own state. | +| DecoratorNode | 1 | Among other things, it may alter the result of the children or tick it multiple times. +| ConditionNode | 0 | Should not alter the system. Shall not return RUNNING. | +| ActionNode | 0 | It can alter the system. | -__ConditionNodes__ are equivalent to ActionNodes, but -they are always atomic and synchronous, i.e. they must not return RUNNING. -They should not alter the state of the system. -![UML hierarchy](images/TypeHierarchy.png) +In the context of __ActionNodes__, we may further distinguish between +synschronous and asynchronous nodes. + +The former are executed atomically and block the tree until a SUCCESS or FAILURE is returned. + +Asynchronous actions, instead, may return RUNNING to communicate that +the action is still being executed. +We need to tick them again, until SUCCESS or FAILURE is eventually returned. -## Examples +# Examples To better understand how 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. +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. @@ -80,7 +88,7 @@ ControlNode: the [SequenceNode](SequenceNode.md). The children of a ControlNode are always __ordered__; in the graphical representation, the order of execution is __from left to right__. -![Simple Sequence: fridge](images/SequenceBasic.png) +![Simple Sequence: fridge](images/SequenceBasic.svg) In short: @@ -99,17 +107,16 @@ In short: Depending on the type of [DecoratorNode](DecoratorNode.md), the goal of this node could be either: -- to transform the result it received from the child -- to halt the execution of the child, +- to transform the result it received from the child. +- to halt the execution of the child. - to repeat ticking the child, depending on the type of Decorator. -You can extend your grammar creating your own Decorators. -![Simple Decorator: Enter Room](images/DecoratorEnterRoom.png) +![Simple Decorator: Enter Room](images/DecoratorEnterRoom.svg) The node __Inverter__ is a Decorator that inverts the result returned by its child; An Inverter followed by the node called -__DoorOpen__ is therefore equivalent to +__isDoorOpen__ is therefore equivalent to "Is the door closed?". @@ -124,7 +131,7 @@ __Apparently__, the branch on the right side means: But... !!! warning "Have you spotted the bug?" - If __DoorOpen__ returns FAILURE, we have the desired behaviour. + If __isDoorOpen__ returns FAILURE, we have the desired behaviour. But if it returns SUCCESS, the left branch fails and the entire Sequence is interrupted. @@ -146,7 +153,7 @@ It ticks the children in order and: In the next example, you can see how Sequences and Fallbacks can be combined: -![FallbackNodes](images/FallbackBasic.png) +![FallbackNodes](images/FallbackBasic.svg) > Is the door open? @@ -168,13 +175,13 @@ We use the color "green" to represent nodes which return SUCCESS and "red" for those which return FAILURE. Black nodes haven't been executed. -![FetchBeer failure](images/FetchBeerFails.png) +![FetchBeer failure](images/FetchBeerFails.svg) Let's create an alternative tree that closes the door even when __GrabBeer__ returns FAILURE. -![FetchBeer failure](images/FetchBeer.png) +![FetchBeer failure](images/FetchBeer.svg) Both these trees will close the door of the fridge, eventually, but: @@ -186,7 +193,7 @@ FAILURE otherwise. Everything works as expected if __GrabBeer__ returns SUCCESS. -![FetchBeer success](images/FetchBeer2.png) +![FetchBeer success](images/FetchBeer2.svg) diff --git a/docs/SequenceNode.md b/docs/SequenceNode.md index 7b42c5164..fcced1d95 100644 --- a/docs/SequenceNode.md +++ b/docs/SequenceNode.md @@ -38,7 +38,7 @@ To understand how the three ControlNodes differ, refer to the following table: This tree represents the behavior of a sniper in a computer game. -![SequenceNode](images/SequenceNode.png) +![SequenceNode](images/SequenceNode.svg) ??? example "See the pseudocode" ``` c++ @@ -76,7 +76,7 @@ sure that they are not ticked more often that expected. Let's take a look at another example: -![ReactiveSequence](images/ReactiveSequence.png) +![ReactiveSequence](images/ReactiveSequence.svg) `ApproachEnemy` is an __asynchronous__ action that returns RUNNING until it is, eventually, completed. @@ -118,7 +118,7 @@ If the action __GoTo(B)__ fails, __GoTo(A)__ will not be ticked again. On the other hand, __isBatteryOK__ must be checked at every tick, for this reason its parent must be a `ReactiveSequence`. -![SequenceStar](images/SequenceStar.png) +![SequenceStar](images/SequenceStar.svg) ??? example "See the pseudocode" ``` c++ diff --git a/docs/images/DecoratorEnterRoom.svg b/docs/images/DecoratorEnterRoom.svg new file mode 100644 index 000000000..07c4a7371 --- /dev/null +++ b/docs/images/DecoratorEnterRoom.svg @@ -0,0 +1,578 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + EnterRoom + + + + EnterRoom + + + + + + + + + CloseDoor + + + + CloseDoor + + + + + + + + + IsDoorOpen + + + + IsDoorOpen + + + + + + + + + + + + OpenDoor + + + + OpenDoor + + + + + + + + + + + Inverter + + + + Inverter + + + + + + + + + + + + + + RetryUntilSuccessful + ... + + + + + + + + + + + + + + RetryUntilSuccessful + ... + + + + + + RetryUntilSuccessful + ... + + + num_attempts = 5 + RetryUntilSuccessful + + diff --git a/docs/images/FallbackBasic.svg b/docs/images/FallbackBasic.svg new file mode 100644 index 000000000..a16a73f10 --- /dev/null +++ b/docs/images/FallbackBasic.svg @@ -0,0 +1,507 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + + + + + + + Fallback + + + + Fallback + + + + + + + + + EnterRoom + + + + EnterRoom + + + + + + + + + IsDoorOpen + + + + IsDoorOpen + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + UnlockDoor + + + + UnlockDoor + + + + + + + + + HaveKey? + + + + HaveKey? + + + + + + + + + OpenDoor + + + + OpenDoor + + + + + + + + + OpenDoor + + + + OpenDoor + + + + diff --git a/docs/images/FetchBeer.svg b/docs/images/FetchBeer.svg new file mode 100644 index 000000000..6eea6676f --- /dev/null +++ b/docs/images/FetchBeer.svg @@ -0,0 +1,642 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + OpenFridge + + + + OpenFridge + + + + + + + + + GrabBeer + + + + GrabBeer + + + + + + + + + CloseFridge + + + + CloseFridge + + + + + + + + + + + ForceSuccess + + + + ForceSuccess + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + OpenFridge + + + + OpenFridge + + + + + + + + + GrabBeer + + + + GrabBeer + + + + + + + + + CloseFridge + + + + CloseFridge + + + + + + + + + + + + + Fallback + + + + Fallback + + + + + + + + + + + ForceFailure + + + + ForceFailure + + + + + + + + + CloseFridge + + + + CloseFridge + + + + diff --git a/docs/images/FetchBeer2.svg b/docs/images/FetchBeer2.svg new file mode 100644 index 000000000..b1818b43d --- /dev/null +++ b/docs/images/FetchBeer2.svg @@ -0,0 +1,3 @@ + + +
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
ForceSuccess
ForceSuccess
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
Fallback
Fallback
ForceFailure
ForceFailure
CloseFridge
CloseFridge
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/images/FetchBeerFails.svg b/docs/images/FetchBeerFails.svg new file mode 100644 index 000000000..eea5fac2d --- /dev/null +++ b/docs/images/FetchBeerFails.svg @@ -0,0 +1,4 @@ + + + +
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
Text is not SVG - cannot display
diff --git a/docs/images/ReactiveSequence.svg b/docs/images/ReactiveSequence.svg new file mode 100644 index 000000000..02cc92a0a --- /dev/null +++ b/docs/images/ReactiveSequence.svg @@ -0,0 +1,208 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + ReactiveSequence + + + + ReactiveSequence + + + + + + + + + ApproachEnemy + + + + ApproachEnemy + + + + + + + + + IsEnemyVisible + + + + IsEnemyVisible + + + + diff --git a/docs/images/SequenceBasic.svg b/docs/images/SequenceBasic.svg new file mode 100644 index 000000000..d167dd27b --- /dev/null +++ b/docs/images/SequenceBasic.svg @@ -0,0 +1,4 @@ + + + +
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
diff --git a/docs/images/SequenceNode.svg b/docs/images/SequenceNode.svg new file mode 100644 index 000000000..5754bf716 --- /dev/null +++ b/docs/images/SequenceNode.svg @@ -0,0 +1,318 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + AimAtEnemy + + + + AimAtEnemy + + + + + + + + + Shoot + + + + Shoot + + + + + + + + + IsEnemyVisible + + + + IsEnemyVisible + + + + + + + + + isRifleLoaded + + + + isRifleLoaded + + + + diff --git a/docs/images/SequenceStar.svg b/docs/images/SequenceStar.svg new file mode 100644 index 000000000..4664bcf6c --- /dev/null +++ b/docs/images/SequenceStar.svg @@ -0,0 +1,314 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + SequenceStar + + + + SequenceStar + + + + + + + + + GoTo(C) + + + + GoTo(C) + + + + + + + + + + + RetryUntilSuccesful + + + + RetryUntilSuccesful + + + + + + + + + GoTo(A) + + + + GoTo(A) + + + + + + + + + GoTo(B) + + + + GoTo(B) + + + + diff --git a/docs/images/Tutorial1.svg b/docs/images/Tutorial1.svg new file mode 100644 index 000000000..ff44a8a29 --- /dev/null +++ b/docs/images/Tutorial1.svg @@ -0,0 +1,3 @@ + + +
Sequence
Sequence
OpenGripper
OpenGripper
ApproachObject
ApproachObject
CloseGripper
CloseGripper
CheckBattery
CheckBattery
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/images/Tutorial2.svg b/docs/images/Tutorial2.svg new file mode 100644 index 000000000..8d8f21485 --- /dev/null +++ b/docs/images/Tutorial2.svg @@ -0,0 +1,804 @@ + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + + + + ThinkWhatToSay + + + + + text={the_answer} + + + + + + + ThinkWhatToSay... + + + + + + + + + + SaySomething2 + + + + message="this works too" + + + + + + SaySomething2... + + + + + + + + + + SaySomething2 + + + +message={the_answer} + + + + + SaySomething2... + + + + + + + + + + SaySomething + + + + message="start thinking" + + + + + + SaySomething... + + + + + + + + + + + Blackboard + + + + + + + + KEY + + + + KEY + + + + + + + + + TYPE + + + + TYPE + + + + + + + + + VALUE + + + + VALUE + + + + + + + + + the_answer + + + + the_answer + + + + + + + + + string + + + + string + + + + + + + + + + "the answer is 42" + + + + + + "the answer is 42" + + + + + + + + + + ... + + + + ... + + + + + + + + + ... + + + + ... + + + + + + + + + ... + + + + ... + + + + + + diff --git a/docs/images/bt_intro_01.gif b/docs/images/bt_intro_01.gif new file mode 100644 index 0000000000000000000000000000000000000000..917db1573482bc977ca1466c7f557eef6ffb38c3 GIT binary patch literal 145274 zcmeF&S5T90zv%rtHv~ct9YrC9UPJE~0!W8QZz@uhqW%$3nm{0-S1HmILhl`NbXo4k>VFxsL0v-PV&+h;q!hwY-U^5ZeO9hS|0w>wP z$p~;V2b}x_h(uySLPC0a`lCmWii(PAYHFIAnw~v-*4x`VG&D3ZF)=$kyRx#fxw*N! zyL)nS@~@BipFbfFshOw&B>;KCV5)0rp{<42m6gI!K~CQ-!41#?<&ZA`Ky%!c>#Z+w zHhG}fXYi(K{%EHeSoo4?yD)kU&FVbE^N2mH;u0Rw%HN-_S?}3 z!6JZY7akQI6B`$ALP|zdXZS5UlPwJm`c6GZxZ|&)SHE^jfdGO81Tk9d>=*0W3vGK{7*_x?|^C2&`cK7@;LEfDoN55|*!O>ipO}%==S#=Pbu!bEV_eNi)(csZ~hgFQ> zk<)BXOIhmq=d5;|@fanXhM8YIh-2}ZHVrM~#n+EibV#pr#k5D~MA^%Z&GN9izbwx* zm-iQ-6T~88{3^yHO!5tDxbIe4-QzRLLM(o-wDIML%;FIjSpU$p)SrVLQk0y2;@wh_ zXp}iK*AbBR@y(FZ)cgyA?;j>(ECi|_4zIqoF|E^-J^Gor&}$|U7P|QBC)M&> zX`{<^yk)?eiTo4zK^);2I&hVrPH~Mwgc~*?h^*G`i;>Kx1GHR<$9`*z(TFIKr5K(B zm~*U9=@gPir1Ah6FO|o$oFG(NRKRD`tiPP3{&Q_P8T%_n3#l|iMM%;Ts#r-i7E=)b zbSEFUq*+>fe9GX{JX7*O-+BF0rc+M&r-weqXI8V_qf~^ly|c1cbG>ETg>rAVo%#GY zU`tu}ap}42&-sMXHsSp1Q)ku+2+W3Sm{8QlT7I0ASX4o>b=>vh)CjGLl1D+Y9;H`q z&a9VPhSH017p7Kvrk3Va>Q+|u&$v|8nnO0DF^{m_)Eu@cAY&tq7gbG*;hicbSrH5j zA_IFW*6?!XU3si5+&dEFDNgBuz6OEnreYj#4STDp_e=U?#3rymUFz*lcYd~YeA^b;k#Rr{n%~@HNvTzQNgjhmWh=L(-18UIEBYxEC~RF zT7-aOLRimL)6)~G3G_l8*zQ-<0{CzSK^bE89*Yy_6`HG(pxu%i*l!H#5`ZT`#dMfw)aCo$`>TVUZo7sA@=i26KgA?IW4ikRz%v!T2MAdT0OvDoFQfRm5W+Oa)jM4PPZx&B z@KJ2*S}TXXsdjB<@Kg^cT|I`1NlM52%bxK zpgB1Ns78&YCVY>V{z73oW@%O4n0C55Z~l&fZo6N)zv#X*Siqr#d&%=0acdZzi*6Rt z0%OXZ-P5m}zw1uqc@*K5GQ2n~P>O2545r}Et#CZmLDLD?c zoRZiV{e5146_gRQZ#K~ z1Yw%QEA&8KH1n|-s@34q6^Tb(^v+n~***j`>S>qkx)s2QVY$b}1FYti0{7Yp*GA6q z10v+^Gh`=Va;co@z*?F#2)Nm=$wmHu1U>swp22Q z8gdG^5>ei`P3p4PxNH~ms^*?J6FuH@Fd;gU{klT2W5x#KQrib{zzn*_3ycd*S+^?U z9&xy6LD^ECKoArs0d>fYI(XyVcM9O%*)D2l!qi!(t~6R6JEmURLT-GQH$)kLS`*si zJ~e7Lak9Q1vj(zDH$j+_Jp@IFh>jX->?T!BSyrMplFC~@CtOLct`gXaV=C`~uzdtfif^_{SXT$3%_u_uYFUfzxA~{A6Xac$_ ze|`JPoZ#foY5SbokN>`3V^<&2wNz2`L3qZgq|aN&*aCCP@^UHPRu zcidl68ZX`d5MOY1_Mrb|)*V*w;bp!B+gI{G8&aa@5Qs8RfCks_02#4zzUtbbtjEsV z9l%W}lb9k~E2~v(Tr2Dq$nR(!mDxF*gqigmc4dB*p%A$$@8I%=wxBULAMzR35;)RR z?wh}o@cHW6Aye3vuLO9W7RQjo5tY~bm_;K_$H?Pd!X&9kiF#c>xNs~wtGNVHuzrm7 z3mRAMkr&Wp+E9!QVk?$vd3>mzWKlK4U-3|<`s#D29RKwD=8NyEmBKe2%^E(mUT>*e zq`hhVC1}dP+D9tM#LIz~I8DBHPnI0w?lImz_3(+JLir!JTVBN3i$4{WyO^%|C{fKC zartMzyXEBDnf>v$mC}W|ug*bLXXb$?`zm`TB7t6{1&5theV`T@{+2}fDWhx#ujPy4 zrCzw?bD%9SaxTuLZ>g*Mpc5I&m&o#HdG`B3x7P8w)K|JIGJqw`5!{t<#^rkykffc3g-%#ys8- zy4{dglJuh@d41z@XZ>U>@UuRDe=|$r>GUg2Qe)M5NB7UaW}h?vxHR(T>z&T0^Z9vK zjEY0PIk)~=fOI-P(bL`{efwvgz3yHw1MGXkg{KrG{~<(e{%c0-#FCuZk0F-4-GdzU zHMOh$tmdJ64KwN+3|E6>@obhp>0dv1Mm$b>_r@@^pBujqPvl~MzTaKl-?4clISw;9s}9%0G`u!!cARU9%Y?&Y}KF_TCfwS zuxrKM1^VtrnM&(W>Aw1oygwW;)^*a*5tOD5 z@V&0HDI)L%oRkk+tQ~4;17>JrSm6*3Y^A99_IqFRW$rvPAIp5dZ(H63j zMYvH7Q&EYL!K@-{Q8Fmib(vHSN)kdsr;vnlkg_k&&}P23MA*4;`a3*Q4o4-K0?K8e z2w7lllestt$+R$1w-<+WmS-0rv@8dU`a~fcaS&{@;xUFwuPEX?Tl5|0XdEn@^->gH zkJ3+hbX6K4+hyx}VD+>qS^;bIV;On4j1RMt?&?+IkVo~CRBRAbqcC6~27g&sh6`f{ zkb#5&Fp3D}-ZKq=3;b%0tjxmfjR`7@f+8ugQ)vpk<46fkDlq~mPKoQv06`UP0kl$~ zw(KrWH=sE7jxrU*11o?g>}MtCWJ!sqBu5Wi>=;jKZHwqC_o}-gsp^&h5P)1c2sZ-q z#ypOj0P?`~w)%8A3807*1V%PI@Kt~01`)wS_MGF6ie-d)wDbd@SI5=3og`_=#(Uh6 z7WxojZ-`HmIzP@722UGs)5%rPI`#mP%azfN$|$?EM3kEiWld`}OP4QI!UF@O1?X)C zKzWIJo>+yBCcM-N@hJ~h;4TzK(V|_+^vI@Jt+p znJsG>DnLZML8h1LR|jqVdUI&uX_hUf=LNHPQqsotawj7~yLyy#0#QI$c0XEe!XJD{ zRAJKB5#f0BRQ}R=lp2QT5xX}@kpNz8N~$05f3S`|m;OL(%tp>x(vhg+J}7exqSz*q ze&2{k_{a-;P#IPn%S*T_UOJ<(=NzvuVCmqOBQkf*Nx1@2^m#jS| zxQc>gHK`7;YfO$MkF6mac`iA*q4;zSNG}V|musNhvScY2%+YGJ^d`;+NI8u5iz$JC z0ra^&hXf+DxkZ)D6D8NBAYH7?shvGGm5Auk60pb@MJY*m=3LU3#!r#Y>e?YuN(;`C z)?%6fIlfxBxPF!L1O-18MNQ(Ap1S5MB9!Ec%MK?>k+Pb? zhYC^jDB=uKPcG9&Ogk(#%$%J?ZlYWl;A`Gf0e!JWlk@;yq}I;0ksD}S zU8zX-tmuiW(D0G>?;!5xTngo32^LWc)~Awig4DYy9xm%6dkls=v-}j)>V8!nOY11P zcHj_)mw~>RrS($I-~jIU%31?CPHh-oq%q6@w%FSw? z`kUGrLDAX=))#uhqnCTLfBTd9*{H_%+MCv6Y_=`# zQDa^7&7Lq+f8cFyKSbB$Vnx@HlVdOJ*e-~#)SwF`XpWHg)QVh#k6UOx)dRgGzo2Rl z8RA~Kv<)4_<7UyxR89ANn~_VGpn&?8QWaP(0rqLZ2r6{CP3L!%)5NH3=+td607+D> zL%&p!jGa)Bk@Jif&Uw5U_hc`=p_NoGcdkgZ5vQLjlOT>_bA5u?!FAr%{N|A5vzM8d zbHPoZ_9~SPQ^ixaji;GGelPSCVE{q03shQuIKlAjlDi};1(Y2H>EXc93^KaeK?Xr3 z)r*tUc_}jv-kQUASx{|pL!u6v_t=V8tL}>a)CKFgFmrtw2*jVgpCazV6c6D=4O&tZ}ZwwXrWwUMlKB$2vu-0^dtkFs%m#t zfGvUEfgW2AO6l7G+E>(e*XRVu#t(rmc`iJpfIeyJh7>gclp%zR!6AsjuotLMH+yL* zc!|_#IxOvUr<9W02Dz~g;+BB0w+5e%6(@{Jic;6b7|kvZh`~$xmwQw;2tO0v{u+ME z;U-B}A0yiZdL?xJ@X^?&zj|fvvbYn39RcAWK&UIVX#8{}RUn=sp?o?jiizW*-gr=r ziU$Gd5^XTmg&02`TxG{7owp9Q4?C6|O+AQvdv1L6AZS8x8I%dR>b-%IDyM;wYZM5f zpME2gUHZ>Q4k!LbE(AbJ^{H0AXv{c{NVutIRMQ9v)^hYt+EPj}_)PLFQXFGfIyCZT z*6n+&2pBKS`b)yC1~rnA9AA!-#zW{+09J1ZHGRq_?Px&(2pt*Vpjh~Qnx?}*oW5$) z#7ayNA*{d*7viaWuRWLsaFC0?ZGyGuXQJ`H&ra^>A0q4b;NhqoF&d_}QwJfG1Rr<(leu@u_NKCiAmk6r?I#~bN>PGxdV zM;B_%oE74o9{>C?#Q(;9<;pKkU+6C!FfI6xjle=7T$my17aw6#;`DrrJwC-8d=l)T zi_5f&XOAhnvx@~bl(w`2L>^`G^3vzWZ6aIq{4bW+ZZEw1w8U~SFFUd%c4hgb#!vOd za*uVW`tdSW*bl3@qVmC4Cv-(xct!ukiuUyt+kNXnOI#G{tCZU@Yyg9gaT*P6~h@b-Q_^(%Kjt$gQ2-plx99;Lv;H*Pmmz`D40sQ-X+YBJ3;04&RM^LV}}(F0o^Ykqiq0o^#3q zi4aCE+44pG)D=#8E_1FJo5qsN z#^m+h+*m2TT_e#jV`ie#Hm!TEtK0c?wNrA)-FF4m@eS9;>BVQYY8+f{F1-H3>0f)< z{_eL8w+#QftL7mm^s5{J_16p|S;ViW2Q(~eC-NKpWDjioq?#e^6_pm)^jYrlg?KLZ zpyqX{60@q()S#A4;hL*M)@;E~zM@+G*&L~vRs1&J7)IqUdB1IAsow-`CKaUO`*tMX zD@p33?2nDqIv4-ykf%#q^Grk*=>YY>&egY@CUtz7&uyekUn=QK@-}w=gV1Yy!R@=|AxyBD#dt@rsoi{8*4dJO%@dXsIz_-@*Bq0FogU z5KbpvjsQn!9dB)O(!wy^bYkhF5(~_VN5Gq&RN#3Y7CHowwdm=eey9@PPqM9&0HDD|4KC3P|cKhG6qlCxHx%0YhxP7j?69)bG`&w2-f9 zwtl0u!vXauQ^_o*nI(~hhsg3D-jzhK~{LtjGMiUgn;l{wB z^5RP2xYouB0w7Ec`iNrhF;|w6R(J;Q+#Q9Wu-){w1Q1R!0bfXPLvY6wwRgH$AdV^r z?63mEpiMzQ06=B64T10&6-avLw(n(tiIVREr;SU`Fs&K_`ecu&r{zSQ7y_%K2^78d zVSlLt?!wGMycCb83!Twoe9c_u_7$Oc!=DyP*>i5|1!90r%=CSgDlw*^akiRUPsW$?*N=~i+c#y2wDmg zKpQ}Sark4b74@6h#1Ifo zf2Yx_wSF7xua7Cg-;N|d|GL-t+s!hxmzDx>dv;Zb*N6WhIn|2>bo+Z^hWQw;DH{Y_ z=BV|~kvb6C$#oN_O z>TAj<^}N#LF!dA!ui`76k?0503M&FbE`#(QjcIQnZr2O~U(bp}3to(HyX_vxL{oYLxl9yF29rjRe0 zxFKn2$5nY-LDD7Uv&E3=%_pVM8izlg*S@HZKfl;t2RVQ92IJB2OFrM){YN*w&KB~p7ZtI&7)@vPky$POy3ero_)S}Pp?DT>UKnRuIbl{15YbB z{z2qB;D5}2e?BPxjr2uL|IZVps_%dP$)}!Erj<76xz)7&Q2xFGOQu1eu7!8K@qIb{ zhr=&zWR{bHe=i^ADGcbD`cN;nt%#VZ5QfP+51&5jmriaU-s~;Qp8dW0uKruJ|CK8z zhN(H~EWaY@A6zT&%IX!HY=1}8EGd)@>DCvH7|$R1Sb9wLc*86?D5PQJ2NUa`jmtMW z-p2CWt9H1&?sif?>6`bnI_&({ThZGy1-$-6`Omi;^N%LJ^VPKOKHdnTJzA&;-tV3b z`BKULY_Y)V;N`CRwzvQN>a)^^Md&>H2X(*ee%A&Lz5QUF{q25Oc(ebz6S|$pSGVqH z>jsYRa{o|Pg)}i^0cv@t)?Dxm2=fML2#9tY$}Qo{nes`Sc|W=|eBDf$=v1dW)S!=w z+LEP=Gi8gJs_W{u!k#Aje9d)LSD2}F;&SL=@g;K4*q&&%^n!hX#~KmY7P zFFiZT*&whMW1%7hovJ<&ajYT)0THeTb>Hh7v>b=j`w6^9V;5fqN`dkLWQ%VrI1Lat zsH7g0PGjt=wp)aa&=wGC*2wS)ybML-(ZKLN;`AR{ZKUuA6i~X0kRXeLT@K6vLaZV} z98)L;Uu_f|WP@L%!Vtfdgb6Ge8kQ5;M`gv~pmMJn3o7hv<9#96={AiXd4jc+s@D;IXgO6q58h#oblq>K{Bf(W?z8J{Qw zpnB$|*5v_FtpSua4^qhjyWy`|z>PBHL9+dbkR*f3=y0Zp$ZI|k`h^i3ezCV*OwnU1 zbSYq9%l$S5JLdrqcUP17xKZ=>gv1#EwcBW0wp61yU#KWP9vF@LsdHZfu53#Ne3ikn zyAn*Gb>A!0k`n4coAf7~hy)ho2V!0q$uo^3&PIaBZ3qeJL#gD=0;G zju_i=@KekMuA_;Rl(XneGxIEpaE~%FGA|)2MiY2!tO4 zxt4BXLJi^HhOiQV>|)LKCR^5R2plh!7$dj1hWWCLumKe6(2#x~;Q2&|b`g<<0%5}{ zKHo)5k^qiC2c=?LXgZCIc_Pv$(ZB*5qHX;WrZx5%(Vj{JlA~|zB{2G448Y4*rf}40k+Ba&e zLbg@;D1g+|>5Wz>yBn+RpHj<}$vlyKw$U2tEMbzS{h~Z|m!s|W7mI>L2VqTi>en=UR%Kj_Xh z;^+|Z$yt%Qk36&zPZgx=*nWZiJ>vcD1GXJ9bA;R?HIi8e*Oo@MCECNS9@6@$u@t6AOqau#3@?x8 z_38j@^%c2iPrpQRy1SbG2ATk+SobhST(*SSS>pP#p{AjtKy%6Zv1KKzxdsEB!VUWh zk3EF4c1G(Op^Yk3dt6R{`VrGoB`a7p!~s;=6kc(UGXhiDQ)zL=EcWLT9|;Z%7x@oHRNL~q5T zIJvi|s*jclz|#u6oQ5k^1#?H0eoz({C|?v?z!FjI8fas1w>?wtAC!AQSJU|e zCE|f>bE%=Viqb$w6{DlXF(B)LBeR9^Fq4LAUYySSWviQj@PyD*Gm0C7_(WBDjPXMPYU|w zn^`V@^DI)h%20GjRn$mvA`VX+EIMmd$JFy=sHK#pF%|ACaeq9ox+#-uC+}i>9g?AB zw7t%~4@?R@$c9kDJYjxa;DVvPshcQLFSs&+0euu_ zQ1!Z<*Glr7Ks9@z_=bJM#1P(h3gPOT*H+ZhKPK5f1NNsryPKtUeW>GY&J)*tRCrpI z)(=Cbo;cP*eQNxp$aZj}Onh${3nMG<>l`;o!jcklVR9qlG#iZQP6xNhih&611pC!zJ(rry5vfuliO5m=@?RO1JT#6gLOZ zc1+ml(4h&BkX!>8IJW$y$o&tp06zf)ctA#ce)_r?tfY6<9F(;OF%{B=Xke}o6hc6X zUTRTOAcIs|xc6bgc#w5ejy%`0#SO~FsWJa9{b}>&!=pE|68Qd9z$feUX7!D40)xb- z0y~k?Js=7WVIBooFp!l&>;X|5z7AYEcmsD;=1P2rz?*%l1ldOc=55H&*A^^YV*v>o zyFTyC?&@OicEa0hK77G^c~&DFA|nXAlOk3s%E4fiDhYVV%ioCCwh!%mX>a~U^aVgK zw}Hofj2az|!)GJa{Hkd%qwYT^GQH&07i3kZuFtWS`a_fP|oR$YX%H=8_;esi;_;y$c9C4@vcs&DE8r z+XlopdSLIT2qt;EV?fM#$Rl^gWx@@-T$y`7W_QhGjlc{$D z8gt|4kpWEuMW1Juzlyiq3Sxsp((ca_Q|H&6Cw6M)r_L+RTwb`^IRESN{e2CS!;dx# z_P7O*@1qkJ1$r#-`!R*_=K?y4!gyPNfp75+>K#XD5OwGx?J8xbulsB*<*L6gN^{9u zWl5;kN7#Q!EYC;q#gf$g9ns?@Sxpy7&1Jj)WQ9iFqjheucELBIC%!V?g36-0Vi*Or5WJlGqAq}oNWGo!GotTnDu`F3}XKm z45G=sw2c1&gKr2d{EGjA!Hi_&hYUx99qlL<376Cfd^d48mrc^LjnMS@SnDyT*ulA9 z(&d*5^*^1t93)?1;cZ+b6=K+uGf{5UgnK$;S@pryu`^DW>t3~;liS-BGHIY7R^)d1 z81b$n(m4*(FS48i}I$rT#Ss~3Kn6$s9Pn(SUn-vA@nSA@0uAC>Bt$hDNaZR1k6FQ^n>#e_305~8yo3ws(9 z0+1H2%I&Vxm=F$Oka9%c?x1&wIn_bOtWzC?V+kO#4S%f%fT=}*T;iCXs8ha^fzV;S zBO)aUfKNATwG-;ucd78(3^wX1D0(R6&OecYFft81&5 z%|XH=r7RPp``I7X*Pew093kH*n90|XXdPvCV#KP00XkUOHerUN6tM>pY8wUVsP}H} zO#mX7k>h~nfjj^wkAe&Wd-s74j8xuOfW5e@hi;5sv!IzpWIm!Q+06YkCQR?bF$iP4 zq4X}F?VoV0y}*LUT-54tkUqucKpd2`gh2pmY;6$ax!KfDPCcWny)hFr+h*9H)RFH> zxWyXo?N?Kg9!_LHfCj*5TOI_~#Q##|Z0JPveDJ`K+exC14L*^|HYd2}0QMi{9YUux za&Z;}4kbuvYM>Uvm3rC|Vhfr@DcU3#t*Tl?3uF7%{m-hiBzv;-&&%DAl+)lDBot5& zd)xz3oFYxTE_}M&9VQJ>NRtX0^bK&paXIT)q*;T_&>d?7m#lSFqAmkXG@KxA~=3)SlD3vIYzgDPH_Yx-c}w76!$k^Ok)y?awnsY zjr9R}=S%J%pN>N_2S|I@V9=}Ld6Va4bfIh%+^sMCyY#|H&PNf6lEv^dMxz*(lCNxm z#wh;e_kA3qqoH%Ml&H85FB#rTCk*jA?p^_Ofav6h19t8hKSH5lZ}&V0ttHiM?S zY`P*Gx#06PWDjRDPFLGaK$s)K%I8Zaufytz_4I2S=W@LCO1CXaT*VsPI=}n)pM)|PgrH+lYXoVZbvg_h)cKY;3K76-F*qKRLDmBk zaKO<9auKgSp^E@g#B;#DyI_Q*Z!i!*ptgfY01{q>(pkJufhQ5kCNe%t3D?vw6N~_T ztY-q%Itd>`VDnCd3i3?p8{}xYmktrFn?~u9RB4l6G zjJqywQamWqej!2%wa_=TbWewPeWU7Wv)$#*rO$2Cx3=z83?18k<0{C#GPV_9k#440 z*lM(K`P*=Z*T?--gN~i^Re_hoKmMMnd~VcS7dEK7utXow^#H`sup~I?iXPl&yuD54 z``rOE$};1S%00~r%Rr@jz2~ITqX*9xz-_#Aj}&l3>)|D?&&Zcz_Zkvz7$bQ2!~2y- zWK?cGic9!H`%-;ACi$&eD#FNh;CD#F1KJ4JT+zV6U+#_1@)+Ix_3epbXumWZK!J>;qxmHoDURi3x#jSsFV*8}odX(Di>q0RT)UcwFY?La-BEji)i zxk4ERRSr^AN&(B|Se;$xcL~=?MN~5D`X8vq*1MWZ*o)VX?N75p`(MpMVoaXqu|cC{ zQg_SD6Wy(=f*2gHM^;^BQZqjaoNV4Is1SraEhZ1%?3uaxdvOiVKVj3dXFrcB8gzeTz9T&~w}@?RA9&1iw<_-AvG;xf z<&EnNm-u$LqG84Ier~ z7i+y9f6-wHPI#Mik2?4HS8p4&2h+^^72Jgzcl|Tx!Zdz98`}RGy6|hh&S<}D^Uqd@ z(z7tyPQRDF=f6k#{|-2Fa(OVCXZxYqQHy!dvb>w9Ef^*g8%cdPyX?rm|qwl0WQANv!e8_{8m{l zDtaf&r$YPwIFdt*i`ZOdz=@?5GaeN00>yx1T^qbZ$QbB>2G~+S$x+Kp0n_y|BjZL5 z*j{M85?Yr?i@S>k@Y*pEh-TK2^}*nb3%!Y0)!mGQ3%oj;rDwa zAziAIyW$XxBkzC^A537oRSqqH6u^LN)Jy=> zi9ty^fv6O7KG|rLlPa$OPBBIdDS~FvHfHOQV<3g0Bha>ONPBlA?@QwTxE#L-($!ta zokvXWL!j@tsfes9-Eln_o)Oa7Vt0EDG<>hg&UOJRD9N9$=38XTEo+>jt<@=l<>ZJS z`wT`Cq4e9)g4_1PD5Se!$U%CnOk?a+tCYzKC(ef7$00aW!p{>rbV*&$GUwqO|ZNYjtp-o~?lmMg|G2x`wdL%2&aDXmCCS&L;drRDXP(B(VHRnpCABTCC>mzo7-LkPnW2ZaTE}n{ zYw&Y`2rT~PZhCl&q69@5QDHf0dFj*%McVI6Q}l;+LRw^%G6#^Ua>&ji)nQsNiAu$L zP`jc%CpAs25)C||0-5WH(s0mf*S;u5oOKXNTbf0Ci1c+s4WSgUqzrby2+l$*vuIek zEmFhffiyV{D~EGrPrm^L%3(Uny1D=*g@-LiQ#M1$Jm;P31@Zc0sc#kvJEC!1J(5g- zN)fyI>m~_Bx(n>)aWFS4Uh_+Rflx)!@C_9cvlbASmRyO>e`6WR(F2O@#VM6X^(&y` z>>Nl$XqAHMpLV1KLP1DC`P_15cRkwV*c{sbMvmh>ySWmh~kn9|C5%^x_n zN3;nj9!wjbc74T$m8@`xMv?pvbQULyY(Eo#3aH>ZZj|sM8Z91z9!0ntIhX9jkh3li ztmMi#!7{>GB9D1lHIF4PT3)RA5u0-rS8A237;peBG8QT7;0pZVTOz%!rXq&r-Z6oW z0`P4$4WiCij4gn8Oe2`U-6+-4BNGu<(XW~>>Wb_vyl`M3K=PKa;YhX(s&TLnqOnIN zdDOx2l_fKB6OC1Dg;+XreX+g5beiHf17u%Z6@aK7@rBl?6!I_tI&0N1@dmc8dbjmb zPu=o*7~Ih_n`fyef&S7R5&7HYs<)>=K{%xBrGjK2G9z8_j!HRdD5KgF=S9p%QIl;g zF79_AYsE6=VQ6S@_AdhsB9_EFTXUS0q9I}wXW5}*7=#qrE4X%86dczQ(51?B+Tn@i zgpUQ95zDwxO>EBbT(WBNxr%c^AZ=CF!G0Z^Z0p$FGLDEe&PIs{Vt$iL7H^{zH*bC6 znQK5j_bBvE~Zf75l3J&x?J2lz1VZq`#$wI5MsPX% zM;d2%oK7SG6(DuU91cK|K}Kbe5g_j;Xj(kSakO6aYsp zv0280|iI>*vE25sh)j_tT9!L zlfr_m6o6?PVBgMTqt?FA_kejca?w#MA?+QnBzU}1D}jM9Q2-=Rzt0Y`Y>(alqH$RG z&gO^ioW9XHgW72cnJwd5vF9?vh@M1<+Vwh!%rNb6?(#3GeW-)0}V~ky>3aN z`UC%y2e+n+^#7`*dBv+?Pobn*?JS6+6Y*EQy9#qU3e8M?R z`jdCqI7JVKln*G6y1X#u?%TZk;ijyr*wdik=fUVkjjj0EMvW`YCPMz_@`ISFI=&+5 zi=Vzoe0|J0cf~yPnZ;aD;2e)^^0py?hX~u=gmr2P;`!WNCjZd!fyva5dU_wD zGiNuR=dr@A%Jyf!J`R4XzR(&${HY;9e6%ndJ#Y7F;l#>p0hnL#P1Ky#ptv?Jz+Q+P zJg0nqGtVsb@ec3eca4u6rj(tKMV_dD3m+EwG=2H_mSm!RQCF6vX_tiZmIU;c#O9Y& zqL!rimL*ob*#4hV@V^-Z3xSiG{{@0W{{q2L;N;`KOz^*T?)X3L1^=%D!LI)r1ld+- zA7UIL5)3Q~hjNrz=Z6P(7mjI}rGx3;ly&1q3-mwQm8T#pEc}ebZ37Gy93!hZD?MwX zS~lO;I1vNSZz@#VIl2z!T~-snW%I<_t^IV)*lMODz~arDq1N%!Ib-o_Z$=lv$*vf| z^Dhn+8kY6d_>Hcgg5amWAo%ldDfkxzqyCnHe?gGz6a+W_f?(<2Qt&SbTAza8w^I;g zV3C?T1;LJFbZgE1_Ajd=m$j2?gH-R1Pu9hc)P6h#!JJNFt3>Ftm7Ue|MP|tX8o^y# z3n%{u!GD9`zd`WdAoy<({5J^x_k-YWcT3$7`R`*STmw%boZpDUYDPay z2cFxde?#ZbUiz~-@Zyb}w@?@_<)q)BJG03{hE5{wAu%jBMv_by`-|tN~ z9p$huhF=*KET`uFUV-?_zP1_Jq50GH36mTcz9+DoGwXO(y0d-6e=FW<_xI-u$ut2b z#(o@bQ<=JEs)3QUd!@du&#nRuVhpt<4s$6 z+-#G-HLU^}S`l#p1Ym1@0(^fuT#O+dM{l$Wl&*i#dmsG(-LMV7jLFo;&ob!F;(?+W zh4xOgPFtjM=~zhIzM0i0K(HQ^ARmKxKWNK)VaXIl5CIV#1x@Z6EER`#^a;!ovD@6i za^~^@2umdpP!JFhB89w`)AxWYyhytM*CF6~aC;mAH10uG?7*xZQtWh|Xh3+54XAd} z=wt(WUxwe@3CFU9smbBka3C51@zepdrc|GNMz(Q~^pqj823Mftq zy!cGbcu)I$iwyS<@MRi^#(*hQ)+h`pjJO=2e9CSiKClaS2O{1sUy>I=ZtUxz@FbD3 z(=Y=R{e<)r0ZW^-P=3U6RD|pfrcVH=-h@3=LMf+4@-{|tHD1yPxS&B5!Db$HJvFKT z=bNXb^p%7vI!*(`;kGmT4!J*~q{x_{6foL3Z-R+m^cU)07epfguc~;TJ^M0aiE&ub0Z2lG_xK*^xuq;1!;rAwxdE ztG-ZuUlI!dvZW~YX(Ja%0CL?yQ^1ZPoknqqB*K=&y(2$(aN*{U1l4To3ziATXaPcV zdLmrgD1a>AgvJZ{#X#CFU8hbo-nF#PrfG|@(MC(G?nkhS#>+)q_-74y#}XKwN_`iN zZsAdxveEi3hhsRyTXDA1EgS&KzZj3W^JvR zT`eR4Qd_Cx&)9nPf=TSDhHfUDkpO#2>hM08)GR@<5%(p=o{PTwY?1VPDZ80* zoMUp_hoBmrJi1Q-7ibNn#9>Jmmec@CEV6JNZRvq3J!A5-=@{JH(X^7wFLFoDjR7fg zs@+BELq2KSa>&vcymbqb)9R6pcN%+J-uRxSI70qcx$5q;v9&%@f{d$=A$qwx$~9)S z=qlUR+ZQe8^Y(z|F1UzZnK03WayupB`_w8I1Gm_ib1gEP=A^?x+Fu^x+$L2foG(vu3Ro3ZRWWGPkL;VVh!CJl)|B(Ew`gJ{axm?gHS#yO+VXIIEB zTRP}m$~Go9*^HwUMa|QBaUA9~rWX~aJ>YQ$^Y7B?7h4*yTiyLtGC7Wk>p*f%XGp{t zIj5Z>Cct(oZ>QnlsGOn21)?32s-q-HDI)9G6FJnV*d~xCouVj4Dm_zD!q%w4ZKvR8 zkGylXTs8)IZzfKwMFv-d8x}>jdLldQOF_a_nHiE?rB|xW1>0X>XHgO8hg`7y8xD4k z%jwG}#z28_4}5O`a?@P=oLqT!Q1xCmj%!E!S6aRf4yHG5xRX^f^}3|gpUkOuMn#5FKm{bEl=t0(?@yd{&v$+Ay6fEY!}%AO1?+k3$K&~G6@zG!09xx3vqaVF zWLd1nWlc0d_lk-+F+(t;3NQ*D%pkCcBj{aIZk1dN;f?~{6{JQ$Gw+L;gu-x}p(UH4 zlCY2EZe=r{z+tR+9hDlaRBby|B3vuKCyGNv%3TSrAjml7I?-C9_ ztx!!RRu@uWKaWiv-t9dgT`XG45Tth&zZ z0$#UZb5GgHrGPK5eqFgu*H>52q=oEts;mcwPg$YO6-qJ%-f^XSa2`hP)2Lr1R|MFq zrQ9(=&7f|&vN;nlRIF5%mNoqtcvUCOmK@2_Ttu#4cYZP=)wS|tZYu{8mrbqGScIK? zom021I&Oer+fo+iQMWU#HgmlA3)6g@B0IF?xooanqa`S81fo&evQcucyMU7fP&gZY z&tH+r2~-t;;zp-Y`8Z7UX<^_6d9pIv-k&ZzOr-@a8QGX%0tga75hFQ}AkFy(RM!(1 za|fX~;FeM_GamGMki?^vm|xs>!hx_?jh?E_lW;crpxK^((2nkqd+ZC9u$Tp-@UcGO zw$|y)U6Kpd)sep>1xh+O=X6bIN~Io$2z12I3TpWr(sq1R!U@LJP(AR^kckd}>*0>T zU%`|#LnWn&F$kg#=NtWp$;Yhrqr9+ZLxhs2#JkMWj~xdP@nYC_y^`cipx6)|)d3)s z0&18q)NgB?B<7tYCIXwX2qv@y9%Lq1Ax!}RK$R`ulqL;^nh2a`zrgzd6fy6)W+#_W z>SWo#$8Q6)brRI;Vd6%hp$gPat=jq8ZfeCTe+m8%^0zOzE~+8DrOCGp*onMl>%njj zyh9Stuk|1Kf=nRdzB;rHNKf~EN|fU9GrKezQ#%^JSTex8`F62+nCA}2qI!wk8YKw# z!vZPGpnu<4Xw*C0?hfVQ?X%EZZwiG;u=kf*R{k;ixPa%0y)Hu+gm}ihvkOGADHc2- zU-ugaAGDZd`+9Cv+!)TvZWxt4ZS!R}EQF3!57P-C)|X?aM}l}q0k|G!#G1GWO;Qs9 zog13lefqCXBj~V`$FrNnWvuoS07mz`3^(fp+sXBGspxXxcwA&Ond+AVPh6{=_keI- zO?6rCM5_Yw!)AMv>W6u=4^Dx-8%+~c%^&!4u`LH5o_)L2^Ja zp!DQFoR!^~MWXL0D$EHp+=2Yzs`$th%ycA~f^QwV+5hDTO8wV5g84^0u!A%|ND>4` zfWIdHn|L4$3E}C%{|WK%zd3?IVSmTN0{|nx?7usL%=!Nb5`3G9{qdVlzjk^kSN8?q zxqj2fFeH4eKbF#o8+~SxMS_H|BWNvdv8#X4BBX|`zhoe!{>J+{cY~&x)NkYG!EuITMlG@VY1_HmgOBT zG|AE^Z?5AUuWV_L>J<;nhEo&s>44V}~m88K|Q zm3(%|FDkzpSrRHn8XOc|QW7g|quCG-6(bD}vIH{)l6Qgl(yAxO$7QEq+rb$z%Biu7 z@`Xdov--miYClS7CCLFi+2@R?o6Rwv*0VI`52PJw1*DAt1SQt}MyRNYJAk0lBH(Dv zlV0EK=E?-H8>sjm7$*@BCLK`YDt1Lh`^q_AqSjugdIUneR_cWB!SRH zg*~yp-3{R?u%q@f{s3aF3hL(+;9BZ;YOOJK2Jl0!B`@{~~Ub4$Zbw;5V;0pP}NkAv-OI zfCngWZYKC}h6d2WHphiG^6CC)fjn(h_NBF!Kr-PS*i*FEq$VVO2aGi6(un~BEjYkd z8cW;s+Lyx@0@{C89oqKYKUo$>Q$g&epBlh(d6-X~PHU(4DAgA>?xbqJOHpptcN1Zc zXKyIhzGhh!tkE-cn0BU#YuqTn91CzXq~QS5?~YEjLtKaFu1Ov*hyz?dI=t&BI!Uh- zPyOw~5Oq&zYlUK0B)uR$lt|U_1**V_VqWlE_Rf(>030BP4???rJ?dh#krFQUhwaH& zMu;(*yXyqk(`%TeCi`%}{c$+wRR5V~d@R`qCh!xRn&jTQ#Oq{>kryrMkAeN9zRzZXgEuHgTq3Y^zY`4+pN&M*PRewHzZ%9 z#lEXp$6k{EQKp}5OREb!BoCJasF)^0?XOOWJ4f5xxPos1iFj6^o`Pj)0fG66TfMwQ z&PZjm$S)oE%1GP(-w1>89b~{zGl5pKPYP(q-o)ustmG=It-Q$M}EgPyP zcfY!hZ#6r#{2E|;@HA}($okseCrNlHDo3Oj^X`msA?(BPu%@2HJ=Ti#EOc}|oh!zO zDzq$2J-V1FD;X#FG9~JlD>+ru?hEO+WKq_<^YHW_Rz|HW#_Nrv#{!0p>&IYZKx@1} zsh6NuN_hNV;`4%xPOlVQs}r{oi@tC?yjon1tBAgG+u736X0=+rAD*^}^5Jn3HccCR z5G|Y4Ip8LL?8(>K&zKR1x3@ZKo;v1y!EE^q=I_=#TA_0`q~g}OiuM#?P|eX2Z)T4E z9FlipAY7NSYdEQ*H-Cf_56cvf)B$xxErKrR?0rXz#OiX)VqA=>eBV{x+-7fo6KV0< z_g)c0ZTT(wKAY06iB@5-{Cmw;d$RDMPC&jSEQaoiddAdS_xh(f^z_%G(%+90?j=+W z(BG&@`(UT@v#!mS-Xmb-qa#}0{~bNUy<4;&f4et4BT6#)Fh+i&tWro_f6C zn%gUKzNw#@e=!-J9%N!Z{pOnC9rEpGpD}|?vQ8D7nFk*^Dh`{5Lil5T6z(pG&$&y- zzunqoZ(BC{3+?+{dan3z)62lDK`A)-@KTI)0X^@*Ifclo0HzHu|OOuUQTsvhzF z?skdre%{cl;RM&J=W}1EI&;T+%69VF+I_z-=-tY{Y+JmgT4#3nyrn^V8-zQokR@_jrxT>~4zO{XMTIbx_-F2R&=p z_kUa@_IAQwwKh2lY8JOWBvWs82S?|ZR-rzGI1nw+V`K?Kbv z*Hr}D58&bSOaw)F3mM`n#_#y-px*hf>2U=0JY9!b1XCJ74VIKL%Vq<5$>wi_RJ3cY zqY}l46W(Bm83XnZgpCbRX>D`7HNFdUgH1s^C;^ydm>PbcFgQP_N-G;sdkv)}^i$ z3L`OsTVG^^O(B#3$ULM&jtwRx-iMdZw2FgSjASGPKx~i^2M&)M_B)#pWW@ZyaNS;s z+?YS_0vfL(A^;+#6&=|?q&+xR7lt$fN6o`FgTkalRH3^;Y{UM>te|cqQo;y?I*cKY zFepxm-xR0RC?;fqV!m^hZ9|5kCqTFwWwQj?r9u1@!TV&gC=19rP1sFWOo7Aq-XYm} zaR(*pY%qAtuWQlLV-h?^q0Wv|r!td7_9)*QvEX(%n|Mc~+XBmJ8a6%wM#83`bhw~^ z^`J52dd2TxG(vVG;^P;z(I_YcfU$iN#+s+tx&lN6Kmlnm-x-4S!Ock=U$^|zkyGER zB|Nvnog2Xoj3%FEI=Zrc)g+aJ86w)!$dVb1*QAss^oLcI_ z3(_LlT5D8jXhYRr6tk0%$gg!iB0@t_KtkzyfZ0a)`K8o!FO((MDUMN9BsqA(-Kb9{ zIe1ZCoJmn|%5*B2WC}{`JwP+*y*=&U=%Da;7fN=7x<-_Sb`bG0ik^F#<$D>)-OA-C zplK7qupWd4Kns+0QKLB9D+-#=X|$rqd&$VR#&ViH$?Ua(oWoe=>j7oq5H>F!O-$5u z#9cB;a-jgqFj~rYwE=;69^(uRk7Ut=!;H}+bul7(BS`M&^+>J_NqT9;LQR!{c?l&& zb@qfv+GI2Szzcmo6iU}0u3kT9TmWj1JSun08cGV`s0Jlvqm-9IUtK}PMp(lJX~h*K z#0n&CBqwT$Ie|)h(U{@wXd%6G zgz(IvZ;oJj_VpQ@AZG47;humQWBE^;3EXoza8dg;7>b?3bp_?v-+3b90$uHwxNZeu z6VIV#)oyTR*4&HVuryGyQsQlbgaoX-2wLa1lP-r8Ib^6ZjTG}I#M|!$wwTKQqCN+k zg2j;}QxH2MyX%<7>5y%A$n7KC_>5~#;%1G(;xgzqf^+S^U~2_^%8R$SQ^biY3bqR3 zNhl)dn(~{-N^U)2%Pr*^E_D_I4z%-(ob%c)`s~&epaoP^t+3okLy{>dpn|Q@8gI0K zLu%?P(cE+B#*I^<{m=S+vm}zBu3`0GK7zs7vINsdHqGUiGJI(wp@e6ZOmQX8Xk;fg zO4)|7)I>sYq}<1D`Ar|FufG(qFMD@~qRJoKY1(MJL)CEIeRoSwdRb)EmWQ8X-p#AS1@DCP(B*Lkli9p^&6cgYB5_BHM<;&P~A z%Z=i4P{zELC%S;NU(hse0=g>UXghIW`mMsn6cTTnR z-)}J%GQLyGZY+l#Y2vf0AE2pQ)2kS8DHC;4ABIcd;Zv!>HHzdlawWwTVByc+K$KDi z#=7n&Wd(X&QeZC4V@WmgdcaSv;G4MI3>pBlsDF?b!al5&OZ&7l5=G^LOt)^0kBl!a zg)Uj+Hoibz9+g5-)|_(T<}O)XcM2_OPTx>|KHica>3O=*l@Q>AiX^MPN7l;ap+|u| ze41n#mOoj!nW&Q}VUQc58-}0@WzISNzS-vDA=$-E zd;5|DrI3(pMt9A9`r5V=k=ApGZDBzgUGvpjEIJ}la@V&X6&hS1%P9VRA7xwfSkMUm zOk~VFYpmxb=I7x3GySq1Z=tQ9Gw z;cZ&@mmFZI=@b`8YDfTu0gzgtNJj*5GP_rQSwq1ma#|co{aR|Z>zvwtAoZf^m;22d zAHYlV&$x$`Oz&bSIMXAk>eDQt8IN|64}Ei|bNO1Kc&CCIu^O9Q#LVFmR=cNx>|2Gf zEU41bu`;3fQlt?!1*LXLrXXQO=_4m_ySB4Z%i{V_K^MF!7;Itos!b^R$P~mrqtNo3 z!2tqsAd?74ht2+ZO`J8^8tDXTxPTgp(#9;nLN)v<3sGT)qgY3b1ZkWb!;9F1$Bkr* zRB{0kP(w_G-OsxOj0edSyz&Y?-|&XRBjzxYQ{D^P%fTFDo*g8S{bmED51WF&PO3a8J0=iP zZ5l&q8wp-(sxw`xNDv=rwx%feI=Mk}5>WCr^h3QYhz$(?hbbtX^@Bev+S-&<&reN7FW+boO*t}=8ZsL}M z68gY5;P-vuIn|BVAL?(|HTntPx5@H9SK7{pq+e+18t6w{{CGLR|9RraqNa~L9*?#n z@tk~?_A4T6vSXIRae}`;`keE6$nt7xc-kOrI%?v>>hH|sShG@vk3XjGk35)Z?h4w! zArba*W~SHdlPx6?Oqn6)CwjH1&G-?oZOqWEiv0Rb{7OH=d~^D)_3XCaG-oXFXWJ~# zOK(k%Iix?y5tQq_13Q8;M~%d+7AI8!jYJM8}}9sW;E!T${letR}M<;Uo(#yEt7&LEF zb!JbB%*5@oCK=whnVOH6qcpl5-xa^urC9E~wK8ERvX)QRBA;4be@7F>f;%KE$V0+{ zbaO9*Q2%z3|_44CPj5Dz$%x?gGk zWcXH`g{<|jS@USWZ7O(EkV<%$>ET@w(x#w8H<90>)&6fR$a`qmaXFOVUnDn#B^ZMY z70RT_jg;^&9uD@jx$F@22Md1ohWp_Tk+5i`BP__i2R_=_#ZboS$ith0=a6tj47{O& zvEWtF+$58io%t#Dq3J@Yw(UO((wqww1=Fw8-!9B>e>sJGd?WKm;S=xA)DDmCX522y z#P{o6%j!0TFOv8$=ofPaAXkc0BGEKDd54>+9m(i50{mEjepQ=6_I&=F4js~@JL#a8s*%P6ZpAHLGTCg|J; zQoX$Tdb$4aqkPx5Q1m~spn+R|7n{J)5{`yA?#kSZ^kOt^4 zk@{h`fAzz0v)wOav+*x!qSt4s8J$R2@JaS%T7l>X?&RXdFcxGfKiFVntPO{;;KJj} zBrMp`10=c6b_+XWy4bk?4GU)Hz*unhM~Ki77L0|l;F)mW4mRPe;=mTlxNLVCMncSG z8toJIfwYowSYSxcnjSmCrAChpH6{ZPG?D}?I7Ip2JG?GPF0DZ$@x)$omc!}*n3wG1 z-U|`7iN{h))Vjm#g4y=>DxIZV3l2jC?KL{cplku3&~D@qE|dwt;up#|)(=8%UCOBq zIjc-x*JBjmlGF#={^nZAvFA-AZ* zA7Md3N)RB&Yf=LjVJz55_mmj$=Jlo7%xjRBC8MSkdB+6*xH_HBS}?nn#+Ht$0+~yn z?UfPxeT+y8H=GX7GzX4LnEt~QtSPj>30!p!c->+LP!|75htERC961}g_}}6RTE@c< zjY;Wnl{4{RXezBQYpRNh!a>|ZA(I>Pv#;m;&A#;92O7LW zuOQdc?is7^7ebmtp>aN}_M09ip-a;3#~;c#l&usiAy!mDrMGM3}nU%ARK4`5PS)xUH(bKgG#mL zB32}q2*7#_R+w?9io-)nQ^Xq}0`7RqIIIU_OF@WD3ltww4oI-2l2@-_j|B_lJb?p- z)@4F`e}Z=7(?azd3m+k~RNKAiGLJp30Stw_-G|XH_YRg0i`N1bTIQdYSuHw!+N@s6 zUvWgkSnv}|r^3ArwvoGE?~|}#+pmFfzjrA!fVE2p2Hq4r5n}HPZwiLHxHt3D&0_V^ ztXV4vndq`II#Uy^b6N} z-u*6VHK>4#gau6^hTx32XnJVbD9Cs87JHqre$0y01I3}Dn|F&XRB6m!zfY_U-Hy8z zQ({v|!h&6;YmQ&-X?-SM{r_P>$5^?PPCtfQYl$DfODpJ)@!h;F&N01b-w?j|bk(6Z z_0wjDS30rW>Hgq{8Qyma4|i`c<0tfpRHt^6m>71BrJ$llP6(8Ub6guVZjI3=>4Xlu+049MY~I_!>jo~ z^j6^s0+WtcbLhE`#|sY)Y*%a|_s2NSZaaH=eKj0x9_wu1u1HM%=6t?+V&v^T)(9_J zt6K*pJ%@LjP}ARTHyji%RqWKx`+f8KA~i$C`1AS1)AemWmAR_JpLQqwe-O=77S=xP ziY@qUu!kxUPp#Q?-)Zkk`0LlG`1AJODF4+Ah2P5*XMLqh{kPxitA0CE>1lqe{rkZc z{*@^IgQ>Mo=i3@A>KKdwa#>Hp!%g?{i?-d)jX(dVDJV2{WC|9nj5T$RX!35zny}rkD-!KIV{A#1 z1rK3c5HxZ!NFD}VVI~OI!%SxBT81kP21YOwBoAoafky_Ybm~xJWJ01zehjcFh?VQ; zR%gk_oZG-HI0{aCp)6Q{pNS+>u$fI{h8d`sKi|y^^o>1q2Lm&i1LRMi!fO4)6m-5s zU5sq<41rBSIoK2gWT`?R1P1wXI7rJO=)$mXqfTH81^Psng25)(dn5}cXdcOe?zX?B7!+*P)5a&`aE`TN9ks9 zh({8{7ZMswAqzP}SBiyQ!h_rl8Q@5ASBZ-rm!1AlO0`4a=aq>-4QU|g(Uv3ea!V;>dR zVIDb%Giii@pwST!v?l>UQaUWC_s?{=Kvumg$daT9648%!&$Dhq9HT+zc)3OtV$cKV z>+v`EqX`n^Uj{+MU_e082J30bkaUc=6fCz9!Gn~0En?v=6vM^pU*Q=o92|Z)*ApYh zb;e~#w$8*zL@TJGPo3|I4wsV|g$UMCG3Id8yxx&y3NriLx!I`RA%cWW!CQ*z!@Z~m zZ`Iu-4Gva-J`vPih;?5=0t7t^CLIYt_PcJF`IR)T1+Y6Iee;^oBUl#Pvp1!V9Gp}| z!u7DbQSW?G=$L$}p0&WT>4cLWry@dR>OqX4%32^rld*zK)5$O{m9qH<0)S$ICSI*J zqg>CrrCSNa|HBl-%hi}g-uJ*ip9|$kibHvri)~1lp|s4eYwRXK^yKlIMUh;fEc|$? zs3Ud@ff^^i?*^A+j#1O8^LQqi`#gT6fAEK!= zQ##y(Bw!|}g<;%G?Mch<3bK%(2IkTs*TnSrri=PC>Cs!bgE=<9 zGaF`tH%73Wk+}?>5aYhKu&FVL3DzX=ROfJlvMWjOCyeVf$+6e89+fq7Qc}I<0%7l* zgCA78^|C)Hy58K)yqTX@M_vTWg86qT^%hL^MK9i?DGYR!h~9_Te4x}MsL51*Z)E(O>QwhAQ%bpP?!v6G>Qba;}u)pIER) zemw&6@P%9*%ZA8+O3Peco&tC35_;DvCUHYfQRIi_)DYvyv^{9v%78^XOq(paj4YZY z3lgj@X{v|iLpjazw<9#mgQ{UHcq1`Oh&9_<(_+5_s^(5crJ<+|VgTalLq<(1ZILQh zJ*tm2)hC9l*f-KoRO6ujN?JCd@xU=@oAbQqH#olA}Gdm;u$@sc~hg zIJustXJrh!LcaHHeIlXlJZKPy*|Ss*+k*~7k!IFnwfhD2Rt5w6(gr2>TOCMnP(!d- zILe@}ImPI8W`KA_;xh<_gSQ^nPF~Sdh^h@!D)n;pvBU%@XoWT}G$>ftZE{pdtxG~4 z8XZfjVTu9#kt)|bD6aTwC~9jS+zI*anfu*@Pyio6i>u?n>2qvIypJkWGQkb@L){LQ zLZ#M?qTv@y%v`MtrPd`DPnYksG_NSu@@`azE5$1&U<9lW6&8GJQjWAi$+&>-VRepR zAOYrs2VjI|vABIw3#lYdDI1C0OK%-svY`)pT!P7Yu;2Dkv|ZwL{S0#(w=phPRHbPG z+u5JuF*93(C49Yp^3s?JHVprLorR$Qs1UfkV>J8&EakZ)?!~$Qlf= zNs4eT{ut429!1Dlk=EO8mUx{umz(j`pj>Y6)TNPUJY7m=S1{pAX&*nBCu~U$mONL< z@S|o^p?0^8Jv1$774J|2LAON=kT+ch%0sjY+ zLtu}@!F4MkSR52k~T<&!nVOi^!C{v{4tY9Ls(cwup{(T{5ZBY0yN$z-(g4{?wz%9JsCB!pM(zl%Rh;Nj~Pka%){($v~TB&Tv#9 z2wO3vp+O*Pol4F5AAAtAcrgm*gX^Ohr$-`6sxTjn;X~wnJzeyI#0N3W-K=#}vGiF7 z##1mKELp+~&$rKxO;qemJft~UK=v$ouArTxG`-d9#M6tAp9ub`FkT`nXu9u(B$A%B zb*%TpjinESGNI33l;4#PjC{Yi+WmY&^7Xcv#_JLx+NR;|bCWOVF{uyGuckGKJf9-w zKDD1j95*uCh?%Z+p6SJ1{RmWu%PA2*hRqziiU0hRIOBJZ?yc`3{V=0HaaeVhTy18h z`XjrVFjf0(m@$!`|1ux{98c)1WYMhPs-VLePYE^8j)^&GHTcEbyzHunl-)e$t)ool zyvj{Sg-`QXe(2?~f9Zq&^+jEa*Ry!*`J@-0gIE+E+LqA&`Li1yjx14415L9_dpF_;FW4%FI zurrWeTql_G$6T*3w?U>2qWX$LlIW#RZ-nnSzRe!+uHbFnN_$gi5(evoavXydj_0pO zL*3V=8lPg0O?BR0ozd6ro)qP6ye;VZ=r6+xUWLuiRau(1B>j9>R>ln+2N`^ocLqK^ zw`Pz!JhitGIhZF^=HE8+bM;5pBPlPn-i+8L7}al&GvCdGIa z>GnwYxuE;@Kf3$`U> z&9U&AaQu~wsbd+gFGY)@ZZ!KGdvfRVvuojM@2?-rynjsT+Eaf9$Aawe6+P!12Owi9 z&l=q?!WoNm5lu=kT+uE_y=UcAnBmd+tSEnl%B9#U+G?dlE;CY$t;8-3q+-OZW66>E z9V->OKlfZT!V($-!62q=u(F_ezw~rxU?Yey7m{EDYy@iGiU^C*Yky9(Wl!{G>|u(avC3s3abHy6bou0ok@~*n@s!u0ka3 z4CYjZ9_W2+)oZLbfuC5xD8=_P^7j4q}DhA{OmR->4TyK z_pZ7SM{igkY>+Np;LL#aK_S9W7pxCH?3!vX9Qbya%#%RU2ZQll3*5|6SX%CX>VuqJ zelLbOpfE(lvQqI{P=R zsLhY+P)Vl%s2w<)wYw4Yc!riC6>`tHrKyVRAaWBRYWUbAm&0RF*Av6;R_qTDGQu1h z)K2!4Q2Y*@VdIrnWP){kK7A~~jS`@BSt1AAG7sq}+i2Uq`f>$AK*zCDe_dI+FVZ?h zlYa);!so8JcKXAyv5C&9DQ5~nV1ljw9@IjCM_9Z;vgc@PvmCpi`OA_2C%JCNZ(9Vy z>P;?!Ubg4M0j)i~LJYpf*8<#*(++&@kcwS$?|W@D+@otiACeu)L@V6Ks`rY!%Q%Iv z|NZe>J-xz#37Uhvi?j=vR}8i_4@VzxoIJHqM+fVJ;x1Q1#rD9Bc#$W}uE|mX&+30( z>7!uQy&7u8R0{~2q*Ay;eW&wr!y&M z_T6_Jlk|3E)}4LD;cXragiyv2AwbZ+t~Z8NQ$h<%-SIMznNz~=*H(&px-hQ%#uE8i z)f_4xbJM2GxF>BbL0}}!>DkK~!KTwoAxnE8d)d1RbK*1=kpsxHMFh4vIano2i*Y2u z?}|CCVIP6O@Is=-oM_SXsUPoEWl9lvx077f2YA#;xX+F2Bm*h&WGZ;_#2`+z)Rq-P zjGG&U^KzqL_88@90dkt}3r^|l17Y!=DU$t?a)0^cePMpp{C&8{DfPqo>-~C!jk(Wi zO<+WkRWFGq*uo#P-siZuoL>u1I_J!sR~3AS(FE9=)E%m1d? zH70+X{*aOG8To{3C!JwZ&=|!m6|GCxbO|A3CwTVCb?UV1*KXE4p8qAR^xBf+ z)?vcaHQp$d*Up0v7*1#N^?b(O=^FIM*5AZdsN|h0zE)= zXz1FkA7Xf>Q2qO{^HEBp`JtP|a+g<30}yWlb?QpB$5t+s`Hp9m-7SlV{%X4H%l3R# z?znwSmNo7DzE(pWg2_2ICkdY6fqO4&)_89?pS}NPto~(P@{=1k-CABu3)hs@@UGr@ z@HlJnW^a>8^Ud3j?l&#JJ=1bV<-O!;GwlPcYeF-RKm7$4#k8Zh63IUrlAY=6 ze3nEiij^2sb$cGl{D?9AD96FE+trl#BiZwT49{SHFO=xk9j(HqW(ZFV+PQzOh9?FC zPE|X?6N6tk1xOQv1*bMimy5|=SmDdXo_BGIs(te!nQYiw6a= z5q*+o{Y*x9GHERNcpJ{cEW(U@Q0-^s>yw>g%_W0hiz$rZizJ>|MeMb!46wz%rB|yj zqA_sItywLWKO%&5kwi#(x#H{)>;&Ge928Pf8-mBv=Q6XxJV6OG^R~XT#5V6518r@ItY&XpvS12|DBg!8-+b@mvFo z@L(2u(#oJlq7fGoFX$nmW+A8`B2(Lxa+aSB{1TC+kQw^R^EF|;=o0Y(}^m#UQPGfcIyOJnaA0)Hn zHHP&;3UTRZfDlDy=7)waq+|m@7GN!#qH(T9R(;+#Vz1RjA~r}o2QSEwT9ap1~Q*ny)mORYMJ^Fbk% zq+BwoC{8&lihHY%ieiFJqSHT$Vtf598I^Q4(!}6eSH!mIDSPCF-h z9@ zCm9?Z6;p+%ocFP~8I)efmT*4gTxwE092LL)qT5X-Wsxm@Pc!jBU>fWW4pM@!J4mss zS+<-}_u|MMgjWWKNGpSun%0GVC#k3;ZiQ>m=pnu9kV6h~n!(8&NmAT%*yDNurNxlO z9n#96)*YNZOA_NIx)h_OYNib^#q$|wJjEnu>BdF~9vX_Tqu(dWZB3zS$6sRttO}`0`f0NXDbd2s!Nd~fI8ie$~ChFJwv#C>27uT@l(3e`I#JD^6;4y?dFUM5y3es zU8;U)ZBCvcDMxf4%L(S#d*XyC&{sEAC0;?i8IVSeA$On#T2O_ZTfWZhoT*viXiy;s zv+U#+4!}O4*ne94Gjx4VN7=>Tb_OJDWaX8ub-pgi@ov#&B~0&dv4BH7XP_Q;uEEv3 ztU{CmhwKJj12e#DHJgd4|Qsw~O$lwFOcFDk@4b#4QWBEAC>E z)%T2vr2s~s8NC!KyhDB}WdFRDCuFdsDASl8lOz~SAnAkM+-1}K_Y?y&bhj?-H)Bdl zN;DEBpGQIrNdV*H63Y=)Hb_Gq&g-Z1%&LuygT zR+#3MMuUK;nu`VjbNe6>iR5IBo(W3Z+R1qpBy4V9$eC{<*Q0K+WGJ$tcFZ-yY8SMM zf(nA6q3X8l%`(E|<$O4a9hd5sukM3G4(QRy=VdLKS|1?k$HlDAP?0Q$ z)%Q#)F!%K+1fC{Lf%|794udq{c~f$;YN>2YNHcim6)7-wpHiwQ&gxf=8C;ZZYKmli zUqt-ybpAv24O;YY3nUDCgn9QF1k3o|Kc63I<1NtWVtKZ`seSNR?$hF5A_`fR#RqSfe;EzIDj_^N=>Fm}t<*?jt0yjsrn7HA^B*c9Qx>}*7B?EtupaWU zNaK;o@JUG!l&k!EbP!9>+Xj?x^v!ik2@jaLzBj!+8ozAyw)@&Jll_Rm9gyEo=1B{3 zy6o5?RYw_`$$#VtG#Q@jaEH?O2{i83uqHC_{>UQ~7E%d>J;J)@jNM}vLj|JJDK@kh z*Ib$&e{Cr|X}>9U@-SV(EC%@s_6T*6BJj80qrezG6Fr+4D)1*Tjx)LSf)p4VJ=NSv z%N>!IGgvduSs%zqQ{=a?klEt?jl;T}P zFYVv2E_wBUa@a*^IGlOXg}HB2Z!*^HBWe!YYikex=cwrqXQyv%tNo6e zu5r7>-cx4X6(@1-W5|t<4})GU<$mO6ZJ#R_S^Iq-K1gy=Zf43hYA5EJ#0x%Ri$fmy zC%-*EBBl2y8ir5K6U6eJ8Hj$CN^P3ej=0r^e&aXmltAQ-6*+b|%lvs3`Svo`st1qV z-1*b@v?u1YI3B?IpzOpQl0HZ|FP}NDsxz4jh|2Ty!|Ig2nz@72`tXm`|1a2;Cq!I=^7fuwfT9_K`Dyg z7Eya$GG8yt?wruwYvY81Ml@f`&&1LCI|{H+sK7kY9>lo(0MYF_+o>A#jmXt>>;0*F zI4}MOQg?^OD{sNmgQs^^A3YB`58omoZhSt-J)h;JdeFQ&(;Fl8T=MsR%eS`3+mX*T z9NtaNW%<7#no}Nu!oXn8MoQ9=Vo080{0;@(QD+Q;!lhYq{+m<|;ermB&Tt_YZ-+=^ z^%8u7%?#7aCelvoj7dj|6%CmlMc*Fkn?C}D@zT5AjBy@R5%7^>oxS{ov+~r~7-JX| zrU=5mf||L9=;t&C-@O7J!-Qv_GjuY13Pmqhi+*{6Y2GX3x<35uOD5lYpD)t4H$;oG z{SQTTGJ}N0uH}RVJ}l0Si+$ysXQ#rwTwrOaFUpbPup*j}akE6bC@V$DsW{hIqvToH z_?}}4ybh5|1E~-@$c{&6<4RkF_r%Jc^shj)G<3KQnzoEcF#^ryR}d|^O-=_nDq29J z3iy`st?2dXuRSHw7 zhxNP_e-4sp&`Q}nMAOlet-FVc0!$iVVpu$YAQutnqUF(nr@Cp}%K&O9cfI2!xgh)} z6sC{3SJY=Zz^Lu_Un2=T&F(MAqza7y{)3y&fq)B>(J4UKiSq|FZ-V=5=yBrhjse3* zA3FG$+;_Xiz41?SsMkx515HAo%W94j`Q0h{MJs?cgphPu7uhY>VsM!9$$B8I5R$2~qa)~oS;Dx5-yiDUkB z@ZUnALv8c1AZGBk<^c=}opd!xpwP0%f#wud$6wcrqopyn^@sXNFep48rAvD$d~{sP zJw$}!iYEUgZzn7iW@{d2$=f6^#?X}$SuG3}Ho2+ESTJQ;H(P@FQzx}VcTZ{2%kqZy zBzG`DgHe1N={y{JI!mxn=q?^F$aTG0oav1wRe0)dGb|Ju_5?{-LGQVDwV8z&e7LPL zke3^w<5($&w>Uu=YrR+IFNZa)m2*qemR{dO$Y{T1y~10>g>*d~_hkLOQ)ovaG{J}0 zuE{S9?K97HH+-Y>U?ICj5Pz1w$=(@(y^5wC>WaHA5>oKmh_+u?hm+Odv2-6KBt9kT z^ioFC{o7ol?gHp7iudALxt8TSb*|p8<}$(^OMUT>7|2m(Pac$rJw0m%Fbh1odz=bb zOeq9BbAZbWzxV-uqfYj40pMMR2;DlnRA3d}$)?9n^HkD1js<3bxr2K_EhC2w*+K5$ z`jDC-r9Hv_Yd*BV9cC0~$`Tsqg}Ylyy@)Y$E6_mT=+oB;OkKrxNhM^#8nojgaAzD# zzD^4a!=166$4HrSRAH!{JxC>(?S{a1bf^f{ytd1MPv(e|5tE16er;2*^erINes-;#e@zszCPeMYf@sIZP&@C$BZqTm+BXuNW^AX z3$7rUvjopo1PB@wJ%8)^_5LhUJ(-0&6mtvJ)&yKG)Enc`u*KokQW;oV-aQv3$fVIH( z;cy#u!Y!`v%FyqM!RJv=R@Etf2~bRUb=~oB|04T@SoU+LD}G~r(zI2OL*d*@%j(;& z&pr|7^Li6U$>L$QwF@69-s?y&gO3#3;Bfv;Z?3fqsJ#328I!8>=FVHVGoCY2V{9Hu zm7QbdnbzWcx$XPtttT5>?$Wux2odM{r;87*r_Hr4?T=NeZKKTnzMkD-9_{2OR*dX^ zbvj=)S(o`U@3C#0^R1T934X68p5Nc!6}L>&pWSI|;9L8!eSh=-?M)!_{}%FPd}J!q zyZxlCS@bQHHug%dSDQQQ@eL0usVaRM)HD5(*HkJoQohWNYFh>7?29IqKL-c7x69Ps z$1k6_fAMMN_Q4IiQr%1Ud-Ep7(i@0>gu;%-LgPO|VKlzk9CK5Q>@{(0g8$x*goW0P zHQy`b>iHy4=uvr+qY(y$ahJCY^7}>f=$*Ca+G73&g~Cjtm4+}V6kw|y5K__Vf$6(h zxXufy|2zP*z1n`2BLFycM6Lt!-LG-$5x~$pP1_R>_Ra(}7@l=#S5T(`_ zY8*v!3YlQ1&|R(*b_z}L=QnVRWMb1_v=pmJtdOS~q>i%=LZT6Xa-x|8!rkVC$Vud+ zuuwRPjZ8}jd&CN{!9TbCL=z0G;Lg}x2A*Bl)HLEo;)Mbwu+D-QjF9p!Ib({Z{(>BP z9iB566vTo_sEa5pC}MB>Ko@Se{O;+h`=t2|C+e>sfkG5M7(EA`lm^AMk?=xc35&5% zQjiuhK*JHoi9t`s5Aq1-NpMp{ zQy?#3xiL1*;(xJs-$6|_?7HZmJR#B%Dbh<4dhZHM~X;C zs(=*f7>a_Th!p7%stAe*A_$863BG>o{nq-{I(yCRHFNfv!!X0}Co>R|JJ1c2 z0!uWYp79S4LbpO*kg-~a)Rdzmpb6<#n8pl40kDnE zNGU0~&k@p4oYS&ez6lL`3&jeD1B?qojzUAxM1`ILx>A=A5p@ceG%=OD%a~C zAg!CIK<>AXj^TrDg(k6I(f%irqQ^W=v3Y93Hl#!nv^E+~OM$?B=vFukDzTZuQ_|VK zg3pqYzlQTC?1lued8-7a=CQ`kps^@=5FV;#s%Pa^kWnk2WO&QyUR@$%b<%5ccs!H% zT!W~$V=_v{mJOv=xo`)`tDJ&MJF%Eqt!&%6paLeSB8h+o1sqi^Uvn{v&D~GQU6a}x z<++4<8zhgdOFdpF$pQ6@^#Uszk+|eUsexo2N2~)bg&r;f&Hj&M_6GiecMHfJrvTyn?b` zhA~|7ch8u0USWbkTzew3%3FlO1x?kA+yE76>++T_HaNxO5E^`xtN+2huuArW&nB5&LxJ9ntZEj3? z#)~S7T11-Al#C2YJfGp;6r%9sZ-GJ_T)xaHorBafR`FXbDdl1icS|-fTvZU~%L9jt zSU1(#n&fXcBR!&!INUv*m)IMWfyTjd;$#n4^UFCq%P&&_P@qtbDl}3>q@!5hmI~h4 zRe%^q&K&}Tow9QJA+gb+kA%I$gQB!Nn50MRO4Wx$a&W=#boKPH6h>S6-&iXEphDFl zRgB@GJQ;AMOQ|%o3|AoDUWTNF4u#QWwnOUIWpmiwE2M}D&-A4&dG8BOJT_P@W}QDg z6q1!nIF(!}BkFSp-mB}Jc?&Y~1 zR*lc0t@c(=Ao?CHq-Q>f(l{uOP!GX}FskO04uu>jZjMZ34Hm6`4;xi;Y^z?1K9R5H zQ8A@Zou$0rOQd2nvZWXKB)RrFW2F#phQ5d?7>)G4dKL;AW|tw~x-0!~R*hmq9q6HI zY*NqfMLuIHU1O0pEc0s*;R6QmCAliUs)>2d0D|VukcM+?GhFIZIHyE%hUDpWbHMi zXLLzhIeMJ6#v6Um%ITnoFnN&j0o=0``{|)cfl>ZtUL%zdyYmv%KfDr-tf*A==8&ZT zueYUIUPK+AC{!BGpVK-)uyLN8E2O4e++Q+XeJ+X)B}K*3x9Bvig-1nTRdP&+A8s5vDgnEMR= zOjXh?fQA^3p_Y_lZ|k-M#S%bUG;kE&DNdi#TmwS*1SLJGa4Zb;>am&1Q)XMG)r+<^ z{RAZ^h6~0mO=gqZheXgIxBI6IB#&L7E z3Ij-7!DtOPkpHL@FbCB|t5)7C_b8FBgyTCP6t05;g;hhbumKa^I}bxrkDT2DhZ;L> zFk#aT%59<%kVKelgBcW*Amar^>F@Fp05bi+rW$`;PDvr4PzXpNGlTvwN{A;wkH(}x zAyP`6t=pWg1Qeo&=?=X_uLkk~g`Hg;>aO^CLsFoSidmdeDniU2v{GyTBBTC%AEnTY zmV}bBzo$u{!Z9CC^J^khIG#+?OpqPqR|kK3#sta3plK46RJG1FpbT9Jha~wPSlBbg z32r2Q(C=qWe)Bjdc=|*cGK4_E%>(;>OEqw zQHLi&kMyVX$)ppZi2c2@(MbM{%H+v58ET&xH6aCcL7>ccA`9J99~W$e68>`~+!BtT zs|}MFctBzZ?ai(hk*}=jqJpv8{1QT9ff(gs22r z^^fI2ezd-@Z=>$+DiR#R6qA0B%U+NR^(`+=LMOs);juWwDZW7rAzGN{!PHi>!22E5 z{zshykLo_xKCOYe!xow^U-HwI4vr{}O}|D42fvtm;Nssl6D>0`Ee<;dy!?EvVN=~_ zwQY9Gbo!v}>~sVR(G?_;9n8Q3h)xbfDv7DD)5PJQVV9X_>9d88o|`)+Fvq1e$4bZF zH9Z&AN#vz-h*tCzknmK1Mv5goR2$|c*4+>3!NZZ_07vP71(g%Xj{mtFVIk=}NSZ3{ z{v#0%{QrGp?HT(B6dbR<1~KN*hhX;lEWab0Et_Ckv?u!LPXZS zmpMEbHhHqX%{MAv4r1S49W}P;%RUQxat&SQJUe5==XG_45V~8*rRKdp|12I&zV7#Z z{oQeF%kAqN+lU0thh~9BoX`8$C$CA;o%dGzPFQ}kV^noQa{t?{*{*oez<|lUZ(iem zhz0Y&;BGC)zQBFvJkVPo_{Ip{{DMy&7+rF`&uK7~hDak}fm_Nk; z0to>HW9U3+ch9OQb>Dt`DcvdVJAe9hHS6U}S8gAH%!d)<%UPbwy8>C4O03^!-|_Vp z%~3`fIA#MbEj&&JLO?*1P_)^f)wCERvWXr>|XF{KQ2t zq0C04BvKfEXc6*asVcvf@l`y&t+Ey_O0oz=c70vSIz&<~hKn9rgb}t6au20 z9aQ2IepRAf?qiTeNFbGtH~J1s$M|PJN^V}afTt1|#z`t2D`^;!EW&|2YP*GFHDUbS zkVUwZS+doy6XHi;7A`Nrwvs0dK&4|s+XX7UKc(ZhMptPu!<@#nm=Q}19!o8jfcXk@ zJbC9C3}%=BQVTjoH-?R$*zl&VH?7R0wB$1Zsl~Gh1ZJTUTCs!4{!Cr)_g-NwXY<}Pi>$s}4!)$z+qJG%?a&H|4rw%p#?Y;9~e7d#Xl;=@chM442Ysn7Gtx@*& z^L+~XI+aIpsknpiO|sBU`_+l7IeG1X$s6yv{-N{p`GOKaVHHjTi=Sg3ILr}p_}&K% z3zd$0_67jG>=BoG+I1RFUHTOT@hErVoQ#|VB1*{T{MUguGrhV> zIyWMKi2IQOW?M_LS1evP+`05JT7-7LGWk&s<=^Po%aYJa0Oe=Y@_q4r8&iDC%YgdE+&C6nHhRg_G63ou;{}caGOWJwq`vXoVc$5{ouTVunB7`l zQpO`dR6dQYdJpOw6LKHKd}P3UuS@9P)NT|Pyy&rLhqh2m{4Q4N{!4aT1$OV;)RaU! zLHVGV)HhCGzHzd5QeZ24M|;nS$DZP^aR-lwY4jlL%UwfETx zi^{u4V}!xat{pUSDZ!ti9HFR7=O-vfNS#XTb@A@H)49=bf@WSNveDW~=y9{t*YhZo zf65V3=imI3BP{HVAms=nDSUd+!ZKQMuWH#yIl^<5hdDw&x4-8IKdsfIl|wl~KA%_b zggkP)V=i4N`A&1=x`)&}r=UWg^>NPtT=wTzQR>tmUfnqtn)3lz!NfZZu+-G%@!wrJ z0p$oIyyYaRXq~lnRp`?y~V`f?57 zHRBlHcNX|tVlJ^)fi0DH4eQ(9!H=TP7u$?_2t27y^rvwo&m4d4rjVKUlg8OBW5Vgo zldQ*Wv{%d1Cg%p8Bz0V)yYVY&%I5ga?YH7bJuZ(;zsEO}jZGi*;fb07A1kJB7}5K` ziI}DQ(%=tVce(}FCz4C=wlillhM;@q5I44;vc)k)RFS5N8!yZCGsG!|&D(uZa){t$ zO)T&H%@EEklKRGs?1v2Dk)?lP2qQ>+<9`CIJ1e#*7^ zskZgK-^lm3X-Zr9ia%>as`l!Gv)`58P!Fo-_8V`Y+J5xDYRk^TcT(d-Th+TCh{wNk zggxpbe{zH)ZJ@h_@Ys>snQxD~iaYpx_eVu>yQl{!Zr?FIuz6?jDd2)ioz{7e(=<@+6WS~`QFc6x5{`}>MhU&bw+q526xGX^ zB*}XNPV<3!yN8uyf+>GeII3C&brGv##kVCWCpe76ZDIBWRjIF_&W|AlpfI|Ul@>0D zEh+5Ue3)uF9&rE*@PVI_3?fAdL+iu35jLKz(nkCm><$`;Tb7%Hsy+)=+@^-9P?XRl z=18F?jgXauy}Y*tsd7A&gmkg+Un%lZ!-jI#sJ)pdMF|tE)XxMt?#%hw)=G>s#R#9 z8A=lZA(HfN_&DxzHU}`Ce61SGsvh&g0??lqcC2o&Kabo4zzk?@ycd)Cn^WD&<5h+H*)Z6ThrDpUm&L5U^E zi-agK$foyl za{xtp*UIEmmN911?<}lWXlAy zE$SiE@c3a-aJrP2B~<{aYfGQq!u{8t=6lFAMTkD$&zA$q;OmwTd&Q zP?7hJO|9b#A<9*I#&=Qy9WT+A<0uCg9FU+8TToV}FE_ba&M}Xn1Rj^Zl%LsBfKr^j zd*BVn3T6*PZDc-oUtwS-@@Vv91_R^7J#6@1*i5r$eNP4t6eVPW9x3Fyc2&9#qlD%1 z3g3ctxq|d~_wRA%;}RnZdD#_zI%5%g^1=00pB<~G_2bHX$`8JGMUCSq^mHHd=~K)M z)u1*X=L@66v`7-6u&A{CKFDB=nu^N2YwCBVtC%aOmaQ|I%UxAvUjYgcCN~wL<*V6} z8b<4jIW|i#7#>wTb<#~pL z0aEoF&XsP?6(S)TLwij;3^HkjwaQGj^%Uu9&FMHW;5C}ya0AWsZY?{WP?^Aa$&QT+W}jor`G%) zLr$IFtbJng{%K=XwL}*U`@*Moj<bw8Bu~Ng91eYsd6lb)0U{HmEiriDB&j& zb(lRVN+=3N3HiDu96?({lePtLr3VOPt^2}IFlc*+4;m^V$b*11R5`{r{Z%=3_azOL z+^tAKT}+QiB*F~Lk8B4LnS<$D(2ca$yUXf-sT(T7^rfb z>MFsf(#dlG>RIZS8$vlk`naR!S^?374PPuDv34snASXB`1nL{-`b+TYyFfWYD%BZQ zfR4HIij9>su}A_F%Sm$*mC{t-TyF)97h_6~$oVfE<_H;}9HB|>cCqMGTKA?qsObx8 zT1%Z_1Xd1ngjI(*!r=lth$WQa>q2*lIGE1cX32!h~mw zqLRZNty1mUy_Dg{M##eoEGz)&l4LigD{rZ~S=MGW22mdLEs)2 z>=CQ-@KC#G?`WQ&Jzia~WUD4Ask&XT{C*6+_RhJdZ302AIl(`BpPfa~F|}rZgD;J$ zT!R7#TT`N((+1QUKUDo*(4IS9S8;YeLG+q`$fs#8tWt*9Oxg12$JavUpQfP%VIIw_ zm+EXv!^{sO$#*}`%}zb=24@6d=ZG6dM2d3)Qee6Y6jA zL5csf@j+<0_#gMd!|dSB`u})p5cu-}^^E_&HB*Aek^jRZq~lWfr=GFX|ISRwzwikE zW6$_M#0USyeQ^GHLaADu;rADdFVj=)`d>BmF8AlkU-71F{(7AHxbFRPTuazcDt4>B zfX(Kh(DBB!;mU-ThJ+bx@HlvH#6&w(GKJV7r80mEGSx!dt&RLS2fxet&s{_Ue{(|IZ$w zhuy#P2wDH(5ss5QLZSb}BV0Etf;>V>fwZ&D9fgobs0Vq3nVUtBN9c^ce=YMS$s=q+ zKDb4<^)MR`zPy~{Fa>#pZgl!WtYN6tE9p@ZtJ;u9=zFm+$(`g8vO^xB4ap{;;Vh5Z~4SHi;kmM0QYAzG5;Cz@%;3dn2Ji>>2WeKV54>1I0Dnsbp z!0-=`(713S2yPjXn@7dXdSATwVA8!$t4xdxnkjjoeZR63DouNmQb1zUZUn2F4hky5s?}mvv#fJB=#1Tn7W7YZBN*r^a zpqY|8C}^gHH>gukZ9pMRkkucc6szF<(=)yd^^8r=!|qawmhfT+$nn2D!VXH26#Hwx zJwj2EN62TFNT3j@Fo8V6bhq18&XTJ62T+t^gFr5zn>|-eQIUXz;2vJ(HN`Qd z+J&K0C$C)?8X+MYZ+I_hjAx8EZA66l_;hXfBI=?oIH|D_+_*jEm zC$q%oJ8hvmAie*5kYwP~x&Hm*z^h^;H`3mXb|8TaFac;D8^O>jSyXaz8i3U!T(!Y@ z^t&CIfTqt>bO~AH06jp*Pc*876Ub!EgBEEe0>qU#!=^0MY3k_#d%v**so^#T8zF?{ z7&82$4u-a=&y`gx=g7sA1xyiuT~tfLG)TaU*gTGUGhsumv(iPgbjs&la30MUF9ez0 z+bF@h++Ta)dD2gEJxAH!QXWvcLD8yDemvMohPG`aW6W#sa~>hbS#NGL0;Jou< zAwgzVpAuf%I#KHos*gSX#Ncf>&rn3@IVzsub{rgqX*j7#T#vZyYUsrAfLse`yrz|4 z&iA2`SBefvJWHH3J))?5jIK;5^pdSTi?*lI!UZAc2+s>)Cy1@#(tQap?TYwpzw6Uo zd=yb(ijo{%>SL5rey%hQf4ESsma(dNO0M$I}vqwO1R_<^_@rGQn3CU~puuAK*Y2k05|;M?zO8d5+EL(j(Of5nZ%hRc;G?qa>iyf`#8IHL6+um;uE>DR>j` zj}ZV2wm|<%#4j{9RrC>!+o;~@0n6it#3b?+E9!Oy8=yphYw=iwqS5e!&sJ~zLiSg^%(sp12mXq# zT;uj4kX4%FZ-x=cR9!m0x>N@rMO?V0=iM13Q|%}jGpA;eZp*n|opqu@Oe|v8PI6xI z7^-{zc#G0ek#k?7FB>|NJ!_Y69;b%#^4veLApYn(I4~b?25KhIUP)PUUz_<*h)EPcAlV z?5*wXr>X;EXD)mW8cl1Lmr3|^`J!s@_{G}_a=Ba=o$rs2xja!&Eb%{gEgC+F{q{|{ z@wLIthTy4h+FnY-XB}<_a!mPoDyl4=74+ZHb%!1yv|Jov@|~~b zyQ^+X@#){o#r9;pBh0^-i*Gd%&|1w1;8d!2`;JKMD8#E-&`BMD!Vnj~p;c!tEPB{8 zh9)MV@#51(0ZnB5)5(|(OMk^A(s;2dR^7xMJN91cF4QyLQr%2K(X zwq^vjlaWFRKm)T75h4j0ts#=|+0tD%hM=q1Ac!P9!3QFFVa{3rPWSwb7pfs8R1YEv zYoR?}Iq)}0xEZYF9(+1K_|$;CVu+RNU4N6TY^NB0WK7z zp7C+_Fqh6SWp6xU&j0qokg=Gl3S|Nqlp5ACV(q>nrN4cGMMeYEw)~v0db`$&17(=x zfe@C8fqQCF?OKXS$={NXKm)b|4#>;${!5`=%BWC|AhlPWAm0WoPDtI%O!_!zDnt+R z@PY*qw!BjDqKne5UCP`;5^M02@!nw~yzx?t(%+$;@ovNdiqtdS#i`PVXrOhYpUU{X z0S`Ay{zek=NWq-zOw7n&JR30RI9R}^(P3tNYy(Cj3CBpC-s3n87I%cThbqH{7`eUS z#~wMoU4R?fC^1uG-87=$O(HDeQl4R)Aw97dwb)3i8k^Ri8EQW=w>SrkIqNl5*gg%?RVMG<-PPk}_(bSDp7O zjGNx%Ib&+jl0pWXEvnRfL`#od87A`Lj`)D?8!({BK~bI(_4pQ&(53SFJuCsO?D2v$ zQ}Vb-wE_(^EWqf9!QvY*Yq)KZH}c74G;?7B8f7WADRu^~Wur$T38|S9w;H0@801*T zK{Y)&J~9OyL=x7J#*2?TC?0!(EP4@XVuddKejxoT8C(xiw>HaBgG!8tBw=T*+MA%{ z+uq1xE0Z(Z$mYl_OMEiaGY;4`7q*xC(W|ok!q6%LDN>ECvErMvMl*YoHcBciRDeCC zh`qd^xzbU_!;KQ0l>{ZQn1OT+PELLSkyRo4=$cS;J2!~r!`6%5Cw5ox9bP}2<78cnwvjS9NWTB5^r z@~D|nW;4!kOj*_{HYtQuGJa$pPoM&xW}+=hQT8f0z+NFLxU7U-ZfvlewT3iPQk*G2 z*`=@Tyrr<8a5tUn%5XRoGX?!e7ecQ>#AWswYL_O03Jj6+|7p!%>_R zdW_Pim^}0dbH5{n`SKmv3I+G2&P{^!!YF8_BtXW`te}|Pq4s!wG&}Ziro;wJ%qZk# zu0HPGFq~S#3^o)$Wrw{TBqg-}h z-c6@4fWCfRukyNHg`l~{+leO5dFhmpT7|DQwJT{#GJ*1i%?nYr_f!LkA{eBpX2+O% zq;lXkG`HQ0`1*eSIH=Bym zmg2r2`Pq7X({qrnVe zghQwJCc&{QRl*4=&CqcW6I-zmwJ(gJthS>qxLp@0pQU34|^%c=aZ#k^(YfCsgRZcVG#A6hr zN}65yFt4MYCaX!H*gH7~buA7=%JpN=+#9hpd|G#|64v#xC_?QQ-+(N~m>}pli1!!U z(1VVHRTHGW66)=aOCnazgd#ECSoSF$9?z!Q%){d#Zz-IKR5Ip)o`K93VAGo2z%?HsXu}jgyMkqaus6vKUqKxDm9K*T?p3x1-t(D zF(z-Il5skSc6&CzFY(r_Rot{dxs#L{ryBr{O2IajNh`+O9{~Fjf0jihl+hq>^{M9+ zhsVJU7-(RA6h9P7b7Eg+&~izes0(sORxY?o@5WTh{*>k?yj2)#qkxWs2^C^Mz`@%X zCny1oYJ({il%m}LJ?>O@Gp#zH|NW)x=SNCb$A?1)z)Fz4gUEsoiww3$6F$>HhQ34dE}pii{0tEQ%=g$1;< zvr~koQA=E9- zaMKlIkMAvXf8nZJor$!z?inFD?F{j zQR77}?8(PTJvn>A2CU&Tx<&fRuF)M`H=1WRc+R)0DPLJ0@KO!r{<-`0?MTu29&UfX z)%BSs*`uep)O=ob$c9inM(%!pHF3iw@J;_rIa~1tIj5UFeNasI%H{LYU;iaSi0t|Y zLU`p5LTK|}A%w^Ojt~~o{J#Mq?Cqpr(Bg$5_^ba7AzZ=2gP8{Yfe@}>VU}|Cnw0$J ze?tge$Skv}=cv(tLkOQk2;s565W)}CmN6!dG<<6I7#Niygb<4B=3-#fCL359%XCpV z2_c-L0!#=uVUdGiuPcHh;Hsp7>!|WXP8tBgb*?{{sSS@CC*bF zAt8i96uCMuCO95K2#c$sIG?L7jGKyt5YkUccZ5kFB82&WLkP=22qAQ!{w(6w*(s(A zA%tSAk1$ly1UKwIBZLGpQNl(irKTteArzv=Bg9&B4-vvgWU*Z&gz%vo0xr}F1XCTg zd;AZCFdMH8V@RkbA%rae4ZAUbfi{e<0~>!w2v7erLTJ^=%ooFo8#wAZrUL&9A+&-J zLbcpB8Zi<=DD^jlFo)(3LTE!E@>b_j0R#vkw1w+>HnRL3A*4D&LI_b(O~;^Tp zx&KXs(B{8F2owKvgs_O_-y?*^utS7U82(QPq0kX#2qCopjSwFBgAlI#MhJ!B{{bPi zg#QylNPm~H4mcuxMUxV=gb>0$KmbArq2HVr{EuMEroRzFT|$r~F9{($%|=29J^l$H z6!{Awv;(LJ-$16nBZRt$e?kax@V_I3!oe(u2;l?De?kb$Saa<`8VDgg{x^hh4?+m* z5J9nb5pt!!5ki~0WFR?!&?WvIAv^*hgdz|^cmn@_4MM0ZcZp_^gb->;$oxhK$A2S) zhQAR)o!OFjqU@_(KSx zXx^1`G`?@Mz2#8sw9Ysa-@&BHx&rF9hy#PGdvCD z>l~jk;e6&>{i9Db*Be+T-w!;A>p07EGdXQ)bK{BP$Thm#8e`LQ3SI$o({#SFRMV7? z8!|Syj`{zJnAN%0@Blc+5SZLUBtPaIL!W&k^l3OWR^sgnZ5W%eM9d4^+`S=13J>Zm zoQA@KST5GY&l88?LE3hxTg>?!ci1h?)%aVt_&qr=G`Je9-sF{my+$7&oY1VAcG6fUjU!HVWhF~ z3I{1RzVq4er{pfnDxBsy8Q&d5CSVU^O82xB#^Yi4nn&MLy$R<6<<0BGTinA{hry0yw}DUV{xEO_Kv4eozL#Laxov8zK(Eg-t++AM~&~$pLHyv($++d-hy{0Wx#TZ?kmrg=jSzgm)C}SfsqK}InZW4X#L}!_eD<)ba(ZXv zU{Jl9sTz2wrO}ma&4d9NHzd-nPBFt#tcAgr3Gz*5uz`HwMPYy;E`&h}WF{!|BqQhQ z0B$`y%@FIODMzLoLlg!>xMbv^jLFUI81}FJRa!BE<`D}iu?MokCtZkgPaI8znS#s5 zG`Mf+uzOm-l`xi+vA-5A8$84odxDNqde-!6v?-z7oq%h48Uv%~jbR9qA!P>XxN0MG{l{MT-JDr^g-tC_8#fv{CJ;aCdg6RvSUV)}IGYmQrKmws5BoLZq z)GsBH1VS=^+8!p*bSF+uZ6gTL?4T(9LNHVq4k3iE6iEmnxQj#AWi~IGundxl#nAaj zSqRRTAYaFvcqhs8yuCfEQvzR*r6?$VMpnzhNAr6=l5RNRi&qpogB+7ETv1O>kWAsk zcd5_rQMh5V+OY&KRAvT6s=R5Yo$LWl;t(O+K12xVe-9YL#nT{!5F15PZ^7$+pLO0c zjqR?0lGPPqxP-mj?wHEW z5FW@Qn~m;NNc*1diU6>UIZ}0h34~g!>OgK3c0N`#C|8%sfMp)T7L|WA1W8Y&Bj{ub z9S3KVlQ=u`SQ+HjJPX-{NCIKqm3(vUhr=F!1VX7S1XcEZhtMzIbyQpo+%l2EzXih3 z6vvCj&z;iSD1prkBx58py%5>#q_F?p@Q4X%tb_>z(_D}%XG&+sLSrQ^x%bmcvqc`t z=>%GjbM3x)0{7oP_SH=d26GQ|>{yrOpEOwGXnn8QBJnl@QL$mW4!6 ziPbdfTf1bnFr9ouVH}TuG4iTu7HAEvSV8g_6@LuprbII+9ejuoo?KCujQE2PGR3o? z%1==S%}_pMA58z&MCum*g%Ea=y2T`f5Sp5Zs(=u}=MX|j%;e8Rj;!9x{f!WY+(*|u z@^KbA=A6NcQd705+;x;|8&hecfD2(@e<6enWv*NITq%l#sYwXo{vU*}lf9zAIg};8 zn*XB4!5EGLtMu4ek7By3h8I=LGMK^JiA7FSaoH#hQAwW@h0}bm35^Py77?*hmG@~z zDqJ;S;%`vm(Buh~p^4Tc3559#W1+=to%QUHKv{H*y&gy;;C_CO@(VyI_+zN>y?sP--a9E^la$mv%Uj5)6IJq+kXH{B755v`oPbtb zK%sA7HxwSM1Cntj{G#wE*%ArN;h6Ejy+;L6`;o10cJ1gq?icIk`R%n`3P;b2o;*P& zG0+Fau`|0I{ph-jAWpGG{=`(@X?8xfcpHuLa*t#Z6lt#{9NH^khxhk(Z1G`Xt(}JHN0_8wNqaE^n zfsKOBp^gzb{Gx0BN=5%sgg8{JmcWBHtxq>()O!pBt5-Cw_D>07po%Pv!5+5htO@dI zv9rN!)BV}MDhb36^7EQ(?t#!#hBCcsJ${&4ED0eLd~M+ZA%umAD=z&kwQp8@hj z9)H=){i5J%Xsm=CK6COl8#Y!@M8S*D!{+|_R!iJag?fJB5qf*mD%ID)`vbq~My#NN zC~z-}>dd-+Q$}A)?EBtGRF(T?P8InJIiFZhT%^F#698IX znDX|S=-0q8U_@CiUPxd4_y!Pb1k2r*DH)NZ;e{zpbTLEWLGhd)rsK32STQtaywE=X zY&2DIFdiJc>5v#q+unQMl-*RGdB+OF;M)9XMCX(vHsC3I z`d-6rk&P1@s{XA;zThRzzGi-k@xd2oM+Ui+GVP|9Ui%JmojWHo&5VJa;h(Lun}sjW z9Qa@GefQd~or@@Ngm{E*+Bk~{8jsPOkc3NI9Q#RhaGz!BpY`>bn>kBlZx?tuJ;xA6 zcmc824`{!Z0X@M@eu;&_Wh~PK1Gm|LK+Rt`Sh^0F++_9$f*NZvfEIaP%&)fA8>g2o;bk zfnSe-UnK&+s+FK7^85twYXJB)^JmKhf9F@Dad2>OOiWBlN=jB%RzX3*qeqWwYinCu zTYt^f{aSk3)z#J4*Ec*oJUKb}>qF14PlJn#i)(9Zzji)uZEgMf_3KZd@c*)}^4GLc*59>N$U({TbNquJbGOLtY0LWDG=rk>@Eq-Il9Z1DBAuRN^K=<05`v6Sy zd7(*xfGIQP85JW>k;}A-&Gf=sONn1fYz{a3FDw8D&nb43;!K zFn*mmvHGq$qb<&8f9&H#qyKdO>y~%xGlUC2>5P92Z_M{KOCcH~nn`-`0swgWpR8sD0a9E-g59)L-3id3_cgFPWqCbB}Pk&^!9+uRMD6#`{@3 zE&|H&3DfHm@A5|E67e)a8@YFmo#`cpOk0;gB7p_I1j1<~r zyOkx`w+UgiPTD3h;>YVylFHvol8(>>&?AqWIG!;Qr^bFzx~R&{nSK{W?&d~3VjvOe zB$-Z;2lbq9e^^ShKL=b&bBJ?(c#owTz*4Kb`QRw|?)YeCTz1#H{J=Y?^j#|SQs;6u z{)mWBI%WfSNE<9rR+7fj-7P4d_M>T~Fy)NPhoUPgdnICt4yzxEbHkc17ARh$D$U7% zShiZ`ljO2mnp7jQR*~1dCsJH8ShiM~KH)Z_J;!=eMVx_z&~pCT^+%bNw(AX_-}#j`ZywjK zYWpD(b))@$o$4hz2}9lvGG;;o?kNrR7fC`Y#m6N&ngbdfo{n~MU#h$FW8V@TnO!FV zAw{s)dG58Q{ZwEiwD1R>u<7WWJP_>bFevGa3l!oJvvLOIOg#>u627oSU{BzPo!>O&i zX(<%INazc^rnx?NpQ0Xh4hyb$K;3TOA!55Vbx?F$_)ccm-VpMK?OpI3O%xOfEQQR16fmH z9q^8`YXj#TbF45KR~GITk+b*{;kLlsS$Jk{mH>a4w}AAC(*`nI^XV!|eUi%3S>cO= z5}|H-0R3mf4`L4wBreEH31hA($(em#WGisVrc7vIM2o-fZllYtPLOC_x_2(2_p!BS zI%;GPL+xuK)fAT;oLQpw!C4?_#*CuZ@I#svyG{ZX^2)~4;KxQj0vS;_4>T&I7is9q ztdTt}^I(}i*!}<(@BV>2l@WiE#|F^sk2MH*HGA(4UN!Ly%|omkpK_=aJjaKrl;6CJ z+xqfD9(KmY=kju9oU^43{>EOfl=in#EK&} zTh6pFDVY2o5dl(++k_I-@~p3s-!{0YJMz6Y93+5cXr6NoWV(n~xwlWGYrYFu8BK$| zi>ul)rPXRVsjA~v`)u0LnBSZFi0kd^EZreo7SxuhA{NdahU@$&)?gGB#v_flKx==( z7B?VEA)8A8-2?%IIjv!c?Pva(+p=?5-YY>Pnzw@8U|s^e*F&-{q`67mU4!w$7!zQ7 z&)=CGh$D6lZg-u99kG?AZoC~s?|s*D!TQ|E0j4k??JL>GKbo=9iFDt?eo=%oTbvHC zvK-;JF?=yOR|&*hO5c-?cD7rH3KH#6xy~Ga^@oEEOu6@#%T3PcR#9ejMuYnGso0!X zQvBqJFU&8EC#c3Oi52v{B>z~G)`hq<8wu^Dh{!JV$1FRSe!l|kD%U@;n^Eesw!X1! zeQ&+BMqPWH%Yv#dm;6zI#{IN`2;;h3+MlZ0s(Ww69lol>g`hPICdBxawH``7V%CSN zuw>~(6&JaFFxhb$)`i!X-VAanD)Ai=bH3Gcj&?1gwE+=(IY9p{0x`Wm$H7o4pfFKf?}=SYUl^YN`H{`1=}yncRhu9|u$KDym^ ziowI|joLf;%U@q#Oxon%;pEd8^%%I&e-m}|!Lstvt+%!{UoAh`i5R^f8fs#=#bo3! zZqZ}%E->k-J0vyV9+rq-?2_t|>nC9e>ll{ZNo>^~U)+hmYAin*D9D*N)zi z8*Sh1eZ%z8&*;aZ+4tRk^7ak%;ExsZ*`11p_AjcRZ9fHb@6Gh6?<}zfybgZ)W0oiI zO-=kk>Vv00?_{^f&prKV`ZN3BebTR=U!GR%Y-xO5eShKOPT=-@AldF6n6A;U_fDu` z$s^u)-G_nj5(U9z0FetE%f0ZeQ<2I9padWv&mpb)!hz@6@8SL!6*-TG{9)6tOkjy?(PvNf5rb$I_Buj#l20c7=$imJc^zwXA zPEte;be5Rc&0$i#!B57O0+*(TuO!<_(Zl6)9bU1*+S{WFbQ`6FH?A1@4F_qWg*7p7N%}YuPZj4arL*~P=?zfEKA!Ff zTuWHj9j&(czu0^4rzRVIU-!-(T0#p=tQa7nmp~|?hbo;&Z(;;giUlbOs1Os7j*;HP z(0d1|B2^I-5l{gY5Rj^ffC{ML#OHb6^{%yM)|#__*n7^}bNC0CNoEr6i|g~fL{;$( z@&l;Ewq>Y(rkVeIgj#FzoFi7THu=SX8GE2nhi%l*6S-;$CgBE0_@v>QDC7VFa&Rp1 zzy>IYFc)bu<=+712@p8V$|OQ}%?={}2X@gDQ@4_R8Vp?gVb$~a0|-Uf>`C1nYz_`0 zM}+kB>bknyz%l6u>`hjcjmnV81sM{XJLrufSiy-mFpv4 z>N5fnDr&PPcd*!V?)udx=5(*@`BwYM6(e1OLUc?-xJY8&a?aNIEahGFy?LW-G(>(D zbbY0pmwBph9=eE4FM4Ht@s*)qZTfLX%Y!JTj9SdI`9x2DqKm&S$V8SSYA@^OBnO_@ z-zB&gp+N?hT>yCzF?t(dHQj@_<0T$n%I5yq$R$Kst?goU$L^#r6c#cA?l7@$PLfz}v64d?QH@YteZ6W*VS7f`AyK4LwTj0Kp!Zb3|ProG2Dx~D)st?#pA`{7rshM8_elQ{t{}Wf zB1(-eCWvbAIvbxQdKX09)xkgoW=}U27)&pqtBFFjcs~}v~%_K&a2I&#psgx zN;kz8cDojK+m;?^gEF=0LZidU3Uq&k`}09`Y)GwYP&s?yJrCZZbBb+ry;`z=Tk~YC zM?)>=GG@kKJ=NFbpmg)O{0D*yt!IWz1a0fW`V3xXbrMBXFWR-F`Q~+Jm*)DNGafLm zHfwQHY%^wS&_iO+_89Rx=}*N(7^}xD`j-sB0cxu8$-Y>FSK0YyP0Z#uuVvhKqbFIp z@G6Qt3klCZVSp18@Mt`cZSGo68!tuoPznVLE4)lp+A7d;@rehw+i$o~dn&ve_Ovbx zX>!D?dGPCM7}r>~G`>EVvrMt`lV+OnXw;x)@&v*_LK4VCEjirn%5d%Oh= z1%SCR6idLBrgYTtF`ieT8h9uN0#L6&zeypg*FtYJoFJzRgzH1|p4sv6Gik6vh6h@7 zv85B&iOfi-1_@ft2b@WMtPNzs3!usyAUmNl!wZ5VJlk3 zW}L7!>b-vIRXR2r>w9Rh(B@r025rA-GyOu5h(7?+{0wSr8nNm-c)fVbvl00PyR}I=; z$KTH&K=|?1&IV*feL$WDbw3D2_!SvvV7xyPuh~LVoS}ETl}khc)p;n62my;vFf&l_ zf>F`8NHqdffTs5SQ=9ccXiBK=*`p5cTSjGnk1A-{3pW5`El}*nQ&|}$Nv3X+J2jb? zNs$0ysDFHZ5W{k#R!@`5l8^?+u}cQp7e2qn5b1WhYfwQ1gf7{1Ul~IF{0z6Pbdl4g z$&-xxmZti4lz-wi|HzvF8|b+z+`xb!8; z)2bW+xt{vyu!Vy?r+$6{%q$Dq1OwzHpjvAW=cS+K)Q0!)HufqO9d4K;)t}K&OL%Pn z;iv@=M2MkOiYh8bXEvX`3*g&u>_NY0M?%ux8ylMtqyib!^Y;R@PIAF%LIc1zQi}RS zoICa2a8HS6hVlDrH%#rJvp? z96Hs;nJDgF*me3rUzGjqnDvLodJ2C@$_LShA5L3CF_=bYwz(4350m*uhliw2sl7qu z&PiP=ygN_AR9{!@obRnKLU=(0Xg2Cw^S$B=4@*9nhu!26QqZL@wCOF_<}RGnwz3KP zSnvMPwR6@<+w^qe+z+)yyW$1)ON+$ZMW5=kXVybprWa{*AN{Apz1$Xqa%C&7h1{54 zx>iyeCbS&?Bbe;A9Csq*cJ4COXgPLz`9{=oqR`5%*H@ewSL}s%nK+pMt$%^iNCsDA zXPgXUfKuLniIo3Ap_KeD;V9J}7z_dCqJX(*;71DZEB!AlS}eR@F1cT=ykDoW|G;>^ z#bUqf%>J|R|B{1_ChSk-?oSo$Pgnh6qVui)fr&15@2@@k2NV6a@P~>1-2V4il;Kk5 z{?B(Q|8%y>QU@Pfvc61)@NUoe@?kt z_15&_%wQz{wdzv_L0?vXCts^Mt#xxBp2!zmdqyRaTUsbNxXwd9;ka2fZ%F-FiBx%C zx1^AU^P=~3;?{XW8<$3ll?yB{hA8_!tv;=hDC?r|dFuA%`2&^Ln`fpwzk%GBuHmk< zKEBg#QT()PkyBH0VDHb85e~_Ri$yajVW7mRn0ND^AFJYFYf)Xo_Ox zf7JQ==g!vJ5AFM3==%VR1o6i2-CKOze}c|r4wYpZ8jkL*}u>e3VjZ%aa)FVyQ<2@k za0|rv_{1#8ij1T#q$u$^6&^idU3NB7!)sQT6aJu9m(|5bZ6P(tlW~XtKm|lA_c~p{)9z*O3_Oa>;_* zZlOlS*|(*q1A&v2TOW;+pc!|k`?3s zI?hNSb9Aam=M{C2u1ZBJ{W;Ev#jVNIzVzvq=KQPOf=)r+YN7*}imIA-SIwAfxLmJ* z6xDd@=eCCr)~flN){%_J^Q^QVd2c;#vXOJzub)k775|UpjH`;c-oKACs($k8f2g^< zp+He!v|A{Of45ukWG?nt4*UZ#iLQE3%z$ypQToquMk!2mFPn<*Q3$8-feW>KO>>NP zi{xWQyM;qOTJKN0MG=rdNd&+-viz7SjCKn!>NfPJ-GV9YoeJ*CLBjXTg}XWgq#i2q zbqM(x4hs!$e1V9+qft1xe^t>q9FJ4UT(}&3*SKp5CosVt%h^Rf3k7sJaPRzj##slB zZ3?imVQz7#mXhQaVfjA+`ZA8+C6p}bdKZAJ&e9kY>^`b$<8_yX3Dibu26e&G{Fq_G;p-~rla-M*j4AAu9dqnhy~2S3t^5dc7N5)dE*ASbbs1mujF`I(OY z>}zgi`fYX-t|tO4h+$z;#$nn92+nGvAuIY4g=0@}nz*cU$mopYl7?o`iD z`_|2N@k^qzxyW&sGQ<9m=+xrA_X1LjNG6~%ELF-wHk)L`%ENP6v`;irsacEpVnRxf zIReI82CamB&G=wIJswhP2mo?=zEIIPDYfU{iHZjE<3%E4leDXySY1&~6q&9(#MEt} z+ogezrk2ryHfO^G2E_;L4PJ!4Hf7~oE++e7lp%p*namjXXZ%ckZ_&#vL2pI5E9qz} zA>*$pn)q&kVM(Q-GTVDG3lMGy=J8>=8RUf-)kuxMH`ISIw}g)bwZuS=E)!YMv>c|6 z-5M~1c)c@@1eiA~Gru!qKEz(~3)mnDOp};EHbL_cDvo3q&!X%*zjrCLJ7={k6QBZ9 z2CU;uJUkEy>RV0%sg8c=TfFfr2-oCeq(Es?6z;~fqww2a!)g9g-h?hk!A8pJ8Az1> zSugU@LCO(CQoTcPE{shAs63Sy@lx|s_oYKvemoKq#0P*9i?qBC-{G-?6-^yu|D%^$#S2qrilTU*$ zD^-6jzSPlpbS=YLQzhe0xJ()Hi|>GeTgu({K{OP1yusDO)RYqQk3dkyWxL_}v}V^_ z>Eo$GM6Q6ehwl>n13gimX(mST#6_h5&*yx)4cWrrd9i_zVQ5(c-&Fkho6AmzuB|s{ z(9M~(+4qj#mNTYtKTj~Abia%bV=3&%tQfNwjCwgX7Ex|_)3Je}V`qnZg|s<+tf_mP zS#m*Amd9A_E1Y?&bM-4vCqz5F>3-d~4y|6hyXyL=;7u;@pyqe&8lM09L@(m1Y)Zlf z+v7jq-d9z#r^l(y*KnQ9jg#3{;7MrSmXB!;m)2GAi@}0yZl~td}5?jKm4uw`tP;( z^tOp7mRG$mJpANk)joARX{D+C_vcf0SS;?DUqgPZe;ZKKK5ZEIL+DxH7gGAkndEyv zx{ieD-rWEBLGW~5_xZMsct$3ga&UJr!0&BJamPnNosfac^o_(99ZNc27KW3jH}je! z7Ofs#8*9k@S{A;&dfMvRn=!Y|42R##mmj&m-Rk_-n*Mt|yynad-=pu{`{cPhH6HWW z`vY|j^iTIMyD!;1di?T7&t}bW_qBjWdr#lcw;x#%za)qEOge0DIK4Psqc-$wNj`k% z)g#eEIcoqj9uFN|tGFjj16aENH0`tl&8@r9z6K2M5ZB~;MMqB7;~yr4xz^s4Awzv5 zSP>&($z*6(04ozwm)TL+l0w3Zs1Q7^MdEKsC7C*I00<030%JRs1acAp?;@uSJFQa- zr*g++cw3mIGDL7B2QCt*lmqOVAT`U#k+3Xn${(VKjF61X5;2@#h7 zRtUjfVN{opg2IoJX2(pt{Zz*JbS1|rCS(H+3|gm@`P4xXUr_*2io{ZZw@s2?MSz|H zq&iU+q`BFbN;n-v!HtE{$%YJFlNWEyv=JpVs=FpGI=mgFL5$|Z|9RRJ!zc?EA=Mp) zxp8QJ*?3oQ@P=U}4X3UFZTRd<&os%m2R)V28LLv&SFEjnIHW_2?hY|SK6c-*mh}e*S7mc*xOO`0W!~B_j zdo_6xa;zg3qNT`t6Z+hYM)$1hQ~`1~0`N3(a|(1prLd@3Cvo{FdFtzBZaMPr>K%?@ z_P3MuMgkh8#zG;?;tj?=fXdVPlRAa*>Mb@7BtYKQ!N15d*XeG=veRI)?6H>H_9np! zpl-dfaGWjB9D`?>(A{m(=G@VfMFB`rs5>foQ%`tnEWIZX8X{?{_Ay7^Hd?G#i=Qna z&MWo1qj1)tQ#^-s)EGxU0qeK=nI+7)X&AtYfuKh0_fa-NefN0~q*6~UfWrJNiH^G# z67s@Ht4ow5idQcdRcTeT=R)2e_OxaLHP1-g=b}Yv;z8f}yN)J_HYajqM)gLPh11X? zAIK^$s^)CE{g}SLO~&k&{9214h&dgjp9(So>!qR@lgQ5| z(Pn*?`=EwKt%_!B3vyE;I%y5RiyUb>IPMTOXZ5CnJ<%Z3ZIPNIaH=(+kl!Eb1vSVJ#Xj+-MmFNgnA3sUe2zKQ z(9CwCw>4V0a2)R4(`xc>@l5C|yyhZR$c@kF7W6+XDAA~w*m1rs1ekH4J zZl!U$7sC{lnVXQZo(8X=#nsz6{BXj@GNi&@#d;wYsHOGp1}l&Yifu~=`zqi`U|$fc z$GAQ9kYmr3{w1v9>%+ny^lWMhk;4(Hx$2h8NXVvC4G#ih162`i$ze~*)z~aV=~r{{ z%8};H(*~ho9tKV7&gO&2&4yH8zDoAFir|&oT#A)njO`UD%0?-bYTb6gB ztkr<+)R-kM2Kj5Xu*^Aszubb||DGmE8G)(UQdg$0Ce^Yj>cMDDn{6r^^Qvlt)%jV- zFlgOE0Q0xqVlR#8qi+jxMIZ2XHT^8CI>BF68Js_USafCuDN|uC+YjaJv)QAx9Ek*> zvFiTG_`E)3&4OxcYjf)0y*;=AX}(Oeuuzm)_h^VAdqu9qS~MW7bVCvwfr)k-f_BER zZcv(eMCzoQDhHqdgo@k9 zrdqUWZU0tJzrT^KzT=l&CA=q{omVbnzU=8%4v$_T|7K(9VC2*6%#wCwT%(?%P3>XVnvL|rDsN{a8(p+|D=LY$S_pQ!0sBIG_dF6KY7=?H@P@{nCoXqB`zo-Dw!GNx zkZZ3g@Xd`~Lw@zQltsmDZso|Zgh6Rs`A--OBHyhdQmV z_j1-7+w;q7t|B#4uAzH7xLUh8L4&tVP@CjOK>}sfYr6BXCj#14+67a7|15)abOx)6 zIyh%zGC&Eu(glN-OMG%1bQ-8c1>p!lIS!c>cnZt-wiwelO2K=l0+NU!dOZpJ)Wo{GlmqQQg{&7RdGuKqCjE*W815T1~}b&r?)$WDfav^ zr=wzTi=cIMKRuG-(Do0g<^(kZi_|o{?kRq9k`j>D)olK3F5hN$_gAW^mTyN`T)&zk zC}N^_is>PTzj9Fs*hNv5O;N7xZIB}AGm~y>AP9`f_ugU6GD$${?2}J{&fX)1&=A(C zM&~rA-jhEQS}L*-BUSv~q_27a3IjFv0y*%hGNm$d{ioCl!Ps)}mXpF+QQ*5jQ~?7S z>DOn*fb_*Jy^D4ciZl?H4ZP5A0Eu9%vzC8lZR_Ni&arX*o7Nw|XR)zh&Cz}?qV}se zGoD{13!hZP|GD{AYtuVWXh>WE?gx*{qtwGVC(yK$nl8=^uTpTT@%%R+<@57z^O*1| zhY+QtSf(_^pJNiDkZ?}Oonu%jzc)7=#uPUreMkVBblNT8mTVRBUc=xCnWWK5B%k*) zz5db9qNB1}woK1PkHu$4c)fKTDO99p%??4uX?GXR#@MT_OCOkwb1&?49~S?ZfkwuE zg8d^Zt!A3M-4LbncU0QXF2QgbMtGxN1gbx^Tw>&6h|@gyN4f!YSMFrSbiGvZ*{SWD z(`u`j^*>eV#C#8J1I^nZvX`#^mYS-PXf0?in|uF4T*o4Z@rcR1RwjE$PGYj7;Qi;R zuP1~>ZEx4kl^n=@-ykJ%OhQYVYe2Rd3q|!SXwQ+ZekiNgE6EfW$1`pUynQhDq3?v+ z*BjD`mUDa^^QAotkHjH7cn34C1-S5nt(>Gi{bM%oM_swa9p1%r+LE5rAHAz(y`~rA z>K7+eKKczyTy|Tch%8+AhLYbXgOM2JelOt^c<)bMJ4-Ghbl8LT0~CbN>af{}b46JGtNK^54y^bLO8k^W$GM^V`3tnG72HKkZnZb4Q2@IHe`yd0RMlfJ1O9lg`-eADgOM;<|EB-}R73*oCO=~_?r-yDIxc=ax zXVc|1dg}G&%cmZOv)>W8(Q?JU{|@6x`bKMj)${viHT*Z*f{b6)_?}L=*?vv`{i8Tm z-ms1zn~O~aR+kyJ=gRtw#vS?7YQOg$f0-Ao4uAB8PG4amk{)mx(=MdsMWVU}{@J`% zA00Sy2hSq8KsDG~W_Qy;F>Fsp>Uw1%8Lj!$GsW6I(-UUv+=@zbww(N!ZhgrMB}_aE zTg>z-W<;+qlskc^Jl3txWe2|YUb+`d-zbi~@>=n4+mm+vJIs~!92Wzo#@joU<~9DB zWZ0gHdlH59#?C9nIa48$#kF3HtCfZ1UCGkwXy?`PN=uk{c}?lmYGqL_d`+^RVS5%o zn07X;ZfEgbspy=GEv+4}pYpBC2eLmkT$3A;kr>wVmCYWtWPe}x=IRmIx+#^Rsx+kx zq%IRLfdq0+Kd2CI`CzS4ouY!lm_w9Xu3voc)yKMuli9V0#4JH0+(L0`fg^@ z#N(Q;m#j|DpnmCjq4KE~HN1ypjM|Cub&rpDsLJ=JXZW4t7XLG9hnds-l9i3AjCnhO zM&V9({iV;XrK$!6_;Dt^OmKbz02SZvLX7|m*&x&uOC_hs8dC!y?B*kS$r>4WJ54I`fLbR`ppz?t#9xexJ9Q8!r&l^8c> zTD?&x1)5(#PkCdlFM{c=RcASmi_^$lS|do^C9_fDHBe@|mI7z)tNQT)*m;hc1u$wj zfbUr?g(0ck0~U1t_?rhtX!`7IZ>v!~ygQxxt-aDud(iBav|cV*O~0oc^z`2B-Cl9k zGEj`!*sq7959?h6YGBkL05jstL&#TY*dF@2_~eh7TQ=6ygf0{bLcG-99UfzCbi8U|7^Mg zeJ3mFe)vKXGe85TbZI660AqI9r^ez4yQc0n3WE@F5-~NDyQTI?S4R|i+(f`WEW_a3 zU|1Gipo#i%AZeiRz`#g2oQb%evaP@*_cR_L9UUjOpxFEsOjLsNQZ3Va#cn?Hw_HH- ziwpOIwhtx^cw)8Q5=>=__AaQue^5}5m#01@=#PpjXN4N zBYSYxL2Q>8mQm~OQRdt`K*zJ@-S~{2N(Xu1U6;}iifA!QPF)v^y&|2_1&T3b&H?js zv5a+e+Bt=B?O6{n8qZl8J9b`dmPs2^0L@f_!Up637?lK%W^KAAX7bQ7YifamU>|FT zhYTopK`oKC-YP$M4t_iBFc#8Hj~rdEGu_msbT<+;>~_-6!`GDf%q6E|7_!AH18#YL_Jlb{br=5bGAW^3Sj>NXXf2@En0~Yqp+pT&JZaGlR7qL{C%uuNjg3XKRB) z&YTgN$vXcLdbDqr`S`{N8xcu4N>Y0+Vl)~RLOp-rF3rV#mGAC>=gUSKdxm(f%>r?Y z71JjYqe%}Mi&d+<&1>|TXk0;T21=yt;5OMj%Wv_z5u~OZXX!GoZ%CsBQeB6-WF1S8 zu-if&C(!-6`G9G)p4A7I=f&g&Xa4c(??%;}{6ybu zk#{Ol&5shOe(fS}7g(ZOJ#MWBj(NOq^lEO`IkrZOzdpS}YL;I}_;PXi?evfJYs&Nl zjxcuDLrf00ySatpBlJB!aLh#ZmO#EnKXIRXRoc?;B>XwZ>&ATka`P#x^Hz;S$3bdyQcH|B>(UC=fi)_ z){K5DIZog7E&Dkk_GtIbKILop{ofl7yn9u7^c~8~@9!_dlNPz*pVnr6?feM;`Xv1R zY&aMk-cKa4wuCX^E`Dn!4G5ADj$xdR{M@)(#$vY)w%in8yDr#rOSSkG()i}F78o4I zxRXql$hd(ng^9P2wTsCZdInkH!%b|)E!fU2)nIp7N0>YtS!+>eT7;r;kgS{$_9b0R z$qxe~0&oDrbXC@=0AQg4+>8~&RT%Ski_SC@rEq zNFdV7aZ**m;y1m}`T-}TsGtDClo^v?U#~x8EdF&nMw^y!fC$yDg-Rk+b(>J}UT9Cp zc)%|{L?kAOdixZ3!s)Dw%{S<-K2(wl_RTvn4!6nrok3)RG6bSvBbBo?4q9l}SBkpo z1(hO!Z+6fcU7!Tf-mZr#LDO<8G6bB&KRBZ2C6soIqt}dMd^Zy<@(m#y@s9*lt20nP zCnO(7#}|v;{OpJ>DX>26uf8$Sj5RT`>{T0{S1Pg#FSSkjSqhCY(YMr(4nLHEHc^m5WXO&XyP!bOu1ifuib|;% zWX#^`ss0l_hyVcD1(OB*zyk==WBtZ_evDrLf!A7y8R(1|Lc}qU<9x~ThDz4;24{m| zF$LNJ2u3A_5Pa~=lmtYK0Lh^+(nByfHG4nk#3(zBI7?RrKb~=N(=E*h61$pq2Wq~yf$baI#Uu;5%h{p2KXsJzftL#rfJivUg6Qhp6Gsq+5e1GtblX77A=FNGsPFtxm+bd1??E@?5;rUaPzI!+^X= zR1TwG-G&k>sFoSDJXct1+M@>N!z}FK0Zd9@Qo5mOq1C2BE}ucGv*nl8@P#EkXsEtp zDhgqcW7)&_(pN#O_Q_8=Xg<^5R!`|i~?2PuKQv}P!G~p?ep@y$}^{slq znILvjgyZ~Er==;Y%oKTP7c_+L#`8whS5LJ}9|B{EZyeXiSmIxqSDoF?GgmC%cP{tw zFE{7K2PLQ_!h zcQm_kHJjHsuX|X=OFlR=bkjCl%)T8Zy$8LDg_vYFUMawwu0ZKF0yS}sG4uEwXv+C) zQv)X8oHRatq_AJAakGtvS#4`R(*BvL!7-qIbTG@fMGPy2ru?ioE23TvpiT!+HEKZ@ zA5Ch2UgtRKd7m1`o)M+IHNOw#wxE_-ZkVTTo6etp$+^uJthG#P+uBnm=ySZmwI4R) z;OgtJCO^<2%CokkmiT~kQ?2W97RP@+>IJlyu#dzviVLM44z`Fg+gzd5~PTgw40EFS8SATJ`o}@-_qCqDoT?2n|ho z6JZOgxRtmQ-q$-e7TUSvyBp1VF8MxiOVQ)&=#1a8wf}^=&Yn27O1f!^jX&J8snj#M z)~lJ-GZ}cpERc#&%Gb<_P^J>hM(-b#cIXQ7e3^s{|q%%h=OcA zf&aYe+!$r;E}!n(@txW3`%sg|+5`5Z7(r}vLPyfJ4f+g6q3KhxcD{}h{g%lgbCwZp zf8)joFL_L(0UWQXY1g4stAX}~&P-~jBLVoTmVRd0yneI)EqOGm>Sdf<74T|?0VnP z@;S+9nOe|2*?3|I2iXE-iBOp?0MgZB;%~NT2UVdeyBHXW8#uCefgq>t=Xt3A4!{fR zJU&(#B2&ad164547(PJTPy*1d9sU}>WVF!>s_IWK>q_N1Sy4=EmJ z=#7u7+9hlesHdj9R_yPf)UgJuIW5F(jh@nc=G6xx0t!i*&3Fq1?)Ya`?&jayy0@Q+ zi4mQjzKSNSpn@p(rA8jM#j*!FR9MKJ zBUb&Xxy9_yKf!08$@+ zi9_sW1;6TVGsc$x?`?iZwt-T_iKau4t(Hj(Ce2Zc_YyRlqzWiwn{T4tMn*%HImh_= z6vs|ErHw~^w#|;wm^8A1jA=pUe=Et>zIz?m=A{@{P6H%1&g%5uCOt&8_r4fHy+%Dm zd4<3fTA|?&@j;vur_LS@x1nlML# zf|7}hyPWKdZGKmKw509}V?#tOz*yg3iF8)&1b9YfE-z$!w8b;F`D&IB<6p}2uM`<_ z>crt!KY|w2hudZN7C7(_JWP|x_Nn*iyE}-!z0tV>f31~Ik)T_IHK@zZv2>K9^u;}y z3!ReEvSk>dC4cR-wqG({>uf&ja@XA?{n>QF6DMvZDhs3f@8TXG$XFUkGVpyXQScOG zyR_8xW7%3n!$520nq^fQ*J>5-ytE^PA2<_Xxgr$2TG}a9uD#Y{z5Lv7;6d&xsdMc! zc`e>=xwBKcN&8a+_$dzg>2cVnhn=4aJLgUeudnDH{=8296ifRwZYkBD`}v;xXPdmW zciNKkOV=0N)=SRcSj=5tb-TVcy}mBTvrJ##)c&Go{N;Ptm#<-8_T1LhN(65GljExW zi{t)pkWnjv{YGHF9oT1Z+-_k1`CkM5t-nz2qtpK#$9)<9AK2~2)Zf(hzelzV88zqs zmr?&u%BaKtYci^GiMWy%~J2BSsQ^DvoKd(PkaPkhL3LgEZ3U0|JnsvF9Q3XGn3tKwm zKU%hwc6HjxDEB&x&&TYrxtKy)wEg7yJa-^#xjso{wZ)k|lgHFa7Fa$-FF; z!Lr+!jK3sP63CJJpj@;x&sx1aLh+Aes?ZYZU0mmLvW(*|$y9=dyj2C%mP;3Qd^a^L z;&RQ?qbOxi*Xr-6tX1+SPBU;P7cs8t!CQ9~=_WcOfRoQDjv)XLRy^$jMM2XKfUp_h zdpR9k<0zcJRdyJK9~>L>@4}DxL>ICPSjZxSaA_(zLROQCfxz%1dKBdhyh10>z=&|` zNA(Y0oDQ1696R%Do*ae2J6Rx52Ja*z8b*k42cjhycwx)c>uLR2rjdZX$v zXznXKD2Y9}0&#GyJi{>~L<2chx;F4{*n5au5Sa-A1kO00eygvKDR28zGd*_sX8AW=aM*vod*XNYQ`1P|p^k#i)SW+qd69D(? zVUNIiNrTFamyQlFA=X16b<%9#1vJDbwqEE;XJFwRAbZ!d$kQKo9w|gsAmI)Cc2k{_|&E50Y`}gE1%E6o-FVZ`AvOS^}e&sW-AIIELNt-8JpRM9> z(G0mIMMFwG`mCe5(C=r_l%rsm?*Y>Vq(d}RX?RVS4S2Jiv)yIlQH}4hb*bo08 zdyRe232D_r<3nt+s6g{>+d3KPW$~tRn>usbpia2J^P;&G#l&738#(7C=t4NqT%7_Y z%xV{Pb2ac$8D&W8Ia=s}(c(u0TMJ+HK^8t>k?ezDymHtyX5@$70}I`QSFZTHZ+xY6 z1<<#jBi%iI1A&>$L|*e@IK;men)yf6nODYizcqf;Qe6fF`e-aF(Gd6oUF;Sytb)Ng zk1dHHfu4`%kT*Wv52ItC%aB)3>yYw&AQlQLd z*i3_aLd*Sr$i;t9^9~L?x{k@#&S^rVd$Y)OVPb4--sq8O87=-ohYqO{1PbNRbo$|7!@z6Jx%JdM@gj$h)8ab0WU>d1|#3IBbY=-@ulr=oxV_cOSs_z{kw zV#Z~&sz|T3{PA%vN>jMP=L^^~Z+n&>G$$}p-_h6KeZ2Iz_5Qs}UX|^yKR-T$&$lb2n zXUXW(KRoD#YoB`4`OQnhrqA!iOY}pbmo0Bk83w%Q7MKqE(K)Xr>Ib@E4_hPLkQ%fIHuYiRwfxtoc1I%XB_hjhh#*vJv@Sk$))847pXENuR{Y%>#5 ziVfSU{Iap?As_m}1^m|dWaCr7%(bx@q3<2y8|#$g*Jdb??Y{dP8_Dw5-yT2y<5|>~ z&4Mq)`EbbY_>(W&4g06pu0wvlWBu~I_m0~aL8iUdA2nYzmBTjUhJLvMk79{_l~8^F z!iiijQoKz9kCGq~#8VCg*ZT_&(W7Cltm<0}$krsfb{ZJ&f(#e8h8iiMIg8W=JzJ|G+P^|?VM3uZ|~DKqbmurkJu zs}@wmLlyiC9EdJ~)=)+&oELy9*V^9MwmptB(+9QoZOD-ul&eZ?5WqHkNl$G~mwj0y zG=;@bR0AMUTKiS;?s^;mO3RViwN%)Iam=j+sXzrxapEsU09pf5g(wXYT;Kt>2eUQD~wRZNAn?}ssskT#6p^os$RmJJB->!l>gF=H&J1S zLH$E#9l8RwTA@%$Iu(qVxBG)H2^7~xuzdjRH;jY1$4L@y_ZFPIREj(<@rPjEVvCR= zfns*T52C@W`ICnWW0mWpxksZx(O5ahm}+Cu%n9USejsGWK_NL(rRBB<809|@JL8Zj z;IFc}Eu5YVC?Xs=adxGAaVjL+`2yq;A7Q{>w<x0Ox@GTSm1CI}7C@Iriw0 zxY4SPMEraNtL$6?7nr!cDVu#BD&q%^IBM$KVEFnNFA6A51LuQXBnZi<1&r%Fj?2b= zB+BTeW2_QBd3zosSDGYqC}BJwl$nf!fjEYY8eSAxeJwy?5F4`Zb}X4hh1nNK4pgObQAoEx(8W(4HH_wF_`hAs zEjH#1q11ENMHS@)rm%>%Mly6zF-avbP}RrqE@$Cg#}V76Bo?sicGbdN2Li^ckVQK{ zoj$HR6b)4kKAA9yzu83jHkK(M866y{-dcal%PTeTT8x0dVV$F}mo4zXTbrpxXE#HW zeFD#p0_Y%AM@e_oTKHvee4hbS0h)}%XHZ!I?`4e#V6KEj@XL(op0aD{Pos})C-CfQ z3I;L&CZSa{^VUb@X_H(ApEYK-Ktuxjhame7#*I+AoMV^N`G9nexg5BnMlO^jhQvh_ zP?T-&|1im|npZpRb)SnAh4TYV=I{2wL;~2nzm(zcLq)E<67F_aQX8kTB+JbzrNYSM zwE?6;Ln>}0U8zBL7@do6O;kex!$B&xE67ii327nu8HetNr|1=J%O(auP38;ICXg>j zf$<=ktx3 za4zs3H}|e}PNx+1dn*Zfsv-h%Sk&%&V;%iqfcYfS6`DKQik#Lfn|Nv}W>5g{Q6A)# zNi@B`ZY+wD#8|H)XXcb42E|2*QJbVEP5VT-kMd6 zqbhX`A|GZU6+E);sOx<(CTn_NQ4x7C#o9EVIyHWP{;C9*luxeBUrjFKQq-7eBf#?i ziVR^i6rctN%kG|*Ah13y_hwQUmWozSVKhr{8wYbE0!<=nvBiPO>=m^#N#&Kw)g1o! za6~KuS+jWjkapa;c{T3wkLpj7gmB8Dr4c^IOx& zScQ?*lHOL48A)LoUp0Q1q6%MJE?=B-Ey&`7BLrxNjUyBKlv{T7WThJ2`;bBl%5!D9 zX6giozPpE38>PXfZd8*{r1n#Nwp#;DUyRv?ZJK#`>u`R#y#DGCM4n+>@zvfs1f>n< zr=I<@l54eabnnKkRiwT?(7BT+>#Kfi2oZbLnjFw@9HB?KX|p zFGI$1()8Bup_<;evHfQ9DsA=kfkr=FIzvnAxp-v<8}W5)S}!tlIWo+rveWOv0YyV& z2ZI>+oZ6;zchA~Yx@j9M-vrJpBgXNFJzw|WPvnEmhI76yh>xwzL$$xyD{u&zH$8Rw zHy+7MwQ%dzFJ^arYw60Ge8lOmGIXSnc_c5>87k)`z0rVY!{dG}Jb3-n0xklLom6KC zs1H`u)+KT?4embsD354Lj0jNs;F3vjh&qteiMY}Ja;|_oUw73+V^t7Ot3V2Qx~L+s zn{ld~N*e9(bUV*J6aAcQ(^|N@-frBJ>+K?rQyDS?pfpm^gsDZ&7uwwe$ReRKGyp;; zG{F2%)C)irsR~C7^p^B(VO?M)2caqedSn3Th;ErlDmi{3TnY)5rz$~aio1R3)?63^}hm?sXcvN%EslAL; zz2J4P?&+gBe%XV*eNpAZ53+%Yv&OWxo|CM@%U<>|k(8gyNM-#jDMCwsH0!aQQsxox zfGuz~82X`*1x~HGPssvDEH1g4-b!UDQKw!TF^e?Jw2~f{RK!FJKoDJ3{3fKAdVn|r zYLxLuLzO6%;s|mP90!#MLnJkMeNo`G9#kF!sVLHACW3uqcw^-VI%Whs1bb2_foHJG z6IvQR@s-WxW13pYI?oNe>xWJ}1j~>1&gyB7To)0OW)AJJl=`QJs*#1?rsy*?)O)yb zP9|LF^EVPSD-AO!Lqp~A1I?vvxq-<^O|4J$Z|u$*vP_r~B^xv@Vt8xcAZjPL$H0K9 zU`&FDS^z5>3GDQO3Pg{x*Q*wF7{lK`V^_TE(3PO(4o*aq+*^PovXt1Z0g3*H_Rh zY5gYV>ig)V_a6RgcW;m?K8Km_4Qo2S{~A@FM*iTU_gri6{jv2As#3RO^gh7Pd?35e z+11~wEtm^2pL_WR{6OiGmz(1$oxhWW=YNZ`dYFYqR zWhwOTn$;2noFyuchKrBNhrYs`xMr41<4AX12}_rc8*p&hU1+#pwDa?;3hqQdHWuE< zv<4d2fLVpVnT#S#FiPT>_^bTS5TjRCf0g<>OWx{=;V-G#n zA!sbPif!Q5DG9p{b{LCEI%;N^#qWr$-qJQ-a$Sh5SD!)<(lnpDB*vLb{8IZ3+C|a~TP@9G9LdW$w_4as#|)}fsrzqJ8fH`BBP(y+;)gTXr!Smgw=gSn zovl7;p5j_(E_`eK{CBD;Seqd>mJY-9K5JO=Euxo;NZi?SjFZAcWZ~QfVHQRs2k_$q zWgK)f`00Kn7+z%8&hL7O|EYYuiiap9YEKr7Bt!M)E?l?f6?k5;cUWzdx=dWC#kT?v z;far*6LZse2{cx-!}Zu#XKHr4<(=(maHN>yEV3uR z+E$pO;_5GW-;3?R8R$4%^hf|&baScKnX@JikFiL!Uk-Rq6JFD?#xR9SADJf>cgyhS-7`DM@h1`X_!ONAGUIh#L?YS<31D+GtjW#}*=yB>7CF!@A&f{2@$ki_` zq1EYD&G3@#Lws2pISmX z{)vSrbUwG+1CnZ@-QWzQ%^R?6RqXw}!#h~D@0MFn;chsFuQp5+h*_w7D$;R;z9yE? z)w?_(fwu;~!S``XWJ^hoEX$~+yVv~)mn+hMFb!L@MM?|Qmmau;-Gmb6ARtWc`Eu^! z;K5JI8h&>-n_knvZwKt9ckO7bkT)OuSnfum) z;iusZr*?Fe)K2CI)(mX_vi)IK?duE8lihxa z1>_=@!o*8+zwNQ}cp>om7c6{VPNoB5gDekjvMc5@#KUSPY_eP}JD)uiQy#YjA6^t` zumai03bH*i0i$wR1S`8*MwVI%v#&9n(EY?0@X*R7~+PgqULXZX_z$#Q<)DqO( zD_NsM76z=?+(Iab3-Q%tk(z`haiq_sh>D9?g?WfZLoj(F*b)~a)M+5Vrot<3FA<^sLp646>h zNA>p)AKTPIV5P3X!lW;;0jJ_AYN}z}Zu%@xxTgTgA|6EMlIg?2Pc%-@LJc9;^-CSJ zupO}XyRZ#MwR6}pMgn>q=6at475JO9cN$vr#H^tlW>XwL1-YJjA819yu>?peRC>UN zC~O$k^&TCBU~92Q!$@VU2e?lq?iblaQk#d-KV}V!+rvGJY$e8H#HNULUEogk=Cf9- zTD!xPXfbamiL%x)(g~6G9AN1!5!eY0sOYrk%AmC&9`bkv*-fWr98tOCj+VbC!y-;( zp>NArXTl2phRS8UkzPrc^#UR)m-k!Nvx$qbTZRC+%wfo7%{_nJ$q-%ymCG`5R4%tA z*s3*Ie~FzZ>KP@EkKs{OV_&?{`CT-JYHU;y#bZ7x=`3}ntwbGH6)$5cMPtx2otjo`TzCgkZ z+o@%<=sXWOM1=^O#GbCr5zCNaAMqrnVhH;fc)83nVSb#_vwLw^)zm?NmlkJKT+gXd z^v(LteVI@kbTL#3GE$Qh8{8eWc2~F%Az`hfLHd+pTdbNk2YAjvk(;P_)=;O0PvJ>x z1P9?H#I_0FV8*3=4%ejKOuCSsp{LuWwO3j&4 z#3A&_i|JD3D*}EP~1$P)ZIOTH~_g6Umy7)u(wM08ZT4EeU4wi(_4 zk08$*&+7dckRr*7u3&S4~-dJOqm*v=8dPYqJ zp>HIJ%d5D@vGAC24liD@Igp$)t=p=VdbSz9;Z)<9ch*@xCC6yxN$`M1Uu{}t{)~3| z$H$kjZm3_1b9v^u>mxE^SJO+lIc>QvM(oI=7E^OoP`}J1eu^xy5L>#pZe3QxnD|v5 zhh&jj(5&or=Cbpv>ib(uN~{ zs5K*`rNLQ(ayOmI>!$Csn%I~W&7&YD%xc>uo}ZmTF1EqWip(oT*`L9GC(fJi=Tkkn6AT$^k|hu{00LUOROK9d22&H z1|!%4l^T~nSIt_Y>nqg(%Q56~&nwuwLQWwX7LSImREFTw;M-g_4c%#LKOucp4Y)~* z=DpSJCW`zvjoUe!h>-f751v|IeHceJ*_ZV2=sNfp%Mv9b3paFr)k_QB=P=k0)wuY*8K(4nqd!wz) zqLgu+ZHMm?YBqil?&QC?Rz3c)2QF70Nqm@8CGe<5_VbQ{|smoV37{L`D zL9=G*N>!l6Ea%oo5>c~MRNwpvm?iCzf?9045o(rCL|8^Xs-)aU$+GBrCU^#9&LwR7DI z0X-^*?u%Q?kGJ2>-RkCF$k!{Y+shLJKgV1>74u^AyoX^9WZV-8`cW&Bls zoID|#qWybSpIry_d|kWxw*HGA{l@F1O!Wr59Qt-i4Qy_g+*CWTKVTp#ZD8Aa$*p>W z&hX#{sllD?63(@QTLT8yked(q3=;H)R@62fQj8MiRFT4@oW1pIcn2{iR%)27M_;52}B;3w?PG zeHntjfK%$Aod0Xk5^!bWKa0!1b8(sZ_j4ubD_4roawY8#xl;27u5AC0;7Y}423Oh} zaDL-TWt1zGX1Q{N$(2&^KXIkM0fiX-l`GqR;>u{(bS}xST&cw5N{9luQis8n2q)l5 zdrl@-#vv$IdZAqD8W1SYyfGhnPY86qgRO~+P$D!Kf_baYcXo4^t-?&n-u4s-cn^CUJ1zagxhie2}SwF{> z=_psm)iJn|%=J55x#LH!bZHQfw3PXgD_s~|`H4#r{Zevg7x;Qt;PYY4-1PrS-45GRc3AD`kJhm5YDk%H(fcnf#|*X@-Sm{}rxu`#B>6G9GUX?(wBh*5l``1xxsnElwteHu%d=eR_d8sP|L@_-Z9(kEZaFT% zU04F%4LIfbD*QC7r?_E{3ZLI`r$C8E%^Qerv1}7g`o^AZYxNDzT&Z(XpkToH=aw@y zc2OA;Te!ALkv4g`?evS>a@+dt`uV^!apXt*2ZIkQ_4fsg9UBS6gJfAKAJr zQwrzaFKg^Ac&}g?Ux7&EzP(S_pDqh7yS9$vD((36=Cb#sj@x^VT2P)vA1hl%- zq4Zc>Ez?T9wDSZN^L+eWnGWP*?cYVAxvF{S;gqz4K2lz^yG@f3J=w6OfxYgvoHCSA77c-v!yiUfT&wu8w?u#d^_l}bBd>5Si z`8DF8!(HHato+IHv9~zyXK&iyv$dv-o!~tl)UU@?#;G^%tMTcD;0jE`%ape#Hhk(4 zTRKxs-SRfhs;Zyl>(RX3XCk?Ie9&KY7Ryc0EzE@!5px_)- z#`tW)`5<`A%0T*j9MNYl9>avnPrK%z67RQAb#`SbTeR^~I=ZqXzuSCWQb$EXj2vqj z9pGn~<|l&3Y#4xK$6+E3Hafyqv{G87P8}?<6>*r=*NxX4^)FJBxYM{oMAQ4_doi%G zV5zf^3s@l^CoXK{_r-1XZZoyZ7)W^h?_Jc`RRbvPnxJ{;|xm|!R_zD!C>(-{aiS2~? zlDZ|&mj|DH?{$9~*?E{@mE*AY8F~3}%PhxmRkGy^Dl*Wup~XNy-*H*s08*i*X*CYh z*`aqH8$2X23lQrDw+K+UTNBANFtk(+#hZunr0c{=W8}=>>&Ci%nf5j8T*)GU~)5_p+bsp`LDIBx&@lfwoZ5%X1Sw8Z`{-)Zqv zEtm})fn=DbtXOA=lTZ|ZmvaQL?XWy~XeOCsQ!gi$W{4+@EEOMTbRk zj_C4R!V+~G%Bk_*1L_YvAwDzM=>A%+An4s!;|Or}6MDi>bCCCiwr*K{+L z+6Y#b(FG&Sm1UPngDepHlgXp;@)J3n45$omQx^-&9aSsr>AOgZRx8ym*a^N@=u3cF zft31#m8FNHH~wX9Rg@32{R##eAgY5~uk+gXsLx zJQIrfFtIV$PQ#Ll+(WM74Yiq8$r_6-&WYNRvGirmBkdBgy(C;(!6>jwxCq<30t;Ok zNmRSts7~*xL@wLpK(0mg80gJzU2gNsg<2`zlq-1TO72wtB8&W2(-+3d2`YxUiPNS| zmc_%4q|9!u%taX4y7NI8^?{Pr+=K!74e*}aUfkj#=iI&=@ni*47zJd+j6zsL#4xn;AfXc44K?YPdJt@bSW>i%WkaBv^Jk#Q) zy`@NeHI@ODnbW#AumNd9@C~&Zhr|dgnz_Hx%18i}jkTjDg{!@fovJA1VnF56WF*5| z9|wk(ZYA52iYhBhcpB8zl{?Z*%Tg$$iK(MfJ(FADFBs?2{KT*)p1f3 zU$i_?pN;INN?Qk>`FuO7l_m>4K5`?y)M_`m@UzGK$|FM+(}gIQcGD`58w1jgwIzu&{TD~juQ^&;y&L3PrI=2bb$9US$g)6 z-&z=2k3exQejHO82e=6zgWb7-!Z&v`70;r_4K-Qf@ z?~yx{GG3pj#>r0uifOhnw@9N;aiT9ims~&VMq3Znrl!Bxr0QST_u>#&FHbT2+_915 z(bSQ(eO^=1I=8r^TVH@Uiwm#u{F97C4?A|O@9@Oa8eo-v?FQ@nx~=+GwM!X`4jfVK zUo&sOa=nyA>VWxJKP_ayu3gerbkJsOU^L`~lb)nw>Y&4cK`i^=z8;CaqC=Jr18eMi zkMs;GrVfz~yiji+@`~|r)))>PJF?$uI5c(GE^9cl2jo&mzDs z^#|}@x0Qb_R)S$=2?Hye7;Shb^kwWHtb83d8ZA3oEad+69D-I546 zrv94t-?Xj#2P^+qdH6qA`NOvIAFTWbE5F}X{)3hO72C@H0ai|D7cY#D9607ufmn?d zYsM(dQ;P5ucA94#f9F%AT9U)wp{X&En z^5S(BEtR@a;?Ls&v4Z|FO+W-YQ!RcsZfBtPB9#&PTIm4H@LSf*<@-ZLeC>5d7OCgV zboAjuSM#N8d$%O!_^8!GgZstDC}%g;gjo+&a&6!CHeBn)%k91|ZjMIv$++%+rHI%H zUO#Y*KlKFn&NWHcd&^dp7VZz+C+_&n_Dl2>1DWjePjGI_vBR z0wJB(wPM~b5P2*+qjazNV&|dZ$WL;TyzQ+uF>a6Y?GzL>Zr{9vKYWL4hNymx>$G6( zVVmy0Au?|zik05k6^w1=Ii)BUB6_Q+^4@KPxviX6kLKa;9MUd;ZKd};>Y=p@l4@4P zWq29hX+MU$m@>~w#{0?8*e@Q(w~igT^D&@D)V=0ojlsdCHy(c(bFbx19S=RPPkWQ< zQ6nt+Cd$3~+0EnAE$2VKJuCgGSC)6?mgAzy)N|E$*`CjINH3boJpXY}apTOr^R>7W z?kApD@dkI_?5WSbRuj7W3)_>I^lKGgJ_mZfVSCQ`yrzDIo_`qcV5hwAmR4V%6A5?N z`qnJ9y?d?JJ?9$R%c|7cnn}xFt|%*w9jtgKyQls#j~T?OR#$eeZ4u1j3eAhRudtd{ zlztnY{kDpJc-%;t{l4s=65r32 zmamh_x&YqZ0Oq7p#l^WjYj#qp6b-5E~G-wIR$!(=%T>iq~P;(3IHOSV+0Zs-hSMt4gZOZ?7tq zi%vlZx~f!VtSU?6zpX0$WW)l%suJS~PDy|}49r!fs|PIU2X`;Bl`8tSs!Xw3)fgH^ zOhZ?d;)`O$wIc5Yz~VFEFI=<*6Rg&2dPQat>cKs=_!Yr@5WWMd=#9ji!F;rpkK>GR zW-wh6$HMMs(ofQf5@3;pSe{QrzOp3Z1IPzG*i2%z@i>L~9cvc0kUXa$353P&uuj7f zHumT<6)O!R->ul4cKU7$L1YAUtkDZLZRX4&F9>5Z*(47x6IErK3V5>3vskr|hndp58S@GuUq_Xpe zNoDWw*;_eg4LM|0dwFSD;~N^0J|0P~Sy4ir@%KZc+YR+4$>^Rk1nenEDd0GfBy&%R zoL^w(`*g7aM~mFf#*MyH6!6?Bgj#{N%I`zdVSF@3)>}FQ z$n-VNui2IVu`G#~pyOT{&GX%)l6UcG%i#_5VaB8qlizmKP?f`g+d*FC2sO@#U58|< zn1ICR#v8OGCvJSmSSUGNG6Ge<&%-ZD~n3Mm{s$}qEKc2)VjP5n}< zLF(bFW0m^b4pRl=;?~Am9Un#vZxRwmk#{yJOEJVi*N}}mnBuVcw@a?#8?KPjQqWZ; zF)is)7FboL>ad@u#0dmkrkQxjtEydnj38C{^VKn#eARZ2IhU^_2UTt)Cn41@?XFZJ zgI(yPQe%&HqpX)@s)!2ig+F5)vB({^Ul+JiP-T` zi!I9P-4q=Y8(KAW%06B_n0xv9uF{h;$=nXh*q$O`mQX&%zgIgz+q-^-q&cmIPAcm@ zz`l%0W!@vLeh=!|QpTimAbn$a-eTKQA)D0a5oJ5Fk-K(e;2kS#FAq>%IqMX9)!rw7NhC~gG^)F)2KJQlMYGbg-us$KYC^0`~If>6rqzd}PL91;(Dzi3@YALQbg&mW+n-Z9?#M@O3Vm zYU8wnpO6I3X0WI9j3{d{Q5+g+!1kIRmB*M-@_9S8)*Q7u9J#EAakCufR*@$^SgLwEQ=OeXx=1z6PYCQODXpPRccAf`oaxb4g{a>`1u#Qh$MGjabwj;fM#J6U9!&)N>7w_R6i5B1RZ-uy8~} z;Ni+Aqp(~~81BdgY#PMdVeTmT3`>K~-8N8`H3jz+xX8~IkiqMuTVBUNypXM9E+UWg z+^@OxsuOx9!lLv+qmgf@QP$zX#+^-P1D-lMXazm>C9Lz|ozOjclh(Ag>4u^Vd#&UR zF6zx^G@hOn*85~x$5@}eloi}2iJR6I9=jnjhRBaECvj1Xo*w_;44(g$Fp_$FaEzzH7MOz&UQb7E8K zfL*}AHlG1oA0GkHK?{(F(+3<6_<=lp9mvDiOIp;jii-~IDd;`M)5oXO=UE^fEPc#R zba+kHF>p*hIQ3`<*jDx&SzR`Kl0LkFeFSVP1NBDEDhlt}5lakJn+9%guhZs+2A7F!(M4mn-#~TUAz}tIAZcs+20F z!C+N+dTv#D7F|__Ml)8Ge!mxitNggC)NBwSSWX-K5P@qlR+YM3a_Fj3soTzdHUe+_ zy;Wt|!XHV9nGTMejYpT?%nRbqopC0 z_j1JkSF#e1Fnz7pFC|@KRa|W=*p;~~eaMa6)LWb#4^+_I%zdt< zkyGGp)Y>KM1e9B^d&j+v-}iJyl3rV_w7|s0<91q-=h|A`V<+1TeqbR`>(&UTlfn*11iC)Qgn|V^Bv1I;zH{IRA#L|N}`*Aqw04m^-IyC>frIp zX>e3s@14sMizb)C1(KI~I!dcVjP{AA8mb3gj>!&UOE1H?(s@- z>oEbJnKPf$XwlFrgwCZ)u*%93wZ2|DmutF%Y0QuC?Y?yK? z3{Hjvs}v{0GBmpaV_3S*H=7=hf3r#jV3h%=RbHHif3pBr z=r{$DQL9vDSmjlhZ&n!~BNhm(Qrr^+rv&n>Rk|6&1T*;YB3to}Z&rEUYSs1ZFvU95 zDkU{zB)3G~GlwM?NA$U9FHW#Bv-Ud4u*!+ARtZPpky)#x;}DqeomCQmRpO(VR(a?< zt6bDV@}7pozFK9`oK@DH?rI?{1y<>ZS|xW5nQzW2YqCuRf3nKX0KS!|RjSCWh#Q%; zN<4e;y4GW3b5?oDMDJ6`inm{_GW`du>}NmMo@3UOLsqtzmz6bcv5NGIPjYLH5}JsA zn2lN`0f$;;7_dqU)G7%~t0bRa;Og76Sb+;zW#3sYgJkgBND9SQ3`f_bI0lbkm0mKf z(lO}e2;|C+Aw;VQRwO+cj!OkrY4pu1W0+PMeR`=3YL(_#%n^oFdIPJ3si;-nOBcYW zc7`5FcM%)>YLz5v)c01|nNpsO^f0Y*Q`&pF(F#oXo!qjB_W%WkfGLjn%8aCDyMCI4DT{^y6NReC=D!73MMo!&gW0b=Ig;;2=s zF|9Ig)+&_~ki@olqtVML;g?i7i-A>+B%)UNg<+K&A{bWLb&1Xi=f!bA^MF;-P^;vB znb=vOVI|M9G0(I;T&1bvSjVtRv$T{M)GE_}RZ`;w(l7V! zMy;~^F+zBfKc5YgNvgJ^?Y_v&z`) zzGjbe8fp=?hIQfD0_l~-h7}6HDjiX)oN1M%s8zm9N}b$Ox^pPrlxdZ{^;p$P!70=#mp!?{o|LBz ztdc}6K8#wWb7jL#O`QtivO{f`n?p*Y7pDNLoX@mMasPgs0No^pRa&A}+0X|2GpzE` zBdx)BaJ`aYm26at+&p3L(j{K0FY?M9fmN!aR_V2xc+ETdnKx>c*$k^J@H%U5nQ77$ zyu-QnGFyh5JZhCQyJ2athj%n;U|6LLI9>*4 zH)IOF@{z2AWf@kv^C|36At&z#6QZF4uMm7R+zkE=UD6JHLXzZBtMtw*Yco+C!8QV` zbpHsOQD?34XymeMp{P~z+Gcub&sn8f&Xjgpv-a)h46Ag~M6EJu3+%fWwMr-qwMxu1 zjJDrUVd^Aml{*<$IoZar$}91SwsTgAyTsj!S|yu*#A;X+jo9 z{hhTIb5_~Gu*xH6c!*(az$&{Q99$0n!e64uuu1|EwMxn})G7}EtL*p9J#t3oBWjfg zxLJI-Rb=cREH!6XWl@oGo!=5*mDJYI{yPxv7H31W6)sAt=x!U|-6b^}-&Ng3bgJ4` zKDH(n%8e&tTK7XzpX(LSY_YsQ>wjDezfI!((SiVs~lR=Px3iow5@-iTffOfpzo~R<#3m=>ztu16xyl1oZ|j2!k%7gU%=Yw$~1>OCNMy4?=NPNxh+c?Y$mK zeFE$IybGj5S04+|8(!CZEYN2-wDxFN?QkTxN&9dZ997>aGZMFLBzW6M{QBX?ncoU< z(qC$opa8!DeW_tADtn+WFaKJx1XlUagOwbAr&Xr@{Z^^^)hY?IR+;vPRw?s?Rkr;{ zSfxTF!z#_-?+S1w)G8Hctulvcm6CBkS>++{pk(A%tGw}(RYtlxa7lc%N^p@Iy}2`P z019wu~t3+lC@Ms)bfbT)A(mo(ij%k%?pfHa_t+JeHl`?1n-pjN~8KzbG0jtdF zNc-6;RTx&8{fL#+a8l?vU*$s8(m;H8|O9;}qF8*li|Dix~J=B%<2waQFj zl`_>31z6?fIjc-XtunfZVU^JD72q3xv`Xs+0SU`RKNjHD46Cf>Qb4Ve*lqWI)+%rQ zu2l;DXqCiStBm@|Dx-hjDu1H@U;po0<>p^oWvu>O0WR|^tNghDkNakoaer!+I4r#Q zUn#)Nf3`~JpRAJoHw$nJV3imD#40uQIqh+jg>iFMY5%=dq6N4r(<%j{QLD^mSY^d; zTP4J1=FReb0dDz6RtXAA#)Fj!KUt;Fw*q|l2dnIWLvMVu%1g6W>H0fX`QKE4uLK2n zAMP)=N*D8~N4&mDQ&K$3T@2*C@R6&G(wANeHI{eijN=KsDCQ4FmExbKlPTP+rvw7whH^I!ngu=99@zTkk!7z;oozyn?rT?eij+-|)C{ z`E+!u6DYuqru{sV-@bC5?8fw7SaoI7@_rttDxoJnQ?bp|DAzYzZob)as3JmfOp6lU zl)SSnW!ELvMjOK(hfMbsx45^T;0$~o^6tGp#IxF8I*^u5DmTK7DFhu3d=cyBVS@Nb zhcyTGniZF?BkHAFaI!rQnke6>$s=-FIjFy0rNYuoN%)Ly&_L#)na%cNi}i(r2hWXM zad2JF={^04IjZ#GRp( z7z=P7?jaAM^bU=~X;; z?;D<{yp1aKPT=PCEYYc*pjdtCUwX=uYkTeFX=N{(7VigE-`Xj+ht-lYr@XoZ1KwQP zRW(`8ZGj~HfiF)g`bed@&!&zO z2n^cq`MB{Ddtv%)`#t@&{qFSr+J4J`_B-ZR?YDuSrM;gBjJDr0G+4P~w*4kD+HVDj z(SEDXw%?1Vy@q~jzgfSv-}2LlBD4L5DVrZ0pKZT8VQdHG`}W&dQ)-QexDccL2A@OG zcPbII{oVuGZ;22O(0*euQjGRnuG}Av7k6ftaFJnCool~U{d5%UVJXmlZvt^Q+jGOxQ|+ix1$e#?ROTRdFlH`{L-{DB>M3)*i1M*FQA zA@jBUo(RF?(f0e4AV!u9*E8GisbKJirnGC+90!(;U#`+zpdxm@5R_Cg@)6h{ls?d?e{wkH2rpTp{LRU zX4`Lz&{Up|U{x|~VtBedENV>!+J5VQZNI1D(HAONp@psf&q4b=8K;V4wBHo8{Z?eO z-*Pr$Ju{Ij--j(!{nmaHbAM>RA8(1^D4uPOl)-vrV6OeH1?@NSBv>}e7tgle!Jz#%${n35 z=%HRzjaDoAa0zX{sR^G#1B)q)_FE!z`Z4lB2yMUjkA^h1d0)@8MFOviov?&ge}ex&da&~p;!d8-}VKAp#5$rMBDGW(g8;M z{kRgjB$Pvkh-mx$613m=%Xu@&-iBB3w9?$t{6&2E!{rx7LHmu#Jqy}zezg5g@779Z z$H@52wcov$>>3k6`@Qo?0cgLMdFdO2_WMc*`2Rv7CWptM@E)W6KE{4U6^FLpd*sDz zRM6xYeqOP5&Bw%_T~x(%)V$q(ThQ`OsSX4~&j(0)^D2eE~Q zI>#bBXWMV#WF*a7p9{3#swFnIMOVGh_M0fDa|E>CgiM*p$P&k@11~cduQ|T*NqjqK zzYS;GZ{9@(g!qz$jP~0BwBM6?O0;um`<<4ULOQu@j|m5({Z{0-SQdWSDCt7~NR2xu z+I|y3`+dZnwXupdrzQim-xiGayCm01cBMn2+MY$5`-E+mf4KVPCSkqfd2l>U2DIN( zRcQMSzA}qO+iw|0`wiYxo^8L+fX6FaKhc}CRmT0eI>LQFD(*I|f9Vc`6(!n!tKLvH zJD1l9%aLJhQSK2L7J2fmv?~#q(Hp!06$e549aQG-oqW$BRS~q`MrA6HdNZ^AmTY!u zj5rF~?}j1=uPkV;{f-tYbX}9*aVrXaq!JfA4%%-@f^=P(1!%v!PRW7x8}d_OwBN5s zwUR;mt;T4-p~4wP`yJ|8F)`PEx93LBfcBdVD@IeK>LBA*|J)d~{gzA1k|WQy-^xX^ z?YB6i{a)4r%Z*1n+m%VVz+Q4X+n*LHWp^sP?xYhz``ysy6%HpIN84}qGGu96_&iV=-K6>Ji7}~ zY~yWkGPXvP_4EVI&iDD3cSXr4t&!69l1;jl*z+LZ?RVX?1s&-i{U#<45S&GvSMHN-2JN?D%O}Ck zKG1#}g13C08reM!aHH9p-%`$f%GE>reE9lVRoeQxnpB4unx;o_$ip#3Jd>+$s66YMu=mon<u(@DhaPkY?j8}aAa zFZ8wjUiOzVC74v^KwrwBFV~?jteQS zT^;nHO4=+_CX-R71gF6{nWw=ScXc`pC?v*d@Fpfx4x>z&{@rPCR`fJD^c$za)fi0q ztJC0O=xOkVT4j_emBC#dPPJQUzhX+ITL|U5hbom@I_8-24$73pfGOo$h=!b8b}#0b zG8bjaWE%6X&hIg$|Bp-=+8`ipY5XHohBEK!a4VxsNdk9uW*@42_Hjf6+sg zY*_G6CH_BxDc|hqiXAS^>Vrm2L%r_pn=Y1HAGJp%yHfb%fh&1ywuW2Zv~dm=X~;WV zKWf|jmc5F;vhW1=QUa^(qQ_5 z+j-dQ@q#g>SQ@4;VRZ!syv-RZz4YqI$!PuY10K!7H#ZEDE8krn+r7v0y8PJcYr@%k ztWPX@`u?m^iMs0eHpQnBSZU2mTAkxM%d4f(_S+q_-|L=AFHpYM9K>k9WzhCJh0%V? zq3w4eXusJX|DU$s&;Et>yYN4t{r37*`nPM*hSlKnLlm63BTKZtAIUaC!_r~{_XZ#Wv=~JW47Pr-}aPW z+ix{62>RN7$D_BvLHjN9tM*&<`}RBi&)RR-x%S%?rh^ZqU)yi#KWx9HzV0diw)T7C zhdt%j_FL_D+HWA(-?!h=f7pIY{dW6pjgkHr+wU!ZP5Vvw?e<&s|7ZK%@PFEV+x$1T z-=w1ddHZeqt^HR2SK9AQ|Nq)=;@{bR3t|56+wTfkq3B!t4c<#euYfb#Z#Im|*F9w& zv;8*wq5YP_VU(Edw*uOJgWK8Q3OL$+)BdpiUh}_dzjNl=?`}r>ZTvrLzoj9JHn;-* zwf*jZy&uoD-vkV}c7xv1v7c?f!54|l_FMKh+i&@w+HdOIp7Pi2cNE%wt1|YK(tp-| zD}L90tNm8{P5Q0&Tlx3fZ<+7gZw}1=sQp&_KX1Pk|Kr>5rmKI~o|4LFzpEMNblyN; zCjSzjgy#PIv#0c5?)%T45?O#av-gI{WM=n?yw< z0RLxC`M)~=zU@C~PxZD=# zXy4h3B^Ov;E3I~Zd_VhGtd#=mzJrEOwCL?zdgQ&Xemdo^UXbVOA~@TFNy~+imWrW- z)WBP|RfDHnYRUv*+&;3d@FVvMFI~~t@+WzQ^YrW25XKEQdA{IUQ9fJ?LUM8Hi&f@F zhvWB;>(*U<{JGz{rqt>WowHpYMEX7GUdp^Dx1J^~5et2%-&&p3xxFG}fZ z5S@LbGX1&X?N#6a___8YyN#%fM=G-p1n1CgLHn&?%s2oph~eG_4uD@2jdBd1ex;u7 zbYD39m#Y-x*QD}*N6*&3FKfoUI$T)QBgpCwuHL*62>3|s=9#|sK4m;;Lp2xcDfjDd zK9764f9iX)ZD-RO(bv(}j=xyEeWqovXk)^cPyMI#Jnls3)n8b#{F&B4?9DvUcR}MH zUp{O1BDVPa!n1z)*h;&P%1?dXf4RSWT>7cE@+Y6^F#){^tle>9lF!UdbG@mTPmU`s z@%_*pqxVaV?Po>1FYl&ar(~60J8|f!@6Cb@3ph_6^@EW#mf9N28#psR3^9%MW=+FE ztuQO2(_h}r-u-s-*)%>ksl?HJ_QJE1$`4;Bl@ot9sdVtO^!u|(<)+z5rSKx}k)I}& z65l43iqnWPb5cp5Z2slDN#*ztlS)%fsdXOWOTM2}lF>=!J}{{?3i0}GQmN4G&l)ej zi(O)m44c~TO)BrBlgf|o;aGZ1xD?{2MM5W)L~F*R((l`(GKV>-3=G~qKPXCOc2X%( z9=g$5{1jtS>B^W?u8&6&x+PQMgX120b^Ur$Y52R7%1`XjJ5C zNu|KIb2@jvn^e-lrt+srWe0Oo$@<+nog@Cb)E_35Hgl6oVc95!UUX8)1}2r)qd6qz zCY5y&xlTV%Dit(0Qoy8=jWR(>;AT!L@&4Oe;`TnAn^e{%_LulhW4@i!`C(G2cJkn( zWDa%4q%t5T;K=c&>5%fp?oYDCPVSDvew|cO&`IUJ?mH$#O2e;{O8(h%I*Ug9Uw}y^-x*aR zV^T>)CzZ;KNu`2~7;SOXYQgY@=HDijs%<|^DxZ2raCFX2Dp_q(vcROWWOh=yQ)6uy zV^TR1Dt3lTdDx;q0W6Z8Yqqi}&FVh|-=P zCzUJXt=04Hdt|V5r9k88q;e;7Qb}P}f zm{hX1CHR0zH zmkI#5I-U09G`(;sTQw4#rBaY5uc^4|Y)jS>VVfH-)>0_~S}J4j!RK3!^*+i6EtO6< zOXX;hUUEe0}Qh2RlABhPNS16nHc8r)J+UwWqtf|g2atfjK| z&{C=L%w|619%!kYtF%rofF4;Yqh%@_?Mh#4;4GCw{@b9XGAD_1rr{!JsocR?DiJ>| zm78nQ>7b=jA7`mVRP5s{mBC3(pN=e*BYlzkhnC7ptff+Y)vLG~XQ^y2;Ia67OQjTO zsicUy{-A-&2Ks#z+>cHoqsDk& z>QIRMr|DSt{Gh_$#AR2oxBOES2DiM1~&cga544d36G^_{&nM zg0)o6-+Vg-S}JGWQf`5k$`v`0RMzV!uAZ~!?gcHCS9%U4Uo3)_$}0_|=2K@MOnFDo zm^uy!_f3%<%>0OX60bX>HS;Lld-fugS4G$C?G2ozQmISWsCx*sROVKm*Nt^LJ&PQ` zS}Nau=VF~Ez#p1-dNI`kS}HAuPy+L>B^Q*3IL;m{I8!ZXEG_72aa{0N)EQcszP@NO z#BO{58Y>r9uFqP@vs-#BS!gZcuPoY5BX1lm=_@X3pynLgmUumug|%iy%a`vvx?Z7Q z@g8!vlU(ulSTPA$32s}_3UCfRScxR_i;@Sk-z%{mt3J2v|FBg4pRLo$12Ba+OJx^; znFKJa0OsreL9y~b-QWMWmCFCr>HMcor)G z4hn5S+>ZX=l>GkhcYptnD3$-65a*xiOEWrgsKx{ zH;0`Fr{n|5oCew*YPu##{NtJyy*`lAUwyl4bFZRv-isWKfGZ0GwGz{wB7bT9?w%Dn zz6;brEN__;4?o5&G5X70vye}{Pam%0B~*N%89tfKja>4NSWDSyj^g0l;gndOFEgzV(}^Sh1x zKRyuK?oWOk`bt#ykm1Ir?7Pn=T|1aPj(Jw>&wkW$Z4pfW=q%_od+PF+r+VgFK?$w% zf)SSePA9jO@xL#f$*>rXk^hj?(7m92`J3WK+GjiM(+uY1?)WKfUs&UR(Az}pW2W1_ zQonvg?@IpQ>p|NtoK8ORT*UXQCm!#8z9>&0NdD0N^y6>SaR+pT!}q^^8Pa?6tgW&3 z@#3q3LcC`(CpSyHms(5(+RhJIcA)nI6tNi+3`IMNig7;#NsZh%Tncn1`Kf81U zZLSU+@hQPB9l786ly`lvWcx}+|EWvo4#=mB!SX5Zxc=6q6Yb5!fR+cIf?$h( z)1^}kcIlu!a}yEyu29TDf~W<^r+nc}h3nF}`>RXG>SveERU4P{g@K-jd`fEXz!hKd zPF$DH2(C+~#+T44=u&pjH3qk0{6F}Vzq)j?{#}<&WCQ^G(WO)UTbGUp7YiEXQ_j0$ zyL5n`e9Bw6E}hq4mrmp#e99EVvmG`;LTD_Xl4UoFg%R7O!!jQH&PIkd$xxHwelU(t z`QaCzvhz<}I$)K~!7o20woB*5&n}&tzws$)dPML2-lgMk#HU0@4fn7zgM3OhET59F z2t|Ixr)(-zr~V6{GTNIO56h?I=QTjZu-y%Mk%)f!kDTPM{WM-((wcNl+?d<=>Qp&LY@io$d7JE*-C+i?cPT{?5FML|uh z$%lMOeJr0cr&#O5+G%63OJ}Ee8po$hYKl0=B}7 zOTh9e??ha#GS>FM8E+QQ}iB5BZeN zSU%;lY5FEltyMwd*+V{Mb_d~h6MZd~Pbrd82RAK|0Qr{wk7nk zwG1-pZ|xc`gM7;EY>-dsa!#m4Hga4R%cso6@hOXC;&o~A)nfcD+1sj~iH+%C%m~Iy#NW72Oyua zB(;D$vzG(pQ#!SC&gBz%{nn)uiQ`j>#gT0VLO?!c%xgQaOXuZLm(ErV$fxv7!}2L@ zK|W=!XR%luvIWbhv?Yby2fK6-uTN3o_>>NnB4{)N$fvy08<;x`jPw(GM;eZV3OhXS z8y#VIbm61>^W*!?eRvZ_Tjl(fNyF<3sT9m_eOT_qZyLvGY0nD&=2s*b#7X7cCuX= z#-XRoxGo*x4R6I(ET0m85~)b|hT>!=H^`^V8I0JT4MWXH%X9XHVfmEvQ}crI4^bx< z>_rwdwK(P5tThf6tmhW=rx(=P9_o24nprKHnJ*ffdr%)N>dh@$PcK?(p-nxO&RZ?n zYq4KwgR>kg*@VwIf0&~ro4;4i>5K2;aj>iw;DVN4@%6athow|Ht0Z8%zt68=DV5$Q zS7XUmp8m$Cl=-iM-y$agIV8Zw#>UIbD=I1~CntyE0F=1_Wo2beO-(&LJu@>iYinzJ zdwXYRXAcjLNCTkG9%#A^^tl0Z0l-`!upS0{jsdXlS1D-xUKB1wZv9YnKsi`?RIb~&KH8nM@t*u>MUH$$2FJHc#oSa-(SXf_Q-`Uy0 zU@%86%0K=WR4LQ`_Xof4ICP-ueJR*DE>O3_2uR-{ZKtG=g8&6Ws&G~{dLb?XAyLZP z8;$HC=fBbn=dQ_Djzrk6DF-?g9BBXFRw-Zq-w%FE{|bI{|Kw9z5Yd=4BK(;Sw8mxw zsBT^Vv!62YPkhRyzXrb<2sp@!7NRu`jB=x#zmF}%>Wl0lV;xnE7vs$)T-oCtY{nN8 zt-W{I6K@3?FD2V+5wInL(66P`tLcQxjE*nvnNqT)TTVa;2OtG)H z5E%RxI|_c2!p%C+czl&QUS&XKF>h|`7j>09O0!u-ABnHns=N+~I1j$d&8? zgWqzQ56DEZ!EZ@0_)XeL{Ahn_e)%x?orwo<2}#094FD8`c#a9i=Pb$m=is*_Huz29 z)lq~Eevd!_3om#Q8F0*6hveS|znT6u_-%F+{BDQE_jI!#TMwkqW$_u~Y@mAa-j^sl z8=BnHP0BG6+-f@Voyxk&+StYiKEq0VlkPO3C23&hs(HYH^}hzc`yr%1gWrPx68t{? zm*DrnAHnYdT<{wYt#Mz=3W2QSP$PXfVtWu{<@dqA1#fX60%g#Yh{TBSb>SZpl^0&cnQG77?P4?H|cL=0ZFY@#W|u@9vKg!C2~ z##D*8MZ2}wKy)wy2EW6hPzJLh28S{RF!(JE2EUOODCSaJ@S6-9{C@SP;5V(%#5nc{SSW1e^4p$lO~rd@1}MPlHJxwnA#Tl%J)2s{O;|Dx8EEjQ?rRT zJ$slnNJ=FYKAgy*J(cqM_-upM_p;kT1jl9O2|EbXExf6@jCt_MwH~Ne(%#7lI?cMP z-hD6TWQ~2R1RKM!iF`T}O)5(6Hp||1S9@q|zsh35sxYClJbj{ue-H1Mul@XFWH>&h zwhz9L16u4j0(OD`^ix{;|Kw8+=dge(rP67DfI%4sx4T;;`3NliZW;5^`dpRrW5Z_i z$(zxkFZCIxnV!*9P1z~;;`o#q)-2@?Ut9NoD1j}X?=V`fczEfXe%cTGpl3q;dCWfs zfPPBO48+qMh3(j{?hE)CZk?uW1Bsj8rz8cxJ@cHV$`X7SpjPp%Gvg#l;O$3K#)9sH z&*ryND}H$1sMvr0?&PPY%}4HTg5O_ZPJZqXJh&TF@c{qv0ddvsHjgC1A8${c`chQU z)>v5aWA^f?Z{wS7<&A;|i=OX@pM&qi?#tZU38zel&w1`@i}_q(&jg6j=-YyE!gw?Y z2zfiS|1RF+Cu**KTptYGarVjsoir*>i}(jjj#y+Rb)|=$<4=1f+=e9$iA2qdNJOJ) zMO2Lt5NZpEAV{o)!YFhA)MtYy?6Sg07F3LWB-G0+(u2zprcDbG)PYH$V9L&Tl`5Q) zAhA*hBIX%!yC)S-2I2WQgRm|eQ2-j^f8_B;fxl8 zI>?hK!iXb%eEnf)mwSjOr!T52+N(md5 zrtAPossNN?fN8xS?V)rT2Wu3C@sB`#4stGnO+dmkW{qP|AsuveBBFK-N|Gpg6O=Bq zeNGv{1lpnAyDX9bj1P>0D~9mlqTr6I_e@-aLJy_OdGENM;6$6VBw!7=MX(#Ks8J#! zXNAYZ9hM4~K*fN%r9fje|6b_J zIVgWq2;sIQbCQa&E4gedB8aMjz3t+^Z8J{ z-0}O&2ysh<@kWZBS`A~$4!$^&o;xRvIBEh<#;KQjL76~%I0==gNfPVaq1bDO1~wDrk_LDDc(oL7m=K`smjJqn4#CKlpBjUP|DB#bjJUH{{F^%@+YMW zgxhkrRuR{m5yEU*(dvHH)cF@iGuGfK}QUNNMq$P-h8sL&f1-1=5ru>?1RTdFI0}7bv z3{b#iwM&_3lDujPxm=VJRf8bhw@bFDYXt79#BTkVdpf3yCF}Dh(0=J1zB;sV1nUjmrr1*785|MOEy|4Z5Xs-O!vZ zX_>G~D^ga81x=PQkMm{f-nTSwwsbs9fpt`O#?jxWSN5i|;#F=zG=``K^nmJRPBpAV z;5E|(NO_oxXUgVh}k^B5^CY@iGq2dS-RRD4;pGg3TC5kZNN+@w<3EBuEf*Q>9 z3#Br7LKa;-t6I6S%|GH?NV1|m+|^|l(k%suukf&>)#%@Q;vbzHnjNV3ytB(Oc<3cn z7BSca4lgcZZfrcq2J$JvCh(h$*mj+qRcIJ*sOyMVqzN#VatyB>Ed_Eb+kx+E(gj#< z<+JQs!y698FgN_>PlhqQtaJ7z0K$ky2r{i6g~z}TuY`)}`0{T7IU(M~bLbQj0pZL- z;jN!0O9=#wPRE2^AK<}pD-RTm(yg&Gc&qDi*9gGfud?KuqXNN?V z4T9>WJE&edql-VqN%W86>p|R4LqbS}g@xXr3z~Ue_}OLxj3F@E#228+GQU-a==3O5 zG|I3tOcMQ~Z~i&=qYLoR7q45o<)|l(9EwF9lIK#uC-L27;!(ZUY(6{gGa4Lf_qm13 z3Oc)?k5`^iw*$mm0Bw7Y7%E1YRDr!2TMW)GZZP`@pwyY*i^ZBO>9&CR^N<~!$&wiH z15(LeKtu)mcz#;0Pk^F*nx;J*1XrF(WxdOf_i&2m4QR3y?IkFj*nE@QoWez2PV$PB zo4$?x)ke<5;OvR%GuQ38S;{Hyg>kW)vor6?aBJ1^hPS>O?Lo-DMa#@ZSfLmvky?yn z%;EFWT8$_6(ek(6sL6Zqq%Y8-AfLW-37)))I#{r)errY;x#T#_e!C5BX})|#arwSE`@M3w+w`(&=d$-S(o>%Dj`@lr zmD{a1E8zkzc3)S((r>+I>7bu7@fLYh`fBR*D&y>G=E*hkJ8s$LYl**1mUwXB>>u)_ zKPUte;{(LR#8gDU2`Ye^nwpuJnUfw6VE&VQ`On&A@+IKey+5?e4-vrE*dy&SgA|iN zfhobsm(2hsn;xrRg3e1&zN}HeG-+d64Kcm<{z1yb4EbUv^Dwh@ziXP9)n}OZFAkMW z%+4%k_XAen-2e2q66YUc=l}nH;UA#Sdi(hL`3D3B1&4%&g-1k2MaRT?0|^On$tkI6 z=^2?>**Up+`8kP2MFpj03t{S<$F)vlE6nm?$io`uJ z>q{*n<^YnVoH})jY6^yRPkIuanBeAmo}+qm*4APc^)y!}heMY(vnzn)RG#fy87^8c z@>3FpbL#OMc@?L`O8NTZ`HaX9Zq7I3@ivs}SDxBfQwhFTaXITDhG>Y{*7{qVH=>W6o-5rUVce|&qoIZt2i`FQi-VD*>=h*bWzLTs*rJiyAR5~~X_{Bph4vAPCH*2MZIO~`l?t?|VK-CH(D z7K^KdOG!5QMWBpYJPy5d<%90E6zA7BmeXA6KIRACc`b519es?4E7Sc8;S~Ngvf`EO zPy^$_tlID6E4i^E-?(zCRZUj&QzzWG^DAv8Rts~z_qYqo15MV7OSK3&iz^Bz)=Klz ziPpKRUlgzB*H4?Mm$w|VTPM8)tQ8%VXt)gftL|=um152uG)8WA4ohrQB8RA00D!_GwCXAI6-mJ-35^a*6oOI~C%ZgP?CG+^P(Q*-JNs%>pL$!-D!(< zBpPCI>q(36jt5;sBsbx)1XqPPe+o%_3NN*3Q`GLRn7n6Pg_=;J8PD;`cGi^{s>>i@ zaN}CbDKl?$^Zcpz>PGM>er_u!dtE#r6PP%isYU~!A@SYP$BYQ?ow0dA2(ggj3aapl zDl~{jkBCs3L!sSH5CFcF3;z31HJMXDbWbi*&xj`x+~Py*CtOVYXL#S$?^o+hp11rw|=G9RiCMj(bk2qBM-%P$@#&-0$z+ zLyde-q;@&9PgzG_qp0P%^MR?7WPz_puV3K3PK-*R5qVzh8FiVUn~9nT((}f?a?o}s z1N9}LH%4&%p$#=6U>ttpbN3C~@?;aLoJDV=UY=P2PmMlPq2b0{dI~237Z_OXXsm9P zOr55!Zgy%Eso_qP9jPtCC2>Jb{eD)sngYpnN_o2T?9#W?rZrFr48=%Cx-4&l7lp$k z`WHfE>i8@sd^cv7~YM}iZb1m1iEonF} zPq~^n*9KkLnEc~%myqLk-|;id7;;crdL&j_T`4l@>Y-Z zi@OQeiPpuaHMysQL-Rk&3Grw2^N@Rv>9f!YCv8ddP-pDga~phAF`nY4e=JoivP2f9 zc6XL}Ug}xUOl3q_-mEc^TMuJMRcJ)0wKc67dN0q}=p=fMe0j>%L5J{~)XVS%#PHsb>yT6En*H_D`+LJ4OFJ?;s1?N= zGzB}Qvnk0Xn|q-u&rL1GvKXUmRM}Ks1bB4k@blAX5?>ijeHv6CeqmLo!TO~Nq^?MX z^~QzR`>&X9i0kN+t_So?9Iq{}Q@Hg$*l?W*(Hibo;dws7;$YNjtox)`j!)FObxhY- z8>+sh0dn)2r2E8Zp@c|o*v+dpri@b`T!h+4!yH1~=@-)dn}$z>I2&GhyKxP#_!VT+ zHN&VHu%@!d4X_*AoQ{)FEC_l!=d1Fb&dZ+Ztc;&(DO z@cxg4IA$JE{ZpDRN0qKCT3-@2r5_GJ zv~9fcJt5Cc1tHXmTpdq+D9mKfL=?*5f0kTk8Vk6hKbnv7PuephOg06?gfqC`{{0nioK6Y4IuDP;Sj|_}lAq z%2{?FUXX6-f-)c;yh^ZB{37}O)c$nxlSbuD&rKxV0|Z>6F_YXL#rqnv1JRW!rO z75Xu+wgRurEl-5&)l){^b{yUrC~vMnYtAumIxa7^163~}S1UmypY!?N>FwT9Ha_@0 zUZ;00WfE;siRjZyXQmx}6kM+;^$^Mxa>zIc5n2F5TL9dJ-#7<277366Fj^Nvyf5e5 z{P@(3yk|u9w4w#Mt@+P45^B40pwOy~2*|lc9@Na~1|2{Q?r#9q@`g&?y25#NjQy!E zAteGrD+IgzN%Z?H^f6EOrZvaMFS70YSv>wl1=QKTca4Fh5mFSo+D zt}OuQ=%BbQ|I5)*&`N)eY8bIaa1E940Thte5P^ST1@P!Xauh@Ei3FO6h}}cNgi(+z zePF_dT~^=Mj!HXU6+UYOkwd{z6tFwg`WhlZ2HE}t1i(-t=ZGrdi$ZpX*o*bz7gZw9 z$WVa)U%7OU@}>i$cZm{4!SGxZsMMl5rBEhyq3WFhatN5vOjxQaOvu9EqDYib=4tah z6?|jP6&v<7E-_4F;C5rsU8{)m*(wl=u*bBLb%{vmIQQUgs7RwXs_7h%se9S+G;uqu zBhNp^Po7K~9w@G;?x?8XCuI0iz97d;t5dt%iBN7U4seK*T{Kk^g7mNpS?=mr`w*TL z(`_8#kTzzQRTDkM_D~6R028c?#uJlL5mnKwh6!&$MP_2Y;=v--&T4f@56z3^srVFj zM??2u5o$_WHGzI^iF|6pA`Xe-BNpv2zt(9Mf+a?WxTD6n@>P(lq< z;UQTsFN7i?f?H7POkmPl@ssE!>MbbMmaycWt}+|DMy-EBq|}-c1QG)Pivg5$;gmB_ zns(`3J)Hzl%-p+t4|z#3mdL{`#EvS_n@zbP$K>|7^4%c9u#1942%vXN%gv2Y#Yeq( zMsj&x?~--2icpYYT>AN!rU^z$yMzhv0!>$91YM0nt9spS9o5K;*$b@!N?S$CMkW0u zl+Bp31`?1z$bor^sZi;G=V~;742xr z^9zO)TTlT&e{Vj$V^La4CXRLs8i;p6Cl4@|ftVR-eu9Z4whI)9roEDkQx`ciJ?bZb zkn6q@bk|u$he`Wv9CErQM286S$_OqPDdnb?a)vu)58v+{jHBumJLHO#n{WKt7!kx` zvO=)pMJmY#WB9n5q$yl_W>56gl~^|v5Hg)j@d5a__QZ>LtpFEyqt2RRDw*z zc`9LYl-wJ=GY8Z{GRa6$wpe8qV_oP)Qh!sK;9&fhx+HxtJ{rqunENrj2#sx+^~+d- zz1RcUz+CNWS5w6O!4-;NR0(C4d>+ZozgNgIT~}qz)V=0 z?b+~RWNMBOB&M7k4ydVddUCUu^dV2pODnuAS+vejQ!E*6R=G?o91m0IUq!YTBk$lX{1qHJbP?4*0&FRLpSj3YMG(+X}M2Gv8_uDfNEe~dg`mH zAF*nC(3*=>LX~ecHK?@XM~jYK1!zWU&&xunDI`5$TI_wu0`BsC`A!8r0>s>pt={xX}Qoua&t*A4Fzw z6y6ECs4H@2=3Bg0_Jw0x0F}_0J1|uzXlgg6m?}dV8@F} z5X$S7X`K#iNbHk+qycG|)DjO7=XEdRZ}GB=&I#bvF34@ zk?xCn6$?R<7UVKDV8_$^Ipn;ndwUlkznt@!CnUcx`H`q*>DF1qMg_i@~lI4K-9g)EF!)`8Wl z7P=EiNo|FkyX9VS5!$f>>r}69p>M4>k5y#mdmOr>KeLZS_ctR+;y6mrM6Mxuzdzy+ z?e^p98dvtv06U&yvlWy5314-gm>L{aG!tkd)aOnc91;Zu(aOTxpw%gzAajQLxDfq(YwYouPkQWj_PI5^94$_*1u>2M1DeN1?vYL$sla&mR8(%&zrcfyv&A(!EflgI8OCAx4&OzNf(M;&bg&{MojyNLNdR)VZ z_7l7e;QQ!p7|ca-m?ZBjU zAnSQ5$7Z1Lm&$>kgJg7I&U^9iVNFm9*n-TNzS7bJ*YTuB<7tCx5TEA@GBEryBm@S5 z`#!T^ZH%t$zAORo|J=aPI`NlAD9xgXA_*N)WFJT`>y9H<`H+$1U zwr-A6cZ*D3GL9GXf8U)Fo-%$`2{OqKS^ps>j(FQ%&^=*W*_8=O=pF}b0sap=i$;v1 zb3#NH;}aZWP&#A8wQu}?T-;$BEsnf6bg(Z<6;22%fx*_g1k4hYr^arkmYojcOVHrS zy3Zf6@k-q>@nlg96{zdZ05sscGPlBORTc6|fP?~a$InEe4H)@xQ5==DsE?wZ0hHt+ zy5Gg;Ux^S?K;GVe^_6x}S)i4#W`RTqa+XjI-rajc@hwr+%v;C#9LLjJn*QOBd=X+j ziGgLxQr0eQ+`>1DWZIS=v>_Efh4iv6t6!M!6j_P$4%l*9AtGBnVYHYu$sb;R!`Xvh z4c-tIoh$~-hJ~*L3CODdSQb4A{t%HR^8rya z?-byBtaYQqe4|WpqfdSV{lV9;cX}hQbK^zZ#_$LK=jQLz6yHzCzkgF6lsNr9tn>X` z+xvGX!^X`&#CUs@z4`D#{(kY-58LvaLHBY$d2H^IxqeLF{64+;b!HPdwS_0_0lmES zL5B5+a4iSsw%SX<`OAD3(IiZ;TXuRxh?{m~%xnr(@D-5gcT*hh&HgK8~2lwicNYanD&S!xnxs}>`Vhwm>c^im-kcX`OMCl9lsYkmEX!2 zCrY^1iuV?A`t8Lqhpjii0xIu z%yzE>O$xa{AE#Y4$`<~jaSoejMVC@?%OKSb<1Te3k{>RWxpjRwv0q<7(F9!~lHZrS zIo>5fztg*bY?UgaY|mkcT}ca zCOesHL1mTgiD<=Wc8coemg}s3_3rGgUEQXSOP)RH>(}b-1!Z;RA@>)rU-)rxa}K|m z?s~<`%hU62sc(*VdHu=i#%9Zht(}7HPhXS1?CuAA`;PJW4mr+s4$Y6-u5?CynBp>5uem-teou%q~bM5MApE~PO-%mC=txpfOG;F?WXNNIp zeSfvZQsGF?8Q$Hvz1SNuBdx`J-e-k$d)H;2o(u`LZdnUs4x{P?A3 zylXk?q{ojhUtcYsd7SY8GlPN9&)kN6lSuc#+jc>C5`L)9^dw#Tf$$t@>;^`HYbmf)m`49_-r5kW>*&f%|ZGcd&#HqZ1%F-M)MC8g#xGv zl<96PM5%Hd$?7_1xff&g4U&-b2G@!}ce2asVuFSh;ZmY?{Eej~?O?`EGW+_~r4)y! z+{>wlviefda{7ZWO-cmH#jDGizI3)LS%DlA9GM7$;+34pvplQ0cSP2>@)EBVujV_M zG~-3tIr6L(=JKo+(PhRLgR=Uxn=M^YJaZr{br*kXYpIiTbkCtXcnCnlBPROcZBAClffS)uv{w&6p##e} zc^$zG1xQE>pa4A5t52#`2LSLKra1byKcH?8h`x~%E~X_f7EKk?yacr0r+eu9!l7Dd z>h;Yzq0jJJR_BWc#8SSAms;*iOQcG`0rd0RYX~J`f!6gUQhLBaA;qTQMi()EJB4(r zXroTkE5cI%n&c)&sn3k>W9}}8;7#=1m;7k+U9yCl8&U^zMO{HKlEC4}EwTn!CTc2R zq7^>mctCo69~A8e$>N6i*2}n(7cNkW4+%rWPMWl};5%&uLb#<`6&C;lPLXa%pz54JKY9 zqe}wrHSbu{Y_S6~bevb~d!2gtmK{dwE2W!*5}aeFW!{eu6_LJoPD-Vg3aC4C`Ex`N zCPWYXyAkY!b*R)wIjgtw_mw21^<(Uvs7DPB_VTyt?)VKV&o5K)$VOW^;m_`;DYr=U zYgjs8zq5VvncV$RsrOpxVKL@x=S@Iol9QiI81?D53_9EIWAaa^q@_~jcfdz(WUGEE zVi6@Opgil0KOoCSq%y(LpcbR0>2vjrUb2GC(_SZA{S$2Oy5*vcMa!J;b3oeqMjZ@l zjp$GC>YSH6z7Zx=;pk|(I_6t-VdzFwS8Pnr%VM7*?z;2ju=a0sE(Q{(ovL2HWJ^2y zMt@*WE7Ix_yYbaG&!_657fwUEE<1WHq0TheRAm0m#e-dnOi$i3RMqrWW*q_y;_udhw*U z4#%V#J4l2OwG!e20H2K@sYs-@L{k~~bL<yi(_G;n`HE7E9n>RSwf65#P4OA ze`)@Tw-v^`Lxu49{uBjuptkIKVa#=h!z`B_nDyy=alp@kH8^ zj7e%#f`9vIm8lVNpqZNFO(T2>bFy$d3+1`?!MrYE_AIkdIKyMYM}fR|(rhdsct{H< z!whE%$FiEo5;~Aj2Zd)Y)W#Sq4WV&R*brIn{ahsiqf$k~1tQOvb!g!86FB3&Y_^mb zA0MzWa5^_ziY6}Hb0Ljc&un}E_YrIe(SunRRZ882YkQjLg@|!gt6qZZW!%?IqE0nA z_t5AX`p98s2l*@1Q29mg*ZiPTaDKU_QU1)zJKgpIx|W|Ls=z*Q6=_&HI!4)9;T_F?r+O zrwHKy6Tr6!zE4pCG=MMoJ_UsUFz{@I0t{pT6FFcZ4Oq)#Uz)=7f$Zx*#SNg@0cgDg zbUFh=?!fQ^V9F0z2*nyAz*q7g$pEGbz;xj7Q(J%IM!+-4Z9)4C2+pB`mAJK>i}P${~_#h9OaesA1r$a7Za*$QakQ z6v>&v&E*z%(l!e|cNZJRn|FnMxmd8Thoo?T@n{?d+&ILH` zjdYvha{KjYKZR6dMx8f`Z*nY7N9$fwr6FY{=n3qx<{=BqckYooPNm1)X*+nW(LzX6 zla9Q9fg@S=()G7DKc%!>eMTJ<+*K|wBz)P!Tp6wVFS8u~=UI*h!Di^dS(*S$KW>V5 z0A>!r%;RR+0KR|t$60Ltb(TbM7PMs~ZWa#($~#TpjT3cP^Sy)4a)uSht)i6cHM_ka z92{i$%5H(T&P{GfC395_kGn{TdcK=1b3=RHwjm(CuXB@-ik|#d5dL|4J4O@Dqv7a} z77FnX!=>St2n+~<@7!QU5Pa>f!c8`g+hR+&$=>58`@8M-Ytis-{$)5rMok0kLK#QA zxC$=R;cyodb>@bt!n8_8chDdq@57y|-bU8Tfc2Y#{SzkP0fS59^~V{_j{ z6YZgczUY7NVZcoy(z`+U#5D92jzQpv*EEhM1h?V>cxO=o$bXm++=r>SA;Aetaa9u) z*sX{e!p->xz)S;}MeLma#qzmZ91FF+5k6NGy;@vfPWX)PW`v(YtCNl;(Me5ohq852 zuA>;&$qRipwKh>E1y4%q1D~5Wne$48zK@QZcj9<>Ek=;KhUrCQ20ea|jGL6u7lMcQ zw%*=`et|(g4}ybq!~6mw&BH8XOcJ8;$;b))lhtW53_@%kxVxwy%?q9+hx2m&!@S_F zmwvRUULlQhv%DeT@&w)I>Sju?MQ-;PwGhEi+?>RG*~w*GE6-xDk3(>Fd;lC&O9MK z)+Cgik~lFng`UYbTle9wsei39?>|qSf}1)Mx0Uk&tYxh6XqCal>m>G8{jXO!;D5Zz zhf{M7I=7ltECp~=d6<)v(mNC2Q#cai`Mq|(0G2BVDd~^l= z?xeztK;Zw~4tKaoa#FK$T+=%BuPfg8+lq^F{#x;$vp;+9aodH-%Y=r?&ybvq(HS3~ z(vc{F)G;E$G9fwTLP~n7dPcfIc7jQsd3I7pQ33&BazO+!EgeO^VdC9p&)*N}!(A`> z57*$=;)6#SI6b)W3vkWX&j1W=*JGbH8%O&coc`aOW_XEzzy3m&gxI@W^}lhK|7rbk z*TBxl%hKOG(14yMSeKF_`~oQv4R|rg9SIVN91}B5GIMehFXR>C>lWo0mKJ9hS{Bt* zS0xgYl$9rv(a@4-wL0bhu_1ol43htFF~B1L+zp4P0C*+9tpFbF;1SS?Jq574VH9`& zgO_COpN@9Cl)t|iC`(WY`18eZ{WnM6zr7fyexYb*TDo9e3d-mUghaI1vjMy!X+*YZ zdH9C;Ma2bbB_+D$`Gr;H<(Bnz6(;#)q}4U0jMRB8y4O0q4UTRQ@F91&Ib{C%dK^9i zz{3H2e767?ux;ou?n=!5`M&r!+v4y!hnG2n_jfl4${0KnEvit~3BPU-qr>ZA^V2&u6L2AN|PKA~-1o?%gG8NPaXxo%ZaNv(O6 zWs^xmYZd`HDM4|4g&JkI!PC3+{q#o{<=1mU{vR$1_*^`E_=68c@StotIws};%)-$z zu?1kBIbr(lV}=7UU)M1EpMO2@fBnEq`TOSt;sSV4P+3yHJtw3NFN*4K7v;C-#P6rZ zUoJ}2!x&Fna>`&`V$$Rb_yiP=gxHfbFY|g)DZW8jWtnq)1_6|c@ zdPV~Vx(i3wgY9UODB=`N(6D@*602x}K4s9D48jwBVH5uF9VbID`3OuQ5>qOGDHp?f zjT<#Fjary?3rw#o=6NV)G6yr2kD0B(%r{~dnhy=dm`@9sZ#$TSeGKN{*A@Ez_Q$c- zc1jCXKBj=qoM_Ogm!icc)|YD%fCrnECgozl7tn9FK<4Ju-k0KHOI&kpZH=5v=!>_%qyXR>_SK#1{2Yn-5&tH|j9t#?O?OHee&V_EA z`9AeH{e7~lG$)xTuF~E^kW!tnWo0C%ym#vOJr;&JIOOLy1RuaR2fnyn2l8-ipy!n}&Z zyh*{lEyB!HVrFYG^9`7#cFg(!W@8BRc@eu%-@jtM@BRuVzb`ry#55CD}AYIHTi=nQci1Ay)^|>!x<JRovhNOUl^rn8cUXGo~(`-%#VLP9PkdX zpHkemxNqJz2fm7H=kwc3Hy>0?pi*zE^4X##^oM%vJ0ryloYj5e!(ZCh7zj~BPdHT3 z=m?QrsJgF8CBzW4et+l~$#fv)!^;l@chSnXNxb~zeEfq%0)xZ&L&KxEBBR4&Q>jBud6@X*yMe?)v4w2>5fj>?kA$pdW8G> z1qX*B+Mer;yySWPCT4U(bA006o7tE1&liW5`&WC`pSr|EP3*P6Y`{jwj$ zm}bJ`s+HJ;05y+U4>ln{!KR+7T9y4IghAAHs;4UFSp=96IIdO=CIq;u{=CsRG)Nfj z*QWNA{-1WvGpgxy-Qp3E-jx~@3{6@LDCmSENdA>JY6)gLN%zgnyM3*l4+V1>}2B~x+f15AE z8|MCLH_!%gx}VMJgXr-ldn}@QqgbxNfwQO$o91l#QnRWngx^Jt>1f{mPay$(7!AS$ z$pjc!fTRWtr@-tD6bnE)J3ftkhs5X@NR0m5Au0PKBnN6_3YD=>PVWp5)B3Xa*xp=? z(U+AadaG;hl+{=iv=MfJw;`E(L@pwzPyw3#&=2#kP$r%NM(ung}(j9|rjItN?-n zg!w8EzVq;q)4*YW0hDNevvQoEl>XnW1S>{x3s&@{bd#$D@I~{rPv2%3V=_<`LUz^X z-sRdVzGX<@n`gi#>grW$Eq&8wR5BRM02wDf{r*=k7NI=C6sq@%=2_u+KDmBH!mG=~8LO2_eIK3e9s6U)fLTp&sUjd}CJ(Q?pBJ$3+&+Oq5~&|wRC z0p74iW-4s^SD`j-do|>KSkKRp0*DDP_5r?A0>W1un$Ej}nGZj8ShxO7%5kI={imd` zM4LCJ-_A9#uF&LH$bpiG5C(;Snn*FQ_0_U*?X;J8z6QWn8(~Q0)T# zYz-^OC(NMzD!W?oI{#!I8FNXa*Va^;MKq6DOc}G$gU)b~fZtU5=jV`UHq1G9mPhk> z!RpvM5~I@(2MSDU_I1H7HY1e^#5@vXBHc9K&F5zl%27N43KO6)0ul<~JOC`faNG<6 z3PPaOK6-xfcS8B+g!0$s6Y-Dc^Shu>90d8=^sv{ z8tx7&ASyHGdVVJnKJyTnZ-|Zgwqs>IYS7!^Q8sF5HBklLXE^ufll6Gh-HVj}PxApN z0aOLp5C91ls1rv(_%RUvBM5(dn+BlscToA$*!0gq<#$#N&F5HFoIk%{$dxa#Y>7#O z#|oDE+ZE6n#WBiBE7%b)J6-L2OIYJgd?gh$E#uP=Ue1eP{bjAb)tkfU4uaXi=UE(o zvlCLs`>t;sN7vo!^C3RfM8BjDk%Nt_M{PJJJmSFH3q>`fM1$if7yGwOJJ8=*0sma6 zO*#}6z=42r35YAe@~{42X9je!|3X^6vtn~hsI~cT54G68w4da^(iL^ef2k{fU}aek zOEaC62G;syP)YkaZz|^2s%U^YG3`SVEqen>W|;oVRcZTLMOpz%=Qf(RX6@8x5!GYn zn=?o>zsjCfoo#*hX%O42_;rGNe!e^+F#XkH@`*6pNqR~BEx9RVEN}wgXfb^L2P*0R zQ0g#Ke=l{o7!K+-;Pv3~joabQ_{fw1p#kiu2!sb_W?)wbwD@g@akuACcYq@Q_z?4F zzxs*40Hux>@NSSyt~vEbsbi5t7wMG=yc^`py`STv0u89WV=~ZYBiF5oMcnjb?A%0D zzPQEO{9)m0A~7-#B#=`7g$-+^fHIV*4|SsX(PMh?Ef{7QbfP z1Ut`$VbxhT!wHF8`E765(W3X2%!7BqYH8+()H~Hwv^`P3sTb(TzDv}*LP8A|)_z%w za=}s21@f;X{#x(*q0Epw0D9@|dOS|(zLv)c5!?rQ4YaSw!byv$z31XHwQii=AXOqJ zbGoAm{XPhCMCi!(m#zO+je{b@ClKKiN$^1JSgDDx(!tldlEl^-oN>kAA~CWFQH1gy7@y^ea&3lCq`bosz6bl zoq4-KHkFgBS2f2Kygz(-N@_ZCqLNwqB#Ip{ZHvT}xX%uDz?g zv%9aLw|@vdI1KPPKIJnxJzJdmVb1&g{F3$J@~X+o+NRFN=P!*PclHdozky=+$gkV6 z%Xkq{uPbNJu+{r-o|EO!GISfZUAN)5W_M1?ft;5P-15BdW{NMyfvYG68c`Q~ z!-`wgP}Fv}HS_k!esvP9CqdeUM{|uSiXsrz5qsX-;WyEt!F>Ik{aL*EM&qp|*@OA_ z>jTd!m*xx?nfGSh#g*ocV(s3yCMsj|e&%H>ix7mi(v?m!S3o4cM@_%Rf4o7&ny1iq zurybXeP!Z0aLEpWxVkV|8$_*@#QNB=KRA9nCJzO-UK~tR8}tB+S*@hiMgBICh}i0T z=YyiINs`#zoKa|so%BF_>)xKPxgsg`2;Yf65r_6XNme%LaEj$>rxlrS8Omc)nmFze zF#}6`b8wPme=|SxnP(R;88d+brE@buFbAYw@a2J{ixD%-@U6M` zz{QA6P5M;*aAo33ap2lQr4@V6DY*q>PAChk3v`MN36ecU1q-i>RKKZi0%f{hTSo`% zvrfc8cI#`Su)eFl32ZXM7zSfSGoCP8rP6ff$Ff@wn4e0DW{5voV8)#BgF9bxC?LmRdIqaw)fL~lg4-pm=R&w=Jn&slHf#9-x*1}YQKNsvH1u%h5T zF$#Km@Gp7zP#yRr*iSh4F~o{jLa`FEXyVP`k0H!z4b#r(mVP2{S{FzA2NrF1Z0}PC zkJ)AFts+(UVwsF0NJEs;^CNqOU#nxs@?2bV5lyqg!s0^NgG&n~lwr7E%FDlns-!F|PjAQxxlQb8n`1i#sP)wZYdo8H}-4Cr!N^9TWPo|QBO5yL?)`Xxvt2(8YS0;;YKb*5;Y(QeU ze@!r5o5|h}X3?@=a$VqPR)<{k;InWz-5NznP=+AAglUVve2*%Fbc4Gik;u7qY5vlK zu4Ks_T8Y5RnLTMLsQtE&m$UjZHL{6d3(o^U6nZiwb6L~;#IG+|$x=!)BzxsN=w;A% zFA-EI(;g>F<-YokYg@W} zarR9|k#2Jcmo0bV@aBWQM9naa{z#!j*PMKf>DiIb)K5|8T zYStIeb#Cm7<7|0!jj?3Mj?r9unr*tl7+h>=s`%b-N#kE1uXZ=)bKu+etTsRNcRrXL zmwc_*w9b#)3He&A6KyPwc4Ub6pitaPA4XZGm%i_BxrX?? zH`Gq{=WrN$88GE_Jw%79oGD&Yxa0b(VC{aSaVVV1>3yi=ei?`I-LlA21fR4yIECaP znLe~P2#Pofb!m1u1=JtHOr!7U)|;GGe8@}}3qg`%luVw(Ok+)<4rb)n@V9liI zY>!&Q%@UnGNE=XY6ZYvGi2Y&3m*W&l<`Rv3)Igv#Oq3k1}IB8uG3?JUOhNVW)G8i1UEO1Hu_prUook3L8&rij_d zek|;TR*meRz9_x2-n$Inc>(UudTUg?Qrq8QX;(PO&D!&pB2r_uz8x-5@OD{aNxgw7 z+jsSy{lwzh4VC~3f^cqhaG^$iYMTQNI#|4p6YdOlXyeOkfp9>$Uu;0cPLEuINa2|` z&&w_96raB~7{AG`Tt8gQuJ&F9!g)KE*@<1tC%%MD&vMv_?Vc91D4VgAj`O((Jn^FE zEXjwr&e|58!Jc(Y*VtxtK}BI%-NX7^SUr8tTxIof(QpL^SVmn12i@!Y!V<=2Wp=4P zB3o$3B$@|N&K!^SPvJ!8Gq`cSswpk6ON_POwaKJ@182@<+pc(B5GM5XQOSneSH^Nr z?AP2X_qDHXbxm*tW8gwAQ0csvQG7)V` ICqQEV13e`tp8x;= literal 0 HcmV?d00001 diff --git a/docs/index.md b/docs/index.md index 5baa7c24d..dbc3ee934 100644 --- a/docs/index.md +++ b/docs/index.md @@ -11,7 +11,7 @@ __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 makes asynchronous Actions, i.e. non-blocking routines, a first-class citizen. - It allows the creation of trees at run-time, using a textual representation (XML). - You can link staticaly your custom TreeNodes or convert them into plugins which are loaded at run-time. @@ -37,7 +37,7 @@ The main advantages of Behavior Trees, when compared to FSMs are: - __They are intrinsically Hierarchical__: this means that we can _compose_ complex behaviors including entire trees as sub-branches of a bigger tree. -For instance, the behavior "Fetch Beer" may reuse in one of its nodes the tree +For instance, the behavior "Fetch Beer" may reuse the tree "Grasp Object". - __Their graphical representation has a semantic meaning__: it is easier to @@ -74,11 +74,7 @@ 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__. -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 +Frequently, the business logic is "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 diff --git a/docs/tutorial_01_first_tree.md b/docs/tutorial_01_first_tree.md index 6a5b93464..f48ea4ca5 100644 --- a/docs/tutorial_01_first_tree.md +++ b/docs/tutorial_01_first_tree.md @@ -102,6 +102,7 @@ We can build a `SimpleActionNode` from any of these functors: Let's consider the following XML file named __my_tree.xml__: +![ReactiveFallback](images/Tutorial1.svg) ``` XML diff --git a/docs/tutorial_02_basic_ports.md b/docs/tutorial_02_basic_ports.md index 1aa179b3a..e15027ab5 100644 --- a/docs/tutorial_02_basic_ports.md +++ b/docs/tutorial_02_basic_ports.md @@ -15,12 +15,20 @@ Similar to functions, we often want to: BehaviorTree.CPP provides a basic mechanism of __dataflow__ through __ports__, that is simple to use but also flexible and type safe. +In this tutorial we will create the following tree: + +![Tutorial2](images/Tutorial2.svg) + +You may notice already as the 2nd child of the Sequence will write on a row +of a Key/Value table (the __Blackboard__) and the 4th node read +from the same row. + ## Inputs ports A valid Input can be either: -- static strings which can be parsed by the Node, or -- "pointers" to an entry of the Blackboard, identified by a __key__. +- a static string which can be parsed by the Node, or +- a "pointer" to an entry of the Blackboard, identified by a __key__. A "blackboard" is a simple __key/value storage__ shared by all the nodes of the Tree. @@ -38,8 +46,8 @@ Such a string will be passed using an input port called `message`. Consider these alternative XML syntaxes: ```XML - - + + ``` The attribute `message` in the __first node__ means: @@ -52,7 +60,7 @@ The syntax of the __second node__ instead means: "Read the current value in the entry of the blackboard called 'greetings' ". -This value can (and probably will) change at run-time. +The value of the entry can (and probably will) change at run-time. The ActionNode `SaySomething` can be implemented as follows: @@ -199,7 +207,7 @@ In this example, a Sequence of 5 Actions is executed: - + @@ -238,7 +246,7 @@ int main() Robot says: start thinking... Robot says: The answer is 42 - Robot says: SaySomething2 works too... + Robot says: this works too Robot says: The answer is 42 */ return 0; From c25380c59015da2f4807612b91ada9d79aba390c Mon Sep 17 00:00:00 2001 From: Philippe Couvignou <82674872+pcouvignou-irobot@users.noreply.github.com> Date: Sat, 22 Jan 2022 01:22:41 -0800 Subject: [PATCH 121/709] Fixed typo "Exeption" -> "Exception" (#331) --- src/loggers/bt_zmq_publisher.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/loggers/bt_zmq_publisher.cpp b/src/loggers/bt_zmq_publisher.cpp index 38914a673..442e2e29b 100644 --- a/src/loggers/bt_zmq_publisher.cpp +++ b/src/loggers/bt_zmq_publisher.cpp @@ -79,7 +79,7 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, { std::cout << "[PublisherZMQ] Server quitting." << std::endl; } - std::cout << "[PublisherZMQ] just died. Exeption " << err.what() << std::endl; + std::cout << "[PublisherZMQ] just died. Exception " << err.what() << std::endl; active_server_ = false; } } @@ -176,7 +176,7 @@ void PublisherZMQ::flush() { std::cout << "[PublisherZMQ] Publisher quitting." << std::endl; } - std::cout << "[PublisherZMQ] just died. Exeption " << err.what() << std::endl; + std::cout << "[PublisherZMQ] just died. Exception " << err.what() << std::endl; } send_pending_ = false; From 472a56461e49aa1f623b959e035230f0abad350c Mon Sep 17 00:00:00 2001 From: Adam Sasine Date: Sat, 22 Jan 2022 04:24:12 -0500 Subject: [PATCH 122/709] Added BlackboardCheckBool decorator node (#326) * Added tests for BlackboardCheck decorator node * Added BlackboardCheckBool decorator node --- .../decorators/blackboard_precondition.h | 2 + src/bt_factory.cpp | 1 + tests/CMakeLists.txt | 1 + tests/gtest_blackboard_precondition.cpp | 198 ++++++++++++++++++ 4 files changed, 202 insertions(+) create mode 100644 tests/gtest_blackboard_precondition.cpp diff --git a/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h b/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h index 4cc445d46..1d7312fa8 100644 --- a/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h +++ b/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h @@ -42,6 +42,8 @@ class BlackboardPreconditionNode : public DecoratorNode setRegistrationID("BlackboardCheckDouble"); else if( std::is_same::value) setRegistrationID("BlackboardCheckString"); + else if( std::is_same::value) + setRegistrationID("BlackboardCheckBool"); } virtual ~BlackboardPreconditionNode() override = default; diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index c25e73ef8..2a161bce9 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -53,6 +53,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType>("BlackboardCheckInt"); registerNodeType>("BlackboardCheckDouble"); registerNodeType>("BlackboardCheckString"); + registerNodeType>("BlackboardCheckBool"); registerNodeType>("Switch2"); registerNodeType>("Switch3"); diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index ca86ba31c..3b97db096 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -13,6 +13,7 @@ set(BT_TESTS gtest_factory.cpp gtest_decorator.cpp gtest_blackboard.cpp + gtest_blackboard_precondition.cpp gtest_ports.cpp navigation_test.cpp gtest_subtree.cpp diff --git a/tests/gtest_blackboard_precondition.cpp b/tests/gtest_blackboard_precondition.cpp new file mode 100644 index 000000000..0c36fd28d --- /dev/null +++ b/tests/gtest_blackboard_precondition.cpp @@ -0,0 +1,198 @@ +#include +#include +#include "behaviortree_cpp_v3/basic_types.h" +#include "behaviortree_cpp_v3/bt_factory.h" + +using namespace BT; + +TEST(BlackboardPreconditionTest, IntEquals) +{ + BehaviorTreeFactory factory; + + const std::string xml_text = R"( + + + + + + + + + + + + + )"; + + auto tree = factory.createTreeFromText(xml_text); + const auto status = tree.tickRoot(); + ASSERT_EQ(status, NodeStatus::FAILURE); +} + +TEST(BlackboardPreconditionTest, IntDoesNotEqual) +{ + BehaviorTreeFactory factory; + + const std::string xml_text = R"( + + + + + + + + + + + + + )"; + + auto tree = factory.createTreeFromText(xml_text); + const auto status = tree.tickRoot(); + ASSERT_EQ(status, NodeStatus::SUCCESS); +} + +TEST(BlackboardPreconditionTest, DoubleEquals) +{ + BehaviorTreeFactory factory; + + const std::string xml_text = R"( + + + + + + + + + + + + + )"; + + auto tree = factory.createTreeFromText(xml_text); + const auto status = tree.tickRoot(); + ASSERT_EQ(status, NodeStatus::FAILURE); +} + +TEST(BlackboardPreconditionTest, DoubleDoesNotEqual) +{ + BehaviorTreeFactory factory; + + const std::string xml_text = R"( + + + + + + + + + + + + + )"; + + auto tree = factory.createTreeFromText(xml_text); + const auto status = tree.tickRoot(); + ASSERT_EQ(status, NodeStatus::SUCCESS); +} + +TEST(BlackboardPreconditionTest, StringEquals) +{ + BehaviorTreeFactory factory; + + const std::string xml_text = R"( + + + + + + + + + + + + + )"; + + auto tree = factory.createTreeFromText(xml_text); + const auto status = tree.tickRoot(); + ASSERT_EQ(status, NodeStatus::FAILURE); +} + +TEST(BlackboardPreconditionTest, StringDoesNotEqual) +{ + BehaviorTreeFactory factory; + + const std::string xml_text = R"( + + + + + + + + + + + + + )"; + + auto tree = factory.createTreeFromText(xml_text); + const auto status = tree.tickRoot(); + ASSERT_EQ(status, NodeStatus::SUCCESS); +} + +TEST(BlackboardPreconditionTest, BoolEquals) +{ + BehaviorTreeFactory factory; + + const std::string xml_text = R"( + + + + + + + + + + + + + )"; + + auto tree = factory.createTreeFromText(xml_text); + const auto status = tree.tickRoot(); + ASSERT_EQ(status, NodeStatus::FAILURE); +} + +TEST(BlackboardPreconditionTest, BoolDoesNotEqual) +{ + BehaviorTreeFactory factory; + + const std::string xml_text = R"( + + + + + + + + + + + + + )"; + + auto tree = factory.createTreeFromText(xml_text); + const auto status = tree.tickRoot(); + ASSERT_EQ(status, NodeStatus::SUCCESS); +} From 65e880ef64c94947c5f7f022d032f66d6f542258 Mon Sep 17 00:00:00 2001 From: Jake Keller Date: Sun, 23 Jan 2022 08:10:09 -0500 Subject: [PATCH 123/709] Build Sample Nodes By Default to Fix Github Action (#332) * Fix github action * Change working directory in github action step * Build samples by default --- .github/workflows/build_ubuntu.yml | 3 ++- CMakeLists.txt | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build_ubuntu.yml b/.github/workflows/build_ubuntu.yml index 0deadca32..73328e998 100644 --- a/.github/workflows/build_ubuntu.yml +++ b/.github/workflows/build_ubuntu.yml @@ -13,7 +13,8 @@ jobs: - name: apt run: sudo apt-get update && sudo apt-get install -yq libzmq3-dev libdw-dev libgtest-dev cmake - name: Install gtest manually - run: cd /usr/src/gtest && sudo cmake CMakeLists.txt && sudo make && sudo cp lib/*.a /usr/lib + working-directory: /usr/src/gtest + run: sudo cmake CMakeLists.txt && sudo make && sudo cp lib/*.a /usr/lib # build project - name: mkdir run: mkdir build diff --git a/CMakeLists.txt b/CMakeLists.txt index 83a4e21fb..e316d0ba2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -42,6 +42,7 @@ set(CMAKE_POSITION_INDEPENDENT_CODE ON) #---- project configuration ---- option(BUILD_EXAMPLES "Build tutorials and examples" ON) +option(BUILD_SAMPLES "Build sample nodes" ON) option(BUILD_UNIT_TESTS "Build the unit tests" ON) option(BUILD_TOOLS "Build commandline tools" ON) option(BUILD_SHARED_LIBS "Build shared libraries" ON) From df73c99f506183dec68b6730933ecd29a7bce89c Mon Sep 17 00:00:00 2001 From: Alberto Soragna Date: Sun, 23 Jan 2022 13:11:04 +0000 Subject: [PATCH 124/709] fix shadowed variable in string_view.hpp (#327) Signed-off-by: Alberto Soragna --- include/behaviortree_cpp_v3/utils/string_view.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/behaviortree_cpp_v3/utils/string_view.hpp b/include/behaviortree_cpp_v3/utils/string_view.hpp index aa52d94ee..2cf140ea6 100644 --- a/include/behaviortree_cpp_v3/utils/string_view.hpp +++ b/include/behaviortree_cpp_v3/utils/string_view.hpp @@ -877,7 +877,7 @@ nssv_DISABLE_MSVC_WARNINGS( 4455 26481 26472 ) { const basic_string_view v; - nssv_constexpr explicit not_in_view( basic_string_view v ) : v( v ) {} + nssv_constexpr explicit not_in_view( basic_string_view view ) : v( view ) {} nssv_constexpr bool operator()( CharT c ) const { From 348b816f9abe120e9d964356b65972a8fdb911eb Mon Sep 17 00:00:00 2001 From: Tobias Fischer Date: Sun, 23 Jan 2022 23:11:34 +1000 Subject: [PATCH 125/709] Fix Windows shared lib build (#323) --- CMakeLists.txt | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e316d0ba2..327198b3d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -193,17 +193,18 @@ endif() if (UNIX) list(APPEND BT_SOURCE src/shared_library_UNIX.cpp ) - if (BUILD_SHARED_LIBS) - add_library(${BEHAVIOR_TREE_LIBRARY} SHARED ${BT_SOURCE}) - else() - add_library(${BEHAVIOR_TREE_LIBRARY} STATIC ${BT_SOURCE}) - endif() endif() if (WIN32) set(CMAKE_DEBUG_POSTFIX "d") list(APPEND BT_SOURCE src/shared_library_WIN.cpp ) - add_library(${BEHAVIOR_TREE_LIBRARY} STATIC ${BT_SOURCE} ) +endif() + +if (BUILD_SHARED_LIBS) + set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + add_library(${BEHAVIOR_TREE_LIBRARY} SHARED ${BT_SOURCE}) +else() + add_library(${BEHAVIOR_TREE_LIBRARY} STATIC ${BT_SOURCE}) endif() if( ZMQ_FOUND ) From 433dc553b4a3c72e9e185bbee188ea8515b5ce6e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 23 Jan 2022 14:12:28 +0100 Subject: [PATCH 126/709] Update README.md --- README.md | 1 - 1 file changed, 1 deletion(-) diff --git a/README.md b/README.md index c5f9dd540..515566214 100644 --- a/README.md +++ b/README.md @@ -3,7 +3,6 @@ [![Build Status](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP.svg?branch=master)](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP) [![ros1](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros1/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros1) [![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros2/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros2) -[![Codacy Badge](https://app.codacy.com/project/badge/Grade/f7489a1758ab47d49f62342f9649b62a)](https://www.codacy.com/manual/davide.faconti/BehaviorTree.CPP?utm_source=github.com&utm_medium=referral&utm_content=BehaviorTree/BehaviorTree.CPP&utm_campaign=Badge_Grade) [![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP)](https://lgtm.com/projects/g/BehaviorTree/BehaviorTree.CPP/context:cpp) [![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/BehaviorTree-ROS/Lobby?utm_source=badge&utm_medium=badge&utm_content=badge) From 5c3445d67893b4b7772753ddda239664588aa1d0 Mon Sep 17 00:00:00 2001 From: Homalozoa X <21300069+homalozoa@users.noreply.github.com> Date: Sun, 23 Jan 2022 21:13:09 +0800 Subject: [PATCH 127/709] [Fix] Fix cmake version warning and -Wformat warning (#319) Signed-off-by: Homalozoa Co-authored-by: Homalozoa --- src/controls/manual_node.cpp | 2 +- tools/CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/controls/manual_node.cpp b/src/controls/manual_node.cpp index d27ec982c..9b9d732a6 100644 --- a/src/controls/manual_node.cpp +++ b/src/controls/manual_node.cpp @@ -155,7 +155,7 @@ uint8_t ManualSelectorNode::selectChild() const // now print all the menu items and highlight the first one for(size_t i=0; i Date: Sun, 23 Jan 2022 14:31:10 +0100 Subject: [PATCH 128/709] updated documentation --- docs/tutorial_01_first_tree.md | 6 +++++- mkdocs.yml | 2 +- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/docs/tutorial_01_first_tree.md b/docs/tutorial_01_first_tree.md index f48ea4ca5..f1c60b60f 100644 --- a/docs/tutorial_01_first_tree.md +++ b/docs/tutorial_01_first_tree.md @@ -12,6 +12,11 @@ information on console, but keep in mind that real "production" code would probably do something more complicated. +Further, we will create this simple tree: + + +![Tutorial1](images/Tutorial1.svg) + ## How to create your own ActionNodes The default (and recommended) way to create a TreeNode is by inheritance. @@ -102,7 +107,6 @@ We can build a `SimpleActionNode` from any of these functors: Let's consider the following XML file named __my_tree.xml__: -![ReactiveFallback](images/Tutorial1.svg) ``` XML diff --git a/mkdocs.yml b/mkdocs.yml index c781ebcc2..9bbc64e9e 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -2,7 +2,7 @@ site_name: BehaviorTree.CPP site_description: Introduction to Behavior Trees site_author: Davide Faconti -copyright: 'Copyright © 2018-2019 Davide Faconti, Eurecat' +copyright: 'Copyright © 2018-2022 Davide Faconti, Eurecat' theme: name: 'material' From 4b87a8e53a575def9706981a15add3ffd0589001 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 23 Jan 2022 14:32:55 +0100 Subject: [PATCH 129/709] remove deprecated code --- src/bt_factory.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 2a161bce9..c31226571 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -33,7 +33,7 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("WhileDoElse"); registerNodeType("Inverter"); - registerNodeType("RetryUntilSuccesful"); //typo but back compatibility + //registerNodeType("RetryUntilSuccesful"); //typo but back compatibility registerNodeType("RetryUntilSuccessful"); // correct one registerNodeType("KeepRunningUntilFailure"); registerNodeType("Repeat"); From f9d47bec5b973fec88b9c73031803cbc7cbd1876 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 23 Jan 2022 14:46:22 +0100 Subject: [PATCH 130/709] doc fix --- .gitignore | 1 + docs/images/Tutorial2.svg | 807 +------------------------------- docs/tutorial_02_basic_ports.md | 8 +- examples/t02_basic_ports.cpp | 14 +- 4 files changed, 13 insertions(+), 817 deletions(-) diff --git a/.gitignore b/.gitignore index 4e76fff0b..5e1d496b2 100644 --- a/.gitignore +++ b/.gitignore @@ -2,3 +2,4 @@ /CMakeLists.txt.user build* site/* +/.vscode/ diff --git a/docs/images/Tutorial2.svg b/docs/images/Tutorial2.svg index 8d8f21485..08552fc10 100644 --- a/docs/images/Tutorial2.svg +++ b/docs/images/Tutorial2.svg @@ -1,804 +1,3 @@ - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - - - - ThinkWhatToSay - - - - - text={the_answer} - - - - - - - ThinkWhatToSay... - - - - - - - - - - SaySomething2 - - - - message="this works too" - - - - - - SaySomething2... - - - - - - - - - - SaySomething2 - - - -message={the_answer} - - - - - SaySomething2... - - - - - - - - - - SaySomething - - - - message="start thinking" - - - - - - SaySomething... - - - - - - - - - - - Blackboard - - - - - - - - KEY - - - - KEY - - - - - - - - - TYPE - - - - TYPE - - - - - - - - - VALUE - - - - VALUE - - - - - - - - - the_answer - - - - the_answer - - - - - - - - - string - - - - string - - - - - - - - - - "the answer is 42" - - - - - - "the answer is 42" - - - - - - - - - - ... - - - - ... - - - - - - - - - ... - - - - ... - - - - - - - - - ... - - - - ... - - - - - - + + +
Sequence
Sequence
OpenGripper
OpenGripper
ApproachObject
ApproachObject
CloseGripper
CloseGripper
CheckBattery
CheckBattery
Sequence
Sequence
ThinkWhatToSay

text={the_answer}
ThinkWhatToSay...
SaySomething2

message="this works too"
SaySomething2...
SaySomething

message={the_answer}
SaySomething...
SaySomething

message="hello"
SaySomething...
Blackboard
KEY
KEY
TYPE
TYPE
VALUE
VALUE
the_answer
the_answer
string
string
"the answer is 42"
"the answer is 42"
...
...
...
...
...
...
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/tutorial_02_basic_ports.md b/docs/tutorial_02_basic_ports.md index e15027ab5..80dee36a6 100644 --- a/docs/tutorial_02_basic_ports.md +++ b/docs/tutorial_02_basic_ports.md @@ -204,11 +204,10 @@ In this example, a Sequence of 5 Actions is executed: - + + - - @@ -244,8 +243,7 @@ int main() /* Expected output: - Robot says: start thinking... - Robot says: The answer is 42 + Robot says: hello Robot says: this works too Robot says: The answer is 42 */ diff --git a/examples/t02_basic_ports.cpp b/examples/t02_basic_ports.cpp index 8e5a7c835..f7f72d8a7 100644 --- a/examples/t02_basic_ports.cpp +++ b/examples/t02_basic_ports.cpp @@ -32,10 +32,9 @@ static const char* xml_text = R"( - + + - - @@ -91,7 +90,7 @@ int main() /* An INPUT can be either a string, for instance: * - * + * * * or contain a "pointer" to a type erased entry in the Blackboard, * using this syntax: {name_of_entry}. Example: @@ -105,16 +104,15 @@ int main() /* Expected output: * - Robot says: start thinking... - Robot says: The answer is 42 - Robot says: SaySomething2 works too... + Robot says: hello + Robot says: this works too Robot says: The answer is 42 * * The way we "connect" output ports to input ports is to "point" to the same * Blackboard entry. * * This means that ThinkSomething will write into the entry with key "the_answer"; - * SaySomething and SaySomething2 will read the message from the same entry. + * SaySomething and SaySomething will read the message from the same entry. * */ return 0; From 44a1fcb69b43ab30f4610224c5790d8ba1ac7612 Mon Sep 17 00:00:00 2001 From: "imgbot[bot]" <31301654+imgbot[bot]@users.noreply.github.com> Date: Sun, 23 Jan 2022 14:48:15 +0100 Subject: [PATCH 131/709] [ImgBot] Optimize images (#333) *Total -- 152.97kb -> 114.57kb (25.1%) /docs/images/ReactiveSequence.svg -- 7.58kb -> 4.59kb (39.47%) /docs/images/SequenceNode.svg -- 11.28kb -> 7.12kb (36.87%) /docs/images/SequenceStar.svg -- 11.22kb -> 7.09kb (36.8%) /docs/images/DecoratorEnterRoom.svg -- 20.71kb -> 13.30kb (35.77%) /docs/images/FallbackBasic.svg -- 19.09kb -> 12.64kb (33.79%) /docs/images/FetchBeer.svg -- 24.30kb -> 16.36kb (32.66%) /docs/images/SequenceBasic.svg -- 6.32kb -> 5.49kb (13.04%) /docs/images/Tutorial1.svg -- 6.67kb -> 5.94kb (10.98%) /docs/images/FetchBeerFails.svg -- 6.46kb -> 5.83kb (9.76%) /docs/images/FetchBeer2.svg -- 14.99kb -> 13.76kb (8.18%) /docs/images/Tutorial2.svg -- 24.35kb -> 22.44kb (7.85%) Signed-off-by: ImgBotApp Co-authored-by: ImgBotApp --- docs/images/DecoratorEnterRoom.svg | 579 +------------------------- docs/images/FallbackBasic.svg | 508 +---------------------- docs/images/FetchBeer.svg | 643 +---------------------------- docs/images/FetchBeer2.svg | 4 +- docs/images/FetchBeerFails.svg | 5 +- docs/images/ReactiveSequence.svg | 209 +--------- docs/images/SequenceBasic.svg | 5 +- docs/images/SequenceNode.svg | 319 +------------- docs/images/SequenceStar.svg | 315 +------------- docs/images/Tutorial1.svg | 4 +- docs/images/Tutorial2.svg | 4 +- 11 files changed, 11 insertions(+), 2584 deletions(-) diff --git a/docs/images/DecoratorEnterRoom.svg b/docs/images/DecoratorEnterRoom.svg index 07c4a7371..b01efcc8e 100644 --- a/docs/images/DecoratorEnterRoom.svg +++ b/docs/images/DecoratorEnterRoom.svg @@ -1,578 +1 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - EnterRoom - - - - EnterRoom - - - - - - - - - CloseDoor - - - - CloseDoor - - - - - - - - - IsDoorOpen - - - - IsDoorOpen - - - - - - - - - - - - OpenDoor - - - - OpenDoor - - - - - - - - - - - Inverter - - - - Inverter - - - - - - - - - - - - - - RetryUntilSuccessful - ... - - - - - - - - - - - - - - RetryUntilSuccessful - ... - - - - - - RetryUntilSuccessful - ... - - - num_attempts = 5 - RetryUntilSuccessful - - +SequenceSequenceSequenceSequenceEnterRoomEnterRoomCloseDoorCloseDoorIsDoorOpenIsDoorOpenOpenDoorOpenDoorInverterInverterRetryUntilSuccessful...RetryUntilSuccessful...RetryUntilSuccessful...num_attempts = 5RetryUntilSuccessful \ No newline at end of file diff --git a/docs/images/FallbackBasic.svg b/docs/images/FallbackBasic.svg index a16a73f10..c979392a0 100644 --- a/docs/images/FallbackBasic.svg +++ b/docs/images/FallbackBasic.svg @@ -1,507 +1 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - - - - - - - Fallback - - - - Fallback - - - - - - - - - EnterRoom - - - - EnterRoom - - - - - - - - - IsDoorOpen - - - - IsDoorOpen - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - UnlockDoor - - - - UnlockDoor - - - - - - - - - HaveKey? - - - - HaveKey? - - - - - - - - - OpenDoor - - - - OpenDoor - - - - - - - - - OpenDoor - - - - OpenDoor - - - - +SequenceSequenceFallbackFallbackEnterRoomEnterRoomIsDoorOpenIsDoorOpenSequenceSequenceUnlockDoorUnlockDoorHaveKey?HaveKey?OpenDoorOpenDoorOpenDoorOpenDoor \ No newline at end of file diff --git a/docs/images/FetchBeer.svg b/docs/images/FetchBeer.svg index 6eea6676f..880a142cc 100644 --- a/docs/images/FetchBeer.svg +++ b/docs/images/FetchBeer.svg @@ -1,642 +1 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - OpenFridge - - - - OpenFridge - - - - - - - - - GrabBeer - - - - GrabBeer - - - - - - - - - CloseFridge - - - - CloseFridge - - - - - - - - - - - ForceSuccess - - - - ForceSuccess - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - OpenFridge - - - - OpenFridge - - - - - - - - - GrabBeer - - - - GrabBeer - - - - - - - - - CloseFridge - - - - CloseFridge - - - - - - - - - - - - - Fallback - - - - Fallback - - - - - - - - - - - ForceFailure - - - - ForceFailure - - - - - - - - - CloseFridge - - - - CloseFridge - - - - +SequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridgeForceSuccessForceSuccessSequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridgeFallbackFallbackForceFailureForceFailureCloseFridgeCloseFridge \ No newline at end of file diff --git a/docs/images/FetchBeer2.svg b/docs/images/FetchBeer2.svg index b1818b43d..8adac582a 100644 --- a/docs/images/FetchBeer2.svg +++ b/docs/images/FetchBeer2.svg @@ -1,3 +1 @@ - - -
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
ForceSuccess
ForceSuccess
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
Fallback
Fallback
ForceFailure
ForceFailure
CloseFridge
CloseFridge
Text is not SVG - cannot display
\ No newline at end of file +
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
ForceSuccess
ForceSuccess
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
Fallback
Fallback
ForceFailure
ForceFailure
CloseFridge
CloseFridge
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/images/FetchBeerFails.svg b/docs/images/FetchBeerFails.svg index eea5fac2d..f2489ce93 100644 --- a/docs/images/FetchBeerFails.svg +++ b/docs/images/FetchBeerFails.svg @@ -1,4 +1 @@ - - - -
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
Text is not SVG - cannot display
+
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/images/ReactiveSequence.svg b/docs/images/ReactiveSequence.svg index 02cc92a0a..7f33658ff 100644 --- a/docs/images/ReactiveSequence.svg +++ b/docs/images/ReactiveSequence.svg @@ -1,208 +1 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - ReactiveSequence - - - - ReactiveSequence - - - - - - - - - ApproachEnemy - - - - ApproachEnemy - - - - - - - - - IsEnemyVisible - - - - IsEnemyVisible - - - - +ReactiveSequenceReactiveSequenceApproachEnemyApproachEnemyIsEnemyVisibleIsEnemyVisible \ No newline at end of file diff --git a/docs/images/SequenceBasic.svg b/docs/images/SequenceBasic.svg index d167dd27b..8c1fb00e6 100644 --- a/docs/images/SequenceBasic.svg +++ b/docs/images/SequenceBasic.svg @@ -1,4 +1 @@ - - - -
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
+
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
\ No newline at end of file diff --git a/docs/images/SequenceNode.svg b/docs/images/SequenceNode.svg index 5754bf716..ef7eec251 100644 --- a/docs/images/SequenceNode.svg +++ b/docs/images/SequenceNode.svg @@ -1,318 +1 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - AimAtEnemy - - - - AimAtEnemy - - - - - - - - - Shoot - - - - Shoot - - - - - - - - - IsEnemyVisible - - - - IsEnemyVisible - - - - - - - - - isRifleLoaded - - - - isRifleLoaded - - - - +SequenceSequenceAimAtEnemyAimAtEnemyShootShootIsEnemyVisibleIsEnemyVisibleisRifleLoadedisRifleLoaded \ No newline at end of file diff --git a/docs/images/SequenceStar.svg b/docs/images/SequenceStar.svg index 4664bcf6c..3d6278937 100644 --- a/docs/images/SequenceStar.svg +++ b/docs/images/SequenceStar.svg @@ -1,314 +1 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - SequenceStar - - - - SequenceStar - - - - - - - - - GoTo(C) - - - - GoTo(C) - - - - - - - - - - - RetryUntilSuccesful - - - - RetryUntilSuccesful - - - - - - - - - GoTo(A) - - - - GoTo(A) - - - - - - - - - GoTo(B) - - - - GoTo(B) - - - - +SequenceStarSequenceStarGoTo(C)GoTo(C)RetryUntilSuccesfulRetryUntilSuccesfulGoTo(A)GoTo(A)GoTo(B)GoTo(B) \ No newline at end of file diff --git a/docs/images/Tutorial1.svg b/docs/images/Tutorial1.svg index ff44a8a29..4b8a84fd8 100644 --- a/docs/images/Tutorial1.svg +++ b/docs/images/Tutorial1.svg @@ -1,3 +1 @@ - - -
Sequence
Sequence
OpenGripper
OpenGripper
ApproachObject
ApproachObject
CloseGripper
CloseGripper
CheckBattery
CheckBattery
Text is not SVG - cannot display
\ No newline at end of file +
Sequence
Sequence
OpenGripper
OpenGripper
ApproachObject
ApproachObject
CloseGripper
CloseGripper
CheckBattery
CheckBattery
Text is not SVG - cannot display
\ No newline at end of file diff --git a/docs/images/Tutorial2.svg b/docs/images/Tutorial2.svg index 08552fc10..f010f3d48 100644 --- a/docs/images/Tutorial2.svg +++ b/docs/images/Tutorial2.svg @@ -1,3 +1 @@ - - -
Sequence
Sequence
OpenGripper
OpenGripper
ApproachObject
ApproachObject
CloseGripper
CloseGripper
CheckBattery
CheckBattery
Sequence
Sequence
ThinkWhatToSay

text={the_answer}
ThinkWhatToSay...
SaySomething2

message="this works too"
SaySomething2...
SaySomething

message={the_answer}
SaySomething...
SaySomething

message="hello"
SaySomething...
Blackboard
KEY
KEY
TYPE
TYPE
VALUE
VALUE
the_answer
the_answer
string
string
"the answer is 42"
"the answer is 42"
...
...
...
...
...
...
Text is not SVG - cannot display
\ No newline at end of file +
Sequence
Sequence
OpenGripper
OpenGripper
ApproachObject
ApproachObject
CloseGripper
CloseGripper
CheckBattery
CheckBattery
Sequence
Sequence
ThinkWhatToSay

text={the_answer}
ThinkWhatToSay...
SaySomething2

message="this works too"
SaySomething2...
SaySomething

message={the_answer}
SaySomething...
SaySomething

message="hello"
SaySomething...
Blackboard
KEY
KEY
TYPE
TYPE
VALUE
VALUE
the_answer
the_answer
string
string
"the answer is 42"
"the answer is 42"
...
...
...
...
...
...
Text is not SVG - cannot display
\ No newline at end of file From deb403b4f9666dd90d880a05197f3765be22d3ce Mon Sep 17 00:00:00 2001 From: fultoncjb Date: Mon, 24 Jan 2022 10:24:56 -0500 Subject: [PATCH 132/709] Add ENABLE_COROUTINES CMake option (#316) * Add DISABLE_COROUTINES CMake option * Change convention of CMake coroutine flag to ENABLE Co-authored-by: Cam Fulton --- CMakeLists.txt | 50 +++++++++++++++++++++++++++----------------------- 1 file changed, 27 insertions(+), 23 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 327198b3d..c013cf992 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,29 +15,6 @@ else() add_definitions(-Wpedantic) endif() -#---- Include boost to add coroutines ---- -find_package(Boost COMPONENTS coroutine QUIET) - -if(Boost_FOUND) - string(REPLACE "." "0" Boost_VERSION_NODOT ${Boost_VERSION}) - if(NOT Boost_VERSION_NODOT VERSION_LESS 105900) - message(STATUS "Found boost::coroutine2.") - add_definitions(-DBT_BOOST_COROUTINE2) - set(BT_COROUTINES true) - elseif(NOT Boost_VERSION_NODOT VERSION_LESS 105300) - message(STATUS "Found boost::coroutine.") - add_definitions(-DBT_BOOST_COROUTINE) - set(BT_COROUTINES true) - endif() - include_directories(${Boost_INCLUDE_DIRS}) -endif() - - -if(NOT DEFINED BT_COROUTINES) - message(STATUS "Coroutines disabled. Install Boost to enable them (version 1.59+ recommended).") - add_definitions(-DBT_NO_COROUTINES) -endif() - set(CMAKE_POSITION_INDEPENDENT_CODE ON) #---- project configuration ---- @@ -46,6 +23,33 @@ option(BUILD_SAMPLES "Build sample nodes" ON) option(BUILD_UNIT_TESTS "Build the unit tests" ON) option(BUILD_TOOLS "Build commandline tools" ON) option(BUILD_SHARED_LIBS "Build shared libraries" ON) +option(ENABLE_COROUTINES "Enable boost coroutines" ON) + +#---- Include boost to add coroutines ---- +if(ENABLE_COROUTINES) + find_package(Boost COMPONENTS coroutine QUIET) + + if(Boost_FOUND) + string(REPLACE "." "0" Boost_VERSION_NODOT ${Boost_VERSION}) + if(NOT Boost_VERSION_NODOT VERSION_LESS 105900) + message(STATUS "Found boost::coroutine2.") + add_definitions(-DBT_BOOST_COROUTINE2) + set(BT_COROUTINES true) + elseif(NOT Boost_VERSION_NODOT VERSION_LESS 105300) + message(STATUS "Found boost::coroutine.") + add_definitions(-DBT_BOOST_COROUTINE) + set(BT_COROUTINES true) + endif() + include_directories(${Boost_INCLUDE_DIRS}) + endif() + + if(NOT DEFINED BT_COROUTINES) + message(STATUS "Boost coroutines disabled. Install Boost (version 1.59+ recommended).") + endif() +else() + message(STATUS "Boost coroutines disabled by CMake option.") + add_definitions(-DBT_NO_COROUTINES) +endif() #---- Find other packages ---- find_package(Threads) From 40b5cc9cd9a9b46746ddb27aa325f9b13aa749de Mon Sep 17 00:00:00 2001 From: fultoncjb Date: Mon, 24 Jan 2022 11:41:59 -0500 Subject: [PATCH 133/709] Fix CMake ENABLE_COROUTINES flag with Boost < 1.59 (#335) Co-authored-by: Cam Fulton --- CMakeLists.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index c013cf992..269c327f1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -48,6 +48,9 @@ if(ENABLE_COROUTINES) endif() else() message(STATUS "Boost coroutines disabled by CMake option.") +endif() + +if(NOT DEFINED BT_COROUTINES) add_definitions(-DBT_NO_COROUTINES) endif() From e3c3aa71b828dadbd46d8429cf41a1b3eea47573 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 2 Feb 2022 10:26:13 +0100 Subject: [PATCH 134/709] fix svg --- docs/images/DecoratorEnterRoom.svg | 451 +++++++++++- docs/images/FetchBeer2.svg | 676 +++++++++++++++++- docs/images/FetchBeerFails.svg | 259 ++++++- docs/images/Tutorial1.svg | 299 +++++++- docs/images/Tutorial2.svg | 1057 +++++++++++++++++++++++++++- 5 files changed, 2737 insertions(+), 5 deletions(-) diff --git a/docs/images/DecoratorEnterRoom.svg b/docs/images/DecoratorEnterRoom.svg index b01efcc8e..f02498e09 100644 --- a/docs/images/DecoratorEnterRoom.svg +++ b/docs/images/DecoratorEnterRoom.svg @@ -1 +1,450 @@ -SequenceSequenceSequenceSequenceEnterRoomEnterRoomCloseDoorCloseDoorIsDoorOpenIsDoorOpenOpenDoorOpenDoorInverterInverterRetryUntilSuccessful...RetryUntilSuccessful...RetryUntilSuccessful...num_attempts = 5RetryUntilSuccessful \ No newline at end of file + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + EnterRoom + + + + EnterRoom + + + + + + + + + CloseDoor + + + + CloseDoor + + + + + + + + + IsDoorOpen + + + + IsDoorOpen + + + + + + + + + + + + OpenDoor + + + + OpenDoor + + + + + + + + + + + Inverter + + + + Inverter + + + + + RetryUntilSuccessful + ... + + + num_attempts = 5 + diff --git a/docs/images/FetchBeer2.svg b/docs/images/FetchBeer2.svg index 8adac582a..b5999a842 100644 --- a/docs/images/FetchBeer2.svg +++ b/docs/images/FetchBeer2.svg @@ -1 +1,675 @@ -
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
ForceSuccess
ForceSuccess
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
Fallback
Fallback
ForceFailure
ForceFailure
CloseFridge
CloseFridge
Text is not SVG - cannot display
\ No newline at end of file + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + OpenFridge + + + + OpenFridge + + + + + + + + + GrabBeer + + + + GrabBeer + + + + + + + + + CloseFridge + + + + CloseFridge + + + + + + + + + + + ForceSuccess + + + + ForceSuccess + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + OpenFridge + + + + OpenFridge + + + + + + + + + GrabBeer + + + + GrabBeer + + + + + + + + + CloseFridge + + + + CloseFridge + + + + + + + + + + + + + Fallback + + + + Fallback + + + + + + + + + + + ForceFailure + + + + ForceFailure + + + + + + + + + CloseFridge + + + + CloseFridge + + + + diff --git a/docs/images/FetchBeerFails.svg b/docs/images/FetchBeerFails.svg index f2489ce93..6e1d92712 100644 --- a/docs/images/FetchBeerFails.svg +++ b/docs/images/FetchBeerFails.svg @@ -1 +1,258 @@ -
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
Text is not SVG - cannot display
\ No newline at end of file + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + OpenFridge + + + + OpenFridge + + + + + + + + + GrabBeer + + + + GrabBeer + + + + + + + + + CloseFridge + + + + CloseFridge + + + + diff --git a/docs/images/Tutorial1.svg b/docs/images/Tutorial1.svg index 4b8a84fd8..3ba73863c 100644 --- a/docs/images/Tutorial1.svg +++ b/docs/images/Tutorial1.svg @@ -1 +1,298 @@ -
Sequence
Sequence
OpenGripper
OpenGripper
ApproachObject
ApproachObject
CloseGripper
CloseGripper
CheckBattery
CheckBattery
Text is not SVG - cannot display
\ No newline at end of file + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + OpenGripper + + + + OpenGripper + + + + + + + + + ApproachObject + + + + ApproachObject + + + + + + + + + CloseGripper + + + + CloseGripper + + + + + + + + + CheckBattery + + + + CheckBattery + + + + diff --git a/docs/images/Tutorial2.svg b/docs/images/Tutorial2.svg index f010f3d48..8d9f461da 100644 --- a/docs/images/Tutorial2.svg +++ b/docs/images/Tutorial2.svg @@ -1 +1,1056 @@ -
Sequence
Sequence
OpenGripper
OpenGripper
ApproachObject
ApproachObject
CloseGripper
CloseGripper
CheckBattery
CheckBattery
Sequence
Sequence
ThinkWhatToSay

text={the_answer}
ThinkWhatToSay...
SaySomething2

message="this works too"
SaySomething2...
SaySomething

message={the_answer}
SaySomething...
SaySomething

message="hello"
SaySomething...
Blackboard
KEY
KEY
TYPE
TYPE
VALUE
VALUE
the_answer
the_answer
string
string
"the answer is 42"
"the answer is 42"
...
...
...
...
...
...
Text is not SVG - cannot display
\ No newline at end of file + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + OpenGripper + + + + OpenGripper + + + + + + + + + ApproachObject + + + + ApproachObject + + + + + + + + + CloseGripper + + + + CloseGripper + + + + + + + + + CheckBattery + + + + CheckBattery + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + + + + ThinkWhatToSay + + + + + text={the_answer} + + + + + + + ThinkWhatToSay... + + + + + + + + + + SaySomething2 + + + + message="this works too" + + + + + + SaySomething2... + + + + + + + + + + SaySomething + + + +message={the_answer} + + + + + SaySomething... + + + + + + + + + + SaySomething + + + + message="hello" + + + + + + SaySomething... + + + + + + + + + + + Blackboard + + + + + + + + KEY + + + + KEY + + + + + + + + + TYPE + + + + TYPE + + + + + + + + + VALUE + + + + VALUE + + + + + + + + + the_answer + + + + the_answer + + + + + + + + + string + + + + string + + + + + + + + + + "the answer is 42" + + + + + + "the answer is 42" + + + + + + + + + ... + + + + ... + + + + + + + + + ... + + + + ... + + + + + + + + + ... + + + + ... + + + + + + From 58b65b350f43c527c00c7625f1bc1192a422c717 Mon Sep 17 00:00:00 2001 From: benjinne Date: Mon, 7 Feb 2022 01:30:32 -0500 Subject: [PATCH 135/709] Docs: BT_basics fix typo (#337) --- docs/BT_basics.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/BT_basics.md b/docs/BT_basics.md index bd593a7ae..f4dfd9aa6 100644 --- a/docs/BT_basics.md +++ b/docs/BT_basics.md @@ -17,7 +17,7 @@ and propagates through the tree until it reaches a leaf node. to complete. - If a TreeNode has one or more children, it is in charge for ticking - them, based on its state, external parameters or the resulkt of the + them, based on its state, external parameters or the result of the previous sibling. - The __LeafNodes__, those TreeNodes which don't have any children, From d0d1177ce1b0b4a4d0aff647c7af867acd9417d1 Mon Sep 17 00:00:00 2001 From: goekce <18174744+goekce@users.noreply.github.com> Date: Mon, 7 Feb 2022 17:50:14 +0300 Subject: [PATCH 136/709] [docs] match text to graphics (#340) --- docs/BT_basics.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/BT_basics.md b/docs/BT_basics.md index f4dfd9aa6..502e677ba 100644 --- a/docs/BT_basics.md +++ b/docs/BT_basics.md @@ -120,13 +120,13 @@ __isDoorOpen__ is therefore equivalent to "Is the door closed?". -The node __Retry__ will repeat ticking the child up to N times (3 in this case) +The node __Retry__ will repeat ticking the child up to __num_attempts__ times (5 in this case) if the child returns FAILURE. __Apparently__, the branch on the right side means: If the door is closed, then try to open it. - Try up to 3 times, otherwise give up and return FAILURE. + Try up to 5 times, otherwise give up and return FAILURE. But... From d8caeb3ecbb1c5d8b5acd9e69f1a8e13475c6918 Mon Sep 17 00:00:00 2001 From: goekce <18174744+goekce@users.noreply.github.com> Date: Wed, 2 Mar 2022 10:17:40 +0100 Subject: [PATCH 137/709] [docs] Clarify sentence (#344) `... will sleep up to 8 hours or less, if he/she is fully rested.` was not clear. It can also be understood as `If he/she is fully rested, the character will sleep ...` --- docs/FallbackNode.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/docs/FallbackNode.md b/docs/FallbackNode.md index 773bb15d2..7d0e0235a 100644 --- a/docs/FallbackNode.md +++ b/docs/FallbackNode.md @@ -80,8 +80,7 @@ This ControlNode is used when you want to interrupt an __asynchronous__ child if one of the previous Conditions changes its state from FAILURE to SUCCESS. -In the following example, character will sleep up to 8 hours or less, -if he/she is fully rested. +In the following example, the character will sleep *up to* 8 hours. If he/she has fully rested, then the node `areYouRested?` will return SUCCESS and the asynchronous nodes `Timeout (8 hrs)` and `Sleep` will be interrupted. ![ReactiveFallback](images/ReactiveFallback.png) From a64b63df89deadb408f4f5a4d6c592d3fb3a232f Mon Sep 17 00:00:00 2001 From: benjinne Date: Wed, 2 Mar 2022 04:17:57 -0500 Subject: [PATCH 138/709] [Docs] BT_basics fix typo (#343) --- docs/BT_basics.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/BT_basics.md b/docs/BT_basics.md index 502e677ba..a9eca0352 100644 --- a/docs/BT_basics.md +++ b/docs/BT_basics.md @@ -23,7 +23,7 @@ and propagates through the tree until it reaches a leaf node. - The __LeafNodes__, those TreeNodes which don't have any children, are the actual commands, i.e. the place where the behavior tree interacts with the rest of the system. - __Actions__ nodes are the most commond type of LeafNodes. + __Actions__ nodes are the most common type of LeafNodes. !!! Note The word __tick__ will be often used as a *verb* (to tick / to be ticked) and it means @@ -63,7 +63,7 @@ it returns SUCCESS (green) too. In the context of __ActionNodes__, we may further distinguish between -synschronous and asynchronous nodes. +synchronous and asynchronous nodes. The former are executed atomically and block the tree until a SUCCESS or FAILURE is returned. From 392f8a7e9bb1163991d7275ac6d6ebc835b76661 Mon Sep 17 00:00:00 2001 From: "imgbot[bot]" <31301654+imgbot[bot]@users.noreply.github.com> Date: Wed, 2 Mar 2022 10:34:48 +0100 Subject: [PATCH 139/709] [ImgBot] Optimize images (#334) *Total -- 90.34kb -> 61.77kb (31.63%) /docs/images/Tutorial1.svg -- 10.08kb -> 6.33kb (37.19%) /docs/images/FetchBeerFails.svg -- 9.00kb -> 5.93kb (34.13%) /docs/images/FetchBeer2.svg -- 21.19kb -> 14.41kb (32%) /docs/images/Tutorial2.svg -- 34.19kb -> 23.75kb (30.54%) /docs/images/DecoratorEnterRoom.svg -- 15.88kb -> 11.35kb (28.54%) Signed-off-by: ImgBotApp Co-authored-by: ImgBotApp --- docs/images/DecoratorEnterRoom.svg | 451 +----------- docs/images/FetchBeer2.svg | 676 +----------------- docs/images/FetchBeerFails.svg | 259 +------ docs/images/Tutorial1.svg | 299 +------- docs/images/Tutorial2.svg | 1057 +--------------------------- 5 files changed, 5 insertions(+), 2737 deletions(-) diff --git a/docs/images/DecoratorEnterRoom.svg b/docs/images/DecoratorEnterRoom.svg index f02498e09..7febd57b3 100644 --- a/docs/images/DecoratorEnterRoom.svg +++ b/docs/images/DecoratorEnterRoom.svg @@ -1,450 +1 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - EnterRoom - - - - EnterRoom - - - - - - - - - CloseDoor - - - - CloseDoor - - - - - - - - - IsDoorOpen - - - - IsDoorOpen - - - - - - - - - - - - OpenDoor - - - - OpenDoor - - - - - - - - - - - Inverter - - - - Inverter - - - - - RetryUntilSuccessful - ... - - - num_attempts = 5 - +SequenceSequenceSequenceSequenceEnterRoomEnterRoomCloseDoorCloseDoorIsDoorOpenIsDoorOpenOpenDoorOpenDoorInverterInverterRetryUntilSuccessful...num_attempts = 5 \ No newline at end of file diff --git a/docs/images/FetchBeer2.svg b/docs/images/FetchBeer2.svg index b5999a842..aaca63d81 100644 --- a/docs/images/FetchBeer2.svg +++ b/docs/images/FetchBeer2.svg @@ -1,675 +1 @@ - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - OpenFridge - - - - OpenFridge - - - - - - - - - GrabBeer - - - - GrabBeer - - - - - - - - - CloseFridge - - - - CloseFridge - - - - - - - - - - - ForceSuccess - - - - ForceSuccess - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - OpenFridge - - - - OpenFridge - - - - - - - - - GrabBeer - - - - GrabBeer - - - - - - - - - CloseFridge - - - - CloseFridge - - - - - - - - - - - - - Fallback - - - - Fallback - - - - - - - - - - - ForceFailure - - - - ForceFailure - - - - - - - - - CloseFridge - - - - CloseFridge - - - - +SequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridgeForceSuccessForceSuccessSequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridgeFallbackFallbackForceFailureForceFailureCloseFridgeCloseFridge \ No newline at end of file diff --git a/docs/images/FetchBeerFails.svg b/docs/images/FetchBeerFails.svg index 6e1d92712..9a596e963 100644 --- a/docs/images/FetchBeerFails.svg +++ b/docs/images/FetchBeerFails.svg @@ -1,258 +1 @@ - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - OpenFridge - - - - OpenFridge - - - - - - - - - GrabBeer - - - - GrabBeer - - - - - - - - - CloseFridge - - - - CloseFridge - - - - +SequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridge \ No newline at end of file diff --git a/docs/images/Tutorial1.svg b/docs/images/Tutorial1.svg index 3ba73863c..9246de0ea 100644 --- a/docs/images/Tutorial1.svg +++ b/docs/images/Tutorial1.svg @@ -1,298 +1 @@ - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - OpenGripper - - - - OpenGripper - - - - - - - - - ApproachObject - - - - ApproachObject - - - - - - - - - CloseGripper - - - - CloseGripper - - - - - - - - - CheckBattery - - - - CheckBattery - - - - +SequenceSequenceOpenGripperOpenGripperApproachObjectApproachObjectCloseGripperCloseGripperCheckBatteryCheckBattery \ No newline at end of file diff --git a/docs/images/Tutorial2.svg b/docs/images/Tutorial2.svg index 8d9f461da..06cf1dd80 100644 --- a/docs/images/Tutorial2.svg +++ b/docs/images/Tutorial2.svg @@ -1,1056 +1 @@ - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - OpenGripper - - - - OpenGripper - - - - - - - - - ApproachObject - - - - ApproachObject - - - - - - - - - CloseGripper - - - - CloseGripper - - - - - - - - - CheckBattery - - - - CheckBattery - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - - - - ThinkWhatToSay - - - - - text={the_answer} - - - - - - - ThinkWhatToSay... - - - - - - - - - - SaySomething2 - - - - message="this works too" - - - - - - SaySomething2... - - - - - - - - - - SaySomething - - - -message={the_answer} - - - - - SaySomething... - - - - - - - - - - SaySomething - - - - message="hello" - - - - - - SaySomething... - - - - - - - - - - - Blackboard - - - - - - - - KEY - - - - KEY - - - - - - - - - TYPE - - - - TYPE - - - - - - - - - VALUE - - - - VALUE - - - - - - - - - the_answer - - - - the_answer - - - - - - - - - string - - - - string - - - - - - - - - - "the answer is 42" - - - - - - "the answer is 42" - - - - - - - - - ... - - - - ... - - - - - - - - - ... - - - - ... - - - - - - - - - ... - - - - ... - - - - - - +SequenceSequenceOpenGripperOpenGripperApproachObjectApproachObjectCloseGripperCloseGripperCheckBatteryCheckBatterySequenceSequenceThinkWhatToSaytext={the_answer}ThinkWhatToSay...SaySomething2message="this works too"SaySomething2...SaySomethingmessage={the_answer}SaySomething...SaySomethingmessage="hello"SaySomething...BlackboardKEYKEYTYPETYPEVALUEVALUEthe_answerthe_answerstringstring"the answer is 42""the answer is 42".................. \ No newline at end of file From 0d04a3e2b83a820e585aecda0412d88e636d0d89 Mon Sep 17 00:00:00 2001 From: benjinne Date: Sun, 6 Mar 2022 04:29:26 -0500 Subject: [PATCH 140/709] ROS2 include ros_pkg attribute support (#351) * ROS2 include pkg support * ros2 build fixed Co-authored-by: Benjamin Linne --- CMakeLists.txt | 64 +++++++++++++++++++++++---------------------- src/xml_parsing.cpp | 23 +++++++++++----- 2 files changed, 49 insertions(+), 38 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 269c327f1..4280648c9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -83,8 +83,7 @@ find_package(ament_cmake QUIET) if ( ament_cmake_FOUND ) - # Not adding -DUSING_ROS since xml_parsing.cpp hasn't been ported to ROS2 - + add_definitions( -DUSING_ROS2 ) message(STATUS "------------------------------------------") message(STATUS "BehaviourTree is being built using AMENT.") message(STATUS "------------------------------------------") @@ -116,35 +115,6 @@ elseif(BUILD_UNIT_TESTS) endif() -############################################################# -if(ament_cmake_FOUND) - set( BEHAVIOR_TREE_LIB_DESTINATION lib ) - set( BEHAVIOR_TREE_INC_DESTINATION include ) - set( BEHAVIOR_TREE_BIN_DESTINATION bin ) - - ament_export_include_directories(include) - ament_export_libraries(${BEHAVIOR_TREE_LIBRARY}) - ament_package() -elseif(catkin_FOUND) - set( BEHAVIOR_TREE_LIB_DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} ) - set( BEHAVIOR_TREE_INC_DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} ) - set( BEHAVIOR_TREE_BIN_DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) -else() - set( BEHAVIOR_TREE_LIB_DESTINATION lib ) - set( BEHAVIOR_TREE_INC_DESTINATION include ) - set( BEHAVIOR_TREE_BIN_DESTINATION bin ) - - set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${BEHAVIOR_TREE_BIN_DESTINATION}" ) - set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${BEHAVIOR_TREE_LIB_DESTINATION}" ) - set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${BEHAVIOR_TREE_BIN_DESTINATION}" ) -endif() - -message( STATUS "BEHAVIOR_TREE_LIB_DESTINATION: ${BEHAVIOR_TREE_LIB_DESTINATION} " ) -message( STATUS "BEHAVIOR_TREE_BIN_DESTINATION: ${BEHAVIOR_TREE_BIN_DESTINATION} " ) -message( STATUS "CMAKE_RUNTIME_OUTPUT_DIRECTORY: ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} " ) -message( STATUS "CMAKE_LIBRARY_OUTPUT_DIRECTORY: ${CMAKE_LIBRARY_OUTPUT_DIRECTORY} " ) -message( STATUS "CMAKE_ARCHIVE_OUTPUT_DIRECTORY: ${CMAKE_ARCHIVE_OUTPUT_DIRECTORY} " ) - ############################################################# # LIBRARY @@ -249,6 +219,38 @@ else() -Wall -Wextra -Werror=return-type) endif() +############################################################# +if(ament_cmake_FOUND) + find_package(ament_index_cpp REQUIRED) + ament_target_dependencies(${BEHAVIOR_TREE_LIBRARY} PUBLIC ament_index_cpp) + + set( BEHAVIOR_TREE_LIB_DESTINATION lib ) + set( BEHAVIOR_TREE_INC_DESTINATION include ) + set( BEHAVIOR_TREE_BIN_DESTINATION bin ) + + ament_export_include_directories(include) + ament_export_libraries(${BEHAVIOR_TREE_LIBRARY}) + ament_package() +elseif(catkin_FOUND) + set( BEHAVIOR_TREE_LIB_DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} ) + set( BEHAVIOR_TREE_INC_DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} ) + set( BEHAVIOR_TREE_BIN_DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) +else() + set( BEHAVIOR_TREE_LIB_DESTINATION lib ) + set( BEHAVIOR_TREE_INC_DESTINATION include ) + set( BEHAVIOR_TREE_BIN_DESTINATION bin ) + + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${BEHAVIOR_TREE_BIN_DESTINATION}" ) + set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${BEHAVIOR_TREE_LIB_DESTINATION}" ) + set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${BEHAVIOR_TREE_BIN_DESTINATION}" ) +endif() + +message( STATUS "BEHAVIOR_TREE_LIB_DESTINATION: ${BEHAVIOR_TREE_LIB_DESTINATION} " ) +message( STATUS "BEHAVIOR_TREE_BIN_DESTINATION: ${BEHAVIOR_TREE_BIN_DESTINATION} " ) +message( STATUS "CMAKE_RUNTIME_OUTPUT_DIRECTORY: ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} " ) +message( STATUS "CMAKE_LIBRARY_OUTPUT_DIRECTORY: ${CMAKE_LIBRARY_OUTPUT_DIRECTORY} " ) +message( STATUS "CMAKE_ARCHIVE_OUTPUT_DIRECTORY: ${CMAKE_ARCHIVE_OUTPUT_DIRECTORY} " ) + ###################################################### # Samples if (BUILD_SAMPLES) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 7dedc941f..f51472b52 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -30,6 +30,10 @@ #include #endif +#ifdef USING_ROS2 +#include +#endif + #include "behaviortree_cpp_v3/blackboard.h" #include "behaviortree_cpp_v3/utils/demangle_util.h" @@ -137,23 +141,28 @@ void XMLParser::Pimpl::loadDocImpl(BT_TinyXML2::XMLDocument* doc) { filesystem::path file_path( include_node->Attribute("path") ); + const char* ros_pkg_relative_path = include_node->Attribute("ros_pkg"); + std::string ros_pkg_path; - if( include_node->Attribute("ros_pkg") ) + if( ros_pkg_relative_path ) { -#ifdef USING_ROS if( file_path.is_absolute() ) { - std::cout << "WARNING: containes an absolute path.\n" + std::cout << "WARNING: contains an absolute path.\n" << "Attribute [ros_pkg] will be ignored."<< std::endl; } - else { - auto ros_pkg_path = ros::package::getPath( include_node->Attribute("ros_pkg") ); - file_path = filesystem::path( ros_pkg_path ) / file_path; - } + else + { +#ifdef USING_ROS + ros_pkg_path = ros::package::getPath(ros_pkg_relative_path); +#elif defined USING_ROS2 + ros_pkg_path = ament_index_cpp::get_package_share_directory(ros_pkg_relative_path); #else throw RuntimeError("Using attribute [ros_pkg] in , but this library was compiled " "without ROS support. Recompile the BehaviorTree.CPP using catkin"); #endif + file_path = filesystem::path( ros_pkg_path ) / file_path; + } } if( !file_path.is_absolute() ) From 0705a49b30cbf99cd5490db9992a2e5a3465eab5 Mon Sep 17 00:00:00 2001 From: goekce <18174744+goekce@users.noreply.github.com> Date: Sun, 6 Mar 2022 10:31:09 +0100 Subject: [PATCH 141/709] [docs] add missing node `SmashDoor` (#342) --- docs/images/FallbackBasic.svg | 508 +++++++++++++++++++++++++++++++++- 1 file changed, 507 insertions(+), 1 deletion(-) diff --git a/docs/images/FallbackBasic.svg b/docs/images/FallbackBasic.svg index c979392a0..2193f1f16 100644 --- a/docs/images/FallbackBasic.svg +++ b/docs/images/FallbackBasic.svg @@ -1 +1,507 @@ -SequenceSequenceFallbackFallbackEnterRoomEnterRoomIsDoorOpenIsDoorOpenSequenceSequenceUnlockDoorUnlockDoorHaveKey?HaveKey?OpenDoorOpenDoorOpenDoorOpenDoor \ No newline at end of file + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + + + + + + + Fallback + + + + Fallback + + + + + + + + + EnterRoom + + + + EnterRoom + + + + + + + + + IsDoorOpen + + + + IsDoorOpen + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + UnlockDoor + + + + UnlockDoor + + + + + + + + + HaveKey? + + + + HaveKey? + + + + + + + + + OpenDoor + + + + OpenDoor + + + + + + + + + OpenDoor + + + + OpenDoor + + + + SmashDoor + + + From d871a0c1919ced3567c78416c10a3a1c6540535d Mon Sep 17 00:00:00 2001 From: "Affonso, Guilherme" Date: Sun, 6 Mar 2022 18:32:48 +0900 Subject: [PATCH 142/709] Don't restart SequenceStar on halt (#329) * Add more SequenceStar tests * Fix typo in test name * Don't reset SequenceStar on halt --- src/controls/sequence_star_node.cpp | 2 +- tests/gtest_sequence.cpp | 88 ++++++++++++++++++++++++++++- 2 files changed, 88 insertions(+), 2 deletions(-) diff --git a/src/controls/sequence_star_node.cpp b/src/controls/sequence_star_node.cpp index 7bd10ce91..216a12516 100644 --- a/src/controls/sequence_star_node.cpp +++ b/src/controls/sequence_star_node.cpp @@ -74,7 +74,7 @@ NodeStatus SequenceStarNode::tick() void SequenceStarNode::halt() { - current_child_idx_ = 0; + // DO NOT reset current_child_idx_ on halt ControlNode::halt(); } diff --git a/tests/gtest_sequence.cpp b/tests/gtest_sequence.cpp index 1141a41c2..c1bdc73d1 100644 --- a/tests/gtest_sequence.cpp +++ b/tests/gtest_sequence.cpp @@ -387,7 +387,7 @@ TEST_F(ComplexSequenceWithMemoryTest, ConditionsTrue) ASSERT_EQ(NodeStatus::IDLE, action_2.status()); } -TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFase) +TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFalse) { BT::NodeStatus state = root.executeTick(); @@ -458,3 +458,89 @@ TEST_F(ComplexSequenceWithMemoryTest, Action1DoneSeq) ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); } + +TEST_F(ComplexSequenceWithMemoryTest, Action2FailureSeq) +{ + root.executeTick(); + std::this_thread::sleep_for(milliseconds(150)); + 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()); + + action_2.setExpectedResult(NodeStatus::FAILURE); + std::this_thread::sleep_for(milliseconds(150)); + root.executeTick(); + + // failure in action_2 does not affect the state of already + // executed nodes (seq_conditions and action_1) + ASSERT_EQ(NodeStatus::FAILURE, root.status()); + ASSERT_EQ(NodeStatus::SUCCESS, 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::SUCCESS, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + + action_2.setExpectedResult(NodeStatus::SUCCESS); + 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(milliseconds(150)); + 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()); +} + +TEST_F(ComplexSequenceWithMemoryTest, Action2HaltSeq) +{ + root.executeTick(); + std::this_thread::sleep_for(milliseconds(150)); + root.executeTick(); + + root.halt(); + + 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.executeTick(); + + // tree retakes execution from action_2 + ASSERT_EQ(NodeStatus::IDLE, 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::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + + std::this_thread::sleep_for(milliseconds(150)); + 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()); +} From 617743b7f931ec10570cb596858f45cd2e9f60cc Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 6 Mar 2022 15:35:58 +0100 Subject: [PATCH 143/709] fix CI --- .github/workflows/build_ubuntu.yml | 28 --------------------- .travis.yml | 40 ------------------------------ CMakeLists.txt | 9 ++++++- README.md | 4 +-- tests/CMakeLists.txt | 16 +++++++----- 5 files changed, 20 insertions(+), 77 deletions(-) delete mode 100644 .github/workflows/build_ubuntu.yml delete mode 100644 .travis.yml diff --git a/.github/workflows/build_ubuntu.yml b/.github/workflows/build_ubuntu.yml deleted file mode 100644 index 73328e998..000000000 --- a/.github/workflows/build_ubuntu.yml +++ /dev/null @@ -1,28 +0,0 @@ -name: build and run tests -on: - push: - branches: [ master ] - pull_request: - branches: [ master ] -jobs: - build: - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v2 - # install dependencies - - name: apt - run: sudo apt-get update && sudo apt-get install -yq libzmq3-dev libdw-dev libgtest-dev cmake - - name: Install gtest manually - working-directory: /usr/src/gtest - run: sudo cmake CMakeLists.txt && sudo make && sudo cp lib/*.a /usr/lib - # build project - - name: mkdir - run: mkdir build - - name: cmake build - run: cmake -Bbuild -H. - - name: cmake make - run: cmake --build build/ --target all - # run tests - - name: run test - run: build/bin/behaviortree_cpp_v3_test - diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index ae4fd354d..000000000 --- a/.travis.yml +++ /dev/null @@ -1,40 +0,0 @@ -# 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: xenial -language: cpp - -os: - - linux - -compiler: - - gcc - -matrix: - include: - - bare_linux: - env: ROS_DISTRO="none" - fast_finish: false - -before_install: - - sudo apt-get update && sudo apt-get --reinstall install -qq build-essential - - if [ "$ROS_DISTRO" = "none" ]; then sudo apt-get --reinstall install -qq libzmq3-dev libdw-dev; fi - # 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 - - cd $TRAVIS_BUILD_DIR - -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: - - if [ "$ROS_DISTRO" = "none" ]; then (cd build; cmake .. ; sudo cmake --build . --target install; ./bin/behaviortree_cpp_v3_test); fi - - if [ "$ROS_DISTRO" != "none" ]; then (.ci_config/travis.sh); fi diff --git a/CMakeLists.txt b/CMakeLists.txt index 4280648c9..b975d8d02 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -111,7 +111,14 @@ elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) set(BUILD_TOOL_INCLUDE_DIRS ${catkin_INCLUDE_DIRS}) elseif(BUILD_UNIT_TESTS) - find_package(GTest REQUIRED) + include(FetchContent) + FetchContent_Declare( + googletest + URL https://github.com/google/googletest/archive/609281088cfefc76f9d0ce82e1ff6c30cc3591e5.zip + ) + # For Windows: Prevent overriding the parent project's compiler/linker settings + set(gtest_force_shared_crt ON CACHE BOOL "" FORCE) + FetchContent_MakeAvailable(googletest) endif() diff --git a/README.md b/README.md index 515566214..14b15a395 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ ![License MIT](https://img.shields.io/github/license/BehaviorTree/BehaviorTree.CPP?color=blue) -![Version](https://img.shields.io/badge/version-3.5-blue.svg) -[![Build Status](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP.svg?branch=master)](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP) +![Version](https://img.shields.io/badge/version-3.6-blue.svg) +[![CMake Build](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/build_vanilla.yml/badge.svg)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/build_vanilla.yml) [![ros1](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros1/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros1) [![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros2/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros2) [![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP)](https://lgtm.com/projects/g/BehaviorTree/BehaviorTree.CPP/context:cpp) diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 3b97db096..0727b153d 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -20,10 +20,16 @@ set(BT_TESTS gtest_switch.cpp ) -if (BT_COROUTINES) - list(APPEND BT_TESTS gtest_coroutines.cpp) +if( BT_COROUTINES ) + LIST( APPEND BT_TESTS gtest_coroutines.cpp) endif() +#if(ament_cmake_FOUND OR catkin_FOUND) +# # This test requires gmock. Since we don't have a uniform way to include +# # gmock for non-users, it is turned of when build without ros. +# list(APPEND BT_TESTS gtest_async_action_node.cpp) +#endif() + if(ament_cmake_FOUND AND BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) @@ -43,15 +49,13 @@ elseif(catkin_FOUND AND CATKIN_ENABLE_TESTING) ${catkin_LIBRARIES}) target_include_directories(${BEHAVIOR_TREE_LIBRARY}_test PRIVATE gtest/include) -elseif(GTEST_FOUND AND BUILD_UNIT_TESTS) +elseif(BUILD_UNIT_TESTS) enable_testing() add_executable(${BEHAVIOR_TREE_LIBRARY}_test ${BT_TESTS}) target_link_libraries(${PROJECT_NAME}_test ${BEHAVIOR_TREE_LIBRARY} - bt_sample_nodes - ${GTEST_LIBRARIES} - ${GTEST_MAIN_LIBRARIES}) + bt_sample_nodes gtest gtest_main) target_include_directories(${BEHAVIOR_TREE_LIBRARY}_test PRIVATE gtest/include ${GTEST_INCLUDE_DIRS}) add_test(BehaviorTreeCoreTest ${CMAKE_RUNTIME_OUTPUT_DIRECTORY}/${BEHAVIOR_TREE_LIBRARY}_test) From 06a1f4cedd6192af9d7e2a9a4b0da3d369a02c8d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 6 Mar 2022 15:36:47 +0100 Subject: [PATCH 144/709] fix thread safety --- docs/images/SequenceStar.svg | 2 +- include/behaviortree_cpp_v3/action_node.h | 3 + include/behaviortree_cpp_v3/blackboard.h | 14 ++- include/behaviortree_cpp_v3/tree_node.h | 1 + package.xml | 1 + src/action_node.cpp | 12 +- src/blackboard.cpp | 2 +- tests/gtest_async_action_node.cpp | 142 ++++++++++++++++++++++ 8 files changed, 171 insertions(+), 6 deletions(-) create mode 100644 tests/gtest_async_action_node.cpp diff --git a/docs/images/SequenceStar.svg b/docs/images/SequenceStar.svg index 3d6278937..c3efde4de 100644 --- a/docs/images/SequenceStar.svg +++ b/docs/images/SequenceStar.svg @@ -1 +1 @@ -SequenceStarSequenceStarGoTo(C)GoTo(C)RetryUntilSuccesfulRetryUntilSuccesfulGoTo(A)GoTo(A)GoTo(B)GoTo(B) \ No newline at end of file +SequenceStarSequenceStarGoTo(C)GoTo(C)RetryUntilSuccessfulRetryUntilSuccessfulGoTo(A)GoTo(A)GoTo(B)GoTo(B) \ No newline at end of file diff --git a/include/behaviortree_cpp_v3/action_node.h b/include/behaviortree_cpp_v3/action_node.h index a7ef2aee6..be19e74d4 100644 --- a/include/behaviortree_cpp_v3/action_node.h +++ b/include/behaviortree_cpp_v3/action_node.h @@ -17,6 +17,8 @@ #include #include #include +#include + #include "leaf_node.h" namespace BT @@ -135,6 +137,7 @@ class AsyncActionNode : public ActionNodeBase std::exception_ptr exptr_; std::atomic_bool halt_requested_; std::future thread_handle_; + std::mutex m_; }; /** diff --git a/include/behaviortree_cpp_v3/blackboard.h b/include/behaviortree_cpp_v3/blackboard.h index 818bd39a3..76004586e 100644 --- a/include/behaviortree_cpp_v3/blackboard.h +++ b/include/behaviortree_cpp_v3/blackboard.h @@ -117,6 +117,7 @@ class Blackboard void set(const std::string& key, const T& value) { std::unique_lock lock(mutex_); + std::unique_lock lock_entry(entry_mutex_); auto it = storage_.find(key); if( auto parent = parent_bb_.lock()) @@ -130,10 +131,10 @@ class Blackboard auto parent_info = parent->portInfo(remapped_key); if( parent_info ) { - storage_.insert( {key, Entry( *parent_info ) } ); + storage_.emplace( key, Entry( *parent_info ) ); } else{ - storage_.insert( {key, Entry( PortInfo() ) } ); + storage_.emplace( key, Entry( PortInfo() ) ); } } parent->set( remapped_key, value ); @@ -195,10 +196,18 @@ class Blackboard storage_.clear(); internal_to_external_.clear(); } + + // Lock this mutex before using get() and getAny() and unlock it while you have + // done using the value. + std::mutex& entryMutex() + { + return entry_mutex_; + } private: struct Entry{ + Any value; const PortInfo port_info; @@ -213,6 +222,7 @@ class Blackboard }; mutable std::mutex mutex_; + mutable std::mutex entry_mutex_; std::unordered_map storage_; std::weak_ptr parent_bb_; std::unordered_map internal_to_external_; diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index aa39138c2..9aa5d847e 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -215,6 +215,7 @@ inline Result TreeNode::getInput(const std::string& key, T& destination) const "but BB is invalid"); } + std::unique_lock entry_lock( config_.blackboard->entryMutex() ); const Any* val = config_.blackboard->getAny(static_cast(remapped_key)); if (val && val->empty() == false) { diff --git a/package.xml b/package.xml index 067d1117c..c478f036e 100644 --- a/package.xml +++ b/package.xml @@ -18,6 +18,7 @@ ament_cmake rclcpp + ament_index_cpp boost libzmq3-dev diff --git a/src/action_node.cpp b/src/action_node.cpp index 79fe35ea5..e33f9c5e9 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -167,6 +167,7 @@ void StatefulActionNode::halt() NodeStatus BT::AsyncActionNode::executeTick() { + using lock_type = std::unique_lock; //send signal to other thread. // The other thread is in charge for changing the status if (status() == NodeStatus::IDLE) @@ -182,16 +183,23 @@ NodeStatus BT::AsyncActionNode::executeTick() { std::cerr << "\nUncaught exception from the method tick(): [" << registrationName() << "/" << name() << "]\n" << std::endl; + // Set the exception pointer and the status atomically. + lock_type l(m_); exptr_ = std::current_exception(); - thread_handle_.wait(); + setStatus(BT::NodeStatus::IDLE); } return status(); }); } + lock_type l(m_); if( exptr_ ) { - std::rethrow_exception(exptr_); + // The official interface of std::exception_ptr does not define any move + // semantics. Thus, we copy and reset exptr_ manually. + const auto exptr_copy = exptr_; + exptr_ = nullptr; + std::rethrow_exception(exptr_copy); } return status(); } diff --git a/src/blackboard.cpp b/src/blackboard.cpp index f86fdddae..fdf0bf379 100644 --- a/src/blackboard.cpp +++ b/src/blackboard.cpp @@ -18,7 +18,7 @@ void Blackboard::setPortInfo(std::string key, const PortInfo& info) auto it = storage_.find(key); if( it == storage_.end() ) { - storage_.insert( { std::move(key), Entry(info) } ); + storage_.emplace( key, Entry(info) ); } else{ auto old_type = it->second.port_info.type(); diff --git a/tests/gtest_async_action_node.cpp b/tests/gtest_async_action_node.cpp new file mode 100644 index 000000000..e2201da10 --- /dev/null +++ b/tests/gtest_async_action_node.cpp @@ -0,0 +1,142 @@ +#include "behaviortree_cpp_v3/action_node.h" +#include "behaviortree_cpp_v3/basic_types.h" + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +// The mocked version of the base. +struct MockedAsyncActionNode : public BT::AsyncActionNode +{ + using BT::AsyncActionNode::AsyncActionNode; + MOCK_METHOD0(tick, BT::NodeStatus()); + + // Tick while the node is running. + BT::NodeStatus spinUntilDone() + { + do + { + executeTick(); + } while (status() == BT::NodeStatus::RUNNING); + return status(); + } + + // Expose the setStatus method. + using BT::AsyncActionNode::setStatus; +}; + +// The fixture taking care of the node-setup. +struct MockedAsyncActionFixture : public testing::Test +{ + BT::NodeConfiguration config; + MockedAsyncActionNode sn; + MockedAsyncActionFixture() : sn("node", config) + { + } +}; + +// Parameters for the terminal node states. +struct NodeStatusFixture : public testing::WithParamInterface, + public MockedAsyncActionFixture +{ +}; + +INSTANTIATE_TEST_CASE_P(/**/, NodeStatusFixture, + testing::Values(BT::NodeStatus::SUCCESS, BT::NodeStatus::FAILURE)); + +TEST_P(NodeStatusFixture, normal_routine) +{ + // Test verifies the "normal" operation: We correctly propagate the result + // from the tick to the caller. + const BT::NodeStatus state = GetParam(); + + // Setup the mock-expectations. + EXPECT_CALL(sn, tick()).WillOnce(testing::Invoke([&]() { + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + return state; + })); + + // Spin the node and check the final status. + ASSERT_EQ(sn.spinUntilDone(), state); +} + +TEST_F(MockedAsyncActionFixture, no_halt) +{ + // Test verifies that halt returns immediately, if the node is idle. It + // further checks if the halt-flag is resetted correctly. + sn.halt(); + ASSERT_TRUE(sn.isHaltRequested()); + + // Below we further verify that the halt flag is cleaned up properly. + const BT::NodeStatus state{BT::NodeStatus::SUCCESS}; + EXPECT_CALL(sn, tick()).WillOnce(testing::Return(state)); + + // Spin the node and check. + ASSERT_EQ(sn.spinUntilDone(), state); + ASSERT_FALSE(sn.isHaltRequested()); +} + +TEST_F(MockedAsyncActionFixture, halt) +{ + // Test verifies that calling halt() is blocking. + bool release = false; + std::mutex m; + std::condition_variable cv; + + const BT::NodeStatus state{BT::NodeStatus::SUCCESS}; + EXPECT_CALL(sn, tick()).WillOnce(testing::Invoke([&]() { + // Sleep until we send the release signal. + std::unique_lock l(m); + while (!release) + cv.wait(l); + + return state; + })); + + // Start the execution. + sn.executeTick(); + + // Try to halt the node (cv will block it...) + std::future halted = std::async(std::launch::async, [&]() { sn.halt(); }); + ASSERT_EQ(halted.wait_for(std::chrono::milliseconds(10)), std::future_status::timeout); + ASSERT_EQ(sn.status(), BT::NodeStatus::RUNNING); + + // Release the method. + { + std::unique_lock l(m); + release = true; + cv.notify_one(); + } + + // Wait for the future to return. + halted.wait(); + ASSERT_EQ(sn.status(), state); +} + +TEST_F(MockedAsyncActionFixture, exception) +{ + // Verifies that we can recover from the exceptions in the tick method: + // 1) catch the exception, 2) re-raise it in the caller thread. + + // Setup the mock. + EXPECT_CALL(sn, tick()).WillOnce(testing::Invoke([&]() { + throw std::runtime_error("This is not good!"); + return BT::NodeStatus::SUCCESS; + })); + + ASSERT_ANY_THROW(sn.spinUntilDone()); + testing::Mock::VerifyAndClearExpectations(&sn); + + // Now verify that the exception is cleared up (we succeed). + sn.setStatus(BT::NodeStatus::IDLE); + const BT::NodeStatus state{BT::NodeStatus::SUCCESS}; + EXPECT_CALL(sn, tick()).WillOnce(testing::Return(state)); + ASSERT_EQ(sn.spinUntilDone(), state); +} From 060f5203e15d25010e7ebf26469d75f875f73882 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 6 Mar 2022 16:00:39 +0100 Subject: [PATCH 145/709] remove windows tests --- .github/workflows/build_vanilla.yml | 52 +++++++++++++++++++++++++++++ 1 file changed, 52 insertions(+) create mode 100644 .github/workflows/build_vanilla.yml diff --git a/.github/workflows/build_vanilla.yml b/.github/workflows/build_vanilla.yml new file mode 100644 index 000000000..88803bd05 --- /dev/null +++ b/.github/workflows/build_vanilla.yml @@ -0,0 +1,52 @@ +name: CMake Build Matrix + +on: [push] + +env: + # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) + BUILD_TYPE: Release + +jobs: + build: + # The CMake configure and build commands are platform agnostic and should work equally + # well on Windows or Mac. You can convert this to a matrix build if you need + # cross-platform coverage. + # See: https://docs.github.com/en/free-pro-team@latest/actions/learn-github-actions/managing-complex-workflows#using-a-build-matrix + runs-on: ${{ matrix.os }} + strategy: + matrix: + os: [ubuntu-latest, windows-latest] + + steps: + - uses: actions/checkout@v2 + + - name: Install Dependencies (Linux) + run: sudo apt-get install libboost-dev + if: matrix.os == 'ubuntu-latest' + + - name: Create Build Environment + # Some projects don't allow in-source building, so create a separate build directory + # We'll use this as our working directory for all subsequent commands + run: cmake -E make_directory ${{github.workspace}}/build + + - name: Configure CMake + # Use a bash shell so we can use the same syntax for environment variable + # access regardless of the host operating system + shell: bash + working-directory: ${{github.workspace}}/build + # Note the current convention is to use the -S and -B options here to specify source + # and build directories, but this is only available with CMake 3.13 and higher. + # The CMake binaries on the Github Actions machines are (as of this writing) 3.12 + run: cmake $GITHUB_WORKSPACE -DCMAKE_BUILD_TYPE=$BUILD_TYPE -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON + + - name: Build + working-directory: ${{github.workspace}}/build + shell: bash + # Execute the build. You can specify a specific target with "--target " + run: cmake --build . --config $BUILD_TYPE + + - name: run test (Linux) + if: matrix.os == 'ubuntu-latest' + working-directory: ${{github.workspace}}/build + run: ./bin/behaviortree_cpp_v3_test + From b498aa61ee16ff6593b9d6a7cd75e00916ecf748 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 6 Mar 2022 17:52:45 +0100 Subject: [PATCH 146/709] prepare release --- CHANGELOG.rst | 70 +++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 70 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index bebd4a073..9872cb187 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,76 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* remove windows tests +* fix thread safety +* fix CI +* Don't restart SequenceStar on halt (`#329 `_) + * Add more SequenceStar tests + * Fix typo in test name + * Don't reset SequenceStar on halt +* [docs] add missing node `SmashDoor` (`#342 `_) +* ROS2 include ros_pkg attribute support (`#351 `_) + * ROS2 include pkg support + * ros2 build fixed + Co-authored-by: Benjamin Linne +* [ImgBot] Optimize images (`#334 `_) + *Total -- 90.34kb -> 61.77kb (31.63%) + /docs/images/Tutorial1.svg -- 10.08kb -> 6.33kb (37.19%) + /docs/images/FetchBeerFails.svg -- 9.00kb -> 5.93kb (34.13%) + /docs/images/FetchBeer2.svg -- 21.19kb -> 14.41kb (32%) + /docs/images/Tutorial2.svg -- 34.19kb -> 23.75kb (30.54%) + /docs/images/DecoratorEnterRoom.svg -- 15.88kb -> 11.35kb (28.54%) + Co-authored-by: ImgBotApp +* [Docs] BT_basics fix typo (`#343 `_) +* [docs] Clarify sentence (`#344 `_) + `... will sleep up to 8 hours or less, if he/she is fully rested.` was not clear. It can also be understood as `If he/she is fully rested, the character will sleep ...` +* [docs] match text to graphics (`#340 `_) +* Docs: BT_basics fix typo (`#337 `_) +* Merge branch 'master' of github.com:BehaviorTree/BehaviorTree.CPP +* fix svg +* Fix CMake ENABLE_COROUTINES flag with Boost < 1.59 (`#335 `_) + Co-authored-by: Cam Fulton +* Add ENABLE_COROUTINES CMake option (`#316 `_) + * Add DISABLE_COROUTINES CMake option + * Change convention of CMake coroutine flag to ENABLE + Co-authored-by: Cam Fulton +* [ImgBot] Optimize images (`#333 `_) + *Total -- 152.97kb -> 114.57kb (25.1%) + /docs/images/ReactiveSequence.svg -- 7.58kb -> 4.59kb (39.47%) + /docs/images/SequenceNode.svg -- 11.28kb -> 7.12kb (36.87%) + /docs/images/SequenceStar.svg -- 11.22kb -> 7.09kb (36.8%) + /docs/images/DecoratorEnterRoom.svg -- 20.71kb -> 13.30kb (35.77%) + /docs/images/FallbackBasic.svg -- 19.09kb -> 12.64kb (33.79%) + /docs/images/FetchBeer.svg -- 24.30kb -> 16.36kb (32.66%) + /docs/images/SequenceBasic.svg -- 6.32kb -> 5.49kb (13.04%) + /docs/images/Tutorial1.svg -- 6.67kb -> 5.94kb (10.98%) + /docs/images/FetchBeerFails.svg -- 6.46kb -> 5.83kb (9.76%) + /docs/images/FetchBeer2.svg -- 14.99kb -> 13.76kb (8.18%) + /docs/images/Tutorial2.svg -- 24.35kb -> 22.44kb (7.85%) + Co-authored-by: ImgBotApp +* doc fix +* Merge branch 'new_doc' +* remove deprecated code +* updated documentation +* [Fix] Fix cmake version warning and -Wformat warning (`#319 `_) + Co-authored-by: Homalozoa +* Update README.md +* Fix Windows shared lib build (`#323 `_) +* fix shadowed variable in string_view.hpp (`#327 `_) +* Build Sample Nodes By Default to Fix Github Action (`#332 `_) + * Fix github action + * Change working directory in github action step + * Build samples by default +* Added BlackboardCheckBool decorator node (`#326 `_) + * Added tests for BlackboardCheck decorator node + * Added BlackboardCheckBool decorator node +* Fixed typo "Exeption" -> "Exception" (`#331 `_) +* WIP +* fix `#325 `_ +* Contributors: Adam Sasine, Affonso, Guilherme, Alberto Soragna, Davide Faconti, Homalozoa X, Jake Keller, Philippe Couvignou, Tobias Fischer, benjinne, fultoncjb, goekce, imgbot[bot] + 3.6.0 (2021-11-10) ------------------ * Build samples independently of examples (`#315 `_) From 59a50cb795ca0c46d911bb4ae5414c93c419d25d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 6 Mar 2022 17:52:58 +0100 Subject: [PATCH 147/709] 3.6.1 --- CHANGELOG.rst | 4 ++-- package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 9872cb187..2490eed27 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +3.6.1 (2022-03-06) +------------------ * remove windows tests * fix thread safety * fix CI diff --git a/package.xml b/package.xml index c478f036e..9549df0ac 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.6.0 + 3.6.1 This package provides the Behavior Trees core library. From dfa90bc05b376885bdf5c0388e2d3fb0a4e549c1 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 11 Mar 2022 16:52:03 +0100 Subject: [PATCH 148/709] Update action_node.h --- include/behaviortree_cpp_v3/action_node.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/behaviortree_cpp_v3/action_node.h b/include/behaviortree_cpp_v3/action_node.h index be19e74d4..52f6a07f3 100644 --- a/include/behaviortree_cpp_v3/action_node.h +++ b/include/behaviortree_cpp_v3/action_node.h @@ -141,8 +141,8 @@ class AsyncActionNode : public ActionNodeBase }; /** - * @brief The ActionNode is the goto option for, - * but it is actually much easier to use correctly. + * @brief The ActionNode is the prefered way to implement asynchronous Actions. + * It is actually easier to use correctly, when compared with AsyncAction * * It is particularly useful when your code contains a request-reply pattern, * i.e. when the actions sends an asychronous request, then checks periodically From f7a1b35ed7e8696f727b6bf9312ee68d9b808034 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 5 Apr 2022 15:26:24 +0200 Subject: [PATCH 149/709] Fix #320 : forbit refrences in Any --- include/behaviortree_cpp_v3/utils/safe_any.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/include/behaviortree_cpp_v3/utils/safe_any.hpp b/include/behaviortree_cpp_v3/utils/safe_any.hpp index 7f9fe5baf..bb440e111 100644 --- a/include/behaviortree_cpp_v3/utils/safe_any.hpp +++ b/include/behaviortree_cpp_v3/utils/safe_any.hpp @@ -92,6 +92,7 @@ class Any template explicit Any(const T& value, EnableNonIntegral = 0) : _any(value), _original_type( &typeid(T) ) { + static_assert(!std::is_reference_v, "Any can not contain references"); } Any& operator = (const Any& other) @@ -118,6 +119,8 @@ class Any template T cast() const { + static_assert(!std::is_reference_v, "Any::cast uses value semantic, can not cast to reference"); + if( _any.empty() ) { throw std::runtime_error("Any::cast failed because it is empty"); From e5151f3bccaa0a42cf04a91d20c7fa93eb2a5685 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 6 Apr 2022 11:33:43 +0200 Subject: [PATCH 150/709] fix compilation --- include/behaviortree_cpp_v3/utils/safe_any.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/behaviortree_cpp_v3/utils/safe_any.hpp b/include/behaviortree_cpp_v3/utils/safe_any.hpp index bb440e111..4b23fae77 100644 --- a/include/behaviortree_cpp_v3/utils/safe_any.hpp +++ b/include/behaviortree_cpp_v3/utils/safe_any.hpp @@ -92,7 +92,7 @@ class Any template explicit Any(const T& value, EnableNonIntegral = 0) : _any(value), _original_type( &typeid(T) ) { - static_assert(!std::is_reference_v, "Any can not contain references"); + static_assert(!std::is_reference::value, "Any can not contain references"); } Any& operator = (const Any& other) @@ -119,7 +119,7 @@ class Any template T cast() const { - static_assert(!std::is_reference_v, "Any::cast uses value semantic, can not cast to reference"); + static_assert(!std::is_reference::value, "Any::cast uses value semantic, can not cast to reference"); if( _any.empty() ) { From e6f241cf31c22db8e91b8376235d1c45cc1b7b25 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 6 Apr 2022 11:33:49 +0200 Subject: [PATCH 151/709] fix message --- src/action_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/action_node.cpp b/src/action_node.cpp index e33f9c5e9..3e452e663 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -138,7 +138,7 @@ NodeStatus StatefulActionNode::tick() NodeStatus new_status = onStart(); if( new_status == NodeStatus::IDLE) { - throw std::logic_error("AsyncActionNode2::onStart() must not return IDLE"); + throw std::logic_error("StatefulActionNode::onStart() must not return IDLE"); } return new_status; } @@ -148,7 +148,7 @@ NodeStatus StatefulActionNode::tick() NodeStatus new_status = onRunning(); if( new_status == NodeStatus::IDLE) { - throw std::logic_error("AsyncActionNode2::onRunning() must not return IDLE"); + throw std::logic_error("StatefulActionNode::onRunning() must not return IDLE"); } return new_status; } From 178a6266a31ac6a42fbafc6aa31906f1f92f464b Mon Sep 17 00:00:00 2001 From: Fabian Schurig Date: Wed, 27 Apr 2022 15:57:36 +0200 Subject: [PATCH 152/709] Change order of lock to prevent deadlock. (#368) Resolves #367. --- include/behaviortree_cpp_v3/blackboard.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/behaviortree_cpp_v3/blackboard.h b/include/behaviortree_cpp_v3/blackboard.h index 76004586e..ee1b61b93 100644 --- a/include/behaviortree_cpp_v3/blackboard.h +++ b/include/behaviortree_cpp_v3/blackboard.h @@ -116,8 +116,8 @@ class Blackboard template void set(const std::string& key, const T& value) { - std::unique_lock lock(mutex_); std::unique_lock lock_entry(entry_mutex_); + std::unique_lock lock(mutex_); auto it = storage_.find(key); if( auto parent = parent_bb_.lock()) From f9c24617153807cef415080f53ebb8865cd6c4ff Mon Sep 17 00:00:00 2001 From: Hyeongsik Min Date: Wed, 27 Apr 2022 22:58:32 +0900 Subject: [PATCH 153/709] Export dependency on ament_index_cpp (#362) To make dependent packages try to link ament_index_cpp, export the dependency explicitly. --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index b975d8d02..a9041f8f7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -230,6 +230,7 @@ endif() if(ament_cmake_FOUND) find_package(ament_index_cpp REQUIRED) ament_target_dependencies(${BEHAVIOR_TREE_LIBRARY} PUBLIC ament_index_cpp) + ament_export_dependencies(ament_index_cpp) set( BEHAVIOR_TREE_LIB_DESTINATION lib ) set( BEHAVIOR_TREE_INC_DESTINATION include ) From 095358f769b0232ae11874ae26a7e1968b3f837c Mon Sep 17 00:00:00 2001 From: Robodrome <98538838+robodrome@users.noreply.github.com> Date: Wed, 27 Apr 2022 15:59:27 +0200 Subject: [PATCH 154/709] Update tutorial_09_coroutines.md (#359) Minor fix, renamed Timepoint to TimePoint. --- docs/tutorial_09_coroutines.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/tutorial_09_coroutines.md b/docs/tutorial_09_coroutines.md index 6458e4f7c..94c9ffd76 100644 --- a/docs/tutorial_09_coroutines.md +++ b/docs/tutorial_09_coroutines.md @@ -105,7 +105,7 @@ class MyAsyncAction: public CoroActionNode CoroActionNode::halt(); } - Timepoint Now() + TimePoint Now() { return std::chrono::high_resolution_clock::now(); }; From a2a5c191b24c0fca6d444ecbd916bb502afae97f Mon Sep 17 00:00:00 2001 From: panwauu <62597223+panwauu@users.noreply.github.com> Date: Fri, 13 May 2022 11:37:30 +0200 Subject: [PATCH 155/709] Update Tutorial 2 Docuemtation (#372) --- docs/tutorial_02_basic_ports.md | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/docs/tutorial_02_basic_ports.md b/docs/tutorial_02_basic_ports.md index 80dee36a6..e4491641d 100644 --- a/docs/tutorial_02_basic_ports.md +++ b/docs/tutorial_02_basic_ports.md @@ -189,16 +189,13 @@ static value into an entry using the built-in Actions called `SetBlackboard`. ## A complete example -In this example, a Sequence of 5 Actions is executed: +In this example, a Sequence of 4 Actions is executed: -- Actions 1 and 4 read the input `message` from a static string. +- Actions 1 and 2 read the input `message` from a static string (`SaySomething2` is a SimpleActionNode). -- Actions 3 and 5 read the input `message` from an entry in the - blackboard called `the_answer`. +- Action 3 writes something into the entry of the blackboard called `the_answer`. -- Action 2 writes something into the entry of the blackboard called `the_answer`. - -`SaySomething2` is a SimpleActionNode. +- Action 4 read the input `message` from an entry in the blackboard called `the_answer`. ```XML From 674764bb724dc71f1fff3444d2b9b0a8a751c99d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 11:56:30 +0200 Subject: [PATCH 156/709] comment changed --- include/behaviortree_cpp_v3/action_node.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/include/behaviortree_cpp_v3/action_node.h b/include/behaviortree_cpp_v3/action_node.h index 52f6a07f3..0452e6ef0 100644 --- a/include/behaviortree_cpp_v3/action_node.h +++ b/include/behaviortree_cpp_v3/action_node.h @@ -183,9 +183,8 @@ class StatefulActionNode : public ActionNodeBase #ifndef BT_NO_COROUTINES /** - * @brief The CoroActionNode class is an ideal candidate for asynchronous actions - * which need to communicate with an external service using an asynch request/reply interface - * (being notable examples ActionLib in ROS, MoveIt clients or move_base clients). + * @brief The CoroActionNode class is an a good candidate for asynchronous actions + * which need to communicate with an external service using an asynch request/reply interface. * * It is up to the user to decide when to suspend execution of the Action and resume * the parent node, invoking the method setStatusRunningAndYield(). From 4b21907a7f876a755c283bdfc816aa53c63ad42b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 11:59:55 +0200 Subject: [PATCH 157/709] fix issue #360 --- CMakeLists.txt | 22 +++++++++++++--------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a9041f8f7..6b9cf5d9a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.5.1) # version on Ubuntu Xenial +cmake_minimum_required(VERSION 3.10.2) # version on Ubuntu Bionic project(behaviortree_cpp_v3) #---- Add the subdirectory cmake ---- @@ -111,14 +111,18 @@ elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) set(BUILD_TOOL_INCLUDE_DIRS ${catkin_INCLUDE_DIRS}) elseif(BUILD_UNIT_TESTS) - include(FetchContent) - FetchContent_Declare( - googletest - URL https://github.com/google/googletest/archive/609281088cfefc76f9d0ce82e1ff6c30cc3591e5.zip - ) - # For Windows: Prevent overriding the parent project's compiler/linker settings - set(gtest_force_shared_crt ON CACHE BOOL "" FORCE) - FetchContent_MakeAvailable(googletest) + if(${CMAKE_VERSION} VERSION_LESS "3.11.0") + find_package(GTest REQUIRED) + else() + include(FetchContent) + FetchContent_Declare( + googletest + URL https://github.com/google/googletest/archive/609281088cfefc76f9d0ce82e1ff6c30cc3591e5.zip + ) + # For Windows: Prevent overriding the parent project's compiler/linker settings + set(gtest_force_shared_crt ON CACHE BOOL "" FORCE) + FetchContent_MakeAvailable(googletest) + endif() endif() From f16a4d285fa5e9b7504c558c3e8782f7f54ae8bf Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 12:13:50 +0200 Subject: [PATCH 158/709] fix issue #330 --- .../decorators/blackboard_precondition.h | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h b/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h index 1d7312fa8..00fd6e57e 100644 --- a/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h +++ b/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h @@ -14,6 +14,7 @@ #define DECORATOR_BLACKBOARD_PRECONDITION_NODE_H #include "behaviortree_cpp_v3/decorator_node.h" +#include namespace BT { @@ -71,10 +72,17 @@ NodeStatus BlackboardPreconditionNode::tick() setStatus(NodeStatus::RUNNING); if( getInput("value_A", value_A) && - getInput("value_B", value_B) && - value_B == value_A ) + getInput("value_B", value_B) ) { - return child_node_->executeTick(); + bool is_equal = (value_B == value_A); + if ( std::is_same::value || std::is_same::value ) + { + is_equal = std::abs(value_B - value_A) <= std::numeric_limits::epsilon(); + } + if(is_equal) + { + return child_node_->executeTick(); + } } if( child()->status() == NodeStatus::RUNNING ) From e493cc1ffdbb42671e8aa73e6ada2735dd66506a Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 12:18:41 +0200 Subject: [PATCH 159/709] fix #338 --- src/controls/while_do_else_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/controls/while_do_else_node.cpp b/src/controls/while_do_else_node.cpp index 4757e2730..c902e5178 100644 --- a/src/controls/while_do_else_node.cpp +++ b/src/controls/while_do_else_node.cpp @@ -33,7 +33,7 @@ NodeStatus WhileDoElseNode::tick() if(children_count != 3) { - throw std::logic_error("WhileDoElse must have either 2 or 3 children"); + throw std::logic_error("WhileDoElse must have 3 children"); } setStatus(NodeStatus::RUNNING); From 5b474b8de0db7511fd6e1680f7234ef3492bebe8 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 12:37:35 +0200 Subject: [PATCH 160/709] fix compilation --- .../decorators/blackboard_precondition.h | 25 +++++++++++-------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h b/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h index 00fd6e57e..c5b2beddb 100644 --- a/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h +++ b/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h @@ -62,6 +62,17 @@ class BlackboardPreconditionNode : public DecoratorNode //---------------------------------------------------- +template inline bool IsSame(const T& a, const T& b) +{ + return a == b; +} + +inline bool IsSame(const double& a, const double& b) +{ + constexpr double EPS = static_cast(std::numeric_limits::epsilon()); + return std::abs(a - b) <= EPS; +} + template inline NodeStatus BlackboardPreconditionNode::tick() { @@ -72,17 +83,10 @@ NodeStatus BlackboardPreconditionNode::tick() setStatus(NodeStatus::RUNNING); if( getInput("value_A", value_A) && - getInput("value_B", value_B) ) + getInput("value_B", value_B) && + IsSame(value_A, value_B)) { - bool is_equal = (value_B == value_A); - if ( std::is_same::value || std::is_same::value ) - { - is_equal = std::abs(value_B - value_A) <= std::numeric_limits::epsilon(); - } - if(is_equal) - { - return child_node_->executeTick(); - } + return child_node_->executeTick(); } if( child()->status() == NodeStatus::RUNNING ) @@ -93,6 +97,7 @@ NodeStatus BlackboardPreconditionNode::tick() return default_return_status; } + } // end namespace #endif From 6812cc6990453141603b7dd73df864e70f4eaa69 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 12:42:48 +0200 Subject: [PATCH 161/709] Update ros1.yaml --- .github/workflows/ros1.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ros1.yaml b/.github/workflows/ros1.yaml index e6d2f9be2..524552c36 100644 --- a/.github/workflows/ros1.yaml +++ b/.github/workflows/ros1.yaml @@ -8,7 +8,7 @@ jobs: matrix: env: - {ROS_DISTRO: melodic, ROS_REPO: main} - - {ROS_DISTRO: kinetic, ROS_REPO: main} + - {ROS_DISTRO: noetic, ROS_REPO: main} runs-on: ubuntu-latest steps: - uses: actions/checkout@v1 From a55c1cee06097327ec15793461d8237e63b3377f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 14:02:53 +0200 Subject: [PATCH 162/709] add the ability to register multiple BTs (#373) --- examples/CMakeLists.txt | 2 + examples/t13_load_multiple_BTs.cpp | 84 ++++++++++++++++++++ include/behaviortree_cpp_v3/bt_factory.h | 14 +++- include/behaviortree_cpp_v3/bt_parser.h | 8 +- include/behaviortree_cpp_v3/xml_parsing.h | 11 ++- src/bt_factory.cpp | 26 +++++++ src/xml_parsing.cpp | 94 +++++++++++++---------- tests/gtest_factory.cpp | 60 +++++++++++++++ 8 files changed, 251 insertions(+), 48 deletions(-) create mode 100644 examples/t13_load_multiple_BTs.cpp diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 59b059cdd..be7560fbf 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -52,3 +52,5 @@ if(CURSES_FOUND) target_link_libraries(t12_ncurses_manual_selector ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) endif() +add_executable(t13_load_multiple_BTs t13_load_multiple_BTs.cpp ) +target_link_libraries(t13_load_multiple_BTs ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) diff --git a/examples/t13_load_multiple_BTs.cpp b/examples/t13_load_multiple_BTs.cpp new file mode 100644 index 000000000..ef05e1ae2 --- /dev/null +++ b/examples/t13_load_multiple_BTs.cpp @@ -0,0 +1,84 @@ +#include "dummy_nodes.h" +#include "behaviortree_cpp_v3/bt_factory.h" + + +/** This example show how it is possible to: + * - load BehaviorTrees from multiple files manually (without the tag) + * - instantiate a specific tree, instead of the one specified by [main_tree_to_execute] + */ + +// clang-format off + +static const char* xml_text_main = R"( + + + + + + + + + )"; + +static const char* xml_text_subA = R"( + + + + + )"; + +static const char* xml_text_subB = R"( + + + + + )"; + +// clang-format on + +using namespace BT; + +int main() +{ + BT::BehaviorTreeFactory factory; + factory.registerNodeType("SaySomething"); + + // Register the behavior tree definitions, but do not instantiate them yet. + // Order is not important. + factory.registerBehaviorTreeFromText(xml_text_subA); + factory.registerBehaviorTreeFromText(xml_text_subB); + factory.registerBehaviorTreeFromText(xml_text_main); + + //Check that the BTs have been registered correctly + std::cout << "Registered BehaviorTrees:" << std::endl; + for(const std::string& bt_name: factory.registeredBehaviorTrees()) + { + std::cout << " - " << bt_name << std::endl; + } + + // You can create the MainTree and the subtrees will be added automatically. + std::cout << "----- MainTree tick ----" << std::endl; + auto main_tree = factory.createdTree("MainTree"); + main_tree.tickRoot(); + + // ... or you can create only one of the subtree + std::cout << "----- SubA tick ----" << std::endl; + auto subA_tree = factory.createdTree("SubA"); + subA_tree.tickRoot(); + + return 0; +} +/* Expected output: + +Registered BehaviorTrees: + - MainTree + - SubA + - SubB +----- MainTree tick ---- +Robot says: starting MainTree +Robot says: Executing SubA +Robot says: Executing SubB +----- SubA tick ---- +Robot says: Executing SubA + +*/ diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index ac7c424d2..f0c69fdf0 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -22,7 +22,6 @@ #include #include - #include "behaviortree_cpp_v3/behavior_tree.h" namespace BT @@ -197,6 +196,8 @@ class Tree }; +class Parser; + /** * @brief The BehaviorTreeFactory is used to create instances of a * TreeNode at run-time. @@ -270,6 +271,12 @@ class BehaviorTreeFactory */ void registerFromROSPlugins(); + void registerBehaviorTreeFromFile(const std::string& filename); + + void registerBehaviorTreeFromText(const std::string& xml_text); + + std::vector registeredBehaviorTrees() const; + /** * @brief instantiateTreeNode creates an instance of a previously registered TreeNode. * @@ -374,11 +381,16 @@ class BehaviorTreeFactory Tree createTreeFromFile(const std::string& file_path, Blackboard::Ptr blackboard = Blackboard::create()); + Tree createdTree(const std::string& tree_name, + Blackboard::Ptr blackboard = Blackboard::create()); + private: std::unordered_map builders_; std::unordered_map manifests_; std::set builtin_IDs_; + std::unordered_map behavior_tree_definitions_; + std::shared_ptr parser_; // clang-format on }; diff --git a/include/behaviortree_cpp_v3/bt_parser.h b/include/behaviortree_cpp_v3/bt_parser.h index c5f979928..46e9b3aa4 100644 --- a/include/behaviortree_cpp_v3/bt_parser.h +++ b/include/behaviortree_cpp_v3/bt_parser.h @@ -21,11 +21,13 @@ class Parser Parser(const Parser& other) = delete; Parser& operator=(const Parser& other) = delete; - virtual void loadFromFile(const std::string& filename) = 0; + virtual void loadFromFile(const std::string& filename, bool add_includes = true) = 0; - virtual void loadFromText(const std::string& xml_text) = 0; + virtual void loadFromText(const std::string& xml_text, bool add_includes = true) = 0; - virtual Tree instantiateTree(const Blackboard::Ptr &root_blackboard) = 0; + virtual std::vector registeredBehaviorTrees() const = 0; + + virtual Tree instantiateTree(const Blackboard::Ptr &root_blackboard, std::string tree_name = {}) = 0; }; } diff --git a/include/behaviortree_cpp_v3/xml_parsing.h b/include/behaviortree_cpp_v3/xml_parsing.h index 401dd1e11..45b196c78 100644 --- a/include/behaviortree_cpp_v3/xml_parsing.h +++ b/include/behaviortree_cpp_v3/xml_parsing.h @@ -16,16 +16,19 @@ class XMLParser: public Parser public: XMLParser(const BehaviorTreeFactory& factory); - ~XMLParser(); + ~XMLParser() override; XMLParser(const XMLParser& other) = delete; XMLParser& operator=(const XMLParser& other) = delete; - void loadFromFile(const std::string& filename) override; + void loadFromFile(const std::string& filename, bool add_includes = true) override; - void loadFromText(const std::string& xml_text) override; + void loadFromText(const std::string& xml_text, bool add_includes = true) override; - Tree instantiateTree(const Blackboard::Ptr &root_blackboard) override; + std::vector registeredBehaviorTrees() const override; + + Tree instantiateTree(const Blackboard::Ptr &root_blackboard, + std::string main_tree_to_execute = {}) override; private: diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index c31226571..12ecdbc1e 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -10,9 +10,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 #include "behaviortree_cpp_v3/bt_factory.h" #include "behaviortree_cpp_v3/utils/shared_library.h" #include "behaviortree_cpp_v3/xml_parsing.h" +#include "private/tinyxml2.h" #ifdef USING_ROS #include "filesystem/path.h" @@ -23,6 +25,7 @@ namespace BT { BehaviorTreeFactory::BehaviorTreeFactory() { + parser_ = std::make_shared(*this); registerNodeType("Fallback"); registerNodeType("Sequence"); registerNodeType("SequenceStar"); @@ -212,6 +215,22 @@ void BehaviorTreeFactory::registerFromROSPlugins() } #endif + +void BehaviorTreeFactory::registerBehaviorTreeFromFile(const std::string &filename) +{ + parser_->loadFromFile(filename); +} + +void BehaviorTreeFactory::registerBehaviorTreeFromText(const std::string &xml_text) +{ + parser_->loadFromText(xml_text); +} + +std::vector BehaviorTreeFactory::registeredBehaviorTrees() const +{ + return parser_->registeredBehaviorTrees(); +} + std::unique_ptr BehaviorTreeFactory::instantiateTreeNode( const std::string& name, const std::string& ID, @@ -268,6 +287,13 @@ Tree BehaviorTreeFactory::createTreeFromFile(const std::string &file_path, return tree; } +Tree BehaviorTreeFactory::createdTree(const std::string &tree_name, Blackboard::Ptr blackboard) +{ + auto tree = parser_->instantiateTree(blackboard, tree_name); + tree.manifests = this->manifests(); + return tree; +} + Tree::~Tree() { haltTree(); diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index f51472b52..b839b0435 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -22,6 +22,7 @@ #pragma warning(disable : 4996) // do not complain about sprintf #endif +#include #include "behaviortree_cpp_v3/xml_parsing.h" #include "private/tinyxml2.h" #include "filesystem/path.h" @@ -59,10 +60,10 @@ struct XMLParser::Pimpl void getPortsRecursively(const XMLElement* element, std::vector &output_ports); - void loadDocImpl(BT_TinyXML2::XMLDocument* doc); + void loadDocImpl(BT_TinyXML2::XMLDocument* doc, bool add_includes); std::list > opened_documents; - std::unordered_map tree_roots; + std::map tree_roots; const BehaviorTreeFactory& factory; @@ -100,7 +101,7 @@ XMLParser::~XMLParser() delete _p; } -void XMLParser::loadFromFile(const std::string& filename) +void XMLParser::loadFromFile(const std::string& filename, bool add_includes) { _p->opened_documents.emplace_back(new BT_TinyXML2::XMLDocument()); @@ -110,20 +111,30 @@ void XMLParser::loadFromFile(const std::string& filename) filesystem::path file_path( filename ); _p->current_path = file_path.parent_path().make_absolute(); - _p->loadDocImpl( doc ); + _p->loadDocImpl( doc, add_includes ); } -void XMLParser::loadFromText(const std::string& xml_text) +void XMLParser::loadFromText(const std::string& xml_text, bool add_includes) { _p->opened_documents.emplace_back(new BT_TinyXML2::XMLDocument()); BT_TinyXML2::XMLDocument* doc = _p->opened_documents.back().get(); doc->Parse(xml_text.c_str(), xml_text.size()); - _p->loadDocImpl( doc ); + _p->loadDocImpl( doc, add_includes ); } -void XMLParser::Pimpl::loadDocImpl(BT_TinyXML2::XMLDocument* doc) +std::vector XMLParser::registeredBehaviorTrees() const +{ + std::vector out; + for(const auto& it: _p->tree_roots) + { + out.push_back(it.first); + } + return out; +} + +void XMLParser::Pimpl::loadDocImpl(BT_TinyXML2::XMLDocument* doc, bool add_includes) { if (doc->Error()) { @@ -139,10 +150,13 @@ void XMLParser::Pimpl::loadDocImpl(BT_TinyXML2::XMLDocument* doc) include_node != nullptr; include_node = include_node->NextSiblingElement("include")) { + if( !add_includes ) + { + break; + } filesystem::path file_path( include_node->Attribute("path") ); const char* ros_pkg_relative_path = include_node->Attribute("ros_pkg"); - std::string ros_pkg_path; if( ros_pkg_relative_path ) { @@ -151,17 +165,18 @@ void XMLParser::Pimpl::loadDocImpl(BT_TinyXML2::XMLDocument* doc) std::cout << "WARNING: contains an absolute path.\n" << "Attribute [ros_pkg] will be ignored."<< std::endl; } - else + else { + std::string ros_pkg_path; #ifdef USING_ROS - ros_pkg_path = ros::package::getPath(ros_pkg_relative_path); + ros_pkg_path = ros::package::getPath(ros_pkg_relative_path); #elif defined USING_ROS2 - ros_pkg_path = ament_index_cpp::get_package_share_directory(ros_pkg_relative_path); + ros_pkg_path = ament_index_cpp::get_package_share_directory(ros_pkg_relative_path); + file_path = filesystem::path( ros_pkg_path ) / file_path; #else - throw RuntimeError("Using attribute [ros_pkg] in , but this library was compiled " - "without ROS support. Recompile the BehaviorTree.CPP using catkin"); + throw RuntimeError("Using attribute [ros_pkg] in , but this library was compiled " + "without ROS support. Recompile the BehaviorTree.CPP using catkin"); #endif - file_path = filesystem::path( ros_pkg_path ) / file_path; } } @@ -173,7 +188,7 @@ void XMLParser::Pimpl::loadDocImpl(BT_TinyXML2::XMLDocument* doc) opened_documents.emplace_back(new BT_TinyXML2::XMLDocument()); BT_TinyXML2::XMLDocument* next_doc = opened_documents.back().get(); next_doc->LoadFile(file_path.str().c_str()); - loadDocImpl(next_doc); + loadDocImpl(next_doc, add_includes); } for (auto bt_node = xml_root->FirstChildElement("BehaviorTree"); @@ -407,41 +422,40 @@ void VerifyXML(const std::string& xml_text, 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()) - { - throw RuntimeError("The tree specified in [main_tree_to_execute] can't be found"); - } - } - else - { - if (tree_count != 1) - { - throw RuntimeError("If you don't specify the attribute [main_tree_to_execute], " - "Your file must contain a single BehaviorTree"); - } - } } -Tree XMLParser::instantiateTree(const Blackboard::Ptr& root_blackboard) +Tree XMLParser::instantiateTree(const Blackboard::Ptr& root_blackboard, + std::string main_tree_to_execute) { Tree output_tree; + std::string main_tree_ID = main_tree_to_execute; - XMLElement* xml_root = _p->opened_documents.front()->RootElement(); - - std::string main_tree_ID; - if (xml_root->Attribute("main_tree_to_execute")) + if( main_tree_ID.empty() ) { - main_tree_ID = xml_root->Attribute("main_tree_to_execute"); + for( const auto& doc: _p->opened_documents) + { + XMLElement* xml_root = doc->RootElement(); + if (xml_root->Attribute("main_tree_to_execute")) + { + if(!main_tree_ID.empty()) + { + throw RuntimeError("The attribute [main_tree_to_execute] has been " + "found multiple times. You must specify explicitly the name " + "of the to instantiate."); + } + main_tree_ID = xml_root->Attribute("main_tree_to_execute"); + } + } } - else if( _p->tree_roots.size() == 1) + + // special case: no name, but there is only one registered BT. + if( main_tree_ID.empty() && _p->tree_roots.size() == 1) { main_tree_ID = _p->tree_roots.begin()->first; } - else{ + + if( main_tree_ID.empty() ) + { throw RuntimeError("[main_tree_to_execute] was not specified correctly"); } //-------------------------------------- diff --git a/tests/gtest_factory.cpp b/tests/gtest_factory.cpp index 406c5e22e..e909ce0cc 100644 --- a/tests/gtest_factory.cpp +++ b/tests/gtest_factory.cpp @@ -71,8 +71,65 @@ static const char* xml_text_subtree = R"( )"; +static const char* xml_text_subtree_part1 = R"( + + + + + + + + + )"; + +static const char* xml_text_subtree_part2 = R"( + + + + + + + + + + + + + )"; + // clang-format on + +TEST(BehaviorTreeFactory, XMLParsingOrder) +{ + BehaviorTreeFactory factory; + CrossDoor::RegisterNodes(factory); + + { + XMLParser parser(factory); + parser.loadFromText(xml_text_subtree); + auto trees = parser.registeredBehaviorTrees(); + ASSERT_EQ(trees[0], "CrossDoorSubtree"); + ASSERT_EQ(trees[1], "MainTree"); + } + { + XMLParser parser(factory); + parser.loadFromText(xml_text_subtree_part1); + parser.loadFromText(xml_text_subtree_part2); + auto trees = parser.registeredBehaviorTrees(); + ASSERT_EQ(trees[0], "CrossDoorSubtree"); + ASSERT_EQ(trees[1], "MainTree"); + } + { + XMLParser parser(factory); + parser.loadFromText(xml_text_subtree_part2); + parser.loadFromText(xml_text_subtree_part1); + auto trees = parser.registeredBehaviorTrees(); + ASSERT_EQ(trees[0], "CrossDoorSubtree"); + ASSERT_EQ(trees[1], "MainTree"); + } +} + TEST(BehaviorTreeFactory, VerifyLargeTree) { BehaviorTreeFactory factory; @@ -114,6 +171,8 @@ TEST(BehaviorTreeFactory, VerifyLargeTree) ASSERT_EQ(decorator->child()->name(), "IsDoorOpen"); } + + TEST(BehaviorTreeFactory, Subtree) { BehaviorTreeFactory factory; @@ -244,3 +303,4 @@ TEST(BehaviorTreeFactory, SubTreeWithRemapping) ASSERT_FALSE( talk_bb->getAny("talk_out") ); } + From b1d85b77222c6b353e03b7b5162342b51cec6d95 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 18:41:31 +0200 Subject: [PATCH 163/709] updated documentation --- docs/asynchronous_nodes.md | 228 +++++++ ...07_legacy.md => example_01_legacy_wrap.md} | 0 docs/images/RunningTree.svg | 566 ++++++++++++++++++ docs/tutorial_04_sequence.md | 9 +- docs/tutorial_07_multiple_xml.md | 114 ++++ examples/CMakeLists.txt | 54 +- ...7_wrap_legacy.cpp => ex01_wrap_legacy.cpp} | 0 ...ntime_ports.cpp => ex02_runtime_ports.cpp} | 0 ...r.cpp => ex03_ncurses_manual_selector.cpp} | 0 ...iple_BTs.cpp => t07_load_multiple_xml.cpp} | 4 +- examples/t10_include_trees.cpp | 27 - include/behaviortree_cpp_v3/bt_factory.h | 2 +- include/behaviortree_cpp_v3/tree_node.h | 33 +- mkdocs.yml | 40 +- sample_nodes/dummy_nodes.h | 70 ++- src/bt_factory.cpp | 2 +- src/tree_node.cpp | 39 +- 17 files changed, 1083 insertions(+), 105 deletions(-) create mode 100644 docs/asynchronous_nodes.md rename docs/{tutorial_07_legacy.md => example_01_legacy_wrap.md} (100%) create mode 100644 docs/images/RunningTree.svg create mode 100644 docs/tutorial_07_multiple_xml.md rename examples/{t07_wrap_legacy.cpp => ex01_wrap_legacy.cpp} (100%) rename examples/{t11_runtime_ports.cpp => ex02_runtime_ports.cpp} (100%) rename examples/{t12_ncurses_manual_selector.cpp => ex03_ncurses_manual_selector.cpp} (100%) rename examples/{t13_load_multiple_BTs.cpp => t07_load_multiple_xml.cpp} (95%) delete mode 100644 examples/t10_include_trees.cpp diff --git a/docs/asynchronous_nodes.md b/docs/asynchronous_nodes.md new file mode 100644 index 000000000..06da2e87d --- /dev/null +++ b/docs/asynchronous_nodes.md @@ -0,0 +1,228 @@ +# Understand Asynchrous Nodes, Concurrency and Parallelism + +When designing reactive Behavior Trees, it is important to understand 2 main concepts: + +- what we mean by **"Asynchronous"** Actions VS **"Synchronous"** ones. +- The difference between **Concurrency** and **Parallelism** in general and in the context of BT.CPP. + +## Concurrency vs Parallelism + +If you Google those words, you will read many good articles about this topic. + +BT.CPP executes all the nodes **Concurrently**, in other words: + +- The Tree execution engine itself is single-threaded. +- all the `tick()` methods are **always** executed sequentially. +- if any `tick()` method is blocking, the entire execution is blocked. + +We achieve reactive behaviors through "concurrency" and asynchronous execution. + +In other words, an Action that takes a long time to execute should, instead, +return as soon as possible the state RUNNING to notify that the action was started, +and only when ticked again check if the action is completed or not. + +An Asynchronous node may delegate this long execution either to another process, +another server or simply another thread. + +## Asynchronous vs Synchronous + +In general, an Asynchronous Action (or TreeNode) is simply one that: + +- May return RUNNING instead of SUCCESS or FAILURE, when ticked. +- Can be stopped as fast as possible when the method `halt()` (to be implemented by the developer) is invoked. + +When your Tree ends up executing an Asynchronous action that returns running, that RUNNING state is usually propagated backbard and the entire Tree is itself in the RUNNING state. + +In the example below, "ActionE" is asynchronous and the RUNNING; when +a node is RUNNING, usually its parent returns RUNNING too. + +![tree in running state](images/RunningTree.svg) + +Let's consider a simple "SleepNode". A good template to get started is the StatefullAction + +```c++ +// Example os Asynchronous node that use StatefulActionNode as base class +class SleepNode : public BT::StatefulActionNode +{ + public: + SleepNode(const std::string& name, const BT::NodeConfiguration& config) + : BT::StatefulActionNode(name, config) + {} + + static BT::PortsList providedPorts() + { + // amount of milliseconds that we want to sleep + return{ BT::InputPort("msec") }; + } + + NodeStatus onStart() override + { + int msec = 0; + getInput("msec", msec); + if( msec <= 0 ) + { + // No need to go into the RUNNING state + return NodeStatus::SUCCESS; + } + else { + using namespace std::chrono; + // once the deadline is reached, we will return SUCCESS. + deadline_ = system_clock::now() + milliseconds(msec); + return NodeStatus::RUNNING; + } + } + + /// method invoked by an action in the RUNNING state. + NodeStatus onRunning() override + { + if ( std::chrono::system_clock::now() >= deadline_ ) + { + return NodeStatus::SUCCESS; + } + else { + return NodeStatus::RUNNING; + } + } + + void onHalted() override + { + // nothing to do here... + std::cout << "SleepNode interrupted" << std::endl; + } + + private: + std::chrono::system_clock::time_point deadline_; +}; +``` + +In the code above: + +1. When the SleedNode is ticked the first time, the `onStart()` method is executed. +This may return SUCCESS immediately if the sleep time is 0 or will return RUNNING otherwise. +2. We should continue ticking the tree in a loop. This will invoke the method +`onRunning()` that may return RUNNING again or, eventually, SUCCESS. +3. Another node might trigger a `halt()` signal. In this case, the `onHalted()` method is invoked. We can take the opportunity to clean up our internal state. + +## Avoid blocking the execution of the tree + +A **wrong** way to implement the `SleepNode` would be this one: + +```c++ +// This is the synchronous version of the Node. probably not what we want. +class BadSleepNode : public BT::ActionNodeBase +{ + public: + BadSleepNode(const std::string& name, const BT::NodeConfiguration& config) + : BT::ActionNodeBase(name, config) + {} + + static BT::PortsList providedPorts() + { + return{ BT::InputPort("msec") }; + } + + NodeStatus tick() override + { + int msec = 0; + getInput("msec", msec); + // This blocking function will FREEZE the entire tree :( + std::this_thread::sleep_for( std::chrono::milliseconds(msec) ); + return NodeStatus::SUCCESS; + } + + void halt() override + { + // No one can invoke this method, because I freezed the tree. + // Even if this method COULD be executed, there is no way I can + // interrupt std::this_thread::sleep_for() + } +}; +``` + +## The problem with multi-threading + +In the early days of this library (version 1.x), spawning a new thread +looked as a good solution to build asynchronous Actions. + +That was a bad idea, for multiple reasons: + +- Accessing the blackboard in a thread-safe way is harder (more about this later). +- You probably don't need to. +- People think that this will magically make the Action "asynchronous", but they forget that it is still **their responsibility** to stop that thread "somehow" when the `halt()`method is invoked. + +For this reason, user a usually discouraged from using `BT::AsyncActionNode` as a +base class. Let's have a look again at the SleepNode. + +```c++ +// This will spawn its own thread. But it still have problems when halted +class BadSleepNode : public BT::AsyncActionNode +{ + public: + BadSleepNode(const std::string& name, const BT::NodeConfiguration& config) + : BT::ActionNodeBase(name, config) + {} + + static BT::PortsList providedPorts() + { + return{ BT::InputPort("msec") }; + } + + NodeStatus tick() override + { + // This code run in its own thread, therefore the Tree is still running. + // Think looks good but the thread can't be aborted + int msec = 0; + getInput("msec", msec); + std::this_thread::sleep_for( std::chrono::milliseconds(msec) ); + return NodeStatus::SUCCESS; + } + + // The halt() method can not kill the spawned thread :() + // void halt(); + } +}; +``` + +A "correct" (but over-engineered) version of it would be: + +```c++ +// I will create my own thread here, for no good reason +class ThreadedSleepNode : public BT::AsyncActionNode +{ + public: + ThreadedSleepNode(const std::string& name, const BT::NodeConfiguration& config) + : BT::ActionNodeBase(name, config) + {} + + static BT::PortsList providedPorts() + { + return{ BT::InputPort("msec") }; + } + + NodeStatus tick() override + { + // This code run in its own thread, therefore the Tree is still running. + int msec = 0; + getInput("msec", msec); + + using namespace std::chrono; + auto deadline = system_clock::now() + milliseconds(msec); + + // periodically check isHaltRequested() + // and sleep for a small amount of time only (1 millisecond) + while( !isHaltRequested() && system_clock::now() < deadline ) + { + std::this_thread::sleep_for( std::chrono::milliseconds(1) ); + } + return NodeStatus::SUCCESS; + } + + // The halt() method can not kill the spawned thread :() + // void halt(); + } +}; +``` + +As you can see, this looks more complicated than the version we implemented +first, using `BT::StatefulActionNode`. +This pattern can still be useful in some case, but you must remember that introducing multi-threading make things more complicated and **should be avoided by default**. diff --git a/docs/tutorial_07_legacy.md b/docs/example_01_legacy_wrap.md similarity index 100% rename from docs/tutorial_07_legacy.md rename to docs/example_01_legacy_wrap.md diff --git a/docs/images/RunningTree.svg b/docs/images/RunningTree.svg new file mode 100644 index 000000000..630a1e2fd --- /dev/null +++ b/docs/images/RunningTree.svg @@ -0,0 +1,566 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + Sequence + + + + Sequence + + + + + + + + + + + + + + + Fallback + + + + Fallback + + + + + + + + + ActionA + + + + ActionA + + + + + + + + + ActionE + + + + ActionE + + + + + + + + + ActionD + + + + ActionD + + + + + + + + + ActionF + + + + ActionF + + + + + + + + + ActionB + + + + ActionB + + + + + + + + + + + root + + + + root + + + + + + + + + RUNNING + + + + RUNNING + + + + + + + + + FAILURE + + + + FAILURE + + + + + + + + + SUCCESS + + + + SUCCESS + + + + diff --git a/docs/tutorial_04_sequence.md b/docs/tutorial_04_sequence.md index 4c59c0ca5..a42c29506 100644 --- a/docs/tutorial_04_sequence.md +++ b/docs/tutorial_04_sequence.md @@ -1,4 +1,4 @@ -# Sequences and AsyncActionNode +# Reactive Sequences and Asynchronous Nodes The next example shows the difference between a `SequenceNode` and a `ReactiveSequence`. @@ -7,6 +7,13 @@ An Asynchronous Action has it's own thread. This allows the user to use blocking functions but to return the flow of execution to the tree. +!!! warning "Learn more about Asynchronous Actions" + + Users should fully understand how Concurrency is achieved in BT.CPP + and learn best practices about how to develop their own Asynchronous + Actions. You will find an extensive article + [here](asynchronous_nodes.md). + ```C++ // Custom type diff --git a/docs/tutorial_07_multiple_xml.md b/docs/tutorial_07_multiple_xml.md new file mode 100644 index 000000000..6107b32ee --- /dev/null +++ b/docs/tutorial_07_multiple_xml.md @@ -0,0 +1,114 @@ +# How to use multiple XML to store your subtrees + +In the examples which we presented so far, we always create an entire Tree +from a single XMl file. + +If multiple Subtrees were used, they were all included into the same XML. + +In recent version of BT.CPP (3.7+), the user can more easily +load trees from multiple files, if needed. + +## Using the \ tag + +We will consider a main tree that invoke 2 different subtrees. + +File **main_tree.xml**: + +```XML hl_lines="2 3" + + + + + + + + + + + +``` +File **subtree_A.xml**: + +```XML + + + + + +``` + +File **subtree_B.xml**: + +```XML + + + + + +``` + +As you may notice, we included two relative paths in **main_tree.xml** +that tells to `BehaviorTreeFactory` where to find the required dependencies. + +We need to create the tree as usual: + +```c++ +factory.createTreeFromFile("main_tree.xml") +``` + +## Load multiple files without \ + +If we don't want to add relative and hard-coded paths into our XML, +or if we want to instantiate a subtree instead of the main tree, there is a +new approach, since BT.CPP 3.7+. + +This process requires few more steps, but offers more flexibility. + +```c++ +int main() +{ + BT::BehaviorTreeFactory factory; + factory.registerNodeType("SaySomething"); + + // Register the behavior tree definitions, but don't instantiate them, yet. + // Order is not important. + factory.registerBehaviorTreeFromText("main_tree.xml"); + factory.registerBehaviorTreeFromText("subtree_A.xml"); + factory.registerBehaviorTreeFromText("subtree_B.xml"); + + //Check that the BTs have been registered correctly + std::cout << "Registered BehaviorTrees:" << std::endl; + for(const std::string& bt_name: factory.registeredBehaviorTrees()) + { + std::cout << " - " << bt_name << std::endl; + } + + // You can create the MainTree and the subtrees will be added automatically. + std::cout << "----- MainTree tick ----" << std::endl; + auto main_tree = factory.createTree("MainTree"); + main_tree.tickRoot(); + + // ... or you can create only one of the subtree + std::cout << "----- SubA tick ----" << std::endl; + auto subA_tree = factory.createTree("SubTreeA"); + subA_tree.tickRoot(); + + return 0; +} +/* Expected output: + +Registered BehaviorTrees: + - MainTree + - SubTreeA + - SubTreeB +----- MainTree tick ---- +Robot says: starting MainTree +Robot says: Executing Sub_A +Robot says: Executing Sub_B +----- SubA tick ---- +Robot says: Executing Sub_A +``` + + + + diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index be7560fbf..4dc4a9a8c 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -4,6 +4,12 @@ include_directories( ../sample_nodes ) set(CMAKE_DEBUG_POSTFIX "") +function(CompileExample name) + add_executable(${name} ${name}.cpp ) + target_link_libraries(${name} ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) +endfunction() + + # The plugin libdummy_nodes.so can be linked statically or # loaded dynamically at run-time. add_executable(t01_first_tree_static t01_build_your_first_tree.cpp ) @@ -13,44 +19,18 @@ target_link_libraries(t01_first_tree_static ${BEHAVIOR_TREE_LIBRARY} bt_sample add_executable(t01_first_tree_dynamic t01_build_your_first_tree.cpp ) target_link_libraries(t01_first_tree_dynamic ${BEHAVIOR_TREE_LIBRARY} ) - -add_executable(t02_basic_ports t02_basic_ports.cpp ) -target_link_libraries(t02_basic_ports ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) - -add_executable(t03_generic_ports t03_generic_ports.cpp ) -target_link_libraries(t03_generic_ports ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) - -add_executable(t04_reactive_sequence t04_reactive_sequence.cpp ) -target_link_libraries(t04_reactive_sequence ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) - -add_executable(t05_cross_door t05_crossdoor.cpp ) -target_link_libraries(t05_cross_door ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) - -add_executable(t06_subtree_port_remapping t06_subtree_port_remapping.cpp ) -target_link_libraries(t06_subtree_port_remapping ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) - -add_executable(t07_wrap_legacy t07_wrap_legacy.cpp ) -target_link_libraries(t07_wrap_legacy ${BEHAVIOR_TREE_LIBRARY} ) - -add_executable(t08_additional_node_args t08_additional_node_args.cpp ) -target_link_libraries(t08_additional_node_args ${BEHAVIOR_TREE_LIBRARY} ) +CompileExample("t02_basic_ports") +CompileExample("t03_generic_ports") +CompileExample("t04_reactive_sequence") +CompileExample("t05_crossdoor") +CompileExample("t06_subtree_port_remapping") +CompileExample("t07_load_multiple_xml") +CompileExample("t08_additional_node_args") if (BT_COROUTINES) - add_executable(t09_async_actions_coroutines t09_async_actions_coroutines.cpp ) - target_link_libraries(t09_async_actions_coroutines ${BEHAVIOR_TREE_LIBRARY} ) -endif() - -add_executable(t10_include_trees t10_include_trees.cpp ) -target_link_libraries(t10_include_trees ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) - - -add_executable(t11_runtime_ports t11_runtime_ports.cpp ) -target_link_libraries(t11_runtime_ports ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) - -if(CURSES_FOUND) - add_executable(t12_ncurses_manual_selector t12_ncurses_manual_selector.cpp ) - target_link_libraries(t12_ncurses_manual_selector ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) + CompileExample("t09_async_actions_coroutines") endif() -add_executable(t13_load_multiple_BTs t13_load_multiple_BTs.cpp ) -target_link_libraries(t13_load_multiple_BTs ${BEHAVIOR_TREE_LIBRARY} bt_sample_nodes ) +CompileExample("ex01_wrap_legacy") +CompileExample("ex02_runtime_ports") +CompileExample("ex03_ncurses_manual_selector") diff --git a/examples/t07_wrap_legacy.cpp b/examples/ex01_wrap_legacy.cpp similarity index 100% rename from examples/t07_wrap_legacy.cpp rename to examples/ex01_wrap_legacy.cpp diff --git a/examples/t11_runtime_ports.cpp b/examples/ex02_runtime_ports.cpp similarity index 100% rename from examples/t11_runtime_ports.cpp rename to examples/ex02_runtime_ports.cpp diff --git a/examples/t12_ncurses_manual_selector.cpp b/examples/ex03_ncurses_manual_selector.cpp similarity index 100% rename from examples/t12_ncurses_manual_selector.cpp rename to examples/ex03_ncurses_manual_selector.cpp diff --git a/examples/t13_load_multiple_BTs.cpp b/examples/t07_load_multiple_xml.cpp similarity index 95% rename from examples/t13_load_multiple_BTs.cpp rename to examples/t07_load_multiple_xml.cpp index ef05e1ae2..53a80e7f0 100644 --- a/examples/t13_load_multiple_BTs.cpp +++ b/examples/t07_load_multiple_xml.cpp @@ -58,12 +58,12 @@ int main() // You can create the MainTree and the subtrees will be added automatically. std::cout << "----- MainTree tick ----" << std::endl; - auto main_tree = factory.createdTree("MainTree"); + auto main_tree = factory.createTree("MainTree"); main_tree.tickRoot(); // ... or you can create only one of the subtree std::cout << "----- SubA tick ----" << std::endl; - auto subA_tree = factory.createdTree("SubA"); + auto subA_tree = factory.createTree("SubA"); subA_tree.tickRoot(); return 0; diff --git a/examples/t10_include_trees.cpp b/examples/t10_include_trees.cpp deleted file mode 100644 index 248350896..000000000 --- a/examples/t10_include_trees.cpp +++ /dev/null @@ -1,27 +0,0 @@ -#include "behaviortree_cpp_v3/bt_factory.h" -#include "dummy_nodes.h" - -using namespace BT; - - -int main(int argc, char** argv) -{ - BehaviorTreeFactory factory; - DummyNodes::RegisterNodes(factory); - - if( argc != 2) - { - std::cout <<" missing name of the XML file to open" << std::endl; - return 1; - } - - // IMPORTANT: when the object tree goes out of scope, - // all the TreeNodes are destroyed - auto tree = factory.createTreeFromFile(argv[1]); - - printTreeRecursively( tree.rootNode() ); - - tree.tickRoot(); - - return 0; -} diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index f0c69fdf0..5bc83ad81 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -381,7 +381,7 @@ class BehaviorTreeFactory Tree createTreeFromFile(const std::string& file_path, Blackboard::Ptr blackboard = Blackboard::create()); - Tree createdTree(const std::string& tree_name, + Tree createTree(const std::string& tree_name, Blackboard::Ptr blackboard = Blackboard::create()); private: diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index 9aa5d847e..a925405ae 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -93,6 +93,9 @@ class TreeNode using StatusChangeSubscriber = StatusChangeSignal::Subscriber; using StatusChangeCallback = StatusChangeSignal::CallableFunction; + using PreTickOverrideCallback = std::function(TreeNode&, NodeStatus)>; + using PostTickOverrideCallback = std::function(TreeNode&, NodeStatus, NodeStatus)>; + /** * @brief subscribeToStatusChange is used to attach a callback to a status change. * When StatusChangeSubscriber goes out of scope (it is a shared_ptr) the callback @@ -104,6 +107,27 @@ class TreeNode */ StatusChangeSubscriber subscribeToStatusChange(StatusChangeCallback callback); + /** This method attaches to the TreeNode a callback with signature: + * + * Optional myCallback(TreeNode& node, NodeStatus current_status) + * + * This callback is executed BEFORE the tick() and, if it returns a valid Optional, + * the actual tick() will NOT be executed and this result will be returned instead. + * + * This is useful to inject a "dummy" implementation of the TreeNode at run-time + */ + void setPreTickOverrideFunction(PreTickOverrideCallback callback); + + /** + * This method attaches to the TreeNode a callback with signature: + * + * Optional myCallback(TreeNode& node, NodeStatus prev_status, NodeStatus tick_status) + * + * This callback is executed AFTER the tick() and, if it returns a valid Optional, + * the value returned by the actual tick() is overriden with this one. + */ + void setPostTickOverrideFunction(PostTickOverrideCallback callback); + // get an unique identifier of this instance of treeNode uint16_t UID() const; @@ -160,10 +184,7 @@ class TreeNode friend class Tree; // Only BehaviorTreeFactory should call this - void setRegistrationID(StringView ID) - { - registration_ID_.assign(ID.data(), ID.size()); - } + void setRegistrationID(StringView ID); void modifyPortsRemapping(const PortsRemapping& new_remapping); @@ -185,6 +206,10 @@ class TreeNode NodeConfiguration config_; std::string registration_ID_; + + PreTickOverrideCallback pre_condition_callback_; + + PostTickOverrideCallback post_condition_callback_; }; //------------------------------------------------------- diff --git a/mkdocs.yml b/mkdocs.yml index 9bbc64e9e..abf37fe92 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -32,25 +32,27 @@ nav: - Home: index.md - Learn the basics: - - Introduction to BT: BT_basics.md - - Getting started: getting_started.md - - Sequence Nodes: SequenceNode.md - - Fallback Nodes: FallbackNode.md - - Decorators Nodes: DecoratorNode.md - - The XML format: xml_format.md + - Introduction to BT: BT_basics.md + - Getting started: getting_started.md + - Sequence Nodes: SequenceNode.md + - Fallback Nodes: FallbackNode.md + - Decorators Nodes: DecoratorNode.md + - The XML format: xml_format.md - Tutorials: - - "Summary": tutorials_summary.md - - "Tutorial 1: Create a Tree": tutorial_01_first_tree.md - - "Tutorial 2: Basic Ports": tutorial_02_basic_ports.md - - "Tutorial 3: Generic ports": tutorial_03_generic_ports.md - - "Tutorial 4: Sequences": tutorial_04_sequence.md - - "Tutorial 5: Subtrees and Loggers": tutorial_05_subtrees.md - - "Tutorial 6: Ports remapping": tutorial_06_subtree_ports.md - - "Tutorial 7: Wrap legacy code": tutorial_07_legacy.md - - "Tutorial 8: Additional arguments": tutorial_08_additional_args.md - - "Tutorial 9: Coroutines": tutorial_09_coroutines.md - - - Migration Guide: - - Migrate from Version 2.X: MigrationGuide.md + - "Summary": tutorials_summary.md + - "Tutorial 1: Create a Tree": tutorial_01_first_tree.md + - "Tutorial 2: Basic Ports": tutorial_02_basic_ports.md + - "Tutorial 3: Generic ports": tutorial_03_generic_ports.md + - "Tutorial 4: Reactive Trees": tutorial_04_sequence.md + - "Tutorial 5: Subtrees and Loggers": tutorial_05_subtrees.md + - "Tutorial 6: Ports remapping": tutorial_06_subtree_ports.md + - "Tutorial 7: Load from multiple XMLs": tutorial_07_multiple_xml.md + - "Tutorial 8: Additional arguments": tutorial_08_additional_args.md + - "Tutorial 9: Coroutines": tutorial_09_coroutines.md + + - Application Notes: + - "Concurrency and Asynchronous Nodes": asynchronous_nodes.md + - "How to Wrap legacy code": example_01_legacy_wrap.md + diff --git a/sample_nodes/dummy_nodes.h b/sample_nodes/dummy_nodes.h index 9fd7096c7..de521d7ea 100644 --- a/sample_nodes/dummy_nodes.h +++ b/sample_nodes/dummy_nodes.h @@ -7,10 +7,12 @@ namespace DummyNodes { -BT::NodeStatus CheckBattery(); +using BT::NodeStatus; -BT::NodeStatus CheckTemperature(); -BT::NodeStatus SayHello(); +NodeStatus CheckBattery(); + +NodeStatus CheckTemperature(); +NodeStatus SayHello(); class GripperInterface { @@ -19,9 +21,9 @@ class GripperInterface { } - BT::NodeStatus open(); + NodeStatus open(); - BT::NodeStatus close(); + NodeStatus close(); private: bool _opened; @@ -40,7 +42,7 @@ class ApproachObject : public BT::SyncActionNode } // You must override the virtual function tick() - BT::NodeStatus tick() override; + NodeStatus tick() override; }; // Example of custom SyncActionNode (synchronous action) @@ -54,7 +56,7 @@ class SaySomething : public BT::SyncActionNode } // You must override the virtual function tick() - BT::NodeStatus tick() override; + NodeStatus tick() override; // It is mandatory to define this static method. static BT::PortsList providedPorts() @@ -64,8 +66,60 @@ class SaySomething : public BT::SyncActionNode }; //Same as class SaySomething, but to be registered with SimpleActionNode -BT::NodeStatus SaySomethingSimple(BT::TreeNode& self); +NodeStatus SaySomethingSimple(BT::TreeNode& self); + +// Example os Asynchronous node that use StatefulActionNode as base class +class SleepNode : public BT::StatefulActionNode +{ + public: + SleepNode(const std::string& name, const BT::NodeConfiguration& config) + : BT::StatefulActionNode(name, config) + {} + + static BT::PortsList providedPorts() + { + // amount of milliseconds that we want to sleep + return{ BT::InputPort("msec") }; + } + NodeStatus onStart() override + { + int msec = 0; + getInput("msec", msec); + if( msec <= 0 ) + { + // no need to go into the RUNNING state + return NodeStatus::SUCCESS; + } + else { + using namespace std::chrono; + // once the deadline is reached, we will return SUCCESS. + deadline_ = system_clock::now() + milliseconds(msec); + return NodeStatus::RUNNING; + } + } + + /// method invoked by an action in the RUNNING state. + NodeStatus onRunning() override + { + if ( std::chrono::system_clock::now() >= deadline_ ) + { + return NodeStatus::SUCCESS; + } + else { + return NodeStatus::RUNNING; + } + } + + void onHalted() override + { + // nothing to do here... + std::cout << "SleepNode interrupted" << std::endl; + } + + private: + std::chrono::system_clock::time_point deadline_; +}; inline void RegisterNodes(BT::BehaviorTreeFactory& factory) { diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 12ecdbc1e..96d0c9148 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -287,7 +287,7 @@ Tree BehaviorTreeFactory::createTreeFromFile(const std::string &file_path, return tree; } -Tree BehaviorTreeFactory::createdTree(const std::string &tree_name, Blackboard::Ptr blackboard) +Tree BehaviorTreeFactory::createTree(const std::string &tree_name, Blackboard::Ptr blackboard) { auto tree = parser_->instantiateTree(blackboard, tree_name); tree.manifests = this->manifests(); diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 7b71f46cd..47f68c32e 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -32,9 +32,33 @@ TreeNode::TreeNode(std::string name, NodeConfiguration config) NodeStatus TreeNode::executeTick() { - const NodeStatus status = tick(); - setStatus(status); - return status; + NodeStatus new_status = status_; + // a pre-condition may return the new status. + // In this case it override the actual tick() + if( pre_condition_callback_ ) + { + if(auto res = pre_condition_callback_(*this, status_)) + { + new_status = res.value(); + } + } + else + { + new_status = tick(); + } + + // a post-condition may overwrite the result of the tick + // with its own result. + if( post_condition_callback_ ) + { + if(auto res = post_condition_callback_(*this, status_, new_status)) + { + new_status = res.value(); + } + } + + setStatus(new_status); + return new_status; } void TreeNode::setStatus(NodeStatus new_status) @@ -93,7 +117,7 @@ uint16_t TreeNode::UID() const const std::string& TreeNode::registrationName() const { - return registration_ID_; + return registration_ID_; } const NodeConfiguration &TreeNode::config() const @@ -157,9 +181,14 @@ Optional TreeNode::getRemappedKey(StringView port_name, StringView r return nonstd::make_unexpected("Not a blackboard pointer"); } +void TreeNode::setRegistrationID(StringView ID) +{ + registration_ID_.assign(ID.data(), ID.size()); +} + void TreeNode::modifyPortsRemapping(const PortsRemapping &new_remapping) { - for (const auto& new_it: new_remapping) + for (const auto& new_it: new_remapping) { auto it = config_.input_ports.find( new_it.first ); if( it != config_.input_ports.end() ) From 8f53b3636d06f48bf926ad54c8f4e0da27cfd399 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 18:52:12 +0200 Subject: [PATCH 164/709] correct docs --- docs/asynchronous_nodes.md | 7 ++++--- docs/getting_started.md | 3 +-- docs/tutorial_07_multiple_xml.md | 4 ++-- mkdocs.yml | 2 +- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/docs/asynchronous_nodes.md b/docs/asynchronous_nodes.md index 06da2e87d..07da306f3 100644 --- a/docs/asynchronous_nodes.md +++ b/docs/asynchronous_nodes.md @@ -177,9 +177,10 @@ class BadSleepNode : public BT::AsyncActionNode return NodeStatus::SUCCESS; } - // The halt() method can not kill the spawned thread :() - // void halt(); - } + // The halt() method can not kill the spawned thread :( + + // Keep in mind that most of the time we should not + // override AsyncActionNode::halt() }; ``` diff --git a/docs/getting_started.md b/docs/getting_started.md index 5b6955823..5784878eb 100644 --- a/docs/getting_started.md +++ b/docs/getting_started.md @@ -44,8 +44,7 @@ Alternatively, the library provides 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; as a reference -please look at the [first tutorial](tutorial_01_first_tree.md) and the one -describing [non intrusive integration with legacy code](tutorial_07_legacy.md). +please look at the [first tutorial](tutorial_01_first_tree.md). ## Dataflow, Ports and Blackboard diff --git a/docs/tutorial_07_multiple_xml.md b/docs/tutorial_07_multiple_xml.md index 6107b32ee..064f853c8 100644 --- a/docs/tutorial_07_multiple_xml.md +++ b/docs/tutorial_07_multiple_xml.md @@ -8,7 +8,7 @@ If multiple Subtrees were used, they were all included into the same XML. In recent version of BT.CPP (3.7+), the user can more easily load trees from multiple files, if needed. -## Using the \ tag +## Load multiple files with "include" We will consider a main tree that invoke 2 different subtrees. @@ -56,7 +56,7 @@ We need to create the tree as usual: factory.createTreeFromFile("main_tree.xml") ``` -## Load multiple files without \ +## Load multiple files manually If we don't want to add relative and hard-coded paths into our XML, or if we want to instantiate a subtree instead of the main tree, there is a diff --git a/mkdocs.yml b/mkdocs.yml index abf37fe92..f95acb187 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -48,7 +48,7 @@ nav: - "Tutorial 4: Reactive Trees": tutorial_04_sequence.md - "Tutorial 5: Subtrees and Loggers": tutorial_05_subtrees.md - "Tutorial 6: Ports remapping": tutorial_06_subtree_ports.md - - "Tutorial 7: Load from multiple XMLs": tutorial_07_multiple_xml.md + - "Tutorial 7: Load multiple XMLs": tutorial_07_multiple_xml.md - "Tutorial 8: Additional arguments": tutorial_08_additional_args.md - "Tutorial 9: Coroutines": tutorial_09_coroutines.md From 6dcd5ff9603936918d9c5032fb5deefde49e2b5c Mon Sep 17 00:00:00 2001 From: Griswald Brooks Date: Fri, 13 May 2022 10:51:05 -0700 Subject: [PATCH 165/709] typos (#376) --- docs/asynchronous_nodes.md | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/docs/asynchronous_nodes.md b/docs/asynchronous_nodes.md index 07da306f3..24f85aa05 100644 --- a/docs/asynchronous_nodes.md +++ b/docs/asynchronous_nodes.md @@ -33,12 +33,12 @@ In general, an Asynchronous Action (or TreeNode) is simply one that: When your Tree ends up executing an Asynchronous action that returns running, that RUNNING state is usually propagated backbard and the entire Tree is itself in the RUNNING state. -In the example below, "ActionE" is asynchronous and the RUNNING; when +In the example below, "ActionE" is asynchronous and RUNNING; when a node is RUNNING, usually its parent returns RUNNING too. ![tree in running state](images/RunningTree.svg) -Let's consider a simple "SleepNode". A good template to get started is the StatefullAction +Let's consider a simple "SleepNode". A good template to get started is the StatefulAction ```c++ // Example os Asynchronous node that use StatefulActionNode as base class @@ -97,7 +97,7 @@ class SleepNode : public BT::StatefulActionNode In the code above: -1. When the SleedNode is ticked the first time, the `onStart()` method is executed. +1. When the SleepNode is ticked the first time, the `onStart()` method is executed. This may return SUCCESS immediately if the sleep time is 0 or will return RUNNING otherwise. 2. We should continue ticking the tree in a loop. This will invoke the method `onRunning()` that may return RUNNING again or, eventually, SUCCESS. @@ -142,7 +142,7 @@ class BadSleepNode : public BT::ActionNodeBase ## The problem with multi-threading In the early days of this library (version 1.x), spawning a new thread -looked as a good solution to build asynchronous Actions. +looked like a good solution to build asynchronous Actions. That was a bad idea, for multiple reasons: @@ -150,11 +150,11 @@ That was a bad idea, for multiple reasons: - You probably don't need to. - People think that this will magically make the Action "asynchronous", but they forget that it is still **their responsibility** to stop that thread "somehow" when the `halt()`method is invoked. -For this reason, user a usually discouraged from using `BT::AsyncActionNode` as a +For this reason, users are usually discouraged from using `BT::AsyncActionNode` as a base class. Let's have a look again at the SleepNode. ```c++ -// This will spawn its own thread. But it still have problems when halted +// This will spawn its own thread. But it still has problems when halted class BadSleepNode : public BT::AsyncActionNode { public: @@ -169,8 +169,8 @@ class BadSleepNode : public BT::AsyncActionNode NodeStatus tick() override { - // This code run in its own thread, therefore the Tree is still running. - // Think looks good but the thread can't be aborted + // This code runs in its own thread, therefore the Tree is still running. + // This seems good but the thread still can't be aborted int msec = 0; getInput("msec", msec); std::this_thread::sleep_for( std::chrono::milliseconds(msec) ); @@ -207,7 +207,7 @@ class ThreadedSleepNode : public BT::AsyncActionNode getInput("msec", msec); using namespace std::chrono; - auto deadline = system_clock::now() + milliseconds(msec); + const auto deadline = system_clock::now() + milliseconds(msec); // periodically check isHaltRequested() // and sleep for a small amount of time only (1 millisecond) From 291db65a186b313aa8f147122084011726dfbe34 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 20:31:52 +0200 Subject: [PATCH 166/709] more docs --- docs/asynchronous_nodes.md | 193 +++++++++++++++++++++---------- docs/tutorial_07_multiple_xml.md | 16 ++- 2 files changed, 150 insertions(+), 59 deletions(-) diff --git a/docs/asynchronous_nodes.md b/docs/asynchronous_nodes.md index 24f85aa05..df17e2fd0 100644 --- a/docs/asynchronous_nodes.md +++ b/docs/asynchronous_nodes.md @@ -9,6 +9,11 @@ When designing reactive Behavior Trees, it is important to understand 2 main con If you Google those words, you will read many good articles about this topic. +!!! info "Defintions" + **Concurrency** is when two or more tasks can start, run, and complete in overlapping time periods. It doesn't necessarily mean they'll ever both be running at the same instant. + + **Parallelism** is when tasks literally run at the same time in different threads, e.g., on a multicore processor. + BT.CPP executes all the nodes **Concurrently**, in other words: - The Tree execution engine itself is single-threaded. @@ -51,43 +56,42 @@ class SleepNode : public BT::StatefulActionNode static BT::PortsList providedPorts() { - // amount of milliseconds that we want to sleep - return{ BT::InputPort("msec") }; + // amount of milliseconds that we want to sleep + return{ BT::InputPort("msec") }; } NodeStatus onStart() override { - int msec = 0; - getInput("msec", msec); - if( msec <= 0 ) - { - // No need to go into the RUNNING state - return NodeStatus::SUCCESS; - } - else { - using namespace std::chrono; - // once the deadline is reached, we will return SUCCESS. - deadline_ = system_clock::now() + milliseconds(msec); - return NodeStatus::RUNNING; - } + int msec = 0; + getInput("msec", msec); + + if( msec <= 0 ) { + // No need to go into the RUNNING state + return NodeStatus::SUCCESS; + } + else { + using namespace std::chrono; + // once the deadline is reached, we will return SUCCESS. + deadline_ = system_clock::now() + milliseconds(msec); + return NodeStatus::RUNNING; + } } /// method invoked by an action in the RUNNING state. NodeStatus onRunning() override { - if ( std::chrono::system_clock::now() >= deadline_ ) - { - return NodeStatus::SUCCESS; - } - else { - return NodeStatus::RUNNING; - } + if ( std::chrono::system_clock::now() >= deadline_ ) { + return NodeStatus::SUCCESS; + } + else { + return NodeStatus::RUNNING; + } } void onHalted() override { - // nothing to do here... - std::cout << "SleepNode interrupted" << std::endl; + // nothing to do here... + std::cout << "SleepNode interrupted" << std::endl; } private: @@ -118,23 +122,23 @@ class BadSleepNode : public BT::ActionNodeBase static BT::PortsList providedPorts() { - return{ BT::InputPort("msec") }; + return{ BT::InputPort("msec") }; } NodeStatus tick() override { - int msec = 0; - getInput("msec", msec); - // This blocking function will FREEZE the entire tree :( - std::this_thread::sleep_for( std::chrono::milliseconds(msec) ); - return NodeStatus::SUCCESS; + int msec = 0; + getInput("msec", msec); + // This blocking function will FREEZE the entire tree :( + std::this_thread::sleep_for( std::chrono::milliseconds(msec) ); + return NodeStatus::SUCCESS; } void halt() override { - // No one can invoke this method, because I freezed the tree. - // Even if this method COULD be executed, there is no way I can - // interrupt std::this_thread::sleep_for() + // No one can invoke this method, because I freezed the tree. + // Even if this method COULD be executed, there is no way I can + // interrupt std::this_thread::sleep_for() } }; ``` @@ -164,18 +168,18 @@ class BadSleepNode : public BT::AsyncActionNode static BT::PortsList providedPorts() { - return{ BT::InputPort("msec") }; + return{ BT::InputPort("msec") }; } NodeStatus tick() override { - // This code runs in its own thread, therefore the Tree is still running. - // This seems good but the thread still can't be aborted - int msec = 0; - getInput("msec", msec); - std::this_thread::sleep_for( std::chrono::milliseconds(msec) ); - return NodeStatus::SUCCESS; - } + // This code runs in its own thread, therefore the Tree is still running. + // This seems good but the thread still can't be aborted + int msec = 0; + getInput("msec", msec); + std::this_thread::sleep_for( std::chrono::milliseconds(msec) ); + return NodeStatus::SUCCESS; + } // The halt() method can not kill the spawned thread :( @@ -197,33 +201,106 @@ class ThreadedSleepNode : public BT::AsyncActionNode static BT::PortsList providedPorts() { - return{ BT::InputPort("msec") }; + return{ BT::InputPort("msec") }; } NodeStatus tick() override { - // This code run in its own thread, therefore the Tree is still running. - int msec = 0; - getInput("msec", msec); - - using namespace std::chrono; - const auto deadline = system_clock::now() + milliseconds(msec); - - // periodically check isHaltRequested() - // and sleep for a small amount of time only (1 millisecond) - while( !isHaltRequested() && system_clock::now() < deadline ) - { - std::this_thread::sleep_for( std::chrono::milliseconds(1) ); - } - return NodeStatus::SUCCESS; - } + // This code run in its own thread, therefore the Tree is still running. + int msec = 0; + getInput("msec", msec); + + using namespace std::chrono; + const auto deadline = system_clock::now() + milliseconds(msec); + + // periodically check isHaltRequested() + // and sleep for a small amount of time only (1 millisecond) + while( !isHaltRequested() && system_clock::now() < deadline ) + { + std::this_thread::sleep_for( std::chrono::milliseconds(1) ); + } + return NodeStatus::SUCCESS; + } // The halt() method can not kill the spawned thread :() // void halt(); - } }; ``` As you can see, this looks more complicated than the version we implemented first, using `BT::StatefulActionNode`. This pattern can still be useful in some case, but you must remember that introducing multi-threading make things more complicated and **should be avoided by default**. + +## Advanced example: client / server communication + +Frequently, people using BT.CPP execute the actual task in a different process. + +A typical (and recommended) way to do this in ROS is using [ActionLib](http://wiki.ros.org/actionlib). + +ActionLib provides exactly the kind of API that we need to implement correctly an asynchronous behavior: + +1. A non-blocking function to start the Action. +2. A way to monitor the current state of execution of the Action. +3. A way to retrieve the result or the error messages. +4. The avility to preempt / abort an action that is being executed. + +None of these operations are "blocking", therefore we don't need to spawn our own thread. + +More generally, let's assume that the developer has their own inter-processing communication, with a client/server relationship between the BT executor and the actual service provider. + +The corresponding **pseudo-code** implementation will look like this: + +```c++ +// This action talk to a remote server +class ActionClientNode : public BT::StatefulActionNode +{ + public: + SleepNode(const std::string& name, const BT::NodeConfiguration& config) + : BT::StatefulActionNode(name, config) + {} + + NodeStatus onStart() override + { + // send a request to the server + bool accepted = sendStartRequestToServer(); + // check if the request was rejected + if( !accepted ) { + return NodeStatus::FAILURE; + } + else { + return NodeStatus::RUNNING; + } + } + + /// method invoked by an action in the RUNNING state. + NodeStatus onRunning() override + { + // more psuedo-code + auto request_state = getCurrentStateFromServer(); + + if( request_state == DONE ) + { + auto result = getResult(); + if( IsValidResult(result) ) { + return NodeStatus::SUCCESS; + } + else { + return NodeStatus::FAILURE; + } + } + else if( request_state == ABORTED ) { + return NodeStatus::FAILURE; + } + else { + // request_state == EXECUTING ? + return NodeStatus::RUNNING; + } + } + + void onHalted() override + { + // notify the server that the operation have been aborted + sendAbortSignalToServer(); + } +}; +``` diff --git a/docs/tutorial_07_multiple_xml.md b/docs/tutorial_07_multiple_xml.md index 064f853c8..139b16a7f 100644 --- a/docs/tutorial_07_multiple_xml.md +++ b/docs/tutorial_07_multiple_xml.md @@ -62,7 +62,21 @@ If we don't want to add relative and hard-coded paths into our XML, or if we want to instantiate a subtree instead of the main tree, there is a new approach, since BT.CPP 3.7+. -This process requires few more steps, but offers more flexibility. +The simplified version of **main_tree.xml** will be: + +```XML + + + + + + + + + +``` + +To load manually the multiple files: ```c++ int main() From 0bcb1850b8de21b8d8fe9e362265e6f9c8083a16 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 20:35:10 +0200 Subject: [PATCH 167/709] docs --- docs/asynchronous_nodes.md | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/docs/asynchronous_nodes.md b/docs/asynchronous_nodes.md index df17e2fd0..f097a9b9a 100644 --- a/docs/asynchronous_nodes.md +++ b/docs/asynchronous_nodes.md @@ -263,7 +263,7 @@ class ActionClientNode : public BT::StatefulActionNode { // send a request to the server bool accepted = sendStartRequestToServer(); - // check if the request was rejected + // check if the request was rejected by the server if( !accepted ) { return NodeStatus::FAILURE; } @@ -280,7 +280,9 @@ class ActionClientNode : public BT::StatefulActionNode if( request_state == DONE ) { + // retrieve the result auto result = getResult(); + // check if this result should be considered "good" if( IsValidResult(result) ) { return NodeStatus::SUCCESS; } @@ -289,10 +291,12 @@ class ActionClientNode : public BT::StatefulActionNode } } else if( request_state == ABORTED ) { + // fail if the action was aborted by some other client + // or by the server itself return NodeStatus::FAILURE; } else { - // request_state == EXECUTING ? + // probably (request_state == EXECUTING) ? return NodeStatus::RUNNING; } } From 2759f1320755b04b6e354e2e1515ff8f4f322813 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 13 May 2022 20:48:37 +0200 Subject: [PATCH 168/709] typo --- docs/asynchronous_nodes.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/asynchronous_nodes.md b/docs/asynchronous_nodes.md index f097a9b9a..ddecf2a09 100644 --- a/docs/asynchronous_nodes.md +++ b/docs/asynchronous_nodes.md @@ -242,7 +242,7 @@ ActionLib provides exactly the kind of API that we need to implement correctly a 1. A non-blocking function to start the Action. 2. A way to monitor the current state of execution of the Action. 3. A way to retrieve the result or the error messages. -4. The avility to preempt / abort an action that is being executed. +4. The ability to preempt / abort an action that is being executed. None of these operations are "blocking", therefore we don't need to spawn our own thread. @@ -282,7 +282,7 @@ class ActionClientNode : public BT::StatefulActionNode { // retrieve the result auto result = getResult(); - // check if this result should be considered "good" + // check if this result is "good" if( IsValidResult(result) ) { return NodeStatus::SUCCESS; } From 6dd0d7462968b93568d76eb8e9e31756843b61e5 Mon Sep 17 00:00:00 2001 From: Griswald Brooks Date: Fri, 13 May 2022 11:49:57 -0700 Subject: [PATCH 169/709] typos (#377) Co-authored-by: Davide Faconti --- docs/tutorial_07_multiple_xml.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/tutorial_07_multiple_xml.md b/docs/tutorial_07_multiple_xml.md index 139b16a7f..91313d54a 100644 --- a/docs/tutorial_07_multiple_xml.md +++ b/docs/tutorial_07_multiple_xml.md @@ -1,7 +1,7 @@ -# How to use multiple XML to store your subtrees +# How to use multiple XML files to store your subtrees In the examples which we presented so far, we always create an entire Tree -from a single XMl file. +from a single XML file. If multiple Subtrees were used, they were all included into the same XML. From 142030cbd3e87420d6d206e65fbbed05e60f3484 Mon Sep 17 00:00:00 2001 From: Adam Sasine Date: Sat, 14 May 2022 11:06:26 -0400 Subject: [PATCH 170/709] Added pure CMake action to PR checks (#378) * Added CMake CI to PR checks * Renamed action to follow pattern --- .github/workflows/{build_vanilla.yml => cmake.yml} | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) rename .github/workflows/{build_vanilla.yml => cmake.yml} (98%) diff --git a/.github/workflows/build_vanilla.yml b/.github/workflows/cmake.yml similarity index 98% rename from .github/workflows/build_vanilla.yml rename to .github/workflows/cmake.yml index 88803bd05..0f318a7b7 100644 --- a/.github/workflows/build_vanilla.yml +++ b/.github/workflows/cmake.yml @@ -1,6 +1,6 @@ -name: CMake Build Matrix +name: cmake -on: [push] +on: [push, pull_request] env: # Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.) From 21b3efe40f97eba06cc0b2f7ab9ca318aa27720b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 15 May 2022 09:57:53 +0200 Subject: [PATCH 171/709] doc fix --- docs/asynchronous_nodes.md | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/docs/asynchronous_nodes.md b/docs/asynchronous_nodes.md index ddecf2a09..c762c312d 100644 --- a/docs/asynchronous_nodes.md +++ b/docs/asynchronous_nodes.md @@ -46,7 +46,7 @@ a node is RUNNING, usually its parent returns RUNNING too. Let's consider a simple "SleepNode". A good template to get started is the StatefulAction ```c++ -// Example os Asynchronous node that use StatefulActionNode as base class +// Example of Asynchronous node that use StatefulActionNode as base class class SleepNode : public BT::StatefulActionNode { public: @@ -188,7 +188,7 @@ class BadSleepNode : public BT::AsyncActionNode }; ``` -A "correct" (but over-engineered) version of it would be: +A correct version would be: ```c++ // I will create my own thread here, for no good reason @@ -222,8 +222,8 @@ class ThreadedSleepNode : public BT::AsyncActionNode return NodeStatus::SUCCESS; } - // The halt() method can not kill the spawned thread :() - // void halt(); + // The halt() method will set isHaltRequested() to true + // and stop the while loop in the spawned thread. }; ``` @@ -276,9 +276,9 @@ class ActionClientNode : public BT::StatefulActionNode NodeStatus onRunning() override { // more psuedo-code - auto request_state = getCurrentStateFromServer(); + auto current_state = getCurrentStateFromServer(); - if( request_state == DONE ) + if( current_state == DONE ) { // retrieve the result auto result = getResult(); @@ -290,13 +290,13 @@ class ActionClientNode : public BT::StatefulActionNode return NodeStatus::FAILURE; } } - else if( request_state == ABORTED ) { + else if( current_state == ABORTED ) { // fail if the action was aborted by some other client // or by the server itself return NodeStatus::FAILURE; } else { - // probably (request_state == EXECUTING) ? + // probably (current_state == EXECUTING) ? return NodeStatus::RUNNING; } } From 47c2ef7f600768d5ca614a6af4b684623841790b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 16 May 2022 10:14:57 +0200 Subject: [PATCH 172/709] Update README.md --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 14b15a395..1aa74fb3f 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ ![License MIT](https://img.shields.io/github/license/BehaviorTree/BehaviorTree.CPP?color=blue) ![Version](https://img.shields.io/badge/version-3.6-blue.svg) -[![CMake Build](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/build_vanilla.yml/badge.svg)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/build_vanilla.yml) +[![cmake](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/cmake.yml/badge.svg)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/cmake.yml) [![ros1](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros1/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros1) [![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros2/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros2) [![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP)](https://lgtm.com/projects/g/BehaviorTree/BehaviorTree.CPP/context:cpp) From 9eccd3aa1ea35192e80f0838781012f09429a06a Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 16 May 2022 10:20:41 +0200 Subject: [PATCH 173/709] Update README.md --- README.md | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index 1aa74fb3f..ddcd1e0c0 100644 --- a/README.md +++ b/README.md @@ -41,12 +41,10 @@ You can learn about the main concepts, the API and the tutorials here: https://w To find more details about the conceptual ideas that make this implementation different from others, you can read the [final deliverable of the project MOOD2Be](https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/MOOD2Be_final_report.pdf). -# Does your company use BehaviorTree.CPP? +# Commercial support -No company, institution or public/private funding is currently supporting the development of BehaviorTree.CPP and Groot. As a consequence, my time to support **BehaviorTree.CPP** is very limited and I decided won't spend any time at all supporting **Groot**. -Pull Requests are welcome and will be reviewed, even if with some delay. - -If your company use this software, consider becoming a **sponsor** to support bug fixing and development of new features. You can find contact details in [package.xml](package.xml). +Are you using BT.CPP in your commercial product and you need technical support / consulting? +You can get in touch at dfaconti@aurynrobotics.com and we will happy to discuss your use case and needs. # Design principles From 12373ad8d85286181658ea91720538cb53082083 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 17 May 2022 12:19:47 +0200 Subject: [PATCH 174/709] forum added --- README.md | 12 +++++++++--- docs/index.md | 5 +++++ 2 files changed, 14 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index ddcd1e0c0..529cd3fd1 100644 --- a/README.md +++ b/README.md @@ -35,13 +35,19 @@ to visualize, record, replay and analyze state transitions. - Last but not least: it is well [documented](https://www.behaviortree.dev/)! -# Documentation +## Documentation You can learn about the main concepts, the API and the tutorials here: https://www.behaviortree.dev/ -To find more details about the conceptual ideas that make this implementation different from others, you can read the [final deliverable of the project MOOD2Be](https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/MOOD2Be_final_report.pdf). +To find more details about the conceptual ideas that make this implementation different from others, +you can read the [final deliverable of the project MOOD2Be](https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/MOOD2Be_final_report.pdf). -# Commercial support +## Forum and Community + +If the documentation doesn't answer your questions and/or you want to +connect with the other **BT.CPP** users, visit https://discourse.behaviortree.dev/ + +## Commercial support Are you using BT.CPP in your commercial product and you need technical support / consulting? You can get in touch at dfaconti@aurynrobotics.com and we will happy to discuss your use case and needs. diff --git a/docs/index.md b/docs/index.md index dbc3ee934..674a2c5bb 100644 --- a/docs/index.md +++ b/docs/index.md @@ -20,6 +20,11 @@ to visualize, record, replay and analyze state transitions. ![ReadTheDocs](images/ReadTheDocs.png) +## Community + +If this documentation doesn't answer your questions or if you simply want to +connect with the community of BT.CPP users, visit https://discourse.behaviortree.dev/ + ## What is a Behavior Tree? A Behavior Tree (__BT__) is a way to structure the switching between different From bef8bdead6630c81861782c5d0bd5ba58bdb9e68 Mon Sep 17 00:00:00 2001 From: "imgbot[bot]" <31301654+imgbot[bot]@users.noreply.github.com> Date: Fri, 20 May 2022 01:28:20 -0700 Subject: [PATCH 175/709] [ImgBot] Optimize images (#380) *Total -- 40.04kb -> 27.97kb (30.14%) /docs/images/RunningTree.svg -- 21.53kb -> 14.50kb (32.67%) /docs/images/FallbackBasic.svg -- 18.51kb -> 13.48kb (27.2%) Signed-off-by: ImgBotApp Co-authored-by: ImgBotApp --- docs/images/FallbackBasic.svg | 508 +----------------------------- docs/images/RunningTree.svg | 567 +--------------------------------- 2 files changed, 2 insertions(+), 1073 deletions(-) diff --git a/docs/images/FallbackBasic.svg b/docs/images/FallbackBasic.svg index 2193f1f16..47c459130 100644 --- a/docs/images/FallbackBasic.svg +++ b/docs/images/FallbackBasic.svg @@ -1,507 +1 @@ - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - - - - - - - Fallback - - - - Fallback - - - - - - - - - EnterRoom - - - - EnterRoom - - - - - - - - - IsDoorOpen - - - - IsDoorOpen - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - UnlockDoor - - - - UnlockDoor - - - - - - - - - HaveKey? - - - - HaveKey? - - - - - - - - - OpenDoor - - - - OpenDoor - - - - - - - - - OpenDoor - - - - OpenDoor - - - - SmashDoor - - - +SequenceSequenceFallbackFallbackEnterRoomEnterRoomIsDoorOpenIsDoorOpenSequenceSequenceUnlockDoorUnlockDoorHaveKey?HaveKey?OpenDoorOpenDoorOpenDoorOpenDoorSmashDoor \ No newline at end of file diff --git a/docs/images/RunningTree.svg b/docs/images/RunningTree.svg index 630a1e2fd..c78c4a657 100644 --- a/docs/images/RunningTree.svg +++ b/docs/images/RunningTree.svg @@ -1,566 +1 @@ - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - - Sequence - - - - Sequence - - - - - - - - - - - - - - - Fallback - - - - Fallback - - - - - - - - - ActionA - - - - ActionA - - - - - - - - - ActionE - - - - ActionE - - - - - - - - - ActionD - - - - ActionD - - - - - - - - - ActionF - - - - ActionF - - - - - - - - - ActionB - - - - ActionB - - - - - - - - - - - root - - - - root - - - - - - - - - RUNNING - - - - RUNNING - - - - - - - - - FAILURE - - - - FAILURE - - - - - - - - - SUCCESS - - - - SUCCESS - - - - +SequenceSequenceFallbackFallbackActionAActionAActionEActionEActionDActionDActionFActionFActionBActionBrootrootRUNNINGRUNNINGFAILUREFAILURESUCCESSSUCCESS \ No newline at end of file From 284b1b79c044246051fe55452dee0b365f116714 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 21 May 2022 16:25:25 +0200 Subject: [PATCH 176/709] Update xml_parsing.cpp Revert changes on "main_tree_to_execute" --- src/xml_parsing.cpp | 37 +++++++++++++++---------------------- 1 file changed, 15 insertions(+), 22 deletions(-) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index b839b0435..17449d41e 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -430,34 +430,27 @@ Tree XMLParser::instantiateTree(const Blackboard::Ptr& root_blackboard, Tree output_tree; std::string main_tree_ID = main_tree_to_execute; + // use the main_tree_to_execute argument if it was provided by the user + // or the one in the FIRST document opened if( main_tree_ID.empty() ) { - for( const auto& doc: _p->opened_documents) + XMLElement* first_xml_root = _p->opened_documents.front()->RootElement(); + + if (auto main_tree_attribute = first_xml_root->Attribute("main_tree_to_execute")) { - XMLElement* xml_root = doc->RootElement(); - if (xml_root->Attribute("main_tree_to_execute")) - { - if(!main_tree_ID.empty()) - { - throw RuntimeError("The attribute [main_tree_to_execute] has been " - "found multiple times. You must specify explicitly the name " - "of the to instantiate."); - } - main_tree_ID = xml_root->Attribute("main_tree_to_execute"); - } + main_tree_ID = main_tree_attribute; + } + else if(_p->tree_roots.size() == 1) + { + // special case: there is only one registered BT. + main_tree_ID = _p->tree_roots.begin()->first; + } + else + { + throw RuntimeError("[main_tree_to_execute] was not specified correctly"); } } - // special case: no name, but there is only one registered BT. - if( main_tree_ID.empty() && _p->tree_roots.size() == 1) - { - main_tree_ID = _p->tree_roots.begin()->first; - } - - if( main_tree_ID.empty() ) - { - throw RuntimeError("[main_tree_to_execute] was not specified correctly"); - } //-------------------------------------- if( !root_blackboard ) { From a4b115a65ae5cb60f5bb1a247764d5d6b13957cf Mon Sep 17 00:00:00 2001 From: Adam Sasine Date: Sat, 21 May 2022 12:30:47 -0400 Subject: [PATCH 177/709] Fixed bug where including relative paths would fail to find the correct file (#358) * Added unit tests to verify current behavior * Fixed bug where including relative paths would fail to find the correct file * Added gtest environment to access executable path This path lets tests access files relative to the executable for better transportability * Changed file commandto add_custom_target The file command only copies during the cmake configure step. If source files change, file is not ran again --- src/xml_parsing.cpp | 8 +++ tests/CMakeLists.txt | 5 ++ tests/gtest_factory.cpp | 55 +++++++++++++++++++ tests/gtest_tree.cpp | 9 +++ tests/include/environment.h | 26 +++++++++ .../child/child/child_child_no_include.xml | 5 ++ tests/trees/child/child_include_child.xml | 10 ++++ tests/trees/child/child_include_parent.xml | 10 ++++ tests/trees/child/child_include_sibling.xml | 10 ++++ tests/trees/child/child_no_include.xml | 5 ++ tests/trees/parent_include_child.xml | 10 ++++ .../parent_include_child_include_child.xml | 10 ++++ .../parent_include_child_include_parent.xml | 10 ++++ .../parent_include_child_include_sibling.xml | 10 ++++ tests/trees/parent_no_include.xml | 5 ++ 15 files changed, 188 insertions(+) create mode 100644 tests/include/environment.h create mode 100644 tests/trees/child/child/child_child_no_include.xml create mode 100644 tests/trees/child/child_include_child.xml create mode 100644 tests/trees/child/child_include_parent.xml create mode 100644 tests/trees/child/child_include_sibling.xml create mode 100644 tests/trees/child/child_no_include.xml create mode 100644 tests/trees/parent_include_child.xml create mode 100644 tests/trees/parent_include_child_include_child.xml create mode 100644 tests/trees/parent_include_child_include_parent.xml create mode 100644 tests/trees/parent_include_child_include_sibling.xml create mode 100644 tests/trees/parent_no_include.xml diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 17449d41e..bffbbb491 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -187,8 +187,16 @@ void XMLParser::Pimpl::loadDocImpl(BT_TinyXML2::XMLDocument* doc, bool add_inclu opened_documents.emplace_back(new BT_TinyXML2::XMLDocument()); BT_TinyXML2::XMLDocument* next_doc = opened_documents.back().get(); + + // change current path to the included file for handling additional relative paths + const filesystem::path previous_path = current_path; + current_path = file_path.parent_path().make_absolute(); + next_doc->LoadFile(file_path.str().c_str()); loadDocImpl(next_doc, add_includes); + + // reset current path to the previous value + current_path = previous_path; } for (auto bt_node = xml_root->FirstChildElement("BehaviorTree"); diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 0727b153d..458a966cb 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -58,6 +58,11 @@ elseif(BUILD_UNIT_TESTS) bt_sample_nodes gtest gtest_main) target_include_directories(${BEHAVIOR_TREE_LIBRARY}_test PRIVATE gtest/include ${GTEST_INCLUDE_DIRS}) + add_custom_command(TARGET ${BEHAVIOR_TREE_LIBRARY}_test POST_BUILD + COMMAND ${CMAKE_COMMAND} -E copy_directory + ${CMAKE_SOURCE_DIR}/tests/trees + ${CMAKE_RUNTIME_OUTPUT_DIRECTORY}/trees) + add_test(BehaviorTreeCoreTest ${CMAKE_RUNTIME_OUTPUT_DIRECTORY}/${BEHAVIOR_TREE_LIBRARY}_test) endif() diff --git a/tests/gtest_factory.cpp b/tests/gtest_factory.cpp index e909ce0cc..50793acc4 100644 --- a/tests/gtest_factory.cpp +++ b/tests/gtest_factory.cpp @@ -2,6 +2,7 @@ #include "action_test_node.h" #include "condition_test_node.h" #include "behaviortree_cpp_v3/xml_parsing.h" +#include "environment.h" #include "../sample_nodes/crossdoor_nodes.h" #include "../sample_nodes/dummy_nodes.h" @@ -303,4 +304,58 @@ TEST(BehaviorTreeFactory, SubTreeWithRemapping) ASSERT_FALSE( talk_bb->getAny("talk_out") ); } +#if !defined(USING_ROS) && !defined(USING_ROS2) +TEST(BehaviorTreeFactory, CreateTreeFromFile) +{ + BehaviorTreeFactory factory; + + // should not throw + Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_no_include.xml").str()); + ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); +} + +TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromSameDirectory) +{ + BehaviorTreeFactory factory; + + // should not throw + Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/child/child_include_sibling.xml").str()); + ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); +} + +TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromChildDirectory) +{ + BehaviorTreeFactory factory; + + // should not throw + Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_include_child.xml").str()); + ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); +} +TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromChildDirectoryWhichIncludesFileFromSameDirectory) +{ + BehaviorTreeFactory factory; + + // should not throw + Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_include_child_include_sibling.xml").str()); + ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); +} + +TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromChildDirectoryWhichIncludesFileFromChildDirectory) +{ + BehaviorTreeFactory factory; + + // should not throw + Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_include_child_include_child.xml").str()); + ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); +} + +TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromChildDirectoryWhichIncludesFileFromParentDirectory) +{ + BehaviorTreeFactory factory; + + // should not throw + Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_include_child_include_parent.xml").str()); + ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); +} +#endif diff --git a/tests/gtest_tree.cpp b/tests/gtest_tree.cpp index 0a963047c..9cb0d8fed 100644 --- a/tests/gtest_tree.cpp +++ b/tests/gtest_tree.cpp @@ -14,6 +14,7 @@ #include "action_test_node.h" #include "condition_test_node.h" #include "behaviortree_cpp_v3/behavior_tree.h" +#include "environment.h" #include #include @@ -118,8 +119,16 @@ TEST_F(BehaviorTreeTest, PrintWithStream) ASSERT_TRUE(std::getline(stream, line, '\n').fail()); } +// define extern variable from environment.h +Environment* environment; + int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); + + // gtest will take ownership of this pointer and free it for us + environment = new Environment(argc, argv); + testing::AddGlobalTestEnvironment(environment); + return RUN_ALL_TESTS(); } diff --git a/tests/include/environment.h b/tests/include/environment.h new file mode 100644 index 000000000..300dfd976 --- /dev/null +++ b/tests/include/environment.h @@ -0,0 +1,26 @@ +#ifndef ENVIRONMENT_H +#define ENVIRONMENT_H + +#include + +#include "filesystem/path.h" + +class Environment : public testing::Environment +{ + public: + Environment(int argc, char** argv) + { + if (argc >= 1) + { + executable_path = filesystem::path(argv[0]).make_absolute(); + } + } + + // the absolute path to the test executable + filesystem::path executable_path; +}; + +// for accessing the environment within a test +extern Environment* environment; + +#endif diff --git a/tests/trees/child/child/child_child_no_include.xml b/tests/trees/child/child/child_child_no_include.xml new file mode 100644 index 000000000..6412de607 --- /dev/null +++ b/tests/trees/child/child/child_child_no_include.xml @@ -0,0 +1,5 @@ + + + + + diff --git a/tests/trees/child/child_include_child.xml b/tests/trees/child/child_include_child.xml new file mode 100644 index 000000000..ab833f869 --- /dev/null +++ b/tests/trees/child/child_include_child.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/tests/trees/child/child_include_parent.xml b/tests/trees/child/child_include_parent.xml new file mode 100644 index 000000000..8312376df --- /dev/null +++ b/tests/trees/child/child_include_parent.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/tests/trees/child/child_include_sibling.xml b/tests/trees/child/child_include_sibling.xml new file mode 100644 index 000000000..56523b750 --- /dev/null +++ b/tests/trees/child/child_include_sibling.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/tests/trees/child/child_no_include.xml b/tests/trees/child/child_no_include.xml new file mode 100644 index 000000000..7f9b7c5c9 --- /dev/null +++ b/tests/trees/child/child_no_include.xml @@ -0,0 +1,5 @@ + + + + + diff --git a/tests/trees/parent_include_child.xml b/tests/trees/parent_include_child.xml new file mode 100644 index 000000000..196e5621e --- /dev/null +++ b/tests/trees/parent_include_child.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/tests/trees/parent_include_child_include_child.xml b/tests/trees/parent_include_child_include_child.xml new file mode 100644 index 000000000..d6f8651d6 --- /dev/null +++ b/tests/trees/parent_include_child_include_child.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/tests/trees/parent_include_child_include_parent.xml b/tests/trees/parent_include_child_include_parent.xml new file mode 100644 index 000000000..f6234da7c --- /dev/null +++ b/tests/trees/parent_include_child_include_parent.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/tests/trees/parent_include_child_include_sibling.xml b/tests/trees/parent_include_child_include_sibling.xml new file mode 100644 index 000000000..ecf595897 --- /dev/null +++ b/tests/trees/parent_include_child_include_sibling.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/tests/trees/parent_no_include.xml b/tests/trees/parent_no_include.xml new file mode 100644 index 000000000..dedc05144 --- /dev/null +++ b/tests/trees/parent_no_include.xml @@ -0,0 +1,5 @@ + + + + + From 60420495344b1e4fcc0658bcb8705755f43d3d81 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 21 May 2022 18:25:53 +0200 Subject: [PATCH 178/709] Event based trigger introduced Added a new mechanism to emit "state changed" events that can "wake up" a tree. In short, it just provide an interruptible "sleep" function. --- docs/index.md | 2 +- docs/tutorial_04_sequence.md | 19 ++++-- docs/tutorial_05_subtrees.md | 11 +++- docs/tutorial_06_subtree_ports.md | 4 +- docs/tutorial_09_coroutines.md | 4 +- examples/t04_reactive_sequence.cpp | 6 +- examples/t05_crossdoor.cpp | 12 +++- examples/t06_subtree_port_remapping.cpp | 4 +- examples/t09_async_actions_coroutines.cpp | 4 +- include/behaviortree_cpp_v3/action_node.h | 5 +- include/behaviortree_cpp_v3/bt_factory.h | 18 +++++- .../decorators/timeout_node.h | 1 + include/behaviortree_cpp_v3/tree_node.h | 8 +++ .../utils/wakeup_signal.hpp | 53 +++++++++++++++++ sample_nodes/crossdoor_nodes.cpp | 5 ++ sample_nodes/crossdoor_nodes.h | 4 -- sample_nodes/movebase_node.cpp | 4 +- sample_nodes/movebase_node.h | 5 -- src/action_node.cpp | 2 +- src/bt_factory.cpp | 5 ++ src/tree_node.cpp | 15 ++++- tests/CMakeLists.txt | 1 + tests/gtest_wakeup.cpp | 59 +++++++++++++++++++ 23 files changed, 219 insertions(+), 32 deletions(-) create mode 100644 include/behaviortree_cpp_v3/utils/wakeup_signal.hpp create mode 100644 tests/gtest_wakeup.cpp diff --git a/docs/index.md b/docs/index.md index 674a2c5bb..5a66bc026 100644 --- a/docs/index.md +++ b/docs/index.md @@ -23,7 +23,7 @@ to visualize, record, replay and analyze state transitions. ## Community If this documentation doesn't answer your questions or if you simply want to -connect with the community of BT.CPP users, visit https://discourse.behaviortree.dev/ +connect with the community of BT.CPP users, visit [discourse.behaviortree.dev](https://discourse.behaviortree.dev/). ## What is a Behavior Tree? diff --git a/docs/tutorial_04_sequence.md b/docs/tutorial_04_sequence.md index a42c29506..ce711998b 100644 --- a/docs/tutorial_04_sequence.md +++ b/docs/tutorial_04_sequence.md @@ -63,11 +63,11 @@ NodeStatus MoveBaseAction::tick() int count = 0; // Pretend that "computing" takes 250 milliseconds. - // It is up to you to check periodicall _halt_requested and interrupt + // It is up to you to check periodically _halt_requested and interrupt // this tick() if it is true. while (!_halt_requested && count++ < 25) { - SleepMS(10); + std::this_thread::sleep_for( std::chrono::milliseconds(10) ); } std::cout << "[ MoveBase: FINISHED ]" << std::endl; @@ -105,6 +105,7 @@ The following example should use a simple `SequenceNode`. int main() { using namespace DummyNodes; + using std::chrono::milliseconds; BehaviorTreeFactory factory; factory.registerSimpleCondition("BatteryOK", std::bind(CheckBattery)); @@ -118,11 +119,11 @@ int main() std::cout << "\n--- 1st executeTick() ---" << std::endl; status = tree.tickRoot(); - SleepMS(150); + tree.sleep( milliseconds(150) ); std::cout << "\n--- 2nd executeTick() ---" << std::endl; status = tree.tickRoot(); - SleepMS(150); + tree.sleep( milliseconds(150) ); std::cout << "\n--- 3rd executeTick() ---" << std::endl; status = tree.tickRoot(); @@ -191,5 +192,15 @@ Expected output: Robot says: "mission completed!" ``` +## Event Driven trees? + +!!! important + We used the command `tree.sleep()` instead of `std::this_thread::sleep_for()` for a reason. + +The method `Tree::sleep()` should be preferred, because it can be interrupted by a Node in the tree when +"something changed". +Tree::sleep() will be interrupted when an `AsyncActionNode::tick()` is completed or, more generally, +when the method `TreeNode::emitStateChanged()` is invoked. + diff --git a/docs/tutorial_05_subtrees.md b/docs/tutorial_05_subtrees.md index 553494beb..bc745e33b 100644 --- a/docs/tutorial_05_subtrees.md +++ b/docs/tutorial_05_subtrees.md @@ -110,9 +110,16 @@ int main() while( status == NodeStatus::RUNNING) { status = tree.tickRoot(); - CrossDoor::SleepMS(1); // optional sleep to avoid "busy loops" + // IMPORTANT: you must always add some sleep if you call tickRoot() + // in a loop, to avoid using 100% of your CPU (busy loop). + // The method Tree::sleep() is recommended, because it can be + // interrupted by an internal event inside the tree. + tree.sleep( milliseconds(10) ); + } + if( LOOP ) + { + std::this_thread::sleep_for( milliseconds(1000) ); } - CrossDoor::SleepMS(2000); } return 0; } diff --git a/docs/tutorial_06_subtree_ports.md b/docs/tutorial_06_subtree_ports.md index b9c5c0aa8..9db8cdd31 100644 --- a/docs/tutorial_06_subtree_ports.md +++ b/docs/tutorial_06_subtree_ports.md @@ -78,7 +78,9 @@ int main() while( status == NodeStatus::RUNNING) { status = tree.tickRoot(); - SleepMS(1); // optional sleep to avoid "busy loops" + // IMPORTANT: add sleep to avoid busy loops. + // You should use Tree::sleep(). Don't be afraid to run this at 1 KHz. + tree.sleep( std::chrono::milliseconds(1) ); } // let's visualize some information about the current state of the blackboards. diff --git a/docs/tutorial_09_coroutines.md b/docs/tutorial_09_coroutines.md index 94c9ffd76..5b214dde3 100644 --- a/docs/tutorial_09_coroutines.md +++ b/docs/tutorial_09_coroutines.md @@ -147,10 +147,10 @@ int main() auto tree = factory.createTreeFromText(xml_text); //--------------------------------------- - // keep executin tick until it returns etiher SUCCESS or FAILURE + // keep executing tick until it returns either SUCCESS or FAILURE while( tree.tickRoot() == NodeStatus::RUNNING) { - std::this_thread::sleep_for( Milliseconds(10) ); + tree.sleep( std::chrono::milliseconds(10) ); } return 0; } diff --git a/examples/t04_reactive_sequence.cpp b/examples/t04_reactive_sequence.cpp index 6e241973a..598a3d122 100644 --- a/examples/t04_reactive_sequence.cpp +++ b/examples/t04_reactive_sequence.cpp @@ -57,9 +57,11 @@ void Assert(bool condition) throw RuntimeError("this is not what I expected"); } + int main() { using namespace DummyNodes; + using std::chrono::milliseconds; BehaviorTreeFactory factory; factory.registerSimpleCondition("BatteryOK", std::bind(CheckBattery)); @@ -85,12 +87,12 @@ int main() status = tree.tickRoot(); Assert(status == NodeStatus::RUNNING); - SleepMS(150); + tree.sleep( milliseconds(150) ); std::cout << "\n--- 2nd executeTick() ---" << std::endl; status = tree.tickRoot(); Assert(status == NodeStatus::RUNNING); - SleepMS(150); + tree.sleep( milliseconds(150) ); std::cout << "\n--- 3rd executeTick() ---" << std::endl; status = tree.tickRoot(); Assert(status == NodeStatus::SUCCESS); diff --git a/examples/t05_crossdoor.cpp b/examples/t05_crossdoor.cpp index 3539e0f4b..033e7ef3b 100644 --- a/examples/t05_crossdoor.cpp +++ b/examples/t05_crossdoor.cpp @@ -85,6 +85,7 @@ int main(int argc, char** argv) const bool LOOP = ( argc == 2 && strcmp( argv[1], "loop") == 0); + using std::chrono::milliseconds; do { NodeStatus status = NodeStatus::RUNNING; @@ -92,9 +93,16 @@ int main(int argc, char** argv) while( status == NodeStatus::RUNNING) { status = tree.tickRoot(); - CrossDoor::SleepMS(1); // optional sleep to avoid "busy loops" + // IMPORTANT: you must always add some sleep if you call tickRoot() + // in a loop, to avoid using 100% of your CPU (busy loop). + // The method Tree::sleep() is recommended, because it can be + // interrupted by an internal event inside the tree. + tree.sleep( milliseconds(10) ); + } + if( LOOP ) + { + std::this_thread::sleep_for( milliseconds(1000) ); } - CrossDoor::SleepMS(1000); } while(LOOP); diff --git a/examples/t06_subtree_port_remapping.cpp b/examples/t06_subtree_port_remapping.cpp index cc0304ba7..32f78b3ca 100644 --- a/examples/t06_subtree_port_remapping.cpp +++ b/examples/t06_subtree_port_remapping.cpp @@ -68,7 +68,9 @@ int main() while( status == NodeStatus::RUNNING) { status = tree.tickRoot(); - SleepMS(1); // optional sleep to avoid "busy loops" + // IMPORTANT: add sleep to avoid busy loops. + // You should use Tree::sleep(). Don't be afraid to run this at 1 KHz. + tree.sleep( std::chrono::milliseconds(1) ); } // let's visualize some information about the current state of the blackboards. diff --git a/examples/t09_async_actions_coroutines.cpp b/examples/t09_async_actions_coroutines.cpp index 7170e724d..e8e3bfca9 100644 --- a/examples/t09_async_actions_coroutines.cpp +++ b/examples/t09_async_actions_coroutines.cpp @@ -115,10 +115,10 @@ int main() auto tree = factory.createTreeFromText(xml_text); //--------------------------------------- - // keep executin tick until it returns etiher SUCCESS or FAILURE + // keep executing tick until it returns either SUCCESS or FAILURE while( tree.tickRoot() == NodeStatus::RUNNING) { - std::this_thread::sleep_for( std::chrono::milliseconds(10) ); + tree.sleep( std::chrono::milliseconds(10) ); } return 0; } diff --git a/include/behaviortree_cpp_v3/action_node.h b/include/behaviortree_cpp_v3/action_node.h index 0452e6ef0..9fca24cbe 100644 --- a/include/behaviortree_cpp_v3/action_node.h +++ b/include/behaviortree_cpp_v3/action_node.h @@ -113,6 +113,9 @@ class SimpleActionNode : public SyncActionNode * - remember, with few exceptions, a halted AsyncAction must return NodeStatus::IDLE. * * For a complete example, look at __AsyncActionTest__ in action_test_node.h in the folder test. + * + * NOTE: when the thread is completed, i.e. the tick() returns its status, + * a TreeNode::emitStateChanged() will be called. */ class AsyncActionNode : public ActionNodeBase { @@ -136,7 +139,7 @@ class AsyncActionNode : public ActionNodeBase std::exception_ptr exptr_; std::atomic_bool halt_requested_; - std::future thread_handle_; + std::future thread_handle_; std::mutex m_; }; diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index 5bc83ad81..45000cbfe 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -143,6 +143,10 @@ class Tree Tree(Tree&& other) { (*this) = std::move(other); + for(auto& node: nodes) + { + node->setWakeUpInstance( &wake_up_ ); + } } Tree& operator=(Tree&& other) @@ -150,6 +154,11 @@ class Tree nodes = std::move(other.nodes); blackboard_stack = std::move(other.blackboard_stack); manifests = std::move(other.manifests); + + for(auto& node: nodes) + { + node->setWakeUpInstance( &wake_up_ ); + } return *this; } @@ -178,7 +187,7 @@ class Tree } NodeStatus tickRoot() - { + { if(!rootNode()) { throw RuntimeError("Empty Tree"); @@ -190,10 +199,17 @@ class Tree return ret; } + /// Sleep for a certain amount of time. + /// This sleep could be interrupted by the method + /// TreeNode::emitStateChanged() + void sleep(std::chrono::system_clock::duration timeout); + ~Tree(); Blackboard::Ptr rootBlackboard(); +private: + WakeUpSignal wake_up_; }; class Parser; diff --git a/include/behaviortree_cpp_v3/decorators/timeout_node.h b/include/behaviortree_cpp_v3/decorators/timeout_node.h index ac345795c..171eca78f 100644 --- a/include/behaviortree_cpp_v3/decorators/timeout_node.h +++ b/include/behaviortree_cpp_v3/decorators/timeout_node.h @@ -85,6 +85,7 @@ class TimeoutNode : public DecoratorNode { child_halted_ = true; haltChild(); + emitStateChanged(); } }); } diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index a925405ae..df143e36b 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -21,6 +21,7 @@ #include "behaviortree_cpp_v3/basic_types.h" #include "behaviortree_cpp_v3/blackboard.h" #include "behaviortree_cpp_v3/utils/strcat.hpp" +#include "behaviortree_cpp_v3/utils/wakeup_signal.hpp" #ifdef _MSC_VER #pragma warning(disable : 4127) @@ -174,6 +175,9 @@ class TreeNode static Optional getRemappedKey(StringView port_name, StringView remapping_value); + // Notify the tree should be ticked again() + void emitStateChanged(); + protected: /// Method to be implemented by the user virtual BT::NodeStatus tick() = 0; @@ -186,6 +190,8 @@ class TreeNode // Only BehaviorTreeFactory should call this void setRegistrationID(StringView ID); + void setWakeUpInstance(WakeUpSignal* instance); + void modifyPortsRemapping(const PortsRemapping& new_remapping); void setStatus(NodeStatus new_status); @@ -210,6 +216,8 @@ class TreeNode PreTickOverrideCallback pre_condition_callback_; PostTickOverrideCallback post_condition_callback_; + + WakeUpSignal* wake_up_ = nullptr; }; //------------------------------------------------------- diff --git a/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp b/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp new file mode 100644 index 000000000..64e25f50d --- /dev/null +++ b/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp @@ -0,0 +1,53 @@ +/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved +* Copyright (C) 2018-2020 Davide Faconti, Eurecat - 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_WAKEUP_SIGNAL_HPP +#define BEHAVIORTREECORE_WAKEUP_SIGNAL_HPP + +#include +#include +#include + +namespace BT +{ + +class WakeUpSignal +{ +public: + /// Return true if the + bool waitFor(std::chrono::system_clock::duration tm) + { + std::unique_lock lk(mutex_); + ready_ = false; + return cv_.wait_for(lk, tm, [this]{ return ready_; }); + } + + void emitSignal() + { + { + std::lock_guard lk(mutex_); + ready_ = true; + } + cv_.notify_all(); + } + +private: + + std::mutex mutex_; + std::condition_variable cv_; + bool ready_ = false; +}; + +} + +#endif // BEHAVIORTREECORE_WAKEUP_SIGNAL_HPP diff --git a/sample_nodes/crossdoor_nodes.cpp b/sample_nodes/crossdoor_nodes.cpp index 1b37c8184..5540cd936 100644 --- a/sample_nodes/crossdoor_nodes.cpp +++ b/sample_nodes/crossdoor_nodes.cpp @@ -7,6 +7,11 @@ BT_REGISTER_NODES(factory) CrossDoor::RegisterNodes(factory); } +inline void SleepMS(int ms) +{ + std::this_thread::sleep_for(std::chrono::milliseconds(ms)); +} + // For simplicity, in this example the status of the door is not shared // using ports and blackboards static bool _door_open = false; diff --git a/sample_nodes/crossdoor_nodes.h b/sample_nodes/crossdoor_nodes.h index 876e5b2de..f5273c97b 100644 --- a/sample_nodes/crossdoor_nodes.h +++ b/sample_nodes/crossdoor_nodes.h @@ -6,10 +6,6 @@ using namespace BT; namespace CrossDoor { -inline void SleepMS(int ms) -{ - std::this_thread::sleep_for(std::chrono::milliseconds(ms)); -} BT::NodeStatus IsDoorOpen(); diff --git a/sample_nodes/movebase_node.cpp b/sample_nodes/movebase_node.cpp index 9c8416763..f303aa901 100644 --- a/sample_nodes/movebase_node.cpp +++ b/sample_nodes/movebase_node.cpp @@ -22,11 +22,11 @@ BT::NodeStatus MoveBaseAction::tick() int count = 0; // Pretend that "computing" takes 250 milliseconds. - // It is up to you to check periodicall _halt_requested and interrupt + // It is up to you to check periodically _halt_requested and interrupt // this tick() if it is true. while (!_halt_requested && count++ < 25) { - SleepMS(10); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); } std::cout << "[ MoveBase: FINISHED ]" << std::endl; diff --git a/sample_nodes/movebase_node.h b/sample_nodes/movebase_node.h index 4a7df1bba..f97cb127c 100644 --- a/sample_nodes/movebase_node.h +++ b/sample_nodes/movebase_node.h @@ -9,11 +9,6 @@ struct Pose2D double x, y, theta; }; -inline void SleepMS(int ms) -{ - std::this_thread::sleep_for(std::chrono::milliseconds(ms)); -} - namespace BT { // This template specialization is needed only if you want diff --git a/src/action_node.cpp b/src/action_node.cpp index 3e452e663..d539b5cf4 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -188,7 +188,7 @@ NodeStatus BT::AsyncActionNode::executeTick() exptr_ = std::current_exception(); setStatus(BT::NodeStatus::IDLE); } - return status(); + emitStateChanged(); }); } diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 96d0c9148..66692308e 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -294,6 +294,11 @@ Tree BehaviorTreeFactory::createTree(const std::string &tree_name, Blackboard::P return tree; } +void Tree::sleep(std::chrono::system_clock::duration timeout) +{ + wake_up_.waitFor(timeout); +} + Tree::~Tree() { haltTree(); diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 47f68c32e..b1eee3c77 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -181,9 +181,22 @@ Optional TreeNode::getRemappedKey(StringView port_name, StringView r return nonstd::make_unexpected("Not a blackboard pointer"); } +void TreeNode::emitStateChanged() +{ + if( wake_up_ ) + { + wake_up_->emitSignal(); + } +} + void TreeNode::setRegistrationID(StringView ID) { - registration_ID_.assign(ID.data(), ID.size()); + registration_ID_.assign(ID.data(), ID.size()); +} + +void TreeNode::setWakeUpInstance(WakeUpSignal *instance) +{ + wake_up_ = instance; } void TreeNode::modifyPortsRemapping(const PortsRemapping &new_remapping) diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 458a966cb..3ff5cd353 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -18,6 +18,7 @@ set(BT_TESTS navigation_test.cpp gtest_subtree.cpp gtest_switch.cpp + gtest_wakeup.cpp ) if( BT_COROUTINES ) diff --git a/tests/gtest_wakeup.cpp b/tests/gtest_wakeup.cpp new file mode 100644 index 000000000..7839ebd07 --- /dev/null +++ b/tests/gtest_wakeup.cpp @@ -0,0 +1,59 @@ +#include +#include "behaviortree_cpp_v3/bt_factory.h" +#include "../sample_nodes/dummy_nodes.h" + +using namespace BT; + + +class FastAction : public BT::AsyncActionNode +{ + public: + // Any TreeNode with ports must have a constructor with this signature + FastAction(const std::string& name, const BT::NodeConfiguration& config) + : AsyncActionNode(name, config) + { + } + + static BT::PortsList providedPorts() + { + return{ }; + } + + BT::NodeStatus tick() override + { + std::this_thread::sleep_for(std::chrono::milliseconds(10) ); + return BT::NodeStatus::SUCCESS; + } +}; + +TEST(WakeUp, BasicTest) +{ + +static const char* xml_text = R"( + + + + + + )"; + + BehaviorTreeFactory factory; + factory.registerNodeType("FastAction"); + + Tree tree = factory.createTreeFromText(xml_text); + + using namespace std::chrono; + + auto t1 = system_clock::now(); + tree.tickRoot(); + tree.sleep(milliseconds(200)); + auto t2 = system_clock::now(); + + auto dT = duration_cast(t2-t1).count(); + std::cout << "Woke up after msec: " << dT << std::endl; + + ASSERT_LT(dT, 25 ); +} + + + From a3bed59065d3f812b9a9e2f8ada8157df756f422 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 21 May 2022 20:29:08 +0200 Subject: [PATCH 179/709] auto-doc --- netlify.toml | 7 +++++++ 1 file changed, 7 insertions(+) create mode 100644 netlify.toml diff --git a/netlify.toml b/netlify.toml new file mode 100644 index 000000000..36d93ed90 --- /dev/null +++ b/netlify.toml @@ -0,0 +1,7 @@ +[build] +publish = "site" +command = """ +pip3 install mkdocs-material && +pip3 install mkdocs-include-markdown-plugin && +mkdocs build -d site +""" From 2408947b8556e3a9767210fb3cdb1e0cebaf43ae Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 21 May 2022 20:40:00 +0200 Subject: [PATCH 180/709] add netlify stuff --- runtime.txt | 1 + 1 file changed, 1 insertion(+) create mode 100644 runtime.txt diff --git a/runtime.txt b/runtime.txt new file mode 100644 index 000000000..cc1923a40 --- /dev/null +++ b/runtime.txt @@ -0,0 +1 @@ +3.8 From e11d3efb198722b5c36126f76c86add582e47149 Mon Sep 17 00:00:00 2001 From: Jeremie Deray Date: Sat, 21 May 2022 14:46:33 -0400 Subject: [PATCH 181/709] revisit export (#379) --- CMakeLists.txt | 35 ++++++++++++++++++++++++++++------- cmake/Config.cmake.in | 7 +++++++ 2 files changed, 35 insertions(+), 7 deletions(-) create mode 100644 cmake/Config.cmake.in diff --git a/CMakeLists.txt b/CMakeLists.txt index 6b9cf5d9a..cd490a571 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -279,7 +279,7 @@ endif() # INSTALL INSTALL(TARGETS ${BEHAVIOR_TREE_LIBRARY} - EXPORT BehaviorTreeV3Config + EXPORT ${PROJECT_NAME}Targets ARCHIVE DESTINATION ${BEHAVIOR_TREE_LIB_DESTINATION} LIBRARY DESTINATION ${BEHAVIOR_TREE_LIB_DESTINATION} RUNTIME DESTINATION ${BEHAVIOR_TREE_BIN_DESTINATION} @@ -289,16 +289,37 @@ INSTALL( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ DESTINATION ${BEHAVIOR_TREE_INC_DESTINATION} FILES_MATCHING PATTERN "*.h*") -install(EXPORT BehaviorTreeV3Config - DESTINATION "${BEHAVIOR_TREE_LIB_DESTINATION}/BehaviorTreeV3/cmake" - NAMESPACE BT::) - -export(TARGETS ${PROJECT_NAME} +install(EXPORT ${PROJECT_NAME}Targets + FILE "${PROJECT_NAME}Targets.cmake" + DESTINATION "${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}" NAMESPACE BT:: - FILE "${CMAKE_CURRENT_BINARY_DIR}/BehaviorTreeV3Config.cmake") + ) export(PACKAGE ${PROJECT_NAME}) +include(CMakePackageConfigHelpers) + +configure_package_config_file( + "${CMAKE_CURRENT_SOURCE_DIR}/cmake/Config.cmake.in" + "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake" + INSTALL_DESTINATION "${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}" +) + +# This requires to declare to project version in the project() macro + +#write_basic_package_version_file( +# "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" +# VERSION ${PROJECT_VERSION} +# COMPATIBILITY AnyNewerVersion +#) + +install( + FILES + "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake" + # "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" + DESTINATION "${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}" +) + ###################################################### # EXAMPLES and TOOLS if(BUILD_TOOLS) diff --git a/cmake/Config.cmake.in b/cmake/Config.cmake.in new file mode 100644 index 000000000..64f20beb5 --- /dev/null +++ b/cmake/Config.cmake.in @@ -0,0 +1,7 @@ +@PACKAGE_INIT@ + +include("${CMAKE_CURRENT_LIST_DIR}/@PROJECT_NAME@Targets.cmake") + +set(@PROJECT_NAME@_TARGETS "BT::@BEHAVIOR_TREE_LIBRARY@") + +check_required_components(@PROJECT_NAME@) From 13c30c8d471e96f2aaf5cc363a766a27beb3df23 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 21 May 2022 21:07:30 +0200 Subject: [PATCH 182/709] fix wakeup --- include/behaviortree_cpp_v3/bt_factory.h | 24 ++++++++++++------- include/behaviortree_cpp_v3/tree_node.h | 4 ++-- .../utils/wakeup_signal.hpp | 17 +++---------- src/bt_factory.cpp | 2 +- src/tree_node.cpp | 2 +- src/xml_parsing.cpp | 1 + tests/gtest_wakeup.cpp | 1 - 7 files changed, 23 insertions(+), 28 deletions(-) diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index 45000cbfe..b89141940 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -143,10 +143,6 @@ class Tree Tree(Tree&& other) { (*this) = std::move(other); - for(auto& node: nodes) - { - node->setWakeUpInstance( &wake_up_ ); - } } Tree& operator=(Tree&& other) @@ -154,12 +150,17 @@ class Tree nodes = std::move(other.nodes); blackboard_stack = std::move(other.blackboard_stack); manifests = std::move(other.manifests); + wake_up_ = other.wake_up_; + return *this; + } + void initialize() + { + wake_up_ = std::make_shared(); for(auto& node: nodes) { - node->setWakeUpInstance( &wake_up_ ); + node->setWakeUpInstance(wake_up_); } - return *this; } void haltTree() @@ -183,11 +184,16 @@ class Tree TreeNode* rootNode() const { - return nodes.empty() ? nullptr : nodes.front().get(); + return nodes.empty() ? nullptr : nodes.front().get(); } NodeStatus tickRoot() - { + { + if(!wake_up_) + { + initialize(); + } + if(!rootNode()) { throw RuntimeError("Empty Tree"); @@ -209,7 +215,7 @@ class Tree Blackboard::Ptr rootBlackboard(); private: - WakeUpSignal wake_up_; + std::shared_ptr wake_up_; }; class Parser; diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index df143e36b..09156ea84 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -190,7 +190,7 @@ class TreeNode // Only BehaviorTreeFactory should call this void setRegistrationID(StringView ID); - void setWakeUpInstance(WakeUpSignal* instance); + void setWakeUpInstance(std::shared_ptr instance); void modifyPortsRemapping(const PortsRemapping& new_remapping); @@ -217,7 +217,7 @@ class TreeNode PostTickOverrideCallback post_condition_callback_; - WakeUpSignal* wake_up_ = nullptr; + std::shared_ptr wake_up_; }; //------------------------------------------------------- diff --git a/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp b/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp index 64e25f50d..75df8f426 100644 --- a/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp +++ b/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp @@ -1,16 +1,3 @@ -/* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved -* Copyright (C) 2018-2020 Davide Faconti, Eurecat - 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_WAKEUP_SIGNAL_HPP #define BEHAVIORTREECORE_WAKEUP_SIGNAL_HPP @@ -29,7 +16,9 @@ class WakeUpSignal { std::unique_lock lk(mutex_); ready_ = false; - return cv_.wait_for(lk, tm, [this]{ return ready_; }); + return cv_.wait_for(lk, tm, [this]{ + return ready_; + }); } void emitSignal() diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 66692308e..fc2f48cd4 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -296,7 +296,7 @@ Tree BehaviorTreeFactory::createTree(const std::string &tree_name, Blackboard::P void Tree::sleep(std::chrono::system_clock::duration timeout) { - wake_up_.waitFor(timeout); + wake_up_->waitFor(timeout); } Tree::~Tree() diff --git a/src/tree_node.cpp b/src/tree_node.cpp index b1eee3c77..39e37b5aa 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -194,7 +194,7 @@ void TreeNode::setRegistrationID(StringView ID) registration_ID_.assign(ID.data(), ID.size()); } -void TreeNode::setWakeUpInstance(WakeUpSignal *instance) +void TreeNode::setWakeUpInstance(std::shared_ptr instance) { wake_up_ = instance; } diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index bffbbb491..add0691cd 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -471,6 +471,7 @@ Tree XMLParser::instantiateTree(const Blackboard::Ptr& root_blackboard, output_tree, root_blackboard, TreeNode::Ptr() ); + output_tree.initialize(); return output_tree; } diff --git a/tests/gtest_wakeup.cpp b/tests/gtest_wakeup.cpp index 7839ebd07..c0502c393 100644 --- a/tests/gtest_wakeup.cpp +++ b/tests/gtest_wakeup.cpp @@ -1,6 +1,5 @@ #include #include "behaviortree_cpp_v3/bt_factory.h" -#include "../sample_nodes/dummy_nodes.h" using namespace BT; From 0b295c707e8be5f4aaf82812531e7355a5a0263f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 21 May 2022 21:07:38 +0200 Subject: [PATCH 183/709] prepare release --- CHANGELOG.rst | 35 +++++++++++++++++++++++++++++++++++ 1 file changed, 35 insertions(+) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 2490eed27..ae89d91d1 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,41 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* add netlify stuff +* Event based trigger introduced + Added a new mechanism to emit "state changed" events that can "wake up" a tree. + In short, it just provide an interruptible "sleep" function. +* Fixed bug where including relative paths would fail to find the correct file (`#358 `_) + * Added unit tests to verify current behavior + * Fixed bug where including relative paths would fail to find the correct file + * Added gtest environment to access executable path + This path lets tests access files relative to the executable for better transportability + * Changed file commandto add_custom_target + The file command only copies during the cmake configure step. If source files change, file is not ran again +* Added pure CMake action to PR checks (`#378 `_) + * Added CMake CI to PR checks + * Renamed action to follow pattern +* updated documentation +* add the ability to register multiple BTs (`#373 `_) +* Update ros1.yaml +* fix `#338 `_ +* fix issue `#330 `_ +* fix issue `#360 `_ +* Merge branch 'master' of github.com:BehaviorTree/BehaviorTree.CPP +* Update Tutorial 2 Docuemtation (`#372 `_) +* Update tutorial_09_coroutines.md (`#359 `_) + Minor fix, renamed Timepoint to TimePoint. +* Export dependency on ament_index_cpp (`#362 `_) + To make dependent packages try to link ament_index_cpp, export the + dependency explicitly. +* Change order of lock to prevent deadlock. (`#368 `_) + Resolves `#367 `_. +* Fix `#320 `_ : forbit refrences in Any +* Update action_node.h +* Contributors: Adam Sasine, Davide Faconti, Fabian Schurig, Griswald Brooks, Hyeongsik Min, Robodrome, imgbot[bot], panwauu + 3.6.1 (2022-03-06) ------------------ * remove windows tests From e24f1dd8e24940e92aa68631cb54ff32e9d5b312 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 May 2022 10:16:41 +0200 Subject: [PATCH 184/709] adding example 4 and queues --- examples/CMakeLists.txt | 1 + examples/ex04_waypoints.cpp | 201 ++++++++++++++++++ .../actions/always_success_node.h | 2 +- .../actions/pop_from_queue.hpp | 148 +++++++++++++ include/behaviortree_cpp_v3/bt_factory.h | 3 +- .../decorators/consume_queue.h | 103 +++++++++ src/xml_parsing.cpp | 8 +- 7 files changed, 463 insertions(+), 3 deletions(-) create mode 100644 examples/ex04_waypoints.cpp create mode 100644 include/behaviortree_cpp_v3/actions/pop_from_queue.hpp create mode 100644 include/behaviortree_cpp_v3/decorators/consume_queue.h diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 4dc4a9a8c..393a9c75d 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -34,3 +34,4 @@ endif() CompileExample("ex01_wrap_legacy") CompileExample("ex02_runtime_ports") CompileExample("ex03_ncurses_manual_selector") +CompileExample("ex04_waypoints") diff --git a/examples/ex04_waypoints.cpp b/examples/ex04_waypoints.cpp new file mode 100644 index 000000000..7ce6a49ef --- /dev/null +++ b/examples/ex04_waypoints.cpp @@ -0,0 +1,201 @@ +#include "behaviortree_cpp_v3/bt_factory.h" +#include "behaviortree_cpp_v3/actions/pop_from_queue.hpp" +#include "behaviortree_cpp_v3/decorators/consume_queue.h" +#include + +using namespace BT; + +/* + * In this example we will show how a common design pattern could be implemented. + * We want to iterate through the elements of a queue, for instance a list of waypoints. + * + * Two ways to create a "loop" are presented, one using the actions "QueueSize" and "PopFromQueue" + * and the other using the decorator "ConsumeQueue". + */ + +struct Pose2D +{ + double x, y, theta; +}; + + +/** + * @brief Dummy action that generates a list of poses. + */ +class GenerateWaypoints : public SyncActionNode +{ + public: + GenerateWaypoints(const std::string& name, const NodeConfiguration& config) + : SyncActionNode(name, config) + {} + + NodeStatus tick() override + { + auto queue = std::make_shared< ProtectedQueue >(); + for(int i=0; i<10; i++) + { + queue->items.push_back( Pose2D{ double(i), double(i), 0} ); + } + setOutput("waypoints", queue); + return NodeStatus::SUCCESS; + } + + static PortsList providedPorts() + { + return { OutputPort< std::shared_ptr > >("waypoints") }; + } +}; +//-------------------------------------------------------------- +class UseWaypointQueue : public AsyncActionNode +{ + public: + UseWaypointQueue(const std::string& name, const NodeConfiguration& config) + : AsyncActionNode(name, config) + { } + + NodeStatus tick() override + { + std::shared_ptr> queue; + if( getInput("waypoints", queue) && queue ) + { + Pose2D wp; + { + // Since we are using reference semantic (the queue is wrapped in + // a shared_ptr) to modify the queue inside the blackboard, + // we are effectively bypassing the thread safety of the BB. + // This is the reason why we need to use a mutex explicitly. + std::unique_lock lk(queue->mtx); + + auto& waypoints = queue->items; + if( waypoints.empty() ) + { + return NodeStatus::FAILURE; + } + wp = waypoints.front(); + waypoints.pop_front(); + + } // end mutex lock + + std::this_thread::sleep_for( std::chrono::milliseconds(100) ); + std::cout << "Using waypoint: " << wp.x << "/" << wp.y << std::endl; + + return NodeStatus::SUCCESS; + } + else{ + return NodeStatus::FAILURE; + } + } + + static PortsList providedPorts() + { + return { InputPort< std::shared_ptr< ProtectedQueue> >("waypoints") }; + } +}; + + +/** + * @brief Simple Action that uses the output of PopFromQueue or ConsumeQueue + */ +class UseWaypoint : public AsyncActionNode +{ + public: + UseWaypoint(const std::string& name, const NodeConfiguration& config) + : AsyncActionNode(name, config) + { } + + NodeStatus tick() override + { + Pose2D wp; + if( getInput("waypoint", wp) ) + { + std::this_thread::sleep_for( std::chrono::milliseconds(100) ); + std::cout << "Using waypoint: " << wp.x << "/" << wp.y << std::endl; + return NodeStatus::SUCCESS; + } + else{ + return NodeStatus::FAILURE; + } + } + + static PortsList providedPorts() + { + return { InputPort("waypoint") }; + } +}; + + +// clang-format off + +static const char* xml_implicit = R"( + + + + + + + + + + + )"; + + +static const char* xml_A = R"( + + + + + + + + + + + + + + + )"; + +static const char* xml_B = R"( + + + + + + + + + + + )"; + +// clang-format on + +int main() +{ + BehaviorTreeFactory factory; + + factory.registerNodeType>("PopFromQueue"); + factory.registerNodeType>("QueueSize"); + factory.registerNodeType>("ConsumeQueue"); + + factory.registerNodeType("UseWaypoint"); + factory.registerNodeType("UseWaypointQueue"); + factory.registerNodeType("GenerateWaypoints"); + + + for(const auto& xml_text : {xml_implicit, xml_A, xml_B} ) + { + auto tree = factory.createTreeFromText(xml_text); + while( tree.tickRoot() == NodeStatus::RUNNING ) + { + tree.sleep( std::chrono::milliseconds(10) ); + } + std::cout << "--------------" << std::endl; + } + + return 0; +} + + diff --git a/include/behaviortree_cpp_v3/actions/always_success_node.h b/include/behaviortree_cpp_v3/actions/always_success_node.h index 5af21986b..ca82b7bc0 100644 --- a/include/behaviortree_cpp_v3/actions/always_success_node.h +++ b/include/behaviortree_cpp_v3/actions/always_success_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2020 Davide Faconti, Eurecat - All Rights Reserved +/* Copyright (C) 2018-2022 Davide Faconti, Eurecat - 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/behaviortree_cpp_v3/actions/pop_from_queue.hpp b/include/behaviortree_cpp_v3/actions/pop_from_queue.hpp new file mode 100644 index 000000000..3a75875c8 --- /dev/null +++ b/include/behaviortree_cpp_v3/actions/pop_from_queue.hpp @@ -0,0 +1,148 @@ +/* Copyright (C) 2018-2022 Davide Faconti, Eurecat - 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 BEHAVIORTREE_POPFROMQUEUE_HPP +#define BEHAVIORTREE_POPFROMQUEUE_HPP + +#include +#include +#include "behaviortree_cpp_v3/action_node.h" +#include "behaviortree_cpp_v3/decorator_node.h" + + +/** + * Template Action used in ex04_waypoints.cpp example. + * + * Its purpose is to do make it easy to create while loops wich consume the elements of a queue. + * + * Note that modifying the queue is not thread safe, therefore the action that creates the queue + * or push elements into it, must be Synchronous. + * + * When ticked, we pop_front from the "queue" and insert that value in "popped_item". + * Return FAILURE if the queue is empty, SUCCESS otherwise. + */ +namespace BT +{ + +template +struct ProtectedQueue +{ + std::list items; + std::mutex mtx; +}; + +/* + * Few words about why we represent the queue as std::shared_ptr: + * + * Since we will pop from the queue, the fact that the blackboard uses + * a value semantic is not very convenient, since it would oblige us to + * copy the entire std::list from the BB and than copy again a new one with one less element. + * + * We avoid this using reference semantic (wrapping the object in a shared_ptr). + * Unfortunately, remember that this makes our access to the list not thread-safe! + * This is the reason why we add a mutex to be used when modyfying the ProtectedQueue::items + * + * */ + + +template +class PopFromQueue : public SyncActionNode +{ + public: + PopFromQueue(const std::string& name, const NodeConfiguration& config) + : SyncActionNode(name, config) + { + } + + NodeStatus tick() override + { + std::shared_ptr> queue; + if( getInput("queue", queue) && queue ) + { + std::unique_lock lk(queue->mtx); + auto& items = queue->items; + + if( items.empty() ) + { + return NodeStatus::FAILURE; + } + else{ + T val = items.front(); + items.pop_front(); + setOutput("popped_item", val); + return NodeStatus::SUCCESS; + } + } + else{ + return NodeStatus::FAILURE; + } + } + + static PortsList providedPorts() + { + return { InputPort>>("queue"), + OutputPort("popped_item")}; + } +}; + +/** + * Get the size of a queue. Usefull is you want to write something like: + * + * + * + * + * + * + * + * + */ +template +class QueueSize : public SyncActionNode +{ + public: + QueueSize(const std::string& name, const NodeConfiguration& config) + : SyncActionNode(name, config) + { + } + + NodeStatus tick() override + { + std::shared_ptr> queue; + if( getInput("queue", queue) && queue ) + { + std::unique_lock lk(queue->mtx); + auto& items = queue->items; + + if( items.empty() ) + { + return NodeStatus::FAILURE; + } + else{ + setOutput("size", int(items.size()) ); + return NodeStatus::SUCCESS; + } + } + return NodeStatus::FAILURE; + } + + static PortsList providedPorts() + { + return { InputPort>>("queue"), + OutputPort("size")}; + } +}; + + +} + +#endif // BEHAVIORTREE_POPFROMQUEUE_HPP diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index b89141940..496adf19c 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -338,7 +338,8 @@ class BehaviorTreeFactory static_assert(default_constructable || param_constructable, "[registerNode]: the registered class must have at least one of these two " "constructors: " - " (const std::string&, const NodeConfiguration&) or (const std::string&)."); + " (const std::string&, const NodeConfiguration&) or (const std::string&).\n" + "Check also if the constructor is public!"); static_assert(!(param_constructable && !has_static_ports_list), "[registerNode]: you MUST implement the static method: " diff --git a/include/behaviortree_cpp_v3/decorators/consume_queue.h b/include/behaviortree_cpp_v3/decorators/consume_queue.h new file mode 100644 index 000000000..6f7a2b0ea --- /dev/null +++ b/include/behaviortree_cpp_v3/decorators/consume_queue.h @@ -0,0 +1,103 @@ +/* Copyright (C) 2018-2022 Davide Faconti, Eurecat - 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 BEHAVIORTREE_CONSUME_QUEUE_H +#define BEHAVIORTREE_CONSUME_QUEUE_H + +#include +#include "behaviortree_cpp_v3/decorator_node.h" +#include "behaviortree_cpp_v3/actions/pop_from_queue.hpp" + +namespace BT +{ + +/** + * Execute the child node as long as the queue is not empty. + * At each iteration, an item of type T is popped from the "queue" and + * inserted in "popped_item". + * + * An empty queue will return SUCCESS + */ +template +class ConsumeQueue : public DecoratorNode +{ + public: + ConsumeQueue(const std::string& name, const NodeConfiguration& config) + : DecoratorNode(name, config) + { + } + + NodeStatus tick() override + { + if( running_child_ ) + { + NodeStatus child_state = child_node_->executeTick(); + running_child_ = (child_state == NodeStatus::RUNNING); + if(running_child_) + { + return NodeStatus::RUNNING; + } + else{ + haltChild(); + } + } + + std::shared_ptr> queue; + if( getInput("queue", queue) && queue ) + { + std::unique_lock lk(queue->mtx); + auto& items = queue->items; + + while( !items.empty() ) + { + setStatus(NodeStatus::RUNNING); + + T val = items.front(); + items.pop_front(); + setOutput("popped_item", val); + + lk.unlock(); + NodeStatus child_state = child_node_->executeTick(); + lk.lock(); + + running_child_ = (child_state == NodeStatus::RUNNING); + if(running_child_) + { + return NodeStatus::RUNNING; + } + else + { + haltChild(); + if( child_state == NodeStatus::FAILURE ) + { + return NodeStatus::FAILURE; + } + } + } + } + + return NodeStatus::SUCCESS; + } + + static PortsList providedPorts() + { + return { InputPort>>("queue"), + OutputPort("popped_item") }; + } + private: + bool running_child_ = false; +}; + +} + +#endif // BEHAVIORTREE_CONSUME_QUEUE_H diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index add0691cd..651b00a11 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -753,7 +753,13 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, } }; - auto root_element = tree_roots[tree_ID]->FirstChildElement(); + auto it = tree_roots.find(tree_ID); + if( it == tree_roots.end() ) + { + throw std::runtime_error(std::string("Can't find a tree with name: ") + tree_ID); + } + + auto root_element = it->second->FirstChildElement(); // start recursion recursiveStep(root_parent, root_element); From a5411c978ec976f66d83b1df5aa4dd7c632a142c Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 May 2022 10:19:19 +0200 Subject: [PATCH 185/709] manual version bump --- CHANGELOG.rst | 2 +- package.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index ae89d91d1..0b4d8f2bd 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,7 +2,7 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming +3.7.0 (2022-05-23) ----------- * add netlify stuff * Event based trigger introduced diff --git a/package.xml b/package.xml index 9549df0ac..670da05e2 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.6.1 + 3.7.0 This package provides the Behavior Trees core library. From 4fa2177850cb0690e46ebb388f1db7293548bb95 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ga=C3=ABl=20=C3=89corchard?= Date: Sun, 29 May 2022 10:18:35 +0200 Subject: [PATCH 186/709] Fix destination in CMakeLists.txt (#389) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Gaël Écorchard --- CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index cd490a571..1613c9786 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -291,7 +291,7 @@ INSTALL( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ install(EXPORT ${PROJECT_NAME}Targets FILE "${PROJECT_NAME}Targets.cmake" - DESTINATION "${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}" + DESTINATION "${BEHAVIOR_TREE_LIB_DESTINATION}/cmake/${PROJECT_NAME}" NAMESPACE BT:: ) @@ -302,7 +302,7 @@ include(CMakePackageConfigHelpers) configure_package_config_file( "${CMAKE_CURRENT_SOURCE_DIR}/cmake/Config.cmake.in" "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake" - INSTALL_DESTINATION "${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}" + INSTALL_DESTINATION "${BEHAVIOR_TREE_LIB_DESTINATION}/cmake/${PROJECT_NAME}" ) # This requires to declare to project version in the project() macro @@ -317,7 +317,7 @@ install( FILES "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake" # "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake" - DESTINATION "${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}" + DESTINATION "${BEHAVIOR_TREE_LIB_DESTINATION}/cmake/${PROJECT_NAME}" ) ###################################################### From 6e2cc034717d7f0053f2b597d0c412672ea5afd7 Mon Sep 17 00:00:00 2001 From: AndyZe Date: Tue, 21 Jun 2022 09:56:29 -0500 Subject: [PATCH 187/709] Small comments on node registration (#399) --- docs/tutorial_05_subtrees.md | 9 ++++++++- examples/t05_crossdoor.cpp | 4 +++- 2 files changed, 11 insertions(+), 2 deletions(-) diff --git a/docs/tutorial_05_subtrees.md b/docs/tutorial_05_subtrees.md index bc745e33b..32c849dd7 100644 --- a/docs/tutorial_05_subtrees.md +++ b/docs/tutorial_05_subtrees.md @@ -44,7 +44,14 @@ It is also the first practical example that uses `Decorators` and `Fallback`. ``` -It may be noticed that we incapsulated a quite complex branch of the tree, +For readability, our custom nodes are registered with the one-liner: + +`CrossDoor::RegisterNodes(factory);` + +Default nodes provided by the BT library such as `Fallback` are already registered by +the BehaviorTreeFactory. + +It may be noticed that we encapsulated a quite complex branch of the tree, the one to execute when the door is closed, into a separate tree called `DoorClosed`. diff --git a/examples/t05_crossdoor.cpp b/examples/t05_crossdoor.cpp index 033e7ef3b..be9272c7d 100644 --- a/examples/t05_crossdoor.cpp +++ b/examples/t05_crossdoor.cpp @@ -61,7 +61,9 @@ int main(int argc, char** argv) { BT::BehaviorTreeFactory factory; - // register all the actions into the factory + // Register our custom nodes into the factory. + // Any default nodes provided by the BT library (such as Fallback) are registered by + // default in the BehaviorTreeFactory. CrossDoor::RegisterNodes(factory); // Important: when the object tree goes out of scope, all the TreeNodes are destroyed From 23568cb155acc62fd2f058b40322a26c000b27a6 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 21 Jun 2022 19:07:53 +0200 Subject: [PATCH 188/709] remove variables that depend on CMAKE_BINARY_DIR being set (#398) * remove variables that depend on CMAKE_BINARY_DIR being set * Update cmake.yml --- .github/workflows/cmake.yml | 2 +- CMakeLists.txt | 8 ++------ tests/CMakeLists.txt | 4 ++-- 3 files changed, 5 insertions(+), 9 deletions(-) diff --git a/.github/workflows/cmake.yml b/.github/workflows/cmake.yml index 0f318a7b7..d44669540 100644 --- a/.github/workflows/cmake.yml +++ b/.github/workflows/cmake.yml @@ -48,5 +48,5 @@ jobs: - name: run test (Linux) if: matrix.os == 'ubuntu-latest' working-directory: ${{github.workspace}}/build - run: ./bin/behaviortree_cpp_v3_test + run: ./tests/behaviortree_cpp_v3_test diff --git a/CMakeLists.txt b/CMakeLists.txt index 1613c9786..00c9f6c8c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -252,16 +252,12 @@ else() set( BEHAVIOR_TREE_INC_DESTINATION include ) set( BEHAVIOR_TREE_BIN_DESTINATION bin ) - set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${BEHAVIOR_TREE_BIN_DESTINATION}" ) - set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${BEHAVIOR_TREE_LIB_DESTINATION}" ) - set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/${BEHAVIOR_TREE_BIN_DESTINATION}" ) endif() message( STATUS "BEHAVIOR_TREE_LIB_DESTINATION: ${BEHAVIOR_TREE_LIB_DESTINATION} " ) message( STATUS "BEHAVIOR_TREE_BIN_DESTINATION: ${BEHAVIOR_TREE_BIN_DESTINATION} " ) -message( STATUS "CMAKE_RUNTIME_OUTPUT_DIRECTORY: ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} " ) -message( STATUS "CMAKE_LIBRARY_OUTPUT_DIRECTORY: ${CMAKE_LIBRARY_OUTPUT_DIRECTORY} " ) -message( STATUS "CMAKE_ARCHIVE_OUTPUT_DIRECTORY: ${CMAKE_ARCHIVE_OUTPUT_DIRECTORY} " ) +message( STATUS "BUILD_UNIT_TESTS: ${BUILD_UNIT_TESTS} " ) + ###################################################### # Samples diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 3ff5cd353..3d24f4685 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -62,8 +62,8 @@ elseif(BUILD_UNIT_TESTS) add_custom_command(TARGET ${BEHAVIOR_TREE_LIBRARY}_test POST_BUILD COMMAND ${CMAKE_COMMAND} -E copy_directory ${CMAKE_SOURCE_DIR}/tests/trees - ${CMAKE_RUNTIME_OUTPUT_DIRECTORY}/trees) + trees) - add_test(BehaviorTreeCoreTest ${CMAKE_RUNTIME_OUTPUT_DIRECTORY}/${BEHAVIOR_TREE_LIBRARY}_test) + add_test(BehaviorTreeCoreTest ${BEHAVIOR_TREE_LIBRARY}_test) endif() From aa375b7bec708030f6204dfcc1082746f40465a7 Mon Sep 17 00:00:00 2001 From: Alberto Soragna Date: Tue, 21 Jun 2022 18:13:06 +0100 Subject: [PATCH 189/709] add option to conditionally build manual selector node (#397) * add option to conditionally build manual selector node Signed-off-by: Alberto Soragna * do not fail if BUILD_MANUAL_SELECTOR is true but Curses is not found Signed-off-by: Alberto Soragna --- CMakeLists.txt | 20 ++++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 00c9f6c8c..7b165468b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,6 +23,7 @@ option(BUILD_SAMPLES "Build sample nodes" ON) option(BUILD_UNIT_TESTS "Build the unit tests" ON) option(BUILD_TOOLS "Build commandline tools" ON) option(BUILD_SHARED_LIBS "Build shared libraries" ON) +option(BUILD_MANUAL_SELECTOR "Build manual selector node" ON) option(ENABLE_COROUTINES "Enable boost coroutines" ON) #---- Include boost to add coroutines ---- @@ -166,14 +167,17 @@ list(APPEND BT_SOURCE 3rdparty/minitrace/minitrace.cpp ) -find_package(Curses QUIET) - -if(CURSES_FOUND) - list(APPEND BT_SOURCE - src/controls/manual_node.cpp - ) - list(APPEND BEHAVIOR_TREE_PUBLIC_LIBRARIES ${CURSES_LIBRARIES}) - add_definitions(-DNCURSES_FOUND) +if(BUILD_MANUAL_SELECTOR) + find_package(Curses QUIET) + if(CURSES_FOUND) + list(APPEND BT_SOURCE + src/controls/manual_node.cpp + ) + list(APPEND BEHAVIOR_TREE_PUBLIC_LIBRARIES ${CURSES_LIBRARIES}) + add_definitions(-DNCURSES_FOUND) + else() + message(WARNING "NCurses NOT found. Skipping the build of manual selector node.") + endif() endif() From f23522659282a89dbc223b6a5f623f01c87e2254 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 21 Jun 2022 19:53:37 +0200 Subject: [PATCH 190/709] Update README.md --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 529cd3fd1..a1b179090 100644 --- a/README.md +++ b/README.md @@ -1,10 +1,10 @@ ![License MIT](https://img.shields.io/github/license/BehaviorTree/BehaviorTree.CPP?color=blue) -![Version](https://img.shields.io/badge/version-3.6-blue.svg) +![Version](https://img.shields.io/badge/version-3.7-blue.svg) [![cmake](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/cmake.yml/badge.svg)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions/workflows/cmake.yml) [![ros1](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros1/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros1) [![ros2](https://github.com/BehaviorTree/BehaviorTree.CPP/workflows/ros2/badge.svg?branch=master)](https://github.com/BehaviorTree/BehaviorTree.CPP/actions?query=workflow%3Aros2) [![LGTM Grade](https://img.shields.io/lgtm/grade/cpp/github/BehaviorTree/BehaviorTree.CPP)](https://lgtm.com/projects/g/BehaviorTree/BehaviorTree.CPP/context:cpp) -[![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/BehaviorTree-ROS/Lobby?utm_source=badge&utm_medium=badge&utm_content=badge) +![Discourse topics](https://img.shields.io/discourse/topics?server=https%3A%2F%2Fdiscourse.behaviortree.dev) # BehaviorTree.CPP From 59c1a809a60d3c077301e9e5a1789334406b15a1 Mon Sep 17 00:00:00 2001 From: Jafar Date: Thu, 23 Jun 2022 20:20:34 +0300 Subject: [PATCH 191/709] Shutdown zmq context after joining the server thread and flushing (#400) --- src/loggers/bt_zmq_publisher.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/loggers/bt_zmq_publisher.cpp b/src/loggers/bt_zmq_publisher.cpp index 442e2e29b..ce9f18b2b 100644 --- a/src/loggers/bt_zmq_publisher.cpp +++ b/src/loggers/bt_zmq_publisher.cpp @@ -91,12 +91,12 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, PublisherZMQ::~PublisherZMQ() { active_server_ = false; - zmq_->context.shutdown(); if (thread_.joinable()) { thread_.join(); } flush(); + zmq_->context.shutdown(); delete zmq_; ref_count = false; } From 73835f1586947ee8c8fbdf653653a71420e8985d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 4 Jul 2022 16:40:54 +0200 Subject: [PATCH 192/709] improve writeTreeNodesModelXML --- include/behaviortree_cpp_v3/xml_parsing.h | 3 +- src/xml_parsing.cpp | 49 +++++++++++++++++------ 2 files changed, 39 insertions(+), 13 deletions(-) diff --git a/include/behaviortree_cpp_v3/xml_parsing.h b/include/behaviortree_cpp_v3/xml_parsing.h index 45b196c78..5ffeb5016 100644 --- a/include/behaviortree_cpp_v3/xml_parsing.h +++ b/include/behaviortree_cpp_v3/xml_parsing.h @@ -40,7 +40,8 @@ class XMLParser: public Parser void VerifyXML(const std::string& xml_text, const std::set ®istered_nodes); -std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory); +std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory, + bool include_builtin = false); } diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 651b00a11..383b85627 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -789,7 +789,8 @@ void XMLParser::Pimpl::getPortsRecursively(const XMLElement *element, } -std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory) +std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory, + bool include_builtin) { using namespace BT_TinyXML2; @@ -801,27 +802,51 @@ std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory) XMLElement* model_root = doc.NewElement("TreeNodesModel"); rootXML->InsertEndChild(model_root); + std::set ordered_names; + for (auto& model_it : factory.manifests()) { - const auto& registration_ID = model_it.first; - const auto& model = model_it.second; + const auto& registration_ID = model_it.first; + if( !include_builtin && + factory.builtinNodes().count( registration_ID ) != 0) + { + continue; + } + ordered_names.insert( registration_ID ); + } - if( factory.builtinNodes().count( registration_ID ) != 0) - { - continue; - } + for (auto& registration_ID : ordered_names) + { + const auto& model = factory.manifests().at(registration_ID); - if (model.type == NodeType::CONTROL) - { - continue; - } XMLElement* element = doc.NewElement( toStr(model.type).c_str() ); element->SetAttribute("ID", model.registration_ID.c_str()); - for (auto& port : model.ports) + std::vector ordered_ports; + PortDirection directions[3] = { PortDirection::INPUT, + PortDirection::OUTPUT, + PortDirection::INOUT }; + for(int d=0; d<3; d++) { + std::set port_names; + for (auto& port : model.ports) + { const auto& port_name = port.first; const auto& port_info = port.second; + if( port_info.direction() == directions[d] ) + { + port_names.insert(port_name); + } + } + for (auto& port : port_names) + { + ordered_ports.push_back(port); + } + } + + for (const auto& port_name : ordered_ports) + { + const auto& port_info = model.ports.at(port_name); XMLElement* port_element = nullptr; switch( port_info.direction() ) From 98c03c8ab87c95e767f1cb17fed4ba9ea48fb2e4 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 18 Aug 2022 01:10:56 +0200 Subject: [PATCH 193/709] documentation and doc correction --- docs/tutorial_07_multiple_xml.md | 6 +++--- include/behaviortree_cpp_v3/bt_factory.h | 20 +++++++++++++++++++- 2 files changed, 22 insertions(+), 4 deletions(-) diff --git a/docs/tutorial_07_multiple_xml.md b/docs/tutorial_07_multiple_xml.md index 91313d54a..628919531 100644 --- a/docs/tutorial_07_multiple_xml.md +++ b/docs/tutorial_07_multiple_xml.md @@ -86,9 +86,9 @@ int main() // Register the behavior tree definitions, but don't instantiate them, yet. // Order is not important. - factory.registerBehaviorTreeFromText("main_tree.xml"); - factory.registerBehaviorTreeFromText("subtree_A.xml"); - factory.registerBehaviorTreeFromText("subtree_B.xml"); + factory.registerBehaviorTreeFromFile("main_tree.xml"); + factory.registerBehaviorTreeFromFile("subtree_A.xml"); + factory.registerBehaviorTreeFromFile("subtree_B.xml"); //Check that the BTs have been registered correctly std::cout << "Registered BehaviorTrees:" << std::endl; diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index 496adf19c..81cd030df 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -235,7 +235,11 @@ class BehaviorTreeFactory /// Remove a registered ID. bool unregisterBuilder(const std::string& ID); - /// The most generic way to register your own builder. + /** The most generic way to register a NodeBuilder. + * + * Throws if you try to register twice a builder with the same + * registration_ID. + */ void registerBuilder(const TreeNodeManifest& manifest, const NodeBuilder& builder); template @@ -293,10 +297,24 @@ class BehaviorTreeFactory */ void registerFromROSPlugins(); + /** + * @brief registerBehaviorTreeFromFile. + * Load the definition of an entire behavior tree, but don't instantiate it. + * You can instantiate it later with: + * + * BehaviorTreeFactory::createTree(tree_id) + * + * where "tree_id" come from the XML attribute + * + */ void registerBehaviorTreeFromFile(const std::string& filename); + /// Same of registerBehaviorTreeFromFile, but passing the XML text, + /// instead of the filename. void registerBehaviorTreeFromText(const std::string& xml_text); + /// Returns the ID of the trees registered either with + /// registerBehaviorTreeFromFile or registerBehaviorTreeFromText. std::vector registeredBehaviorTrees() const; /** From bf0c888cdff547960294b0c477b5d61a0484509a Mon Sep 17 00:00:00 2001 From: Tim Clephas Date: Thu, 18 Aug 2022 01:12:31 +0200 Subject: [PATCH 194/709] Example suggests it's not restricted to a few (#414) * Example suggests it's not restricted to a few * Update delay_node.h Fix flow of sentence, milliseconds is already put in specification. --- include/behaviortree_cpp_v3/decorators/delay_node.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/delay_node.h b/include/behaviortree_cpp_v3/decorators/delay_node.h index 39cd1fd51..2fb85e85b 100644 --- a/include/behaviortree_cpp_v3/decorators/delay_node.h +++ b/include/behaviortree_cpp_v3/decorators/delay_node.h @@ -8,9 +8,8 @@ namespace BT { /** - * @brief The delay node will introduce a delay of a few milliseconds - * and then tick the child returning the status of the child as it is - * upon completion + * @brief The delay node will introduce a delay and then tick the + * child returning the status of the child as it is upon completion * The delay is in milliseconds and it is passed using the port "delay_msec". * * During the delay the node changes status to RUNNING From 8a8ec27099de69230830ce06c73c00dcfc4564be Mon Sep 17 00:00:00 2001 From: Luca Bonamini Date: Thu, 18 Aug 2022 01:13:07 +0200 Subject: [PATCH 195/709] fix(README): change find_package() instruction for BT external usage (#401) Co-authored-by: Luca Bonamini --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index a1b179090..72eac0269 100644 --- a/README.md +++ b/README.md @@ -115,7 +115,7 @@ project(hello_BT) set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) -find_package(BehaviorTreeV3) +find_package(behaviortree_cpp_v3) add_executable(${PROJECT_NAME} "hello_BT.cpp") target_link_libraries(${PROJECT_NAME} BT::behaviortree_cpp_v3) From b8fd0b2443f1171365b693387b9e4e3155384c3b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 17 Aug 2022 17:15:30 -0600 Subject: [PATCH 196/709] Adding the reserved word "_description" (#394) --- include/behaviortree_cpp_v3/basic_types.h | 17 ++++++-- include/behaviortree_cpp_v3/bt_factory.h | 4 ++ include/behaviortree_cpp_v3/tree_node.h | 1 + src/bt_factory.cpp | 10 +++++ src/xml_parsing.cpp | 26 ++++++------ tests/gtest_ports.cpp | 48 +++++++++++++++++++++++ 6 files changed, 91 insertions(+), 15 deletions(-) diff --git a/include/behaviortree_cpp_v3/basic_types.h b/include/behaviortree_cpp_v3/basic_types.h index 0f301bd9a..8d87c117c 100644 --- a/include/behaviortree_cpp_v3/basic_types.h +++ b/include/behaviortree_cpp_v3/basic_types.h @@ -209,6 +209,12 @@ template using Optional = nonstd::expected; * */ using Result = Optional; + +const std::unordered_set ReservedPortNames = +{ + "ID", "name", "_description" +}; + class PortInfo { @@ -261,15 +267,20 @@ std::pair CreatePort(PortDirection direction, StringView name, StringView description = {}) { + auto sname = static_cast(name); + if( ReservedPortNames.count(sname) != 0 ) + { + throw std::runtime_error("A port can not use a reserved name. See ReservedPortNames"); + } + std::pair out; if( std::is_same::value) { - out = {static_cast(name), PortInfo(direction) }; + out = {sname, PortInfo(direction) }; } else{ - out = {static_cast(name), PortInfo(direction, typeid(T), - GetAnyFromStringFunctor() ) }; + out = {sname, PortInfo(direction, typeid(T), GetAnyFromStringFunctor() ) }; } if( !description.empty() ) { diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index 81cd030df..09a1c782f 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -425,6 +425,10 @@ class BehaviorTreeFactory Tree createTree(const std::string& tree_name, Blackboard::Ptr blackboard = Blackboard::create()); + /// Add a description to a specific manifest. This description will be added + /// to with the function writeTreeNodesModelXML() + void addDescriptionToManifest(const std::string& node_id, const std::string& description ); + private: std::unordered_map builders_; std::unordered_map manifests_; diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index 09156ea84..5c6d74542 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -35,6 +35,7 @@ struct TreeNodeManifest NodeType type; std::string registration_ID; PortsList ports; + std::string description; }; typedef std::unordered_map PortsRemapping; diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index fc2f48cd4..21cde3184 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -294,6 +294,16 @@ Tree BehaviorTreeFactory::createTree(const std::string &tree_name, Blackboard::P return tree; } +void BehaviorTreeFactory::addDescriptionToManifest(const std::string &node_id, const std::string &description) +{ + auto it = manifests_.find(node_id); + if( it == manifests_.end() ) + { + throw std::runtime_error("addDescriptionToManifest: wrong ID"); + } + it->second.description = description; +} + void Tree::sleep(std::chrono::system_clock::duration timeout) { wake_up_->waitFor(timeout); diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 383b85627..758105c69 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -516,7 +516,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, for (const XMLAttribute* att = element->FirstAttribute(); att; att = att->Next()) { const std::string attribute_name = att->Name(); - if (attribute_name != "ID" && attribute_name != "name") + if ( ReservedPortNames.count(attribute_name) == 0 ) { port_remap[attribute_name] = att->Value(); } @@ -661,10 +661,10 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) { - if( strcmp(attr->Name(), "__shared_blackboard") == 0 && - convertFromString(attr->Value()) == true ) + if( StrEqual(attr->Name(), "__shared_blackboard") ) { - is_isolated = false; + is_isolated = !convertFromString(attr->Value()); + break; } } @@ -678,11 +678,10 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) { - if( strcmp(attr->Name(), "ID") == 0 ) + if( ReservedPortNames.count(attr->Name()) == 0 ) { - continue; + new_bb->addSubtreeRemapping( attr->Name(), attr->Value() ); } - new_bb->addSubtreeRemapping( attr->Name(), attr->Value() ); } output_tree.blackboard_stack.emplace_back(new_bb); recursivelyCreateTree( node->name(), output_tree, new_bb, node ); @@ -701,7 +700,7 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, const char* attr_name = attr->Name(); const char* attr_value = attr->Value(); - if( StrEqual(attr_name, "ID") ) + if( ReservedPortNames.count(attr->Name()) != 0 ) { continue; } @@ -772,9 +771,8 @@ void XMLParser::Pimpl::getPortsRecursively(const XMLElement *element, { const char* attr_name = attr->Name(); const char* attr_value = attr->Value(); - if( !StrEqual(attr_name, "ID") && - !StrEqual(attr_name, "name") && - TreeNode::isBlackboardPointer(attr_value) ) + if( ReservedPortNames.count(attr_name) == 0 && + TreeNode::isBlackboardPointer(attr_value) ) { auto port_name = TreeNode::stripBlackboardPointer(attr_value); output_ports.push_back( static_cast(port_name) ); @@ -870,10 +868,14 @@ std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory, { port_element->SetText( port_info.description().c_str() ); } - element->InsertEndChild(port_element); } + if(!model.description.empty()) + { + element->SetAttribute("description", model.registration_ID.c_str()); + } + model_root->InsertEndChild(element); } diff --git a/tests/gtest_ports.cpp b/tests/gtest_ports.cpp index c0a86acfd..29e98b1ac 100644 --- a/tests/gtest_ports.cpp +++ b/tests/gtest_ports.cpp @@ -50,6 +50,32 @@ TEST(PortTest, DefaultPorts) ASSERT_EQ( status, NodeStatus::SUCCESS ); } +TEST(PortTest, Descriptions) +{ + std::string xml_txt = R"( + + + + + + + + + + + + + )"; + + BehaviorTreeFactory factory; + factory.registerNodeType("NodeWithPorts"); + + auto tree = factory.createTreeFromText(xml_txt); + + NodeStatus status = tree.tickRoot(); + ASSERT_EQ( status, NodeStatus::FAILURE ); // failure because in_port_B="99" +} + struct MyType { std::string value; @@ -126,3 +152,25 @@ TEST(PortTest, EmptyPort) ASSERT_EQ( status, NodeStatus::FAILURE ); } + +class IllegalPorts: public SyncActionNode +{ + public: + IllegalPorts(const std::string & name, const NodeConfiguration & config) + : SyncActionNode(name, config) + { } + + NodeStatus tick() { return NodeStatus::SUCCESS; } + + static PortsList providedPorts() + { + return { BT::InputPort("name") }; + } +}; + +TEST(PortTest, IllegalPorts) +{ + BehaviorTreeFactory factory; + ASSERT_ANY_THROW(factory.registerNodeType("nope")); +} + From a363bdcae88350bc748598a7d2950e300859469c Mon Sep 17 00:00:00 2001 From: Will <1305536+zflat@users.noreply.github.com> Date: Wed, 17 Aug 2022 19:19:08 -0400 Subject: [PATCH 197/709] threshold child count dynamically in parallel control node (#363) --- .../controls/parallel_node.h | 8 +- src/controls/parallel_node.cpp | 25 +++--- tests/gtest_parallel.cpp | 80 +++++++++++++++++++ 3 files changed, 100 insertions(+), 13 deletions(-) diff --git a/include/behaviortree_cpp_v3/controls/parallel_node.h b/include/behaviortree_cpp_v3/controls/parallel_node.h index b5a5ffb72..c7c73f8eb 100644 --- a/include/behaviortree_cpp_v3/controls/parallel_node.h +++ b/include/behaviortree_cpp_v3/controls/parallel_node.h @@ -41,12 +41,12 @@ class ParallelNode : public ControlNode unsigned int thresholdM(); unsigned int thresholdFM(); - void setThresholdM(unsigned int threshold_M); - void setThresholdFM(unsigned int threshold_M); + void setThresholdM(int threshold_M); + void setThresholdFM(int threshold_M); private: - unsigned int success_threshold_; - unsigned int failure_threshold_; + int success_threshold_; + int failure_threshold_; std::set skip_list_; diff --git a/src/controls/parallel_node.cpp b/src/controls/parallel_node.cpp index 18ff9e7f6..090c7d0cb 100644 --- a/src/controls/parallel_node.cpp +++ b/src/controls/parallel_node.cpp @@ -11,6 +11,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 +#include + #include "behaviortree_cpp_v3/controls/parallel_node.h" namespace BT @@ -58,12 +61,12 @@ NodeStatus ParallelNode::tick() const size_t children_count = children_nodes_.size(); - if( children_count < success_threshold_) + if( children_count < thresholdM()) { throw LogicError("Number of children is less than threshold. Can never succeed."); } - if( children_count < failure_threshold_) + if( children_count < thresholdFM()) { throw LogicError("Number of children is less than threshold. Can never fail."); } @@ -94,7 +97,7 @@ NodeStatus ParallelNode::tick() } success_childred_num++; - if (success_childred_num == success_threshold_) + if (success_childred_num == thresholdM()) { skip_list_.clear(); haltChildren(); @@ -112,8 +115,8 @@ NodeStatus ParallelNode::tick() // It fails if it is not possible to succeed anymore or if // number of failures are equal to failure_threshold_ - if ((failure_childred_num > children_count - success_threshold_) - || (failure_childred_num == failure_threshold_)) + if ((failure_childred_num > children_count - thresholdM()) + || (failure_childred_num == thresholdFM())) { skip_list_.clear(); haltChildren(); @@ -144,20 +147,24 @@ void ParallelNode::halt() unsigned int ParallelNode::thresholdM() { - return success_threshold_; + return success_threshold_ < 0 + ? std::max(children_nodes_.size() + success_threshold_ + 1, static_cast(0)) + : success_threshold_; } unsigned int ParallelNode::thresholdFM() { - return failure_threshold_; + return failure_threshold_ < 0 + ? std::max(children_nodes_.size() + failure_threshold_ + 1, static_cast(0)) + : failure_threshold_; } -void ParallelNode::setThresholdM(unsigned int threshold_M) +void ParallelNode::setThresholdM(int threshold_M) { success_threshold_ = threshold_M; } -void ParallelNode::setThresholdFM(unsigned int threshold_M) +void ParallelNode::setThresholdFM(int threshold_M) { failure_threshold_ = threshold_M; } diff --git a/tests/gtest_parallel.cpp b/tests/gtest_parallel.cpp index 08f79f8fe..06375d091 100644 --- a/tests/gtest_parallel.cpp +++ b/tests/gtest_parallel.cpp @@ -145,6 +145,85 @@ TEST_F(SimpleParallelTest, Threshold_3) ASSERT_EQ(NodeStatus::SUCCESS, state); } +TEST_F(SimpleParallelTest, Threshold_neg2) +{ + root.setThresholdM(-2); + action_1.setTime( milliseconds(100) ); + action_2.setTime( milliseconds(500) ); // this takes a lot of time + + BT::NodeStatus state = root.executeTick(); + // first tick, zero wait + ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status()); + ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for( milliseconds(150) ); + state = root.executeTick(); + // second tick: action1 should be completed, but not action2 + // nevertheless it is sufficient because threshold is 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::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); +} + + +TEST_F(SimpleParallelTest, Threshold_neg1) +{ + root.setThresholdM(-1); + action_1.setTime( milliseconds(100) ); + action_2.setTime( milliseconds(500) ); // this takes a lot of time + + BT::NodeStatus state = root.executeTick(); + // first tick, zero wait + ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status()); + ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for( milliseconds(150) ); + state = root.executeTick(); + // second tick: action1 should be completed, but not action2 + ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status()); + ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for( milliseconds(650) ); + state = root.executeTick(); + // third tick: all actions completed + 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); +} + + +TEST_F(SimpleParallelTest, Threshold_thresholdFneg1) +{ + root.setThresholdM(1); + root.setThresholdFM(-1); + action_1.setTime( milliseconds(100) ); + action_1.setExpectedResult(NodeStatus::FAILURE); + condition_1.setExpectedResult(NodeStatus::FAILURE); + action_2.setTime( milliseconds(200) ); + condition_2.setExpectedResult(NodeStatus::FAILURE); + action_2.setExpectedResult(NodeStatus::FAILURE); + + BT::NodeStatus state = root.executeTick(); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(milliseconds(250)); + state = root.executeTick(); + ASSERT_EQ(NodeStatus::FAILURE, state); +} + TEST_F(SimpleParallelTest, Threshold_2) { root.setThresholdM(2); @@ -271,6 +350,7 @@ TEST_F(ComplexParallelTest, ConditionRightFalse_thresholdF_2) ASSERT_EQ(NodeStatus::SUCCESS, state); } + TEST_F(ComplexParallelTest, ConditionRightFalseAction1Done) { condition_R.setExpectedResult(NodeStatus::FAILURE); From ce6503a559844f716c7ca86ae6897340927ddf6c Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 18 Aug 2022 01:33:16 +0200 Subject: [PATCH 198/709] parallel node fix --- .../controls/parallel_node.h | 37 +++++++++++++++---- src/controls/parallel_node.cpp | 26 ++++++------- 2 files changed, 42 insertions(+), 21 deletions(-) diff --git a/include/behaviortree_cpp_v3/controls/parallel_node.h b/include/behaviortree_cpp_v3/controls/parallel_node.h index c7c73f8eb..1d81ab616 100644 --- a/include/behaviortree_cpp_v3/controls/parallel_node.h +++ b/include/behaviortree_cpp_v3/controls/parallel_node.h @@ -20,29 +20,50 @@ namespace BT { +/** + * @brief The ParallelNode execute all its children + * __concurrently__, but not in separate threads! + * + * Even if this may look similar to ReactiveSequence, + * this Control Node is the only one that may have + * multiple children in the RUNNING state at the same time. + * + * The Node is completed either when the THRESHOLD_SUCCESS + * or THRESHOLD_FAILURE number is reached (both configured using ports). + * + * If any of the threahold is reached, and other childen are still running, + * they will be halted. + * + * Note that threshold indexes work as in Python: + * https://www.i2tutorials.com/what-are-negative-indexes-and-why-are-they-used/ + * + * Therefore -1 is equivalent to the number of children. + */ class ParallelNode : public ControlNode { public: - ParallelNode(const std::string& name, unsigned success_threshold, - unsigned failure_threshold = 1); + ParallelNode(const std::string& name, int success_threshold, + int failure_threshold = 1); ParallelNode(const std::string& name, const NodeConfiguration& config); static PortsList providedPorts() { - return { InputPort(THRESHOLD_SUCCESS, "number of childen which need to succeed to trigger a SUCCESS" ), - InputPort(THRESHOLD_FAILURE, 1, "number of childen which need to fail to trigger a FAILURE" ) }; + return { InputPort(THRESHOLD_SUCCESS, + "number of childen which need to succeed to trigger a SUCCESS" ), + InputPort(THRESHOLD_FAILURE, 1, + "number of childen which need to fail to trigger a FAILURE" ) }; } ~ParallelNode() = default; virtual void halt() override; - unsigned int thresholdM(); - unsigned int thresholdFM(); - void setThresholdM(int threshold_M); - void setThresholdFM(int threshold_M); + size_t successThreshold() const; + size_t failureThreshold() const; + void setSuccessThreshold(int threshold_M); + void setFailureThreshold(int threshold_M); private: int success_threshold_; diff --git a/src/controls/parallel_node.cpp b/src/controls/parallel_node.cpp index 090c7d0cb..8ff1c7eb8 100644 --- a/src/controls/parallel_node.cpp +++ b/src/controls/parallel_node.cpp @@ -22,8 +22,8 @@ namespace BT constexpr const char* ParallelNode::THRESHOLD_FAILURE; constexpr const char* ParallelNode::THRESHOLD_SUCCESS; -ParallelNode::ParallelNode(const std::string& name, unsigned success_threshold, - unsigned failure_threshold) +ParallelNode::ParallelNode(const std::string& name, int success_threshold, + int failure_threshold) : ControlNode::ControlNode(name, {} ), success_threshold_(success_threshold), failure_threshold_(failure_threshold), @@ -61,12 +61,12 @@ NodeStatus ParallelNode::tick() const size_t children_count = children_nodes_.size(); - if( children_count < thresholdM()) + if( children_count < successThreshold()) { throw LogicError("Number of children is less than threshold. Can never succeed."); } - if( children_count < thresholdFM()) + if( children_count < failureThreshold()) { throw LogicError("Number of children is less than threshold. Can never fail."); } @@ -97,7 +97,7 @@ NodeStatus ParallelNode::tick() } success_childred_num++; - if (success_childred_num == thresholdM()) + if (success_childred_num == successThreshold()) { skip_list_.clear(); haltChildren(); @@ -115,8 +115,8 @@ NodeStatus ParallelNode::tick() // It fails if it is not possible to succeed anymore or if // number of failures are equal to failure_threshold_ - if ((failure_childred_num > children_count - thresholdM()) - || (failure_childred_num == thresholdFM())) + if ((failure_childred_num > children_count - successThreshold()) + || (failure_childred_num == failureThreshold())) { skip_list_.clear(); haltChildren(); @@ -145,26 +145,26 @@ void ParallelNode::halt() ControlNode::halt(); } -unsigned int ParallelNode::thresholdM() +size_t ParallelNode::successThreshold() const { return success_threshold_ < 0 - ? std::max(children_nodes_.size() + success_threshold_ + 1, static_cast(0)) + ? std::max(children_nodes_.size() + success_threshold_ + 1, size_t(0)) : success_threshold_; } -unsigned int ParallelNode::thresholdFM() +size_t ParallelNode::failureThreshold() const { return failure_threshold_ < 0 - ? std::max(children_nodes_.size() + failure_threshold_ + 1, static_cast(0)) + ? std::max(children_nodes_.size() + failure_threshold_ + 1, size_t(0)) : failure_threshold_; } -void ParallelNode::setThresholdM(int threshold_M) +void ParallelNode::setSuccessThreshold(int threshold_M) { success_threshold_ = threshold_M; } -void ParallelNode::setThresholdFM(int threshold_M) +void ParallelNode::setFailureThreshold(int threshold_M) { failure_threshold_ = threshold_M; } From ef68cf1c2e9f30ad63e7e5f5fe4b10fe215db6a2 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 18 Aug 2022 21:59:40 +0200 Subject: [PATCH 199/709] fix test --- tests/gtest_parallel.cpp | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/tests/gtest_parallel.cpp b/tests/gtest_parallel.cpp index 06375d091..897d3f34e 100644 --- a/tests/gtest_parallel.cpp +++ b/tests/gtest_parallel.cpp @@ -122,7 +122,7 @@ TEST_F(SimpleParallelTest, ConditionsTrue) TEST_F(SimpleParallelTest, Threshold_3) { - root.setThresholdM(3); + root.setSuccessThreshold(3); action_1.setTime( milliseconds(100) ); action_2.setTime( milliseconds(500) ); // this takes a lot of time @@ -147,7 +147,7 @@ TEST_F(SimpleParallelTest, Threshold_3) TEST_F(SimpleParallelTest, Threshold_neg2) { - root.setThresholdM(-2); + root.setSuccessThreshold(-2); action_1.setTime( milliseconds(100) ); action_2.setTime( milliseconds(500) ); // this takes a lot of time @@ -173,7 +173,7 @@ TEST_F(SimpleParallelTest, Threshold_neg2) TEST_F(SimpleParallelTest, Threshold_neg1) { - root.setThresholdM(-1); + root.setSuccessThreshold(-1); action_1.setTime( milliseconds(100) ); action_2.setTime( milliseconds(500) ); // this takes a lot of time @@ -207,8 +207,8 @@ TEST_F(SimpleParallelTest, Threshold_neg1) TEST_F(SimpleParallelTest, Threshold_thresholdFneg1) { - root.setThresholdM(1); - root.setThresholdFM(-1); + root.setSuccessThreshold(1); + root.setFailureThreshold(-1); action_1.setTime( milliseconds(100) ); action_1.setExpectedResult(NodeStatus::FAILURE); condition_1.setExpectedResult(NodeStatus::FAILURE); @@ -226,7 +226,7 @@ TEST_F(SimpleParallelTest, Threshold_thresholdFneg1) TEST_F(SimpleParallelTest, Threshold_2) { - root.setThresholdM(2); + root.setSuccessThreshold(2); BT::NodeStatus state = root.executeTick(); ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); @@ -270,8 +270,8 @@ TEST_F(ComplexParallelTest, ConditionsTrue) TEST_F(ComplexParallelTest, ConditionsLeftFalse) { - parallel_left.setThresholdFM(3); - parallel_left.setThresholdM(3); + parallel_left.setFailureThreshold(3); + parallel_left.setSuccessThreshold(3); condition_L1.setExpectedResult(NodeStatus::FAILURE); condition_L2.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = parallel_root.executeTick(); @@ -315,7 +315,7 @@ TEST_F(ComplexParallelTest, ConditionRightFalse) TEST_F(ComplexParallelTest, ConditionRightFalse_thresholdF_2) { - parallel_right.setThresholdFM(2); + parallel_right.setFailureThreshold(2); condition_R.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = parallel_root.executeTick(); @@ -355,8 +355,8 @@ TEST_F(ComplexParallelTest, ConditionRightFalseAction1Done) { condition_R.setExpectedResult(NodeStatus::FAILURE); - parallel_right.setThresholdFM(2); - parallel_left.setThresholdM(4); + parallel_right.setFailureThreshold(2); + parallel_left.setSuccessThreshold(4); BT::NodeStatus state = parallel_root.executeTick(); std::this_thread::sleep_for(milliseconds(300)); From 8f7d0e27204d2a8f307eee7cd55d0a4c76d2779d Mon Sep 17 00:00:00 2001 From: Dennis Date: Tue, 13 Sep 2022 16:29:52 +0200 Subject: [PATCH 200/709] Update expected-lite to 0.6.2 (#418) --- .../behaviortree_cpp_v3/utils/expected.hpp | 1561 +++++++++++------ 1 file changed, 1062 insertions(+), 499 deletions(-) diff --git a/include/behaviortree_cpp_v3/utils/expected.hpp b/include/behaviortree_cpp_v3/utils/expected.hpp index 65e089ca4..f2b7f9402 100644 --- a/include/behaviortree_cpp_v3/utils/expected.hpp +++ b/include/behaviortree_cpp_v3/utils/expected.hpp @@ -1,6 +1,6 @@ // This version targets C++11 and later. // -// Copyright (C) 2016-2018 Martin Moene. +// Copyright (C) 2016-2020 Martin Moene. // // 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) @@ -13,8 +13,8 @@ #define NONSTD_EXPECTED_LITE_HPP #define expected_lite_MAJOR 0 -#define expected_lite_MINOR 2 -#define expected_lite_PATCH 0 +#define expected_lite_MINOR 6 +#define expected_lite_PATCH 2 #define expected_lite_VERSION expected_STRINGIFY(expected_lite_MAJOR) "." expected_STRINGIFY(expected_lite_MINOR) "." expected_STRINGIFY(expected_lite_PATCH) @@ -27,6 +27,20 @@ #define nsel_EXPECTED_NONSTD 1 #define nsel_EXPECTED_STD 2 +// tweak header support: + +#ifdef __has_include +# if __has_include() +# include +# endif +#define expected_HAVE_TWEAK_HEADER 1 +#else +#define expected_HAVE_TWEAK_HEADER 0 +//# pragma message("expected.hpp: Note: Tweak header not supported.") +#endif + +// expected selection and configuration: + #if !defined( nsel_CONFIG_SELECT_EXPECTED ) # define nsel_CONFIG_SELECT_EXPECTED ( nsel_HAVE_STD_EXPECTED ? nsel_EXPECTED_STD : nsel_EXPECTED_NONSTD ) #endif @@ -42,17 +56,36 @@ // P0323R2: 2 (2017-06-15) // P0323R3: 3 (2017-10-15) // P0323R4: 4 (2017-11-26) -// P0323R5: 5 (2018-02-08) * +// P0323R5: 5 (2018-02-08) // P0323R6: 6 (2018-04-02) -// P0323R7: 7 (2018-06-22) +// P0323R7: 7 (2018-06-22) * // // expected-lite uses 2 and higher #ifndef nsel_P0323R -# define nsel_P0323R 5 +# define nsel_P0323R 7 +#endif + +// Control presence of C++ exception handling (try and auto discover): + +#ifndef nsel_CONFIG_NO_EXCEPTIONS +# if defined(_MSC_VER) +# include // for _HAS_EXCEPTIONS +# endif +# if defined(__cpp_exceptions) || defined(__EXCEPTIONS) || (_HAS_EXCEPTIONS) +# define nsel_CONFIG_NO_EXCEPTIONS 0 +# else +# define nsel_CONFIG_NO_EXCEPTIONS 1 +# endif #endif -// C++ language version detection (C++20 is speculative): +// at default use SEH with MSVC for no C++ exceptions + +#ifndef nsel_CONFIG_NO_EXCEPTIONS_SEH +# define nsel_CONFIG_NO_EXCEPTIONS_SEH ( nsel_CONFIG_NO_EXCEPTIONS && _MSC_VER ) +#endif + +// C++ language version detection (C++23 is speculative): // Note: VC14.0/1900 (VS2015) lacks too much from C++14. #ifndef nsel_CPLUSPLUS @@ -67,11 +100,12 @@ #define nsel_CPP11_OR_GREATER ( nsel_CPLUSPLUS >= 201103L ) #define nsel_CPP14_OR_GREATER ( nsel_CPLUSPLUS >= 201402L ) #define nsel_CPP17_OR_GREATER ( nsel_CPLUSPLUS >= 201703L ) -#define nsel_CPP20_OR_GREATER ( nsel_CPLUSPLUS >= 202000L ) +#define nsel_CPP20_OR_GREATER ( nsel_CPLUSPLUS >= 202002L ) +#define nsel_CPP23_OR_GREATER ( nsel_CPLUSPLUS >= 202300L ) -// Use C++20 std::expected if available and requested: +// Use C++23 std::expected if available and requested: -#if nsel_CPP20_OR_GREATER && defined(__has_include ) +#if nsel_CPP23_OR_GREATER && defined(__has_include ) # if __has_include( ) # define nsel_HAVE_STD_EXPECTED 1 # else @@ -84,7 +118,7 @@ #define nsel_USES_STD_EXPECTED ( (nsel_CONFIG_SELECT_EXPECTED == nsel_EXPECTED_STD) || ((nsel_CONFIG_SELECT_EXPECTED == nsel_EXPECTED_DEFAULT) && nsel_HAVE_STD_EXPECTED) ) // -// in_place: code duplicated in any-lite, expected-lite, optional-lite, value-ptr-lite, variant-lite: +// in_place: code duplicated in any-lite, expected-lite, expected-lite, value-ptr-lite, variant-lite: // #ifndef nonstd_lite_HAVE_IN_PLACE_TYPES @@ -191,12 +225,26 @@ namespace nonstd { #include #include #include +#include #include -#include #include #include #include +// additional includes: + +#if nsel_CONFIG_NO_EXCEPTIONS +# if nsel_CONFIG_NO_EXCEPTIONS_SEH +# include // for ExceptionCodes +# else +// already included: +# endif +#else +# include +#endif + +// C++ feature usage: + #if nsel_CPP11_OR_GREATER # define nsel_constexpr constexpr #else @@ -215,32 +263,19 @@ namespace nonstd { # define nsel_inline17 /*inline*/ #endif -// Method enabling - -#define nsel_REQUIRES_A(...) \ - , typename std::enable_if<__VA_ARGS__, void*>::type = nullptr - -#define nsel_REQUIRES_0(...) \ - template< bool B = (__VA_ARGS__), typename std::enable_if::type = 0 > - -#define nsel_REQUIRES_R(R, ...) \ - typename std::enable_if<__VA_ARGS__, R>::type - -#define nsel_REQUIRES_T(...) \ - , typename = typename std::enable_if< (__VA_ARGS__), nonstd::expected_lite::detail::enabler >::type - // Compiler versions: // -// MSVC++ 6.0 _MSC_VER == 1200 (Visual Studio 6.0) -// MSVC++ 7.0 _MSC_VER == 1300 (Visual Studio .NET 2002) -// MSVC++ 7.1 _MSC_VER == 1310 (Visual Studio .NET 2003) -// MSVC++ 8.0 _MSC_VER == 1400 (Visual Studio 2005) -// MSVC++ 9.0 _MSC_VER == 1500 (Visual Studio 2008) -// MSVC++ 10.0 _MSC_VER == 1600 (Visual Studio 2010) -// MSVC++ 11.0 _MSC_VER == 1700 (Visual Studio 2012) -// MSVC++ 12.0 _MSC_VER == 1800 (Visual Studio 2013) -// MSVC++ 14.0 _MSC_VER == 1900 (Visual Studio 2015) -// MSVC++ 14.1 _MSC_VER >= 1910 (Visual Studio 2017) +// MSVC++ 6.0 _MSC_VER == 1200 nsel_COMPILER_MSVC_VERSION == 60 (Visual Studio 6.0) +// MSVC++ 7.0 _MSC_VER == 1300 nsel_COMPILER_MSVC_VERSION == 70 (Visual Studio .NET 2002) +// MSVC++ 7.1 _MSC_VER == 1310 nsel_COMPILER_MSVC_VERSION == 71 (Visual Studio .NET 2003) +// MSVC++ 8.0 _MSC_VER == 1400 nsel_COMPILER_MSVC_VERSION == 80 (Visual Studio 2005) +// MSVC++ 9.0 _MSC_VER == 1500 nsel_COMPILER_MSVC_VERSION == 90 (Visual Studio 2008) +// MSVC++ 10.0 _MSC_VER == 1600 nsel_COMPILER_MSVC_VERSION == 100 (Visual Studio 2010) +// MSVC++ 11.0 _MSC_VER == 1700 nsel_COMPILER_MSVC_VERSION == 110 (Visual Studio 2012) +// MSVC++ 12.0 _MSC_VER == 1800 nsel_COMPILER_MSVC_VERSION == 120 (Visual Studio 2013) +// MSVC++ 14.0 _MSC_VER == 1900 nsel_COMPILER_MSVC_VERSION == 140 (Visual Studio 2015) +// MSVC++ 14.1 _MSC_VER >= 1910 nsel_COMPILER_MSVC_VERSION == 141 (Visual Studio 2017) +// MSVC++ 14.2 _MSC_VER >= 1920 nsel_COMPILER_MSVC_VERSION == 142 (Visual Studio 2019) #if defined(_MSC_VER) && !defined(__clang__) # define nsel_COMPILER_MSVC_VER (_MSC_VER ) @@ -267,6 +302,20 @@ namespace nonstd { // half-open range [lo..hi): //#define nsel_BETWEEN( v, lo, hi ) ( (lo) <= (v) && (v) < (hi) ) +// Method enabling + +#define nsel_REQUIRES_0(...) \ + template< bool B = (__VA_ARGS__), typename std::enable_if::type = 0 > + +#define nsel_REQUIRES_T(...) \ + , typename std::enable_if< (__VA_ARGS__), int >::type = 0 + +#define nsel_REQUIRES_R(R, ...) \ + typename std::enable_if< (__VA_ARGS__), R>::type + +#define nsel_REQUIRES_A(...) \ + , typename std::enable_if< (__VA_ARGS__), void*>::type = nullptr + // Presence of language and library features: #ifdef _HAS_CPP0X @@ -313,16 +362,87 @@ nsel_DISABLE_MSVC_WARNINGS( 26409 ) namespace nonstd { namespace expected_lite { -namespace std20 { +// type traits C++17: + +namespace std17 { + +#if nsel_CPP17_OR_GREATER + +using std::conjunction; +using std::is_swappable; +using std::is_nothrow_swappable; + +#else // nsel_CPP17_OR_GREATER + +namespace detail { + +using std::swap; + +struct is_swappable +{ + template< typename T, typename = decltype( swap( std::declval(), std::declval() ) ) > + static std::true_type test( int /* unused */); + + template< typename > + static std::false_type test(...); +}; + +struct is_nothrow_swappable +{ + // wrap noexcept(expr) in separate function as work-around for VC140 (VS2015): + + template< typename T > + static constexpr bool satisfies() + { + return noexcept( swap( std::declval(), std::declval() ) ); + } + + template< typename T > + static auto test( int ) -> std::integral_constant()>{} + + template< typename > + static auto test(...) -> std::false_type; +}; +} // namespace detail + +// is [nothow] swappable: + +template< typename T > +struct is_swappable : decltype( detail::is_swappable::test(0) ){}; + +template< typename T > +struct is_nothrow_swappable : decltype( detail::is_nothrow_swappable::test(0) ){}; + +// conjunction: + +template< typename... > struct conjunction : std::true_type{}; +template< typename B1 > struct conjunction : B1{}; + +template< typename B1, typename... Bn > +struct conjunction : std::conditional, B1>::type{}; + +#endif // nsel_CPP17_OR_GREATER + +} // namespace std17 // type traits C++20: +namespace std20 { + +#if defined(__cpp_lib_remove_cvref) + +using std::remove_cvref; + +#else + template< typename T > struct remove_cvref { typedef typename std::remove_cv< typename std::remove_reference::type >::type type; }; +#endif + } // namespace std20 // forward declaration: @@ -332,29 +452,45 @@ class expected; namespace detail { -/// for nsel_REQUIRES_T - -enum class enabler{}; - /// discriminated union to hold value or 'error'. template< typename T, typename E > -union storage_t +class storage_t_impl { - friend class expected; + template< typename, typename > friend class nonstd::expected_lite::expected; -private: +public: using value_type = T; using error_type = E; // no-op construction - storage_t() {} - ~storage_t() {} + storage_t_impl() {} + ~storage_t_impl() {} + + explicit storage_t_impl( bool has_value ) + : m_has_value( has_value ) + {} + + void construct_value( value_type const & e ) + { + new( &m_value ) value_type( e ); + } - template - void construct_value(Args&& ...args) + void construct_value( value_type && e ) { - new(&m_value) value_type(std::forward(args)...); + new( &m_value ) value_type( std::move( e ) ); + } + + template< class... Args > + void emplace_value( Args&&... args ) + { + new( &m_value ) value_type( std::forward(args)...); + } + + template< class U, class... Args > + void emplace_value( std::initializer_list il, Args&&... args ) + { + new( &m_value ) value_type( il, std::forward(args)... ); } void destruct_value() @@ -372,6 +508,18 @@ union storage_t new( &m_error ) error_type( std::move( e ) ); } + template< class... Args > + void emplace_error( Args&&... args ) + { + new( &m_error ) error_type( std::forward(args)...); + } + + template< class U, class... Args > + void emplace_error( std::initializer_list il, Args&&... args ) + { + new( &m_error ) error_type( il, std::forward(args)... ); + } + void destruct_error() { m_error.~error_type(); @@ -407,35 +555,64 @@ union storage_t return &m_value; } - error_type const & error() const + error_type const & error() const & { return m_error; } - error_type & error() + error_type & error() & { return m_error; } + constexpr error_type const && error() const && + { + return std::move( m_error ); + } + + nsel_constexpr14 error_type && error() && + { + return std::move( m_error ); + } + + bool has_value() const + { + return m_has_value; + } + + void set_has_value( bool v ) + { + m_has_value = v; + } + private: - value_type m_value; - error_type m_error; + union + { + value_type m_value; + error_type m_error; + }; + + bool m_has_value = false; }; /// discriminated union to hold only 'error'. template< typename E > -union storage_t +struct storage_t_impl { - friend class expected; + template< typename, typename > friend class nonstd::expected_lite::expected; -private: +public: using value_type = void; using error_type = E; // no-op construction - storage_t() {} - ~storage_t() {} + storage_t_impl() {} + ~storage_t_impl() {} + + explicit storage_t_impl( bool has_value ) + : m_has_value( has_value ) + {} void construct_error( error_type const & e ) { @@ -447,28 +624,217 @@ union storage_t new( &m_error ) error_type( std::move( e ) ); } + template< class... Args > + void emplace_error( Args&&... args ) + { + new( &m_error ) error_type( std::forward(args)...); + } + + template< class U, class... Args > + void emplace_error( std::initializer_list il, Args&&... args ) + { + new( &m_error ) error_type( il, std::forward(args)... ); + } + void destruct_error() { m_error.~error_type(); } - error_type const & error() const + error_type const & error() const & { return m_error; } - error_type & error() + error_type & error() & { return m_error; } + constexpr error_type const && error() const && + { + return std::move( m_error ); + } + + nsel_constexpr14 error_type && error() && + { + return std::move( m_error ); + } + + bool has_value() const + { + return m_has_value; + } + + void set_has_value( bool v ) + { + m_has_value = v; + } + private: - error_type m_error; + union + { + char m_dummy; + error_type m_error; + }; + + bool m_has_value = false; +}; + +template< typename T, typename E, bool isConstructable, bool isMoveable > +class storage_t +{ +public: + storage_t() = default; + ~storage_t() = default; + + explicit storage_t( bool has_value ) + : storage_t_impl( has_value ) + {} + + storage_t( storage_t const & other ) = delete; + storage_t( storage_t && other ) = delete; +}; + +template< typename T, typename E > +class storage_t : public storage_t_impl +{ +public: + storage_t() = default; + ~storage_t() = default; + + explicit storage_t( bool has_value ) + : storage_t_impl( has_value ) + {} + + storage_t( storage_t const & other ) + : storage_t_impl( other.has_value() ) + { + if ( this->has_value() ) this->construct_value( other.value() ); + else this->construct_error( other.error() ); + } + + storage_t(storage_t && other ) + : storage_t_impl( other.has_value() ) + { + if ( this->has_value() ) this->construct_value( std::move( other.value() ) ); + else this->construct_error( std::move( other.error() ) ); + } +}; + +template< typename E > +class storage_t : public storage_t_impl +{ +public: + storage_t() = default; + ~storage_t() = default; + + explicit storage_t( bool has_value ) + : storage_t_impl( has_value ) + {} + + storage_t( storage_t const & other ) + : storage_t_impl( other.has_value() ) + { + if ( this->has_value() ) ; + else this->construct_error( other.error() ); + } + + storage_t(storage_t && other ) + : storage_t_impl( other.has_value() ) + { + if ( this->has_value() ) ; + else this->construct_error( std::move( other.error() ) ); + } +}; + +template< typename T, typename E > +class storage_t : public storage_t_impl +{ +public: + storage_t() = default; + ~storage_t() = default; + + explicit storage_t( bool has_value ) + : storage_t_impl( has_value ) + {} + + storage_t( storage_t const & other ) + : storage_t_impl(other.has_value()) + { + if ( this->has_value() ) this->construct_value( other.value() ); + else this->construct_error( other.error() ); + } + + storage_t( storage_t && other ) = delete; +}; + +template< typename E > +class storage_t : public storage_t_impl +{ +public: + storage_t() = default; + ~storage_t() = default; + + explicit storage_t( bool has_value ) + : storage_t_impl( has_value ) + {} + + storage_t( storage_t const & other ) + : storage_t_impl(other.has_value()) + { + if ( this->has_value() ) ; + else this->construct_error( other.error() ); + } + + storage_t( storage_t && other ) = delete; +}; + +template< typename T, typename E > +class storage_t : public storage_t_impl +{ +public: + storage_t() = default; + ~storage_t() = default; + + explicit storage_t( bool has_value ) + : storage_t_impl( has_value ) + {} + + storage_t( storage_t const & other ) = delete; + + storage_t( storage_t && other ) + : storage_t_impl( other.has_value() ) + { + if ( this->has_value() ) this->construct_value( std::move( other.value() ) ); + else this->construct_error( std::move( other.error() ) ); + } +}; + +template< typename E > +class storage_t : public storage_t_impl +{ +public: + storage_t() = default; + ~storage_t() = default; + + explicit storage_t( bool has_value ) + : storage_t_impl( has_value ) + {} + + storage_t( storage_t const & other ) = delete; + + storage_t( storage_t && other ) + : storage_t_impl( other.has_value() ) + { + if ( this->has_value() ) ; + else this->construct_error( std::move( other.error() ) ); + } }; } // namespace detail -/// // x.x.3 Unexpected object type; unexpected_type; C++17 and later can also use aliased type unexpected. +/// x.x.5 Unexpected object type; unexpected_type; C++17 and later can also use aliased type unexpected. #if nsel_P0323R <= 2 template< typename E = std::exception_ptr > @@ -481,57 +847,135 @@ class unexpected_type public: using error_type = E; - unexpected_type() = delete; - constexpr unexpected_type( unexpected_type const &) = default; - constexpr unexpected_type( unexpected_type &&) = default; - nsel_constexpr14 unexpected_type& operator=( unexpected_type const &) = default; - nsel_constexpr14 unexpected_type& operator=( unexpected_type &&) = default; + // x.x.5.2.1 Constructors + +// unexpected_type() = delete; + + constexpr unexpected_type( unexpected_type const & ) = default; + constexpr unexpected_type( unexpected_type && ) = default; + + template< typename... Args + nsel_REQUIRES_T( + std::is_constructible::value + ) + > + constexpr explicit unexpected_type( nonstd_lite_in_place_t(E), Args &&... args ) + : m_error( std::forward( args )...) + {} + + template< typename U, typename... Args + nsel_REQUIRES_T( + std::is_constructible, Args&&...>::value + ) + > + constexpr explicit unexpected_type( nonstd_lite_in_place_t(E), std::initializer_list il, Args &&... args ) + : m_error( il, std::forward( args )...) + {} template< typename E2 nsel_REQUIRES_T( - std::is_constructible::value + std::is_constructible::value + && !std::is_same< typename std20::remove_cvref::type, nonstd_lite_in_place_t(E2) >::value + && !std::is_same< typename std20::remove_cvref::type, unexpected_type >::value ) > constexpr explicit unexpected_type( E2 && error ) : m_error( std::forward( error ) ) {} - template< typename E2 > - constexpr explicit unexpected_type( unexpected_type const & error - nsel_REQUIRES_A( - std::is_constructible::value - && !std::is_convertible::value /*=> explicit */ ) + template< typename E2 + nsel_REQUIRES_T( + std::is_constructible< E, E2>::value + && !std::is_constructible & >::value + && !std::is_constructible >::value + && !std::is_constructible const & >::value + && !std::is_constructible const >::value + && !std::is_convertible< unexpected_type &, E>::value + && !std::is_convertible< unexpected_type , E>::value + && !std::is_convertible< unexpected_type const &, E>::value + && !std::is_convertible< unexpected_type const , E>::value + && !std::is_convertible< E2 const &, E>::value /*=> explicit */ ) - : m_error( error ) + > + constexpr explicit unexpected_type( unexpected_type const & error ) + : m_error( E{ error.value() } ) {} - template< typename E2 > - constexpr /*non-explicit*/ unexpected_type( unexpected_type const & error - nsel_REQUIRES_A( - std::is_constructible::value - && std::is_convertible::value /*=> non-explicit */ ) + template< typename E2 + nsel_REQUIRES_T( + std::is_constructible< E, E2>::value + && !std::is_constructible & >::value + && !std::is_constructible >::value + && !std::is_constructible const & >::value + && !std::is_constructible const >::value + && !std::is_convertible< unexpected_type &, E>::value + && !std::is_convertible< unexpected_type , E>::value + && !std::is_convertible< unexpected_type const &, E>::value + && !std::is_convertible< unexpected_type const , E>::value + && std::is_convertible< E2 const &, E>::value /*=> explicit */ ) - : m_error( error ) + > + constexpr /*non-explicit*/ unexpected_type( unexpected_type const & error ) + : m_error( error.value() ) {} - template< typename E2 > - constexpr explicit unexpected_type( unexpected_type && error - nsel_REQUIRES_A( - std::is_constructible::value - && !std::is_convertible::value /*=> explicit */ ) + template< typename E2 + nsel_REQUIRES_T( + std::is_constructible< E, E2>::value + && !std::is_constructible & >::value + && !std::is_constructible >::value + && !std::is_constructible const & >::value + && !std::is_constructible const >::value + && !std::is_convertible< unexpected_type &, E>::value + && !std::is_convertible< unexpected_type , E>::value + && !std::is_convertible< unexpected_type const &, E>::value + && !std::is_convertible< unexpected_type const , E>::value + && !std::is_convertible< E2 const &, E>::value /*=> explicit */ ) - : m_error( error ) + > + constexpr explicit unexpected_type( unexpected_type && error ) + : m_error( E{ std::move( error.value() ) } ) {} - template< typename E2 > - constexpr /*non-explicit*/ unexpected_type( unexpected_type && error - nsel_REQUIRES_A( - std::is_constructible::value - && std::is_convertible::value /*=> non-explicit */ ) + template< typename E2 + nsel_REQUIRES_T( + std::is_constructible< E, E2>::value + && !std::is_constructible & >::value + && !std::is_constructible >::value + && !std::is_constructible const & >::value + && !std::is_constructible const >::value + && !std::is_convertible< unexpected_type &, E>::value + && !std::is_convertible< unexpected_type , E>::value + && !std::is_convertible< unexpected_type const &, E>::value + && !std::is_convertible< unexpected_type const , E>::value + && std::is_convertible< E2 const &, E>::value /*=> non-explicit */ ) - : m_error( error ) + > + constexpr /*non-explicit*/ unexpected_type( unexpected_type && error ) + : m_error( std::move( error.value() ) ) {} + // x.x.5.2.2 Assignment + + nsel_constexpr14 unexpected_type& operator=( unexpected_type const & ) = default; + nsel_constexpr14 unexpected_type& operator=( unexpected_type && ) = default; + + template< typename E2 = E > + nsel_constexpr14 unexpected_type & operator=( unexpected_type const & other ) + { + unexpected_type{ other.value() }.swap( *this ); + return *this; + } + + template< typename E2 = E > + nsel_constexpr14 unexpected_type & operator=( unexpected_type && other ) + { + unexpected_type{ std::move( other.value() ) }.swap( *this ); + return *this; + } + + // x.x.5.2.3 Observers + nsel_constexpr14 E & value() & noexcept { return m_error; @@ -542,6 +986,8 @@ class unexpected_type return m_error; } +#if !nsel_COMPILER_GNUC_VERSION || nsel_COMPILER_GNUC_VERSION >= 490 + nsel_constexpr14 E && value() && noexcept { return std::move( m_error ); @@ -552,33 +998,43 @@ class unexpected_type return std::move( m_error ); } -// nsel_REQUIRES_A( -// std::is_move_constructible::value -// && std::is_swappable::value -// ) - - void swap( unexpected_type & other ) noexcept ( -#if nsel_CPP17_OR_GREATER - std::is_nothrow_move_constructible::value - && std::is_nothrow_swappable::value -#else - std::is_nothrow_move_constructible::value - && noexcept ( std::swap( std::declval(), std::declval() ) ) #endif + + // x.x.5.2.4 Swap + + nsel_REQUIRES_R( void, + std17::is_swappable::value + ) + swap( unexpected_type & other ) noexcept ( + std17::is_nothrow_swappable::value ) { using std::swap; swap( m_error, other.m_error ); } + // TODO: ??? unexpected_type: in-class friend operator==, != + private: error_type m_error; }; +#if nsel_CPP17_OR_GREATER + +/// template deduction guide: + +template< typename E > +unexpected_type( E ) -> unexpected_type< E >; + +#endif + /// class unexpected_type, std::exception_ptr specialization (P0323R2) -#if nsel_P0323R <= 2 +#if !nsel_CONFIG_NO_EXCEPTIONS +#if nsel_P0323R <= 2 +// TODO: Should expected be specialized for particular E types such as exception_ptr and how? +// See p0323r7 2.1. Ergonomics, http://wg21.link/p0323 template<> class unexpected_type< std::exception_ptr > { @@ -617,17 +1073,18 @@ class unexpected_type< std::exception_ptr > }; #endif // nsel_P0323R +#endif // !nsel_CONFIG_NO_EXCEPTIONS /// x.x.4, Unexpected equality operators -template< typename E > -constexpr bool operator==( unexpected_type const & x, unexpected_type const & y ) +template< typename E1, typename E2 > +constexpr bool operator==( unexpected_type const & x, unexpected_type const & y ) { return x.value() == y.value(); } -template< typename E > -constexpr bool operator!=( unexpected_type const & x, unexpected_type const & y ) +template< typename E1, typename E2 > +constexpr bool operator!=( unexpected_type const & x, unexpected_type const & y ) { return ! ( x == y ); } @@ -658,14 +1115,22 @@ constexpr bool operator>=( unexpected_type const & x, unexpected_type cons return ! ( x < y ); } +#endif // nsel_P0323R + /// x.x.5 Specialized algorithms -template< typename E > +template< typename E + nsel_REQUIRES_T( + std17::is_swappable::value + ) +> void swap( unexpected_type & x, unexpected_type & y) noexcept ( noexcept ( x.swap(y) ) ) { x.swap( y ); } +#if nsel_P0323R <= 2 + // unexpected: relational operators for std::exception_ptr: inline constexpr bool operator<( unexpected_type const & /*x*/, unexpected_type const & /*y*/ ) @@ -723,19 +1188,13 @@ make_unexpected_from_current_exception() -> unexpected_type< std::exception_ptr #endif // nsel_P0323R -/// unexpect tag, in_place_unexpected tag: construct an error - -struct unexpect_t{}; -using in_place_unexpected_t = unexpect_t; - -nsel_inline17 constexpr unexpect_t unexpect{}; -nsel_inline17 constexpr unexpect_t in_place_unexpected{}; - -/// expected access error +/// x.x.6, x.x.7 expected access error template< typename E > class bad_expected_access; +/// x.x.7 bad_expected_access: expected access error + template <> class bad_expected_access< void > : public std::exception { @@ -745,6 +1204,10 @@ class bad_expected_access< void > : public std::exception {} }; +/// x.x.6 bad_expected_access: expected access error + +#if !nsel_CONFIG_NO_EXCEPTIONS + template< typename E > class bad_expected_access : public bad_expected_access< void > { @@ -770,6 +1233,8 @@ class bad_expected_access : public bad_expected_access< void > return m_error; } +#if !nsel_COMPILER_GNUC_VERSION || nsel_COMPILER_GNUC_VERSION >= 490 + nsel_constexpr14 error_type && error() && { return std::move( m_error ); @@ -780,12 +1245,71 @@ class bad_expected_access : public bad_expected_access< void > return std::move( m_error ); } +#endif + private: error_type m_error; }; +#endif // nsel_CONFIG_NO_EXCEPTIONS + +/// x.x.8 unexpect tag, in_place_unexpected tag: construct an error + +struct unexpect_t{}; +using in_place_unexpected_t = unexpect_t; + +nsel_inline17 constexpr unexpect_t unexpect{}; +nsel_inline17 constexpr unexpect_t in_place_unexpected{}; + /// class error_traits +#if nsel_CONFIG_NO_EXCEPTIONS + +namespace detail { + inline bool text( char const * /*text*/ ) { return true; } +} + +template< typename Error > +struct error_traits +{ + static void rethrow( Error const & /*e*/ ) + { +#if nsel_CONFIG_NO_EXCEPTIONS_SEH + RaiseException( EXCEPTION_ACCESS_VIOLATION, EXCEPTION_NONCONTINUABLE, 0, NULL ); +#else + assert( false && detail::text("throw bad_expected_access{ e };") ); +#endif + } +}; + +template<> +struct error_traits< std::exception_ptr > +{ + static void rethrow( std::exception_ptr const & /*e*/ ) + { +#if nsel_CONFIG_NO_EXCEPTIONS_SEH + RaiseException( EXCEPTION_ACCESS_VIOLATION, EXCEPTION_NONCONTINUABLE, 0, NULL ); +#else + assert( false && detail::text("throw bad_expected_access{ e };") ); +#endif + } +}; + +template<> +struct error_traits< std::error_code > +{ + static void rethrow( std::error_code const & /*e*/ ) + { +#if nsel_CONFIG_NO_EXCEPTIONS_SEH + RaiseException( EXCEPTION_ACCESS_VIOLATION, EXCEPTION_NONCONTINUABLE, 0, NULL ); +#else + assert( false && detail::text("throw std::system_error( e );") ); +#endif + } +}; + +#else // nsel_CONFIG_NO_EXCEPTIONS + template< typename Error > struct error_traits { @@ -813,6 +1337,8 @@ struct error_traits< std::error_code > } }; +#endif // nsel_CONFIG_NO_EXCEPTIONS + } // namespace expected_lite // provide nonstd::unexpected_type: @@ -831,6 +1357,9 @@ template< typename T, typename E > class expected #endif // nsel_P0323R { +private: + template< typename, typename > friend class expected; + public: using value_type = T; using error_type = E; @@ -842,264 +1371,261 @@ class expected using type = expected; }; - // x.x.4.1 constructors - - nsel_REQUIRES_0( - std::is_default_constructible::value - ) - nsel_constexpr14 expected() noexcept - ( - std::is_nothrow_default_constructible::value - ) - : has_value_( true ) - { - contained.construct_value( value_type() ); - } - - nsel_constexpr14 expected( expected const & other -// nsel_REQUIRES_A( -// std::is_copy_constructible::value -// && std::is_copy_constructible::value -// ) - ) - : has_value_( other.has_value_ ) - { - if ( has_value() ) contained.construct_value( other.contained.value() ); - else contained.construct_error( other.contained.error() ); - } + // x.x.4.1 constructors - nsel_constexpr14 expected( expected && other -// nsel_REQUIRES_A( -// std::is_move_constructible::value -// && std::is_move_constructible::value -// ) - ) noexcept ( - std::is_nothrow_move_constructible::value - && std::is_nothrow_move_constructible::value + nsel_REQUIRES_0( + std::is_default_constructible::value ) - : has_value_( other.has_value_ ) + nsel_constexpr14 expected() + : contained( true ) { - if ( has_value() ) contained.construct_value( std::move( other.contained.value() ) ); - else contained.construct_error( std::move( other.contained.error() ) ); + contained.construct_value( value_type() ); } - template< typename U, typename G > - nsel_constexpr14 explicit expected( expected const & other - nsel_REQUIRES_A( - std::is_constructible::value - && std::is_constructible::value - && !std::is_constructible&>::value - && !std::is_constructible&&>::value - && !std::is_constructible&>::value - && !std::is_constructible&&>::value - && !std::is_convertible&, T>::value - && !std::is_convertible&&, T>::value - && !std::is_convertible&, T>::value - && !std::is_convertible&&, T>::value - && (!std::is_convertible::value || !std::is_convertible::value ) /*=> explicit */ ) + nsel_constexpr14 expected( expected const & ) = default; + nsel_constexpr14 expected( expected && ) = default; + + template< typename U, typename G + nsel_REQUIRES_T( + std::is_constructible< T, U const &>::value + && std::is_constructible::value + && !std::is_constructible & >::value + && !std::is_constructible && >::value + && !std::is_constructible const & >::value + && !std::is_constructible const && >::value + && !std::is_convertible< expected & , T>::value + && !std::is_convertible< expected &&, T>::value + && !std::is_convertible< expected const & , T>::value + && !std::is_convertible< expected const &&, T>::value + && (!std::is_convertible::value || !std::is_convertible::value ) /*=> explicit */ ) - : has_value_( other.has_value_ ) + > + nsel_constexpr14 explicit expected( expected const & other ) + : contained( other.has_value() ) { - if ( has_value() ) contained.construct_value( other.contained.value() ); - else contained.construct_error( other.contained.error() ); + if ( has_value() ) contained.construct_value( T{ other.contained.value() } ); + else contained.construct_error( E{ other.contained.error() } ); } - template< typename U, typename G > - nsel_constexpr14 /*non-explicit*/ expected( expected const & other - nsel_REQUIRES_A( - std::is_constructible::value - && std::is_constructible::value - && !std::is_constructible&>::value - && !std::is_constructible&&>::value - && !std::is_constructible&>::value - && !std::is_constructible&&>::value - && !std::is_convertible&, T>::value - && !std::is_convertible&&, T>::value - && !std::is_convertible&, T>::value - && !std::is_convertible&&, T>::value - && !(!std::is_convertible::value || !std::is_convertible::value ) /*=> explicit */ ) + template< typename U, typename G + nsel_REQUIRES_T( + std::is_constructible< T, U const &>::value + && std::is_constructible::value + && !std::is_constructible & >::value + && !std::is_constructible && >::value + && !std::is_constructible const & >::value + && !std::is_constructible const && >::value + && !std::is_convertible< expected & , T>::value + && !std::is_convertible< expected &&, T>::value + && !std::is_convertible< expected const &, T>::value + && !std::is_convertible< expected const &&, T>::value + && !(!std::is_convertible::value || !std::is_convertible::value ) /*=> non-explicit */ ) - : has_value_( other.has_value_ ) + > + nsel_constexpr14 /*non-explicit*/ expected( expected const & other ) + : contained( other.has_value() ) { if ( has_value() ) contained.construct_value( other.contained.value() ); else contained.construct_error( other.contained.error() ); } - template< typename U, typename G > - nsel_constexpr14 explicit expected( expected && other - nsel_REQUIRES_A( - std::is_constructible::value - && std::is_constructible::value - && !std::is_constructible&>::value - && !std::is_constructible&&>::value - && !std::is_constructible&>::value - && !std::is_constructible&&>::value - && !std::is_convertible&, T>::value - && !std::is_convertible&&, T>::value - && !std::is_convertible&, T>::value - && !std::is_convertible&&, T>::value - && (!std::is_convertible::value || !std::is_convertible::value ) /*=> explicit */ ) + template< typename U, typename G + nsel_REQUIRES_T( + std::is_constructible< T, U>::value + && std::is_constructible::value + && !std::is_constructible & >::value + && !std::is_constructible && >::value + && !std::is_constructible const & >::value + && !std::is_constructible const && >::value + && !std::is_convertible< expected & , T>::value + && !std::is_convertible< expected &&, T>::value + && !std::is_convertible< expected const & , T>::value + && !std::is_convertible< expected const &&, T>::value + && (!std::is_convertible::value || !std::is_convertible::value ) /*=> explicit */ ) - : has_value_( other.has_value_ ) + > + nsel_constexpr14 explicit expected( expected && other ) + : contained( other.has_value() ) { - if ( has_value() ) contained.construct_value( std::move( other.contained.value() ) ); - else contained.construct_error( std::move( other.contained.error() ) ); + if ( has_value() ) contained.construct_value( T{ std::move( other.contained.value() ) } ); + else contained.construct_error( E{ std::move( other.contained.error() ) } ); } - template< typename U, typename G > - nsel_constexpr14 /*non-explicit*/ expected( expected && other - nsel_REQUIRES_A( - std::is_constructible::value - && std::is_constructible::value - && !std::is_constructible&>::value - && !std::is_constructible&&>::value - && !std::is_constructible&>::value - && !std::is_constructible&&>::value - && !std::is_convertible&, T>::value - && !std::is_convertible&&, T>::value - && !std::is_convertible&, T>::value - && !std::is_convertible&&, T>::value - && !(!std::is_convertible::value || !std::is_convertible::value ) /*=> non-explicit */ ) + template< typename U, typename G + nsel_REQUIRES_T( + std::is_constructible< T, U>::value + && std::is_constructible::value + && !std::is_constructible & >::value + && !std::is_constructible && >::value + && !std::is_constructible const & >::value + && !std::is_constructible const && >::value + && !std::is_convertible< expected & , T>::value + && !std::is_convertible< expected &&, T>::value + && !std::is_convertible< expected const & , T>::value + && !std::is_convertible< expected const &&, T>::value + && !(!std::is_convertible::value || !std::is_convertible::value ) /*=> non-explicit */ ) - : has_value_( other.has_value_ ) + > + nsel_constexpr14 /*non-explicit*/ expected( expected && other ) + : contained( other.has_value() ) { if ( has_value() ) contained.construct_value( std::move( other.contained.value() ) ); else contained.construct_error( std::move( other.contained.error() ) ); } - nsel_constexpr14 expected( value_type const & value -// nsel_REQUIRES_A( -// std::is_copy_constructible::value ) - ) - : has_value_( true ) + template< typename U = T + nsel_REQUIRES_T( + std::is_copy_constructible::value + ) + > + nsel_constexpr14 expected( value_type const & value ) + : contained( true ) { contained.construct_value( value ); } - template< typename U = T > - nsel_constexpr14 explicit expected( U && value - nsel_REQUIRES_A( + template< typename U = T + nsel_REQUIRES_T( std::is_constructible::value && !std::is_same::type, nonstd_lite_in_place_t(U)>::value - && !std::is_same, typename std20::remove_cvref::type>::value + && !std::is_same< expected , typename std20::remove_cvref::type>::value && !std::is_same, typename std20::remove_cvref::type>::value && !std::is_convertible::value /*=> explicit */ ) - ) noexcept + > + nsel_constexpr14 explicit expected( U && value ) noexcept ( std::is_nothrow_move_constructible::value && std::is_nothrow_move_constructible::value ) - : has_value_( true ) + : contained( true ) { - contained.construct_value( std::forward( value ) ); + contained.construct_value( T{ std::forward( value ) } ); } - template< typename U = T > - nsel_constexpr14 expected( U && value - nsel_REQUIRES_A( + template< typename U = T + nsel_REQUIRES_T( std::is_constructible::value && !std::is_same::type, nonstd_lite_in_place_t(U)>::value - && !std::is_same, typename std20::remove_cvref::type>::value + && !std::is_same< expected , typename std20::remove_cvref::type>::value && !std::is_same, typename std20::remove_cvref::type>::value && std::is_convertible::value /*=> non-explicit */ ) - ) noexcept + > + nsel_constexpr14 /*non-explicit*/ expected( U && value ) noexcept ( std::is_nothrow_move_constructible::value && std::is_nothrow_move_constructible::value ) - : has_value_( true ) + : contained( true ) { contained.construct_value( std::forward( value ) ); } - template< typename... Args + // construct error: + + template< typename G = E nsel_REQUIRES_T( - std::is_constructible::value + std::is_constructible::value + && !std::is_convertible< G const &, E>::value /*=> explicit */ ) > - nsel_constexpr14 explicit expected( nonstd_lite_in_place_t(T), Args&&... args ) - : has_value_( true ) + nsel_constexpr14 explicit expected( nonstd::unexpected_type const & error ) + : contained( false ) { - contained.construct_value( std::forward( args )... ); + contained.construct_error( E{ error.value() } ); } - template< typename U, typename... Args - nsel_REQUIRES_T( - std::is_constructible, Args&&...>::value + template< typename G = E + nsel_REQUIRES_T( + std::is_constructible::value + && std::is_convertible< G const &, E>::value /*=> non-explicit */ ) > - nsel_constexpr14 explicit expected( nonstd_lite_in_place_t(T), std::initializer_list il, Args&&... args ) - : has_value_( true ) + nsel_constexpr14 /*non-explicit*/ expected( nonstd::unexpected_type const & error ) + : contained( false ) { - contained.construct_value( il, std::forward( args )... ); + contained.construct_error( error.value() ); } - template< typename G = E > - nsel_constexpr14 explicit expected( nonstd::unexpected_type const & error - nsel_REQUIRES_A( - !std::is_convertible::value /*=> explicit */ ) + template< typename G = E + nsel_REQUIRES_T( + std::is_constructible::value + && !std::is_convertible< G&&, E>::value /*=> explicit */ ) - : has_value_( false ) + > + nsel_constexpr14 explicit expected( nonstd::unexpected_type && error ) + : contained( false ) { - contained.construct_error( error.value() ); + contained.construct_error( E{ std::move( error.value() ) } ); } - template< typename G = E > - nsel_constexpr14 /*non-explicit*/ expected( nonstd::unexpected_type const & error - nsel_REQUIRES_A( - std::is_convertible::value /*=> non-explicit */ ) + template< typename G = E + nsel_REQUIRES_T( + std::is_constructible::value + && std::is_convertible< G&&, E>::value /*=> non-explicit */ ) - : has_value_( false ) + > + nsel_constexpr14 /*non-explicit*/ expected( nonstd::unexpected_type && error ) + : contained( false ) { - contained.construct_error( error.value() ); + contained.construct_error( std::move( error.value() ) ); } - template< typename G = E > - nsel_constexpr14 explicit expected( nonstd::unexpected_type && error - nsel_REQUIRES_A( - !std::is_convertible::value /*=> explicit */ ) + // in-place construction, value + + template< typename... Args + nsel_REQUIRES_T( + std::is_constructible::value ) - : has_value_( false ) + > + nsel_constexpr14 explicit expected( nonstd_lite_in_place_t(T), Args&&... args ) + : contained( true ) { - contained.construct_error( std::move( error.value() ) ); + contained.emplace_value( std::forward( args )... ); } - template< typename G = E > - nsel_constexpr14 /*non-explicit*/ expected( nonstd::unexpected_type && error - nsel_REQUIRES_A( - std::is_convertible::value /*=> non-explicit */ ) + template< typename U, typename... Args + nsel_REQUIRES_T( + std::is_constructible, Args&&...>::value ) - : has_value_( false ) + > + nsel_constexpr14 explicit expected( nonstd_lite_in_place_t(T), std::initializer_list il, Args&&... args ) + : contained( true ) { - contained.construct_error( std::move( error.value() ) ); + contained.emplace_value( il, std::forward( args )... ); } + // in-place construction, error + template< typename... Args nsel_REQUIRES_T( std::is_constructible::value ) > nsel_constexpr14 explicit expected( unexpect_t, Args&&... args ) - : has_value_( false ) + : contained( false ) { - contained.construct_error( std::forward( args )... ); + contained.emplace_error( std::forward( args )... ); } template< typename U, typename... Args nsel_REQUIRES_T( - std::is_constructible, Args&&...>::value + std::is_constructible, Args&&...>::value ) > nsel_constexpr14 explicit expected( unexpect_t, std::initializer_list il, Args&&... args ) - : has_value_( false ) + : contained( false ) { - contained.construct_error( il, std::forward( args )... ); + contained.emplace_error( il, std::forward( args )... ); } // x.x.4.2 destructor + // TODO: ~expected: triviality + // Effects: If T is not cv void and is_trivially_destructible_v is false and bool(*this), calls val.~T(). If is_trivially_destructible_v is false and !bool(*this), calls unexpect.~unexpected(). + // Remarks: If either T is cv void or is_trivially_destructible_v is true, and is_trivially_destructible_v is true, then this destructor shall be a trivial destructor. + ~expected() { if ( has_value() ) contained.destruct_value(); @@ -1108,30 +1634,18 @@ class expected // x.x.4.3 assignment -// nsel_REQUIRES_A( -// std::is_copy_constructible::value && -// std::is_copy_assignable::value && -// std::is_copy_constructible::value && -// std::is_copy_assignable::value ) - - expected operator=( expected const & other ) + expected & operator=( expected const & other ) { expected( other ).swap( *this ); return *this; } -// nsel_REQUIRES_A( -// std::is_move_constructible::value && -// std::is_move_assignable::value && -// std::is_move_constructible::value && -// std::is_move_assignable::value ) - expected & operator=( expected && other ) noexcept ( - std::is_nothrow_move_assignable::value && - std::is_nothrow_move_constructible::value&& - std::is_nothrow_move_assignable::value && - std::is_nothrow_move_constructible::value ) + std::is_nothrow_move_constructible< T>::value + && std::is_nothrow_move_assignable< T>::value + && std::is_nothrow_move_constructible::value // added for missing + && std::is_nothrow_move_assignable< E>::value ) // nothrow above { expected( std::move( other ) ).swap( *this ); return *this; @@ -1139,9 +1653,11 @@ class expected template< typename U nsel_REQUIRES_T( - std::is_constructible::value && - std::is_assignable::value - ) + !std::is_same, typename std20::remove_cvref::type>::value + && std17::conjunction, std::is_same> >::value + && std::is_constructible::value + && std::is_assignable< T&,U>::value + && std::is_nothrow_move_constructible::value ) > expected & operator=( U && value ) { @@ -1149,61 +1665,66 @@ class expected return *this; } -// nsel_REQUIRES_A( -// std::is_copy_constructible::value && -// std::is_assignable::value ) - - expected & operator=( unexpected_type const & uvalue ) + template< typename G = E + nsel_REQUIRES_T( + std::is_constructible::value && + std::is_copy_constructible::value // TODO: std::is_nothrow_copy_constructible + && std::is_copy_assignable::value + ) + > + expected & operator=( nonstd::unexpected_type const & error ) { - expected( std::move( uvalue ) ).swap( *this ); + expected( unexpect, error.value() ).swap( *this ); return *this; } -// nsel_REQUIRES_A( -// std::is_copy_constructible::value && -// std::is_assignable::value ) - - expected & operator=( unexpected_type && uvalue ) + template< typename G = E + nsel_REQUIRES_T( + std::is_constructible::value && + std::is_move_constructible::value // TODO: std::is_nothrow_move_constructible + && std::is_move_assignable::value + ) + > + expected & operator=( nonstd::unexpected_type && error ) { - expected( std::move( uvalue ) ).swap( *this ); + expected( unexpect, std::move( error.value() ) ).swap( *this ); return *this; } template< typename... Args nsel_REQUIRES_T( - std::is_constructible::value + std::is_nothrow_constructible::value ) > - void emplace( Args &&... args ) + value_type & emplace( Args &&... args ) { expected( nonstd_lite_in_place(T), std::forward(args)... ).swap( *this ); + return value(); } template< typename U, typename... Args nsel_REQUIRES_T( - std::is_constructible&, Args&&...>::value + std::is_nothrow_constructible&, Args&&...>::value ) > - void emplace( std::initializer_list il, Args &&... args ) + value_type & emplace( std::initializer_list il, Args &&... args ) { expected( nonstd_lite_in_place(T), il, std::forward(args)... ).swap( *this ); + return value(); } // x.x.4.4 swap -// nsel_REQUIRES_A( -// std::is_move_constructible::value && -// std::is_move_constructible::value ) - - void swap( expected & other ) noexcept + template< typename U=T, typename G=E > + nsel_REQUIRES_R( void, + std17::is_swappable< U>::value + && std17::is_swappable::value + && ( std::is_move_constructible::value || std::is_move_constructible::value ) + ) + swap( expected & other ) noexcept ( -#if nsel_CPP17_OR_GREATER - std::is_nothrow_move_constructible::value && std::is_nothrow_swappable::value && - std::is_nothrow_move_constructible::value && std::is_nothrow_swappable::value -#else - std::is_nothrow_move_constructible::value && noexcept ( std::swap( std::declval(), std::declval() ) ) && - std::is_nothrow_move_constructible::value && noexcept ( std::swap( std::declval(), std::declval() ) ) -#endif + std::is_nothrow_move_constructible::value && std17::is_nothrow_swappable::value && + std::is_nothrow_move_constructible::value && std17::is_nothrow_swappable::value ) { using std::swap; @@ -1211,11 +1732,15 @@ class expected if ( bool(*this) && bool(other) ) { swap( contained.value(), other.contained.value() ); } else if ( ! bool(*this) && ! bool(other) ) { swap( contained.error(), other.contained.error() ); } else if ( bool(*this) && ! bool(other) ) { error_type t( std::move( other.error() ) ); - other.contained.destruct_error(); - other.contained.construct_value( std::move( contained.value() ) ); - contained.destruct_value(); - contained.construct_error( std::move( t ) ); - swap( has_value_, other.has_value_ ); } + other.contained.destruct_error(); + other.contained.construct_value( std::move( contained.value() ) ); + contained.destruct_value(); + contained.construct_error( std::move( t ) ); + bool has_value = contained.has_value(); + bool other_has_value = other.has_value(); + other.contained.set_has_value(has_value); + contained.set_has_value(other_has_value); + } else if ( ! bool(*this) && bool(other) ) { other.swap( *this ); } } @@ -1241,16 +1766,20 @@ class expected return assert( has_value() ), contained.value(); } +#if !nsel_COMPILER_GNUC_VERSION || nsel_COMPILER_GNUC_VERSION >= 490 + constexpr value_type const && operator *() const && { - return assert( has_value() ), std::move( contained.value() ); + return std::move( ( assert( has_value() ), contained.value() ) ); } nsel_constexpr14 value_type && operator *() && { - return assert( has_value() ), std::move( contained.value() ); + return std::move( ( assert( has_value() ), contained.value() ) ); } +#endif + constexpr explicit operator bool() const noexcept { return has_value(); @@ -1258,7 +1787,7 @@ class expected constexpr bool has_value() const noexcept { - return has_value_; + return contained.has_value(); } constexpr value_type const & value() const & @@ -1275,6 +1804,8 @@ class expected : ( error_traits::rethrow( contained.error() ), contained.value() ); } +#if !nsel_COMPILER_GNUC_VERSION || nsel_COMPILER_GNUC_VERSION >= 490 + constexpr value_type const && value() const && { return std::move( has_value() @@ -1289,6 +1820,8 @@ class expected : ( error_traits::rethrow( contained.error() ), contained.value() ) ); } +#endif + constexpr error_type const & error() const & { return assert( ! has_value() ), contained.error(); @@ -1299,16 +1832,20 @@ class expected return assert( ! has_value() ), contained.error(); } +#if !nsel_COMPILER_GNUC_VERSION || nsel_COMPILER_GNUC_VERSION >= 490 + constexpr error_type const && error() const && { - return assert( ! has_value() ), std::move( contained.error() ); + return std::move( ( assert( ! has_value() ), contained.error() ) ); } error_type && error() && { - return assert( ! has_value() ), std::move( contained.error() ); + return std::move( ( assert( ! has_value() ), contained.error() ) ); } +#endif + constexpr unexpected_type get_unexpected() const { return make_unexpected( contained.error() ); @@ -1323,8 +1860,8 @@ class expected template< typename U nsel_REQUIRES_T( - std::is_copy_constructible::value && - std::is_convertible::value + std::is_copy_constructible< T>::value + && std::is_convertible::value ) > value_type value_or( U && v ) const & @@ -1336,8 +1873,8 @@ class expected template< typename U nsel_REQUIRES_T( - std::is_move_constructible::value && - std::is_convertible::value + std::is_move_constructible< T>::value + && std::is_convertible::value ) > value_type value_or( U && v ) && @@ -1379,8 +1916,14 @@ class expected // 'see below' then(F&& func); private: - bool has_value_; - detail::storage_t contained; + detail::storage_t + < + T + ,E + , std::is_copy_constructible::value && std::is_copy_constructible::value + , std::is_move_constructible::value && std::is_move_constructible::value + > + contained; }; /// class expected, void specialization @@ -1388,6 +1931,9 @@ class expected template< typename E > class expected { +private: + template< typename, typename > friend class expected; + public: using value_type = void; using error_type = E; @@ -1396,73 +1942,56 @@ class expected // x.x.4.1 constructors constexpr expected() noexcept - : has_value_( true ) - { - } - - nsel_constexpr14 expected( expected const & other ) - : has_value_( other.has_value_ ) - { - if ( ! has_value() ) contained.construct_error( other.contained.error() ); - } + : contained( true ) + {} - nsel_REQUIRES_0( - std::is_move_constructible::value - ) - nsel_constexpr14 expected( expected && other ) noexcept - ( - true // TBD - see also non-void specialization - ) - : has_value_( other.has_value_ ) - { - if ( ! has_value() ) contained.construct_error( std::move( other.contained.error() ) ); - } + nsel_constexpr14 expected( expected const & other ) = default; + nsel_constexpr14 expected( expected && other ) = default; constexpr explicit expected( nonstd_lite_in_place_t(void) ) - : has_value_( true ) - { - } + : contained( true ) + {} - template< typename G = E > - nsel_constexpr14 explicit expected( nonstd::unexpected_type const & error - nsel_REQUIRES_A( - !std::is_convertible::value /*=> explicit */ + template< typename G = E + nsel_REQUIRES_T( + !std::is_convertible::value /*=> explicit */ ) - ) - : has_value_( false ) + > + nsel_constexpr14 explicit expected( nonstd::unexpected_type const & error ) + : contained( false ) { - contained.construct_error( error.value() ); + contained.construct_error( E{ error.value() } ); } - template< typename G = E > - nsel_constexpr14 /*non-explicit*/ expected( nonstd::unexpected_type const & error - nsel_REQUIRES_A( - std::is_convertible::value /*=> non-explicit */ + template< typename G = E + nsel_REQUIRES_T( + std::is_convertible::value /*=> non-explicit */ ) - ) - : has_value_( false ) + > + nsel_constexpr14 /*non-explicit*/ expected( nonstd::unexpected_type const & error ) + : contained( false ) { contained.construct_error( error.value() ); } - template< typename G = E > - nsel_constexpr14 explicit expected( nonstd::unexpected_type && error - nsel_REQUIRES_A( + template< typename G = E + nsel_REQUIRES_T( !std::is_convertible::value /*=> explicit */ ) - ) - : has_value_( false ) + > + nsel_constexpr14 explicit expected( nonstd::unexpected_type && error ) + : contained( false ) { - contained.construct_error( std::move( error.value() ) ); + contained.construct_error( E{ std::move( error.value() ) } ); } - template< typename G = E > - nsel_constexpr14 /*non-explicit*/ expected( nonstd::unexpected_type && error - nsel_REQUIRES_A( + template< typename G = E + nsel_REQUIRES_T( std::is_convertible::value /*=> non-explicit */ ) - ) - : has_value_( false ) + > + nsel_constexpr14 /*non-explicit*/ expected( nonstd::unexpected_type && error ) + : contained( false ) { contained.construct_error( std::move( error.value() ) ); } @@ -1473,46 +2002,40 @@ class expected ) > nsel_constexpr14 explicit expected( unexpect_t, Args&&... args ) - : has_value_( false ) + : contained( false ) { - contained.construct_error( std::forward( args )... ); + contained.emplace_error( std::forward( args )... ); } template< typename U, typename... Args nsel_REQUIRES_T( - std::is_constructible, Args&&...>::value + std::is_constructible, Args&&...>::value ) > nsel_constexpr14 explicit expected( unexpect_t, std::initializer_list il, Args&&... args ) - : has_value_( false ) + : contained( false ) { - contained.construct_error( il, std::forward( args )... ); + contained.emplace_error( il, std::forward( args )... ); } - // destructor ~expected() { - if ( ! has_value() ) contained.destruct_error(); + if ( ! has_value() ) + { + contained.destruct_error(); + } } // x.x.4.3 assignment -// nsel_REQUIRES_A( -// std::is_copy_constructible::value && -// std::is_copy_assignable::value ) - expected & operator=( expected const & other ) { expected( other ).swap( *this ); return *this; } -// nsel_REQUIRES_A( -// std::is_move_constructible::value && -// std::is_move_assignable::value ) - expected & operator=( expected && other ) noexcept ( std::is_nothrow_move_assignable::value && @@ -1523,27 +2046,31 @@ class expected } void emplace() - {} + { + expected().swap( *this ); + } // x.x.4.4 swap -// nsel_REQUIRES_A( -// std::is_move_constructible::value ) - - void swap( expected & other ) noexcept + template< typename G = E > + nsel_REQUIRES_R( void, + std17::is_swappable::value + && std::is_move_constructible::value + ) + swap( expected & other ) noexcept ( -#if nsel_CPP17_OR_GREATER - std::is_nothrow_move_constructible::value && std::is_nothrow_swappable::value -#else - std::is_nothrow_move_constructible::value && noexcept ( std::swap( std::declval(), std::declval() ) ) -#endif + std::is_nothrow_move_constructible::value && std17::is_nothrow_swappable::value ) { using std::swap; if ( ! bool(*this) && ! bool(other) ) { swap( contained.error(), other.contained.error() ); } else if ( bool(*this) && ! bool(other) ) { contained.construct_error( std::move( other.error() ) ); - swap( has_value_, other.has_value_ ); } + bool has_value = contained.has_value(); + bool other_has_value = other.has_value(); + other.contained.set_has_value(has_value); + contained.set_has_value(other_has_value); + } else if ( ! bool(*this) && bool(other) ) { other.swap( *this ); } } @@ -1556,11 +2083,16 @@ class expected constexpr bool has_value() const noexcept { - return has_value_; + return contained.has_value(); } void value() const - {} + { + if ( ! has_value() ) + { + error_traits::rethrow( contained.error() ); + } + } constexpr error_type const & error() const & { @@ -1572,16 +2104,20 @@ class expected return assert( ! has_value() ), contained.error(); } +#if !nsel_COMPILER_GNUC_VERSION || nsel_COMPILER_GNUC_VERSION >= 490 + constexpr error_type const && error() const && { - return assert( ! has_value() ), std::move( contained.error() ); + return std::move( ( assert( ! has_value() ), contained.error() ) ); } error_type && error() && { - return assert( ! has_value() ), std::move( contained.error() ); + return std::move( ( assert( ! has_value() ), contained.error() ) ); } +#endif + constexpr unexpected_type get_unexpected() const { return make_unexpected( contained.error() ); @@ -1590,7 +2126,8 @@ class expected template< typename Ex > bool has_exception() const { - return ! has_value() && std::is_base_of< Ex, decltype( get_unexpected().value() ) >::value; + using ContainedEx = typename std::remove_reference< decltype( get_unexpected().value() ) >::type; + return ! has_value() && std::is_base_of< Ex, ContainedEx>::value; } // template constexpr 'see below' unwrap() const&; @@ -1615,24 +2152,38 @@ class expected // 'see below' then(F&& func); private: - bool has_value_; - detail::storage_t contained; + detail::storage_t + < + void + , E + , std::is_copy_constructible::value + , std::is_move_constructible::value + > + contained; }; -// expected: relational operators +// x.x.4.6 expected<>: comparison operators -template< typename T, typename E > -constexpr bool operator==( expected const & x, expected const & y ) +template< typename T1, typename E1, typename T2, typename E2 > +constexpr bool operator==( expected const & x, expected const & y ) { - return bool(x) != bool(y) ? false : bool(x) == false ? true : *x == *y; + return bool(x) != bool(y) ? false : bool(x) == false ? x.error() == y.error() : *x == *y; } -template< typename T, typename E > -constexpr bool operator!=( expected const & x, expected const & y ) +template< typename T1, typename E1, typename T2, typename E2 > +constexpr bool operator!=( expected const & x, expected const & y ) { return !(x == y); } +template< typename E1, typename E2 > +constexpr bool operator==( expected const & x, expected const & y ) +{ + return bool(x) != bool(y) ? false : bool(x) == false ? x.error() == y.error() : true; +} + +#if nsel_P0323R <= 2 + template< typename T, typename E > constexpr bool operator<( expected const & x, expected const & y ) { @@ -1657,161 +2208,173 @@ constexpr bool operator>=( expected const & x, expected const & y ) return !(x < y); } -// expected: comparison with unexpected_type +#endif + +// x.x.4.7 expected: comparison with T -template< typename T, typename E > -constexpr bool operator==( expected const & x, unexpected_type const & u ) +template< typename T1, typename E1, typename T2 > +constexpr bool operator==( expected const & x, T2 const & v ) { - return (!x) ? x.get_unexpected() == u : false; + return bool(x) ? *x == v : false; } -template< typename T, typename E > -constexpr bool operator==( unexpected_type const & u, expected const & x ) +template< typename T1, typename E1, typename T2 > +constexpr bool operator==(T2 const & v, expected const & x ) { - return ( x == u ); + return bool(x) ? v == *x : false; } -template< typename T, typename E > -constexpr bool operator!=( expected const & x, unexpected_type const & u ) +template< typename T1, typename E1, typename T2 > +constexpr bool operator!=( expected const & x, T2 const & v ) { - return ! ( x == u ); + return bool(x) ? *x != v : true; } -template< typename T, typename E > -constexpr bool operator!=( unexpected_type const & u, expected const & x ) +template< typename T1, typename E1, typename T2 > +constexpr bool operator!=( T2 const & v, expected const & x ) { - return ! ( x == u ); + return bool(x) ? v != *x : true; } +#if nsel_P0323R <= 2 + template< typename T, typename E > -constexpr bool operator<( expected const & x, unexpected_type const & u ) +constexpr bool operator<( expected const & x, T const & v ) { - return (!x) ? ( x.get_unexpected() < u ) : false; + return bool(x) ? *x < v : true; } -#if nsel_P0323R <= 2 - template< typename T, typename E > -constexpr bool operator<( unexpected_type const & u, expected const & x ) +constexpr bool operator<( T const & v, expected const & x ) { - return (!x) ? ( u < x.get_unexpected() ) : true ; + return bool(x) ? v < *x : false; } template< typename T, typename E > -constexpr bool operator>( expected const & x, unexpected_type const & u ) +constexpr bool operator>( T const & v, expected const & x ) { - return ( u < x ); + return bool(x) ? *x < v : false; } template< typename T, typename E > -constexpr bool operator>( unexpected_type const & u, expected const & x ) +constexpr bool operator>( expected const & x, T const & v ) { - return ( x < u ); + return bool(x) ? v < *x : false; } template< typename T, typename E > -constexpr bool operator<=( expected const & x, unexpected_type const & u ) +constexpr bool operator<=( T const & v, expected const & x ) { - return ! ( u < x ); + return bool(x) ? ! ( *x < v ) : false; } template< typename T, typename E > -constexpr bool operator<=( unexpected_type const & u, expected const & x) +constexpr bool operator<=( expected const & x, T const & v ) { - return ! ( x < u ); + return bool(x) ? ! ( v < *x ) : true; } template< typename T, typename E > -constexpr bool operator>=( expected const & x, unexpected_type const & u ) +constexpr bool operator>=( expected const & x, T const & v ) { - return ! ( u > x ); + return bool(x) ? ! ( *x < v ) : false; } template< typename T, typename E > -constexpr bool operator>=( unexpected_type const & u, expected const & x ) +constexpr bool operator>=( T const & v, expected const & x ) { - return ! ( x > u ); + return bool(x) ? ! ( v < *x ) : true; } #endif // nsel_P0323R -// expected: comparison with T +// x.x.4.8 expected: comparison with unexpected_type -template< typename T, typename E > -constexpr bool operator==( expected const & x, T const & v ) +template< typename T1, typename E1 , typename E2 > +constexpr bool operator==( expected const & x, unexpected_type const & u ) { - return bool(x) ? *x == v : false; + return (!x) ? x.get_unexpected() == u : false; } -template< typename T, typename E > -constexpr bool operator==(T const & v, expected const & x ) +template< typename T1, typename E1 , typename E2 > +constexpr bool operator==( unexpected_type const & u, expected const & x ) { - return bool(x) ? v == *x : false; + return ( x == u ); } -template< typename T, typename E > -constexpr bool operator!=( expected const & x, T const & v ) +template< typename T1, typename E1 , typename E2 > +constexpr bool operator!=( expected const & x, unexpected_type const & u ) { - return bool(x) ? *x != v : true; + return ! ( x == u ); } -template< typename T, typename E > -constexpr bool operator!=( T const & v, expected const & x ) +template< typename T1, typename E1 , typename E2 > +constexpr bool operator!=( unexpected_type const & u, expected const & x ) { - return bool(x) ? v != *x : true; + return ! ( x == u ); } +#if nsel_P0323R <= 2 + template< typename T, typename E > -constexpr bool operator<( expected const & x, T const & v ) +constexpr bool operator<( expected const & x, unexpected_type const & u ) { - return bool(x) ? *x < v : true; + return (!x) ? ( x.get_unexpected() < u ) : false; } template< typename T, typename E > -constexpr bool operator<( T const & v, expected const & x ) +constexpr bool operator<( unexpected_type const & u, expected const & x ) { - return bool(x) ? v < *x : false; + return (!x) ? ( u < x.get_unexpected() ) : true ; } template< typename T, typename E > -constexpr bool operator>( T const & v, expected const & x ) +constexpr bool operator>( expected const & x, unexpected_type const & u ) { - return bool(x) ? *x < v : false; + return ( u < x ); } template< typename T, typename E > -constexpr bool operator>( expected const & x, T const & v ) +constexpr bool operator>( unexpected_type const & u, expected const & x ) { - return bool(x) ? v < *x : false; + return ( x < u ); } template< typename T, typename E > -constexpr bool operator<=( T const & v, expected const & x ) +constexpr bool operator<=( expected const & x, unexpected_type const & u ) { - return bool(x) ? ! ( *x < v ) : false; + return ! ( u < x ); } template< typename T, typename E > -constexpr bool operator<=( expected const & x, T const & v ) +constexpr bool operator<=( unexpected_type const & u, expected const & x) { - return bool(x) ? ! ( v < *x ) : true; + return ! ( x < u ); } template< typename T, typename E > -constexpr bool operator>=( expected const & x, T const & v ) +constexpr bool operator>=( expected const & x, unexpected_type const & u ) { - return bool(x) ? ! ( *x < v ) : false; + return ! ( u > x ); } template< typename T, typename E > -constexpr bool operator>=( T const & v, expected const & x ) +constexpr bool operator>=( unexpected_type const & u, expected const & x ) { - return bool(x) ? ! ( v < *x ) : true; + return ! ( x > u ); } +#endif // nsel_P0323R + /// x.x.x Specialized algorithms -template< typename T, typename E > +template< typename T, typename E + nsel_REQUIRES_T( + ( std::is_void::value || std::is_move_constructible::value ) + && std::is_move_constructible::value + && std17::is_swappable::value + && std17::is_swappable::value ) +> void swap( expected & x, expected & y ) noexcept ( noexcept ( x.swap(y) ) ) { x.swap( y ); @@ -1850,11 +2413,11 @@ constexpr auto make_expected_from_error( E e ) -> expected::type>( make_unexpected( e ) ); } -template< typename F > +template< typename F + nsel_REQUIRES_T( ! std::is_same::type, void>::value ) +> /*nsel_constexpr14*/ -auto make_expected_from_call( F f, - nsel_REQUIRES_A( ! std::is_same::type, void>::value ) -) -> expected< typename std::result_of::type > +auto make_expected_from_call( F f ) -> expected< typename std::result_of::type > { try { @@ -1866,11 +2429,11 @@ auto make_expected_from_call( F f, } } -template< typename F > +template< typename F + nsel_REQUIRES_T( std::is_same::type, void>::value ) +> /*nsel_constexpr14*/ -auto make_expected_from_call( F f, - nsel_REQUIRES_A( std::is_same::type, void>::value ) -) -> expected +auto make_expected_from_call( F f ) -> expected { try { @@ -1901,7 +2464,7 @@ namespace std { template< typename T, typename E > struct hash< nonstd::expected > { - using result_type = typename hash::result_type; + using result_type = std::size_t; using argument_type = nonstd::expected; constexpr result_type operator()(argument_type const & arg) const @@ -1914,7 +2477,7 @@ struct hash< nonstd::expected > template< typename T, typename E > struct hash< nonstd::expected > { - using result_type = typename hash::result_type; + using result_type = std::size_t; using argument_type = nonstd::expected; constexpr result_type operator()(argument_type const & arg) const @@ -1939,7 +2502,7 @@ namespace nonstd { // void unexpected() is deprecated && removed in C++17 -#if nsel_CPP17_OR_GREATER && nsel_COMPILER_MSVC_VERSION > 141 +#if nsel_CPP17_OR_GREATER || nsel_COMPILER_MSVC_VERSION > 141 template< typename E > using unexpected = unexpected_type; #endif From 474f33ba84913506d0e12f3d58a438fc986d05e3 Mon Sep 17 00:00:00 2001 From: Adam Sasine Date: Tue, 13 Sep 2022 10:31:50 -0400 Subject: [PATCH 201/709] Added XML validation for decorators without children (#424) * Added unit tests to demonstrate failure * Added validation that decorators have only one child --- include/behaviortree_cpp_v3/xml_parsing.h | 4 ++- src/xml_parsing.cpp | 20 ++++++++++---- tests/gtest_factory.cpp | 32 +++++++++++++++++++++++ 3 files changed, 50 insertions(+), 6 deletions(-) diff --git a/include/behaviortree_cpp_v3/xml_parsing.h b/include/behaviortree_cpp_v3/xml_parsing.h index 5ffeb5016..6537c140e 100644 --- a/include/behaviortree_cpp_v3/xml_parsing.h +++ b/include/behaviortree_cpp_v3/xml_parsing.h @@ -3,6 +3,8 @@ #include "behaviortree_cpp_v3/bt_parser.h" +#include + namespace BT { @@ -38,7 +40,7 @@ class XMLParser: public Parser }; void VerifyXML(const std::string& xml_text, - const std::set ®istered_nodes); + const std::unordered_map ®istered_nodes); std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory, bool include_builtin = false); diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 758105c69..ce3734ecf 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -214,25 +214,25 @@ void XMLParser::Pimpl::loadDocImpl(BT_TinyXML2::XMLDocument* doc, bool add_inclu tree_roots.insert( {tree_name, bt_node} ); } - std::set registered_nodes; + std::unordered_map registered_nodes; XMLPrinter printer; doc->Print(&printer); auto xml_text = std::string(printer.CStr(), size_t(printer.CStrSize() - 1)); for( const auto& it: factory.manifests()) { - registered_nodes.insert( it.first ); + registered_nodes.insert({it.first, it.second.type}); } for( const auto& it: tree_roots) { - registered_nodes.insert( it.first ); + registered_nodes.insert({it.first, NodeType::SUBTREE}); } VerifyXML(xml_text, registered_nodes); } void VerifyXML(const std::string& xml_text, - const std::set& registered_nodes) + const std::unordered_map& registered_nodes) { BT_TinyXML2::XMLDocument doc; @@ -391,12 +391,22 @@ void VerifyXML(const std::string& xml_text, else { // search in the factory and the list of subtrees - bool found = ( registered_nodes.find(name) != registered_nodes.end() ); + const auto search = registered_nodes.find(name); + bool found = ( search != registered_nodes.end() ); if (!found) { ThrowError(node->GetLineNum(), std::string("Node not recognized: ") + name); } + + if (search->second == NodeType::DECORATOR) + { + if (children_count != 1) + { + ThrowError(node->GetLineNum(), + std::string("The node <") + name + "> must have exactly 1 child"); + } + } } //recursion if (StrEqual(name, "SubTree") == false) diff --git a/tests/gtest_factory.cpp b/tests/gtest_factory.cpp index 50793acc4..60e1fe3c8 100644 --- a/tests/gtest_factory.cpp +++ b/tests/gtest_factory.cpp @@ -359,3 +359,35 @@ TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromChildDirectoryW ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); } #endif + +TEST(BehaviorTreeFactory, DecoratorWithoutChildThrows) +{ + BehaviorTreeFactory factory; + const std::string tree_xml = R"( + + + + + + +)"; + + ASSERT_THROW(factory.createTreeFromText(tree_xml), BehaviorTreeException); +} + +TEST(BehaviorTreeFactory, DecoratorWithTwoChildrenThrows) +{ + BehaviorTreeFactory factory; + const std::string tree_xml = R"( + + + + + + + + +)"; + + ASSERT_THROW(factory.createTreeFromText(xml_text), BehaviorTreeException); +} From 22ecdd4c73632fd76fab16cd2c7efb9747beca36 Mon Sep 17 00:00:00 2001 From: Paul Bovbel Date: Thu, 15 Sep 2022 11:13:04 -0400 Subject: [PATCH 202/709] Added ros_environment dependency to make sure ROS_VERSION is initialized (#420) --- package.xml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/package.xml b/package.xml index 670da05e2..9588ea247 100644 --- a/package.xml +++ b/package.xml @@ -13,6 +13,8 @@ Michele Colledanchise Davide Faconti + ros_environment + catkin roslib @@ -23,7 +25,7 @@ boost libzmq3-dev libncurses-dev - + ament_cmake_gtest From 2b6ecbac4e1da23cb7f9515106c80874eca2b542 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 23 Sep 2022 23:26:41 +0200 Subject: [PATCH 203/709] fix issue #433 --- src/blackboard.cpp | 15 +++++++++++++-- tests/gtest_subtree.cpp | 36 ++++++++++++++++++++++++++++++++++++ 2 files changed, 49 insertions(+), 2 deletions(-) diff --git a/src/blackboard.cpp b/src/blackboard.cpp index fdf0bf379..2a1307f86 100644 --- a/src/blackboard.cpp +++ b/src/blackboard.cpp @@ -12,6 +12,7 @@ void Blackboard::setPortInfo(std::string key, const PortInfo& info) if( remapping_it != internal_to_external_.end()) { parent->setPortInfo( remapping_it->second, info ); + return; } } @@ -25,8 +26,8 @@ void Blackboard::setPortInfo(std::string key, const PortInfo& info) if( old_type && old_type != info.type() ) { throw LogicError( "Blackboard::set() failed: once declared, the type of a port shall not change. " - "Declared type [", BT::demangle( old_type ), - "] != current type [", BT::demangle( info.type() ), "]" ); + "Previously declared type [", BT::demangle( old_type ), + "] != new type [", BT::demangle( info.type() ), "]" ); } } } @@ -34,6 +35,16 @@ void Blackboard::setPortInfo(std::string key, const PortInfo& info) const PortInfo* Blackboard::portInfo(const std::string &key) { std::unique_lock lock(mutex_); + + if( auto parent = parent_bb_.lock()) + { + auto remapping_it = internal_to_external_.find(key); + if( remapping_it != internal_to_external_.end()) + { + return parent->portInfo( remapping_it->second ); + } + } + auto it = storage_.find(key); if( it == storage_.end() ) { diff --git a/tests/gtest_subtree.cpp b/tests/gtest_subtree.cpp index c79fd8182..cf505aa8c 100644 --- a/tests/gtest_subtree.cpp +++ b/tests/gtest_subtree.cpp @@ -275,5 +275,41 @@ TEST(SubTree, SubtreePlusD) ASSERT_EQ(ret, BT::NodeStatus::SUCCESS); } +TEST(SubTree, SubtreeIssue433) +{ + BT::NodeConfiguration config; + config.blackboard = BT::Blackboard::create(); + static const char* xml_text = R"( + + + + + + + + + + + + + + + + + + + + )"; + + BT::BehaviorTreeFactory factory; + + BT::Tree tree = factory.createTreeFromText(xml_text, config.blackboard); + auto ret = tree.tickRoot(); + + ASSERT_EQ(ret, BT::NodeStatus::SUCCESS); +} + + + From d23578bbd1b6745ff9ac718efea632d259b72573 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 23 Sep 2022 23:28:57 +0200 Subject: [PATCH 204/709] fix warnings --- include/behaviortree_cpp_v3/bt_factory.h | 2 +- src/bt_factory.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index 09a1c782f..262344a68 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -79,7 +79,7 @@ template inline template inline TreeNodeManifest CreateManifest(const std::string& ID, PortsList portlist = getProvidedPorts()) { - return { getType(), ID, portlist }; + return { getType(), ID, portlist, {} }; } diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 21cde3184..27c2a79df 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -109,7 +109,7 @@ void BehaviorTreeFactory::registerSimpleCondition(const std::string& ID, return std::make_unique(name, tick_functor, config); }; - TreeNodeManifest manifest = { NodeType::CONDITION, ID, std::move(ports) }; + TreeNodeManifest manifest = { NodeType::CONDITION, ID, std::move(ports), {} }; registerBuilder(manifest, builder); } @@ -121,7 +121,7 @@ void BehaviorTreeFactory::registerSimpleAction(const std::string& ID, return std::make_unique(name, tick_functor, config); }; - TreeNodeManifest manifest = { NodeType::ACTION, ID, std::move(ports) }; + TreeNodeManifest manifest = { NodeType::ACTION, ID, std::move(ports), {} }; registerBuilder(manifest, builder); } @@ -133,7 +133,7 @@ void BehaviorTreeFactory::registerSimpleDecorator(const std::string& ID, return std::make_unique(name, tick_functor, config); }; - TreeNodeManifest manifest = { NodeType::DECORATOR, ID, std::move(ports) }; + TreeNodeManifest manifest = { NodeType::DECORATOR, ID, std::move(ports), {} }; registerBuilder(manifest, builder); } From efc28b1d06a8faa44a40515798feea3b45847113 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Tue, 27 Sep 2022 12:42:29 +0200 Subject: [PATCH 205/709] Update README.md --- README.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 72eac0269..6d0063a35 100644 --- a/README.md +++ b/README.md @@ -161,7 +161,10 @@ The Preprint version (free) is available here: https://arxiv.org/abs/1709.00084 The MIT License (MIT) Copyright (c) 2014-2018 Michele Colledanchise -Copyright (c) 2018-2021 Davide Faconti + +Copyright (c) 2018-2019 Davide Faconti, Eurecat + +Copyright (c) 2019-2021 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 From cc7717108276bc687c57a9b63cb1a4a7b1f94b8f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 28 Sep 2022 12:43:31 +0200 Subject: [PATCH 206/709] backporting changes from v4.x --- include/behaviortree_cpp_v3/action_node.h | 9 ++-- .../actions/always_failure_node.h | 4 +- .../actions/always_success_node.h | 4 +- .../actions/pop_from_queue.hpp | 7 +-- include/behaviortree_cpp_v3/basic_types.h | 6 +++ include/behaviortree_cpp_v3/behavior_tree.h | 1 + include/behaviortree_cpp_v3/blackboard.h | 48 ++++++++----------- include/behaviortree_cpp_v3/bt_parser.h | 17 +++++-- include/behaviortree_cpp_v3/condition_node.h | 5 +- include/behaviortree_cpp_v3/control_node.h | 4 +- .../controls/fallback_node.h | 4 +- .../controls/if_then_else_node.h | 6 +-- .../controls/manual_node.h | 6 +-- .../controls/parallel_node.h | 14 +++--- .../controls/reactive_fallback.h | 6 +-- .../controls/reactive_sequence.h | 6 +-- .../controls/sequence_node.h | 4 +- .../controls/sequence_star_node.h | 4 +- .../controls/switch_node.h | 34 +++++-------- .../controls/while_do_else_node.h | 6 +-- .../decorators/consume_queue.h | 7 +-- .../decorators/delay_node.h | 4 +- .../decorators/force_failure_node.h | 4 +- .../decorators/force_success_node.h | 4 +- .../decorators/inverter_node.h | 5 +- .../keep_running_until_failure_node.h | 4 +- .../decorators/repeat_node.h | 8 ++-- .../decorators/retry_node.h | 8 ++-- .../decorators/timeout_node.h | 6 +-- .../decorators/timer_queue.h | 5 +- include/behaviortree_cpp_v3/tree_node.h | 9 ++-- .../utils/wakeup_signal.hpp | 5 +- src/action_node.cpp | 11 +++-- src/blackboard.cpp | 4 +- src/control_node.cpp | 3 +- src/decorator_node.cpp | 5 +- src/decorators/repeat_node.cpp | 14 +++--- src/decorators/retry_node.cpp | 14 +++--- src/tree_node.cpp | 10 +++- tests/gtest_factory.cpp | 18 ++++--- tests/include/action_test_node.h | 2 +- tests/src/action_test_node.cpp | 2 +- 42 files changed, 156 insertions(+), 191 deletions(-) diff --git a/include/behaviortree_cpp_v3/action_node.h b/include/behaviortree_cpp_v3/action_node.h index 9fca24cbe..7417cdf4d 100644 --- a/include/behaviortree_cpp_v3/action_node.h +++ b/include/behaviortree_cpp_v3/action_node.h @@ -25,10 +25,9 @@ namespace BT { // IMPORTANT: Actions which returned SUCCESS or FAILURE will not be ticked -// again unless setStatus(IDLE) is called first. +// again unless resetStatus() is called first. // Keep this in mind when writing your custom Control and Decorator nodes. - /** * @brief The ActionNodeBase is the base class to use to create any kind of action. * A particular derived class is free to override executeTick() as needed. @@ -64,9 +63,7 @@ class SyncActionNode : public ActionNodeBase /// You don't need to override this virtual void halt() override final - { - setStatus(NodeStatus::IDLE); - } + { } }; /** @@ -140,7 +137,7 @@ class AsyncActionNode : public ActionNodeBase std::exception_ptr exptr_; std::atomic_bool halt_requested_; std::future thread_handle_; - std::mutex m_; + std::mutex mutex_; }; /** diff --git a/include/behaviortree_cpp_v3/actions/always_failure_node.h b/include/behaviortree_cpp_v3/actions/always_failure_node.h index 495cb44a2..0455bbe1e 100644 --- a/include/behaviortree_cpp_v3/actions/always_failure_node.h +++ b/include/behaviortree_cpp_v3/actions/always_failure_node.h @@ -10,8 +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. */ -#ifndef ACTION_ALWAYS_FAILURE_NODE_H -#define ACTION_ALWAYS_FAILURE_NODE_H +#pragma once #include "behaviortree_cpp_v3/action_node.h" @@ -37,4 +36,3 @@ class AlwaysFailureNode : public SyncActionNode }; } -#endif diff --git a/include/behaviortree_cpp_v3/actions/always_success_node.h b/include/behaviortree_cpp_v3/actions/always_success_node.h index ca82b7bc0..593be88a2 100644 --- a/include/behaviortree_cpp_v3/actions/always_success_node.h +++ b/include/behaviortree_cpp_v3/actions/always_success_node.h @@ -10,8 +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. */ -#ifndef ACTION_ALWAYS_SUCCESS_NODE_H -#define ACTION_ALWAYS_SUCCESS_NODE_H +#pragma once #include "behaviortree_cpp_v3/action_node.h" @@ -37,4 +36,3 @@ class AlwaysSuccessNode : public SyncActionNode }; } -#endif diff --git a/include/behaviortree_cpp_v3/actions/pop_from_queue.hpp b/include/behaviortree_cpp_v3/actions/pop_from_queue.hpp index 3a75875c8..c1e8a82e5 100644 --- a/include/behaviortree_cpp_v3/actions/pop_from_queue.hpp +++ b/include/behaviortree_cpp_v3/actions/pop_from_queue.hpp @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2022 Davide Faconti, Eurecat - All Rights Reserved +/* Copyright (C) 2022 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,9 +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. */ - -#ifndef BEHAVIORTREE_POPFROMQUEUE_HPP -#define BEHAVIORTREE_POPFROMQUEUE_HPP +#pragma once #include #include @@ -145,4 +143,3 @@ class QueueSize : public SyncActionNode } -#endif // BEHAVIORTREE_POPFROMQUEUE_HPP diff --git a/include/behaviortree_cpp_v3/basic_types.h b/include/behaviortree_cpp_v3/basic_types.h index 8d87c117c..3627da42e 100644 --- a/include/behaviortree_cpp_v3/basic_types.h +++ b/include/behaviortree_cpp_v3/basic_types.h @@ -40,6 +40,12 @@ enum class NodeStatus FAILURE }; +inline bool StatusCompleted(const NodeStatus& status) +{ + return status == NodeStatus::SUCCESS || + status == NodeStatus::FAILURE; +} + enum class PortDirection{ INPUT, OUTPUT, diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index d3052f7e0..150d32c74 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -89,6 +89,7 @@ inline NodeType getType() return NodeType::UNDEFINED; // clang-format on } + } #endif // BEHAVIOR_TREE_H diff --git a/include/behaviortree_cpp_v3/blackboard.h b/include/behaviortree_cpp_v3/blackboard.h index ee1b61b93..1bfcf1a7e 100644 --- a/include/behaviortree_cpp_v3/blackboard.h +++ b/include/behaviortree_cpp_v3/blackboard.h @@ -51,7 +51,7 @@ class Blackboard const Any* getAny(const std::string& key) const { std::unique_lock lock(mutex_); - + // search first if this port was remapped if( auto parent = parent_bb_.lock()) { auto remapping_it = internal_to_external_.find(key); @@ -67,7 +67,7 @@ class Blackboard Any* getAny(const std::string& key) { std::unique_lock lock(mutex_); - + // search first if this port was remapped if( auto parent = parent_bb_.lock()) { auto remapping_it = internal_to_external_.find(key); @@ -118,39 +118,33 @@ class Blackboard { std::unique_lock lock_entry(entry_mutex_); std::unique_lock lock(mutex_); - auto it = storage_.find(key); - if( auto parent = parent_bb_.lock()) + // search first if this port was remapped. + // Change the parent_bb_ in that case + auto remapping_it = internal_to_external_.find(key); + if( remapping_it != internal_to_external_.end()) { - auto remapping_it = internal_to_external_.find(key); - if( remapping_it != internal_to_external_.end()) + const auto& remapped_key = remapping_it->second; + if( auto parent = parent_bb_.lock()) { - const auto& remapped_key = remapping_it->second; - if( it == storage_.end() ) // virgin entry - { - auto parent_info = parent->portInfo(remapped_key); - if( parent_info ) - { - storage_.emplace( key, Entry( *parent_info ) ); - } - else{ - storage_.emplace( key, Entry( PortInfo() ) ); - } - } parent->set( remapped_key, value ); return; } } - if( it != storage_.end() ) // already there. check the type + // check local storage + auto it = storage_.find(key); + if( it != storage_.end() ) { const PortInfo& port_info = it->second.port_info; auto& previous_any = it->second.value; - const auto locked_type = port_info.type(); + const auto previous_type = port_info.type(); - Any temp(value); + Any new_value(value); - if( locked_type && *locked_type != typeid(T) && *locked_type != temp.type() ) + if( previous_type && + *previous_type != typeid(T) && + *previous_type != new_value.type() ) { bool mismatching = true; if( std::is_constructible::value ) @@ -159,7 +153,7 @@ class Blackboard if( any_from_string.empty() == false) { mismatching = false; - temp = std::move( any_from_string ); + new_value = std::move( any_from_string ); } } @@ -168,11 +162,11 @@ class Blackboard debugMessage(); throw LogicError( "Blackboard::set() failed: once declared, the type of a port shall not change. " - "Declared type [", demangle( locked_type ), - "] != current type [", demangle( typeid(T) ),"]" ); + "Declared type [", BT::demangle(previous_type), + "] != current type [", BT::demangle(typeid(T)),"]" ); } } - previous_any = std::move(temp); + previous_any = std::move(new_value); } else{ // create for the first time without any info storage_.emplace( key, Entry( Any(value), PortInfo() ) ); @@ -201,7 +195,7 @@ class Blackboard // done using the value. std::mutex& entryMutex() { - return entry_mutex_; + return entry_mutex_; } private: diff --git a/include/behaviortree_cpp_v3/bt_parser.h b/include/behaviortree_cpp_v3/bt_parser.h index 46e9b3aa4..f87978e70 100644 --- a/include/behaviortree_cpp_v3/bt_parser.h +++ b/include/behaviortree_cpp_v3/bt_parser.h @@ -1,5 +1,17 @@ -#ifndef PARSING_BT_H -#define PARSING_BT_H +/* Copyright (C) 2022 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. +*/ + + +#pragma once #include "behaviortree_cpp_v3/bt_factory.h" #include "behaviortree_cpp_v3/blackboard.h" @@ -32,4 +44,3 @@ class Parser } -#endif // PARSING_BT_H diff --git a/include/behaviortree_cpp_v3/condition_node.h b/include/behaviortree_cpp_v3/condition_node.h index 4dc11aaca..db332f408 100644 --- a/include/behaviortree_cpp_v3/condition_node.h +++ b/include/behaviortree_cpp_v3/condition_node.h @@ -26,10 +26,7 @@ class ConditionNode : public LeafNode virtual ~ConditionNode() override = default; //Do nothing - virtual void halt() override final - { - setStatus(NodeStatus::IDLE); - } + virtual void halt() override final {} virtual NodeType type() const override final { diff --git a/include/behaviortree_cpp_v3/control_node.h b/include/behaviortree_cpp_v3/control_node.h index 558b788d2..4a5de311c 100644 --- a/include/behaviortree_cpp_v3/control_node.h +++ b/include/behaviortree_cpp_v3/control_node.h @@ -11,8 +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. */ -#ifndef CONTROLNODE_H -#define CONTROLNODE_H +#pragma once #include #include "behaviortree_cpp_v3/tree_node.h" @@ -57,4 +56,3 @@ class ControlNode : public TreeNode }; } -#endif diff --git a/include/behaviortree_cpp_v3/controls/fallback_node.h b/include/behaviortree_cpp_v3/controls/fallback_node.h index 5492c8b39..bb9e64d27 100644 --- a/include/behaviortree_cpp_v3/controls/fallback_node.h +++ b/include/behaviortree_cpp_v3/controls/fallback_node.h @@ -11,8 +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. */ -#ifndef FALLBACKNODE_H -#define FALLBACKNODE_H +#pragma once #include "behaviortree_cpp_v3/control_node.h" @@ -47,4 +46,3 @@ class FallbackNode : public ControlNode } -#endif diff --git a/include/behaviortree_cpp_v3/controls/if_then_else_node.h b/include/behaviortree_cpp_v3/controls/if_then_else_node.h index 2e1ab401e..5cf136fed 100644 --- a/include/behaviortree_cpp_v3/controls/if_then_else_node.h +++ b/include/behaviortree_cpp_v3/controls/if_then_else_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2020 Davide Faconti - All Rights Reserved +/* Copyright (C) 2020-2022 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,8 +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. */ -#ifndef BT_IF_THEN_ELSE_H -#define BT_IF_THEN_ELSE_H +#pragma once #include "behaviortree_cpp_v3/control_node.h" @@ -49,4 +48,3 @@ class IfThenElseNode : public ControlNode } -#endif // BT_IF_THEN_ELSE_H diff --git a/include/behaviortree_cpp_v3/controls/manual_node.h b/include/behaviortree_cpp_v3/controls/manual_node.h index 895385b42..59215281e 100644 --- a/include/behaviortree_cpp_v3/controls/manual_node.h +++ b/include/behaviortree_cpp_v3/controls/manual_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2020 Davide Faconti - All Rights Reserved +/* Copyright (C) 2020-2022 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,8 +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. */ -#ifndef MANUAL_SELECTION_NODE_H -#define MANUAL_SELECTION_NODE_H +#pragma once #include "behaviortree_cpp_v3/control_node.h" @@ -56,4 +55,3 @@ class ManualSelectorNode : public ControlNode } -#endif // MANUAL_SELECTION_NODE_H diff --git a/include/behaviortree_cpp_v3/controls/parallel_node.h b/include/behaviortree_cpp_v3/controls/parallel_node.h index 1d81ab616..919680044 100644 --- a/include/behaviortree_cpp_v3/controls/parallel_node.h +++ b/include/behaviortree_cpp_v3/controls/parallel_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2020 Davide Faconti, Eurecat - All Rights Reserved + * Copyright (C) 2018-2022 Davide Faconti, Eurecat - 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,8 +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. */ -#ifndef PARALLEL_NODE_H -#define PARALLEL_NODE_H +#pragma once #include #include "behaviortree_cpp_v3/control_node.h" @@ -25,13 +24,13 @@ namespace BT * __concurrently__, but not in separate threads! * * Even if this may look similar to ReactiveSequence, - * this Control Node is the only one that may have - * multiple children in the RUNNING state at the same time. + * this Control Node is the __only__ one that can have + * multiple children RUNNING at the same time. * * The Node is completed either when the THRESHOLD_SUCCESS * or THRESHOLD_FAILURE number is reached (both configured using ports). * - * If any of the threahold is reached, and other childen are still running, + * If any of the threaholds is reached, and other children are still running, * they will be halted. * * Note that threshold indexes work as in Python: @@ -56,7 +55,7 @@ class ParallelNode : public ControlNode "number of childen which need to fail to trigger a FAILURE" ) }; } - ~ParallelNode() = default; + ~ParallelNode() override = default; virtual void halt() override; @@ -79,4 +78,3 @@ class ParallelNode : public ControlNode }; } -#endif // PARALLEL_NODE_H diff --git a/include/behaviortree_cpp_v3/controls/reactive_fallback.h b/include/behaviortree_cpp_v3/controls/reactive_fallback.h index 14b453c0b..063878c71 100644 --- a/include/behaviortree_cpp_v3/controls/reactive_fallback.h +++ b/include/behaviortree_cpp_v3/controls/reactive_fallback.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2020 Davide Faconti, Eurecat - All Rights Reserved +/* Copyright (C) 2020-2022 Davide Faconti, Eurecat - 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,8 +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. */ -#ifndef REACTIVE_FALLBACK_NODE_H -#define REACTIVE_FALLBACK_NODE_H +#pragma once #include "behaviortree_cpp_v3/control_node.h" @@ -45,4 +44,3 @@ class ReactiveFallback : public ControlNode }; } -#endif // REACTIVE_FALLBACK_NODE_H diff --git a/include/behaviortree_cpp_v3/controls/reactive_sequence.h b/include/behaviortree_cpp_v3/controls/reactive_sequence.h index aa0aa3b1b..f0682305d 100644 --- a/include/behaviortree_cpp_v3/controls/reactive_sequence.h +++ b/include/behaviortree_cpp_v3/controls/reactive_sequence.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2020 Davide Faconti, Eurecat - All Rights Reserved +/* Copyright (C) 2020-2022 Davide Faconti, Eurecat - 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,8 +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. */ -#ifndef REACTIVE_SEQUENCE_NODE_H -#define REACTIVE_SEQUENCE_NODE_H +#pragma once #include "behaviortree_cpp_v3/control_node.h" @@ -44,4 +43,3 @@ class ReactiveSequence : public ControlNode }; } -#endif // REACTIVE_SEQUENCE_NODE_H diff --git a/include/behaviortree_cpp_v3/controls/sequence_node.h b/include/behaviortree_cpp_v3/controls/sequence_node.h index 20baadce3..863768bad 100644 --- a/include/behaviortree_cpp_v3/controls/sequence_node.h +++ b/include/behaviortree_cpp_v3/controls/sequence_node.h @@ -11,8 +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. */ -#ifndef SEQUENCENODE_H -#define SEQUENCENODE_H +#pragma once #include "behaviortree_cpp_v3/control_node.h" @@ -48,4 +47,3 @@ class SequenceNode : public ControlNode } -#endif // SEQUENCENODE_H diff --git a/include/behaviortree_cpp_v3/controls/sequence_star_node.h b/include/behaviortree_cpp_v3/controls/sequence_star_node.h index 611a26f8f..448b1f247 100644 --- a/include/behaviortree_cpp_v3/controls/sequence_star_node.h +++ b/include/behaviortree_cpp_v3/controls/sequence_star_node.h @@ -11,8 +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. */ -#ifndef SEQUENCE_NODE_WITH_MEMORY_H -#define SEQUENCE_NODE_WITH_MEMORY_H +#pragma once #include "behaviortree_cpp_v3/control_node.h" @@ -50,4 +49,3 @@ class SequenceStarNode : public ControlNode } -#endif // SEQUENCE_NODE_WITH_MEMORY_H diff --git a/include/behaviortree_cpp_v3/controls/switch_node.h b/include/behaviortree_cpp_v3/controls/switch_node.h index 5095bf825..f3eebde67 100644 --- a/include/behaviortree_cpp_v3/controls/switch_node.h +++ b/include/behaviortree_cpp_v3/controls/switch_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2020 Davide Faconti - All Rights Reserved +/* Copyright (C) 2020-2022 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,8 +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. */ -#ifndef SWITCH_NODE_H -#define SWITCH_NODE_H +#pragma once #include "behaviortree_cpp_v3/control_node.h" @@ -80,9 +79,6 @@ class SwitchNode : public ControlNode template inline NodeStatus SwitchNode::tick() { - constexpr const char * case_port_names[9] = { - "case_1", "case_2", "case_3", "case_4", "case_5", "case_6", "case_7", "case_8", "case_9"}; - if( childrenCount() != NUM_CASES+1) { throw LogicError("Wrong number of children in SwitchNode; " @@ -91,43 +87,36 @@ NodeStatus SwitchNode::tick() std::string variable; std::string value; - int child_index = NUM_CASES; // default index; + int match_index = int(NUM_CASES); // default index; if (getInput("variable", variable)) // no variable? jump to default { // check each case until you find a match - for (unsigned index = 0; index < NUM_CASES; ++index) + for (int index = 0; index < int(NUM_CASES); ++index) { - bool found = false; - if( index < 9 ) - { - found = (bool)getInput(case_port_names[index], value); - } - else{ - char case_str[20]; - sprintf(case_str, "case_%d", index+1); - found = (bool)getInput(case_str, value); - } + char case_key[20]; + sprintf(case_key, "case_%d", int(index+1)); + bool found = static_cast(getInput(case_key, value)); if (found && variable == value) { - child_index = index; + match_index = index; break; } } } // if another one was running earlier, halt it - if( running_child_ != -1 && running_child_ != child_index) + if( running_child_ != -1 && running_child_ != match_index) { haltChild(running_child_); } - auto& selected_child = children_nodes_[child_index]; + auto& selected_child = children_nodes_[match_index]; NodeStatus ret = selected_child->executeTick(); if( ret == NodeStatus::RUNNING ) { - running_child_ = child_index; + running_child_ = match_index; } else{ haltChildren(); @@ -138,4 +127,3 @@ NodeStatus SwitchNode::tick() } -#endif // SWITCH_NODE_H diff --git a/include/behaviortree_cpp_v3/controls/while_do_else_node.h b/include/behaviortree_cpp_v3/controls/while_do_else_node.h index 21d393a92..5f359e719 100644 --- a/include/behaviortree_cpp_v3/controls/while_do_else_node.h +++ b/include/behaviortree_cpp_v3/controls/while_do_else_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2020 Davide Faconti - All Rights Reserved +/* Copyright (C) 2020-2022 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,8 +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. */ -#ifndef BT_WHILE_DO_ELSE_H -#define BT_WHILE_DO_ELSE_H +#pragma once #include "behaviortree_cpp_v3/control_node.h" @@ -47,4 +46,3 @@ class WhileDoElseNode : public ControlNode } -#endif // BT_WHILE_DO_ELSE_H diff --git a/include/behaviortree_cpp_v3/decorators/consume_queue.h b/include/behaviortree_cpp_v3/decorators/consume_queue.h index 6f7a2b0ea..f7ece8107 100644 --- a/include/behaviortree_cpp_v3/decorators/consume_queue.h +++ b/include/behaviortree_cpp_v3/decorators/consume_queue.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2022 Davide Faconti, Eurecat - All Rights Reserved +/* Copyright (C) 2022 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,9 +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. */ - -#ifndef BEHAVIORTREE_CONSUME_QUEUE_H -#define BEHAVIORTREE_CONSUME_QUEUE_H +#pragma once #include #include "behaviortree_cpp_v3/decorator_node.h" @@ -100,4 +98,3 @@ class ConsumeQueue : public DecoratorNode } -#endif // BEHAVIORTREE_CONSUME_QUEUE_H diff --git a/include/behaviortree_cpp_v3/decorators/delay_node.h b/include/behaviortree_cpp_v3/decorators/delay_node.h index 2fb85e85b..b255d8734 100644 --- a/include/behaviortree_cpp_v3/decorators/delay_node.h +++ b/include/behaviortree_cpp_v3/decorators/delay_node.h @@ -1,5 +1,4 @@ -#ifndef DECORATOR_DELAY_NODE_H -#define DECORATOR_DELAY_NODE_H +#pragma once #include "behaviortree_cpp_v3/decorator_node.h" #include @@ -59,4 +58,3 @@ class DelayNode : public DecoratorNode } // namespace BT -#endif // DELAY_NODE_H diff --git a/include/behaviortree_cpp_v3/decorators/force_failure_node.h b/include/behaviortree_cpp_v3/decorators/force_failure_node.h index 532beddde..98f2f2589 100644 --- a/include/behaviortree_cpp_v3/decorators/force_failure_node.h +++ b/include/behaviortree_cpp_v3/decorators/force_failure_node.h @@ -10,8 +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. */ -#ifndef DECORATOR_ALWAYS_FAILURE_NODE_H -#define DECORATOR_ALWAYS_FAILURE_NODE_H +#pragma once #include "behaviortree_cpp_v3/decorator_node.h" @@ -63,4 +62,3 @@ inline NodeStatus ForceFailureNode::tick() } } -#endif diff --git a/include/behaviortree_cpp_v3/decorators/force_success_node.h b/include/behaviortree_cpp_v3/decorators/force_success_node.h index 699d23f8e..ec7679b5e 100644 --- a/include/behaviortree_cpp_v3/decorators/force_success_node.h +++ b/include/behaviortree_cpp_v3/decorators/force_success_node.h @@ -10,8 +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. */ -#ifndef DECORATOR_ALWAYS_SUCCESS_NODE_H -#define DECORATOR_ALWAYS_SUCCESS_NODE_H +#pragma once #include "behaviortree_cpp_v3/decorator_node.h" @@ -63,4 +62,3 @@ inline NodeStatus ForceSuccessNode::tick() } } -#endif diff --git a/include/behaviortree_cpp_v3/decorators/inverter_node.h b/include/behaviortree_cpp_v3/decorators/inverter_node.h index 4d4a10371..5059855a7 100644 --- a/include/behaviortree_cpp_v3/decorators/inverter_node.h +++ b/include/behaviortree_cpp_v3/decorators/inverter_node.h @@ -11,8 +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. */ -#ifndef DECORATOR_INVERTER_NODE_H -#define DECORATOR_INVERTER_NODE_H +#pragma once #include "behaviortree_cpp_v3/decorator_node.h" @@ -35,4 +34,4 @@ class InverterNode : public DecoratorNode }; } -#endif + diff --git a/include/behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h b/include/behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h index af9c88fba..dc039a209 100644 --- a/include/behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h +++ b/include/behaviortree_cpp_v3/decorators/keep_running_until_failure_node.h @@ -11,8 +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. */ -#ifndef DECORATOR_KEEP_RUNNING_UNTIL_FAILURE_H -#define DECORATOR_KEEP_RUNNING_UNTIL_FAILURE_H +#pragma once #include "behaviortree_cpp_v3/decorator_node.h" @@ -63,4 +62,3 @@ inline NodeStatus KeepRunningUntilFailureNode::tick() } } -#endif diff --git a/include/behaviortree_cpp_v3/decorators/repeat_node.h b/include/behaviortree_cpp_v3/decorators/repeat_node.h index 35c45945f..f6ff5210a 100644 --- a/include/behaviortree_cpp_v3/decorators/repeat_node.h +++ b/include/behaviortree_cpp_v3/decorators/repeat_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2020 Davide Faconti, Eurecat - All Rights Reserved + * Copyright (C) 2018-2022 Davide Faconti, Eurecat - 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,8 +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. */ -#ifndef DECORATOR_REPEAT_NODE_H -#define DECORATOR_REPEAT_NODE_H +#pragma once #include "behaviortree_cpp_v3/decorator_node.h" @@ -52,7 +51,7 @@ class RepeatNode : public DecoratorNode private: int num_cycles_; - int try_index_; + int repeat_count_; bool read_parameter_from_ports_; static constexpr const char* NUM_CYCLES = "num_cycles"; @@ -64,4 +63,3 @@ class RepeatNode : public DecoratorNode } -#endif diff --git a/include/behaviortree_cpp_v3/decorators/retry_node.h b/include/behaviortree_cpp_v3/decorators/retry_node.h index 61d329348..7dd881276 100644 --- a/include/behaviortree_cpp_v3/decorators/retry_node.h +++ b/include/behaviortree_cpp_v3/decorators/retry_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2020 Davide Faconti, Eurecat - All Rights Reserved + * Copyright (C) 2018-2022 Davide Faconti, Eurecat - 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,8 +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. */ -#ifndef DECORATORRETRYNODE_H -#define DECORATORRETRYNODE_H +#pragma once #include "behaviortree_cpp_v3/decorator_node.h" @@ -58,7 +57,7 @@ class RetryNode : public DecoratorNode private: int max_attempts_; - int try_index_; + int try_count_; bool read_parameter_from_ports_; static constexpr const char* NUM_ATTEMPTS = "num_attempts"; @@ -83,4 +82,3 @@ RetryNodeTypo : public RetryNode{ } -#endif diff --git a/include/behaviortree_cpp_v3/decorators/timeout_node.h b/include/behaviortree_cpp_v3/decorators/timeout_node.h index 171eca78f..3f137e067 100644 --- a/include/behaviortree_cpp_v3/decorators/timeout_node.h +++ b/include/behaviortree_cpp_v3/decorators/timeout_node.h @@ -1,9 +1,8 @@ -#ifndef DECORATOR_TIMEOUT_NODE_H -#define DECORATOR_TIMEOUT_NODE_H +#pragma once #include "behaviortree_cpp_v3/decorator_node.h" #include -#include "timer_queue.h" +#include "behaviortree_cpp_v3/decorators/timer_queue.h" namespace BT { @@ -122,4 +121,3 @@ class TimeoutNode : public DecoratorNode }; } -#endif // DEADLINE_NODE_H diff --git a/include/behaviortree_cpp_v3/decorators/timer_queue.h b/include/behaviortree_cpp_v3/decorators/timer_queue.h index 2715dff54..247bb6413 100644 --- a/include/behaviortree_cpp_v3/decorators/timer_queue.h +++ b/include/behaviortree_cpp_v3/decorators/timer_queue.h @@ -1,11 +1,11 @@ -#ifndef TIMERQUEUE_H -#define TIMERQUEUE_H +#pragma once #include #include #include #include #include +#include #include namespace BT @@ -260,4 +260,3 @@ class TimerQueue }; } -#endif // TIMERQUEUE_H diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index 5c6d74542..761085216 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -11,11 +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. */ -#ifndef BEHAVIORTREECORE_TREENODE_H -#define BEHAVIORTREECORE_TREENODE_H +#pragma once #include #include +#include + #include "behaviortree_cpp_v3/utils/signal.h" #include "behaviortree_cpp_v3/exceptions.h" #include "behaviortree_cpp_v3/basic_types.h" @@ -219,6 +220,9 @@ class TreeNode PostTickOverrideCallback post_condition_callback_; std::shared_ptr wake_up_; + + /// Set the status to IDLE + void resetStatus(); }; //------------------------------------------------------- @@ -326,4 +330,3 @@ inline void assignDefaultRemapping(NodeConfiguration& config) } // namespace BT -#endif diff --git a/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp b/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp index 75df8f426..e675eb8a8 100644 --- a/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp +++ b/include/behaviortree_cpp_v3/utils/wakeup_signal.hpp @@ -15,10 +15,11 @@ class WakeUpSignal bool waitFor(std::chrono::system_clock::duration tm) { std::unique_lock lk(mutex_); - ready_ = false; - return cv_.wait_for(lk, tm, [this]{ + auto res = cv_.wait_for(lk, tm, [this]{ return ready_; }); + ready_ = false; + return res; } void emitSignal() diff --git a/src/action_node.cpp b/src/action_node.cpp index d539b5cf4..b6c4408d8 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -162,7 +162,6 @@ void StatefulActionNode::halt() { onHalted(); } - setStatus(NodeStatus::IDLE); } NodeStatus BT::AsyncActionNode::executeTick() @@ -177,14 +176,18 @@ NodeStatus BT::AsyncActionNode::executeTick() thread_handle_ = std::async(std::launch::async, [this]() { try { - setStatus(tick()); + auto status = tick(); + if( !isHaltRequested() ) + { + setStatus(status); + } } catch (std::exception&) { std::cerr << "\nUncaught exception from the method tick(): [" << registrationName() << "/" << name() << "]\n" << std::endl; // Set the exception pointer and the status atomically. - lock_type l(m_); + lock_type l(mutex_); exptr_ = std::current_exception(); setStatus(BT::NodeStatus::IDLE); } @@ -192,7 +195,7 @@ NodeStatus BT::AsyncActionNode::executeTick() }); } - lock_type l(m_); + lock_type l(mutex_); if( exptr_ ) { // The official interface of std::exception_ptr does not define any move diff --git a/src/blackboard.cpp b/src/blackboard.cpp index 2a1307f86..095dcd803 100644 --- a/src/blackboard.cpp +++ b/src/blackboard.cpp @@ -26,8 +26,8 @@ void Blackboard::setPortInfo(std::string key, const PortInfo& info) if( old_type && old_type != info.type() ) { throw LogicError( "Blackboard::set() failed: once declared, the type of a port shall not change. " - "Previously declared type [", BT::demangle( old_type ), - "] != new type [", BT::demangle( info.type() ), "]" ); + "Declared type [", BT::demangle(old_type), + "] != current type [", BT::demangle(info.type()), "]" ); } } } diff --git a/src/control_node.cpp b/src/control_node.cpp index ad9e14b51..2503da6bc 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -33,7 +33,6 @@ size_t ControlNode::childrenCount() const void ControlNode::halt() { haltChildren(); - setStatus(NodeStatus::IDLE); } const std::vector& ControlNode::children() const @@ -48,7 +47,7 @@ void ControlNode::haltChild(size_t i) { child->halt(); } - child->setStatus(NodeStatus::IDLE); + child->resetStatus(); } void ControlNode::haltChildren() diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index d79da5d6d..3a5ca5da0 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -33,7 +33,6 @@ void DecoratorNode::setChild(TreeNode* child) void DecoratorNode::halt() { haltChild(); - setStatus(NodeStatus::IDLE); } const TreeNode* DecoratorNode::child() const @@ -55,7 +54,7 @@ void DecoratorNode::haltChild() { child_node_->halt(); } - child_node_->setStatus(NodeStatus::IDLE); + child_node_->resetStatus(); } SimpleDecoratorNode::SimpleDecoratorNode(const std::string& name, TickFunctor tick_functor, @@ -75,7 +74,7 @@ NodeStatus DecoratorNode::executeTick() NodeStatus child_status = child()->status(); if( child_status == NodeStatus::SUCCESS || child_status == NodeStatus::FAILURE ) { - child()->setStatus(NodeStatus::IDLE); + child()->resetStatus(); } return status; } diff --git a/src/decorators/repeat_node.cpp b/src/decorators/repeat_node.cpp index 7a4509a56..6c121db20 100644 --- a/src/decorators/repeat_node.cpp +++ b/src/decorators/repeat_node.cpp @@ -20,7 +20,7 @@ constexpr const char* RepeatNode::NUM_CYCLES; RepeatNode::RepeatNode(const std::string& name, int NTries) : DecoratorNode(name, {} ), num_cycles_(NTries), - try_index_(0), + repeat_count_(0), read_parameter_from_ports_(false) { setRegistrationID("Repeat"); @@ -29,7 +29,7 @@ RepeatNode::RepeatNode(const std::string& name, int NTries) RepeatNode::RepeatNode(const std::string& name, const NodeConfiguration& config) : DecoratorNode(name, config), num_cycles_(0), - try_index_(0), + repeat_count_(0), read_parameter_from_ports_(true) { @@ -47,7 +47,7 @@ NodeStatus RepeatNode::tick() setStatus(NodeStatus::RUNNING); - while (try_index_ < num_cycles_ || num_cycles_== -1 ) + while (repeat_count_ < num_cycles_ || num_cycles_== -1 ) { NodeStatus child_state = child_node_->executeTick(); @@ -55,14 +55,14 @@ NodeStatus RepeatNode::tick() { case NodeStatus::SUCCESS: { - try_index_++; + repeat_count_++; haltChild(); } break; case NodeStatus::FAILURE: { - try_index_ = 0; + repeat_count_ = 0; haltChild(); return (NodeStatus::FAILURE); } @@ -79,13 +79,13 @@ NodeStatus RepeatNode::tick() } } - try_index_ = 0; + repeat_count_ = 0; return NodeStatus::SUCCESS; } void RepeatNode::halt() { - try_index_ = 0; + repeat_count_ = 0; DecoratorNode::halt(); } diff --git a/src/decorators/retry_node.cpp b/src/decorators/retry_node.cpp index 6f8386ddc..0865e2ed2 100644 --- a/src/decorators/retry_node.cpp +++ b/src/decorators/retry_node.cpp @@ -20,7 +20,7 @@ constexpr const char* RetryNode::NUM_ATTEMPTS; RetryNode::RetryNode(const std::string& name, int NTries) : DecoratorNode(name, {} ), max_attempts_(NTries), - try_index_(0), + try_count_(0), read_parameter_from_ports_(false) { setRegistrationID("RetryUntilSuccessful"); @@ -29,14 +29,14 @@ RetryNode::RetryNode(const std::string& name, int NTries) RetryNode::RetryNode(const std::string& name, const NodeConfiguration& config) : DecoratorNode(name, config), max_attempts_(0), - try_index_(0), + try_count_(0), read_parameter_from_ports_(true) { } void RetryNode::halt() { - try_index_ = 0; + try_count_ = 0; DecoratorNode::halt(); } @@ -52,21 +52,21 @@ NodeStatus RetryNode::tick() setStatus(NodeStatus::RUNNING); - while (try_index_ < max_attempts_ || max_attempts_ == -1) + while (try_count_ < max_attempts_ || max_attempts_ == -1) { NodeStatus child_state = child_node_->executeTick(); switch (child_state) { case NodeStatus::SUCCESS: { - try_index_ = 0; + try_count_ = 0; haltChild(); return (NodeStatus::SUCCESS); } case NodeStatus::FAILURE: { - try_index_++; + try_count_++; haltChild(); } break; @@ -83,7 +83,7 @@ NodeStatus RetryNode::tick() } } - try_index_ = 0; + try_count_ = 0; return NodeStatus::FAILURE; } diff --git a/src/tree_node.cpp b/src/tree_node.cpp index 39e37b5aa..6af2c95f9 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -77,6 +77,12 @@ void TreeNode::setStatus(NodeStatus new_status) } } +void TreeNode::resetStatus() +{ + std::unique_lock lock(state_mutex_); + status_ = NodeStatus::IDLE; +} + NodeStatus TreeNode::status() const { std::lock_guard lock(state_mutex_); @@ -117,7 +123,7 @@ uint16_t TreeNode::UID() const const std::string& TreeNode::registrationName() const { - return registration_ID_; + return registration_ID_; } const NodeConfiguration &TreeNode::config() const @@ -201,7 +207,7 @@ void TreeNode::setWakeUpInstance(std::shared_ptr instance) void TreeNode::modifyPortsRemapping(const PortsRemapping &new_remapping) { - for (const auto& new_it: new_remapping) + for (const auto& new_it: new_remapping) { auto it = config_.input_ports.find( new_it.first ); if( it != config_.input_ports.end() ) diff --git a/tests/gtest_factory.cpp b/tests/gtest_factory.cpp index 60e1fe3c8..bc6e8c395 100644 --- a/tests/gtest_factory.cpp +++ b/tests/gtest_factory.cpp @@ -310,7 +310,8 @@ TEST(BehaviorTreeFactory, CreateTreeFromFile) BehaviorTreeFactory factory; // should not throw - Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_no_include.xml").str()); + auto path = (environment->executable_path.parent_path() / "trees/parent_no_include.xml"); + Tree tree = factory.createTreeFromFile(path.str()); ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); } @@ -319,7 +320,8 @@ TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromSameDirectory) BehaviorTreeFactory factory; // should not throw - Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/child/child_include_sibling.xml").str()); + auto path = (environment->executable_path.parent_path() / "trees/child/child_include_sibling.xml"); + Tree tree = factory.createTreeFromFile(path.str()); ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); } @@ -328,7 +330,8 @@ TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromChildDirectory) BehaviorTreeFactory factory; // should not throw - Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_include_child.xml").str()); + auto path = (environment->executable_path.parent_path() / "trees/parent_include_child.xml"); + Tree tree = factory.createTreeFromFile(path.str()); ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); } @@ -337,7 +340,8 @@ TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromChildDirectoryW BehaviorTreeFactory factory; // should not throw - Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_include_child_include_sibling.xml").str()); + auto path = (environment->executable_path.parent_path() / "trees/parent_include_child_include_sibling.xml"); + Tree tree = factory.createTreeFromFile(path.str()); ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); } @@ -346,7 +350,8 @@ TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromChildDirectoryW BehaviorTreeFactory factory; // should not throw - Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_include_child_include_child.xml").str()); + auto path = (environment->executable_path.parent_path() / "trees/parent_include_child_include_child.xml"); + Tree tree = factory.createTreeFromFile(path.str()); ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); } @@ -355,7 +360,8 @@ TEST(BehaviorTreeFactory, CreateTreeFromFileWhichIncludesFileFromChildDirectoryW BehaviorTreeFactory factory; // should not throw - Tree tree = factory.createTreeFromFile((environment->executable_path.parent_path() / "trees/parent_include_child_include_parent.xml").str()); + auto path = (environment->executable_path.parent_path() / "trees/parent_include_child_include_parent.xml"); + Tree tree = factory.createTreeFromFile(path.str()); ASSERT_EQ(NodeStatus::SUCCESS, tree.tickRoot()); } #endif diff --git a/tests/include/action_test_node.h b/tests/include/action_test_node.h index 0815210e5..2cc10dbc0 100644 --- a/tests/include/action_test_node.h +++ b/tests/include/action_test_node.h @@ -34,7 +34,7 @@ class AsyncActionTest : public AsyncActionNode public: AsyncActionTest(const std::string& name, BT::Duration deadline_ms = std::chrono::milliseconds(100) ); - virtual ~AsyncActionTest() + virtual ~AsyncActionTest() override { halt(); } diff --git a/tests/src/action_test_node.cpp b/tests/src/action_test_node.cpp index d18c8ca9b..a4735e5ef 100644 --- a/tests/src/action_test_node.cpp +++ b/tests/src/action_test_node.cpp @@ -37,7 +37,7 @@ BT::NodeStatus BT::AsyncActionTest::tick() std::this_thread::sleep_for(std::chrono::milliseconds(1)); } - // check if we exited the while(9 loop because of the flag stop_loop_ + // check if we exited the while() loop because of the flag stop_loop_ if( isHaltRequested() ){ return NodeStatus::IDLE; } From 390257cceab10c4cc7c00ada9d1564202c8e0d59 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 29 Sep 2022 12:37:18 +0200 Subject: [PATCH 207/709] Moving tinyxml2 to 3rdparty --- .../tinyxml2}/tinyxml2.cpp | 367 ++++++++++++------ {src/private => 3rdparty/tinyxml2}/tinyxml2.h | 137 +++++-- CMakeLists.txt | 2 +- src/bt_factory.cpp | 1 - src/xml_parsing.cpp | 28 +- 5 files changed, 376 insertions(+), 159 deletions(-) rename {src/private => 3rdparty/tinyxml2}/tinyxml2.cpp (85%) rename {src/private => 3rdparty/tinyxml2}/tinyxml2.h (91%) diff --git a/src/private/tinyxml2.cpp b/3rdparty/tinyxml2/tinyxml2.cpp similarity index 85% rename from src/private/tinyxml2.cpp rename to 3rdparty/tinyxml2/tinyxml2.cpp index 41b1f39b0..31925d964 100755 --- a/src/private/tinyxml2.cpp +++ b/3rdparty/tinyxml2/tinyxml2.cpp @@ -45,14 +45,14 @@ distribution. { va_list va; va_start( va, format ); - int result = vsnprintf_s( buffer, size, _TRUNCATE, format, va ); + const 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 ); + const int result = vsnprintf_s( buffer, size, _TRUNCATE, format, va ); return result; } @@ -100,10 +100,24 @@ distribution. #define TIXML_SSCANF sscanf #endif +#if defined(_WIN64) + #define TIXML_FSEEK _fseeki64 + #define TIXML_FTELL _ftelli64 +#elif defined(__APPLE__) || defined(__FreeBSD__) || defined(__ANDROID__) + #define TIXML_FSEEK fseeko + #define TIXML_FTELL ftello +#elif defined(__unix__) && defined(__x86_64__) + #define TIXML_FSEEK fseeko64 + #define TIXML_FTELL ftello64 +#else + #define TIXML_FSEEK fseek + #define TIXML_FTELL ftell +#endif + -static const char LINE_FEED = (char)0x0a; // all line endings are normalized to LF +static const char LINE_FEED = static_cast(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 CARRIAGE_RETURN = static_cast(0x0d); // CR gets filtered out static const char CR = CARRIAGE_RETURN; static const char SINGLE_QUOTE = '\''; static const char DOUBLE_QUOTE = '\"'; @@ -116,7 +130,7 @@ 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 BT_TinyXML2 +namespace tinyxml2 { struct Entity { @@ -197,7 +211,7 @@ char* StrPair::ParseText( char* p, const char* endTag, int strFlags, int* curLin TIXMLASSERT(curLineNumPtr); char* start = p; - char endChar = *endTag; + const char endChar = *endTag; size_t length = strlen( endTag ); // Inner loop of text parsing. @@ -220,13 +234,13 @@ char* StrPair::ParseName( char* p ) if ( !p || !(*p) ) { return 0; } - if ( !XMLUtil::IsNameStartChar( *p ) ) { + if ( !XMLUtil::IsNameStartChar( (unsigned char) *p ) ) { return 0; } char* const start = p; ++p; - while ( *p && XMLUtil::IsNameChar( *p ) ) { + while ( *p && XMLUtil::IsNameChar( (unsigned char) *p ) ) { ++p; } @@ -310,7 +324,7 @@ const char* StrPair::GetStr() const int buflen = 10; char buf[buflen] = { 0 }; int len = 0; - char* adjusted = const_cast( XMLUtil::GetCharacterRef( p, buf, &len ) ); + const char* adjusted = const_cast( XMLUtil::GetCharacterRef( p, buf, &len ) ); if ( adjusted == 0 ) { *q = *p; ++p; @@ -430,22 +444,22 @@ void XMLUtil::ConvertUTF32ToUTF8( unsigned long input, char* output, int* length switch (*length) { case 4: --output; - *output = (char)((input | BYTE_MARK) & BYTE_MASK); + *output = static_cast((input | BYTE_MARK) & BYTE_MASK); input >>= 6; //fall through case 3: --output; - *output = (char)((input | BYTE_MARK) & BYTE_MASK); + *output = static_cast((input | BYTE_MARK) & BYTE_MASK); input >>= 6; //fall through case 2: --output; - *output = (char)((input | BYTE_MARK) & BYTE_MASK); + *output = static_cast((input | BYTE_MARK) & BYTE_MASK); input >>= 6; //fall through case 1: --output; - *output = (char)(input | FIRST_BYTE_MARK[*length]); + *output = static_cast(input | FIRST_BYTE_MARK[*length]); break; default: TIXMLASSERT( false ); @@ -582,24 +596,38 @@ void XMLUtil::ToStr( double v, char* buffer, int bufferSize ) } -void XMLUtil::ToStr(int64_t v, char* buffer, int bufferSize) +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); + TIXML_SNPRINTF(buffer, bufferSize, "%lld", static_cast(v)); } +void XMLUtil::ToStr( uint64_t v, char* buffer, int bufferSize ) +{ + // horrible syntax trick to make the compiler happy about %llu + TIXML_SNPRINTF(buffer, bufferSize, "%llu", (long long)v); +} -bool XMLUtil::ToInt( const char* str, int* value ) +bool XMLUtil::ToInt(const char* str, int* value) { - if ( TIXML_SSCANF( str, "%d", value ) == 1 ) { - return true; + if (IsPrefixHex(str)) { + unsigned v; + if (TIXML_SSCANF(str, "%x", &v) == 1) { + *value = static_cast(v); + return true; + } + } + else { + if (TIXML_SSCANF(str, "%d", value) == 1) { + return true; + } } return false; } -bool XMLUtil::ToUnsigned( const char* str, unsigned *value ) +bool XMLUtil::ToUnsigned(const char* str, unsigned* value) { - if ( TIXML_SSCANF( str, "%u", value ) == 1 ) { + if (TIXML_SSCANF(str, IsPrefixHex(str) ? "%x" : "%u", value) == 1) { return true; } return false; @@ -612,13 +640,20 @@ bool XMLUtil::ToBool( const char* str, bool* value ) *value = (ival==0) ? false : true; return true; } - if ( StringEqual( str, "true" ) ) { - *value = true; - return true; + static const char* TRUE_VALS[] = { "true", "True", "TRUE", 0 }; + static const char* FALSE_VALS[] = { "false", "False", "FALSE", 0 }; + + for (int i = 0; TRUE_VALS[i]; ++i) { + if (StringEqual(str, TRUE_VALS[i])) { + *value = true; + return true; + } } - else if ( StringEqual( str, "false" ) ) { - *value = false; - return true; + for (int i = 0; FALSE_VALS[i]; ++i) { + if (StringEqual(str, FALSE_VALS[i])) { + *value = false; + return true; + } } return false; } @@ -644,15 +679,34 @@ bool XMLUtil::ToDouble( const char* str, double* value ) 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; - } + if (IsPrefixHex(str)) { + unsigned long long v = 0; // horrible syntax trick to make the compiler happy about %llx + if (TIXML_SSCANF(str, "%llx", &v) == 1) { + *value = static_cast(v); + return true; + } + } + else { + long long v = 0; // horrible syntax trick to make the compiler happy about %lld + if (TIXML_SSCANF(str, "%lld", &v) == 1) { + *value = static_cast(v); + return true; + } + } return false; } +bool XMLUtil::ToUnsigned64(const char* str, uint64_t* value) { + unsigned long long v = 0; // horrible syntax trick to make the compiler happy about %llu + if(TIXML_SSCANF(str, IsPrefixHex(str) ? "%llx" : "%llu", &v) == 1) { + *value = (uint64_t)v; + return true; + } + return false; +} + + char* XMLDocument::Identify( char* p, XMLNode** node ) { TIXMLASSERT( node ); @@ -1017,7 +1071,7 @@ char* XMLNode::ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr ) break; } - int initialLineNum = node->_parseLineNum; + const int initialLineNum = node->_parseLineNum; StrPair endTag; p = node->ParseDeep( p, &endTag, curLineNumPtr ); @@ -1029,7 +1083,7 @@ char* XMLNode::ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr ) break; } - XMLDeclaration* decl = node->ToDeclaration(); + const XMLDeclaration* const decl = node->ToDeclaration(); if ( decl ) { // Declarations are only allowed at document level // @@ -1038,7 +1092,7 @@ char* XMLNode::ParseDeep( char* p, StrPair* parentEndTag, int* curLineNumPtr ) // // Optimized due to a security test case. If the first node is // a declaration, and the last node is a declaration, then only - // declarations have so far been addded. + // declarations have so far been added. bool wellLocated = false; if (ToDocument()) { @@ -1373,7 +1427,7 @@ char* XMLAttribute::ParseDeep( char* p, bool processEntities, int* curLineNumPtr return 0; } - char endTag[2] = { *p, 0 }; + const 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 ); @@ -1414,6 +1468,15 @@ XMLError XMLAttribute::QueryInt64Value(int64_t* value) const } +XMLError XMLAttribute::QueryUnsigned64Value(uint64_t* value) const +{ + if(XMLUtil::ToUnsigned64(Value(), value)) { + return XML_SUCCESS; + } + return XML_WRONG_ATTRIBUTE_TYPE; +} + + XMLError XMLAttribute::QueryBoolValue( bool* value ) const { if ( XMLUtil::ToBool( Value(), value )) { @@ -1470,6 +1533,12 @@ void XMLAttribute::SetAttribute(int64_t v) _value.SetStr(buf); } +void XMLAttribute::SetAttribute(uint64_t v) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr(v, buf, BUF_SIZE); + _value.SetStr(buf); +} void XMLAttribute::SetAttribute( bool v ) @@ -1556,6 +1625,13 @@ int64_t XMLElement::Int64Attribute(const char* name, int64_t defaultValue) const return i; } +uint64_t XMLElement::Unsigned64Attribute(const char* name, uint64_t defaultValue) const +{ + uint64_t i = defaultValue; + QueryUnsigned64Attribute(name, &i); + return i; +} + bool XMLElement::BoolAttribute(const char* name, bool defaultValue) const { bool b = defaultValue; @@ -1579,8 +1655,18 @@ float XMLElement::FloatAttribute(const char* name, float defaultValue) const const char* XMLElement::GetText() const { - if ( FirstChild() && FirstChild()->ToText() ) { - return FirstChild()->Value(); + /* skip comment node */ + const XMLNode* node = FirstChild(); + while (node) { + if (node->ToComment()) { + node = node->NextSibling(); + continue; + } + break; + } + + if ( node && node->ToText() ) { + return node->Value(); } return 0; } @@ -1620,6 +1706,12 @@ void XMLElement::SetText(int64_t v) SetText(buf); } +void XMLElement::SetText(uint64_t v) { + char buf[BUF_SIZE]; + XMLUtil::ToStr(v, buf, BUF_SIZE); + SetText(buf); +} + void XMLElement::SetText( bool v ) { @@ -1684,6 +1776,19 @@ XMLError XMLElement::QueryInt64Text(int64_t* ival) const } +XMLError XMLElement::QueryUnsigned64Text(uint64_t* ival) const +{ + if(FirstChild() && FirstChild()->ToText()) { + const char* t = FirstChild()->Value(); + if(XMLUtil::ToUnsigned64(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() ) { @@ -1743,6 +1848,13 @@ int64_t XMLElement::Int64Text(int64_t defaultValue) const return i; } +uint64_t XMLElement::Unsigned64Text(uint64_t defaultValue) const +{ + uint64_t i = defaultValue; + QueryUnsigned64Text(&i); + return i; +} + bool XMLElement::BoolText(bool defaultValue) const { bool b = defaultValue; @@ -1825,12 +1937,12 @@ char* XMLElement::ParseAttributes( char* p, int* curLineNumPtr ) } // attribute. - if (XMLUtil::IsNameStartChar( *p ) ) { + if (XMLUtil::IsNameStartChar( (unsigned char) *p ) ) { XMLAttribute* attrib = CreateAttribute(); TIXMLASSERT( attrib ); attrib->_parseLineNum = _document->_parseCurLineNum; - int attrLineNum = attrib->_parseLineNum; + const int attrLineNum = attrib->_parseLineNum; p = attrib->ParseDeep( p, _document->ProcessEntities(), curLineNumPtr ); if ( !p || Attribute( attrib->Name() ) ) { @@ -1891,6 +2003,39 @@ XMLAttribute* XMLElement::CreateAttribute() return attrib; } + +XMLElement* XMLElement::InsertNewChildElement(const char* name) +{ + XMLElement* node = _document->NewElement(name); + return InsertEndChild(node) ? node : 0; +} + +XMLComment* XMLElement::InsertNewComment(const char* comment) +{ + XMLComment* node = _document->NewComment(comment); + return InsertEndChild(node) ? node : 0; +} + +XMLText* XMLElement::InsertNewText(const char* text) +{ + XMLText* node = _document->NewText(text); + return InsertEndChild(node) ? node : 0; +} + +XMLDeclaration* XMLElement::InsertNewDeclaration(const char* text) +{ + XMLDeclaration* node = _document->NewDeclaration(text); + return InsertEndChild(node) ? node : 0; +} + +XMLUnknown* XMLElement::InsertNewUnknown(const char* text) +{ + XMLUnknown* node = _document->NewUnknown(text); + return InsertEndChild(node) ? node : 0; +} + + + // // // foobar @@ -2031,7 +2176,7 @@ XMLDocument::~XMLDocument() } -void XMLDocument::MarkInUse(XMLNode* node) +void XMLDocument::MarkInUse(const XMLNode* const node) { TIXMLASSERT(node); TIXMLASSERT(node->_parent == 0); @@ -2136,7 +2281,7 @@ static FILE* callfopen( const char* filepath, const char* mode ) TIXMLASSERT( mode ); #if defined(_MSC_VER) && (_MSC_VER >= 1400 ) && (!defined WINCE) FILE* fp = 0; - errno_t err = fopen_s( &fp, filepath, mode ); + const errno_t err = fopen_s( &fp, filepath, mode ); if ( err ) { return 0; } @@ -2183,49 +2328,34 @@ XMLError XMLDocument::LoadFile( const char* filename ) 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 ); + TIXML_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; + TIXML_FSEEK( fp, 0, SEEK_END ); + + unsigned long long filelength; + { + const long long fileLengthSigned = TIXML_FTELL( fp ); + TIXML_FSEEK( fp, 0, SEEK_SET ); + if ( fileLengthSigned == -1L ) { + SetError( XML_ERROR_FILE_READ_ERROR, 0, 0 ); + return _errorID; + } + TIXMLASSERT( fileLengthSigned >= 0 ); + filelength = static_cast(fileLengthSigned); } - TIXMLASSERT( filelength >= 0 ); - if ( !LongFitsIntoSizeTMinusOne<>::Fits( filelength ) ) { + const size_t maxSizeT = static_cast(-1); + // We'll do the comparison as an unsigned long long, because that's guaranteed to be at + // least 8 bytes, even on a 32-bit platform. + if ( filelength >= static_cast(maxSizeT) ) { // Cannot handle files which won't fit in buffer together with null terminator SetError( XML_ERROR_FILE_READ_ERROR, 0, 0 ); return _errorID; @@ -2236,10 +2366,10 @@ XMLError XMLDocument::LoadFile( FILE* fp ) return _errorID; } - const size_t size = filelength; + const size_t size = static_cast(filelength); TIXMLASSERT( _charBuffer == 0 ); _charBuffer = new char[size+1]; - size_t read = fread( _charBuffer, 1, size, fp ); + const size_t read = fread( _charBuffer, 1, size, fp ); if ( read != size ) { SetError( XML_ERROR_FILE_READ_ERROR, 0, 0 ); return _errorID; @@ -2290,7 +2420,7 @@ XMLError XMLDocument::Parse( const char* p, size_t len ) SetError( XML_ERROR_EMPTY_DOCUMENT, 0, 0 ); return _errorID; } - if ( len == (size_t)(-1) ) { + if ( len == static_cast(-1) ) { len = strlen( p ); } TIXMLASSERT( _charBuffer == 0 ); @@ -2325,6 +2455,13 @@ void XMLDocument::Print( XMLPrinter* streamer ) const } +void XMLDocument::ClearError() { + _errorID = XML_SUCCESS; + _errorLineNum = 0; + _errorStr.Reset(); +} + + void XMLDocument::SetError( XMLError error, int lineNum, const char* format, ... ) { TIXMLASSERT( error >= 0 && error < XML_ERROR_COUNT ); @@ -2332,7 +2469,7 @@ void XMLDocument::SetError( XMLError error, int lineNum, const char* format, ... _errorLineNum = lineNum; _errorStr.Reset(); - size_t BUFFER_SIZE = 1000; + const size_t BUFFER_SIZE = 1000; char* buffer = new char[BUFFER_SIZE]; TIXMLASSERT(sizeof(error) <= sizeof(int)); @@ -2424,13 +2561,13 @@ XMLPrinter::XMLPrinter( FILE* file, bool compact, int depth ) : } for( int i=0; i(entityValue); TIXMLASSERT( flagIndex < ENTITY_RANGE ); _entityFlag[flagIndex] = true; } - _restrictedEntityFlag[(unsigned char)'&'] = true; - _restrictedEntityFlag[(unsigned char)'<'] = true; - _restrictedEntityFlag[(unsigned char)'>'] = true; // not required, but consistency is nice + _restrictedEntityFlag[static_cast('&')] = true; + _restrictedEntityFlag[static_cast('<')] = true; + _restrictedEntityFlag[static_cast('>')] = true; // not required, but consistency is nice _buffer.Push( 0 ); } @@ -2505,10 +2642,10 @@ void XMLPrinter::PrintString( const char* p, bool restricted ) // 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)] ) { + if ( flag[static_cast(*q)] ) { while ( p < q ) { const size_t delta = q - p; - const int toPrint = ( INT_MAX < delta ) ? INT_MAX : (int)delta; + const int toPrint = ( INT_MAX < delta ) ? INT_MAX : static_cast(delta); Write( p, toPrint ); p += toPrint; } @@ -2536,7 +2673,7 @@ void XMLPrinter::PrintString( const char* p, bool restricted ) // string if an entity wasn't found. if ( p < q ) { const size_t delta = q - p; - const int toPrint = ( INT_MAX < delta ) ? INT_MAX : (int)delta; + const int toPrint = ( INT_MAX < delta ) ? INT_MAX : static_cast(delta); Write( p, toPrint ); } } @@ -2557,24 +2694,33 @@ void XMLPrinter::PushHeader( bool writeBOM, bool writeDec ) } } - -void XMLPrinter::OpenElement( const char* name, bool compactMode ) +void XMLPrinter::PrepareForNewNode( bool compactMode ) { SealElementIfJustOpened(); - _stack.Push( name ); - if ( _textDepth < 0 && !_firstElement && !compactMode ) { - Putc( '\n' ); + if ( compactMode ) { + return; } - if ( !compactMode ) { + + if ( _firstElement ) { + PrintSpace (_depth); + } else if ( _textDepth < 0) { + Putc( '\n' ); PrintSpace( _depth ); } + _firstElement = false; +} + +void XMLPrinter::OpenElement( const char* name, bool compactMode ) +{ + PrepareForNewNode( compactMode ); + _stack.Push( name ); + Write ( "<" ); Write ( name ); _elementJustOpened = true; - _firstElement = false; ++_depth; } @@ -2614,6 +2760,14 @@ void XMLPrinter::PushAttribute(const char* name, int64_t v) } +void XMLPrinter::PushAttribute(const char* name, uint64_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]; @@ -2683,6 +2837,7 @@ void XMLPrinter::PushText( const char* text, bool cdata ) } } + void XMLPrinter::PushText( int64_t value ) { char buf[BUF_SIZE]; @@ -2690,6 +2845,15 @@ void XMLPrinter::PushText( int64_t value ) PushText( buf, false ); } + +void XMLPrinter::PushText( uint64_t value ) +{ + char buf[BUF_SIZE]; + XMLUtil::ToStr(value, buf, BUF_SIZE); + PushText(buf, false); +} + + void XMLPrinter::PushText( int value ) { char buf[BUF_SIZE]; @@ -2732,12 +2896,7 @@ void XMLPrinter::PushText( double value ) void XMLPrinter::PushComment( const char* comment ) { - SealElementIfJustOpened(); - if ( _textDepth < 0 && !_firstElement && !_compactMode) { - Putc( '\n' ); - PrintSpace( _depth ); - } - _firstElement = false; + PrepareForNewNode( _compactMode ); Write( "fXu+I% zt2>Xo;5s7l-FkYLrjkMr2Z1aDn}zkHOr8KcG`M@96XqVCmx_ zmz^+|rttD%$~{*s&)vfitn;J)yUzHTJUvdfULgvAdkE2~$4Y5Y^C?=M{Vvy({GYu7 zk`!=&Cx`fBLh!WJW1sa#RG~Du&f5zAMmuFq&Btm&i<8Z4`NNHwzDYybpBbs3h-IDd zFe4bzwH#ANdKaIB;|tysarre9gO}^> zMMi*?{z6R9O}IRkM^BUv*Xd?=%o$dS*S2^|Kb;ROEBe1>$~FZ?XS~wecmIuD9&2gz z1F-LyDg+d~#zRq%cc>yI6lkN&{g;_|ItARQF&=C^bti!keJ&};e-t3FH1AtH?UjBt zfsk@8A;`a%GNu0n?4=&btvL2D%ONJnpMtdiS~0MYU~8yn*_HV&d!V4Pzi&zg5D??X zE|&3bY_SxG6fX>c0^{*9bFf?s7a*)6vm% zsqJo+Bp^%K1+L)BJ!lXfq-754)b=Y+akybGSD7MPt9aU44u?O_&mW+YSyWUMRR7wf z%3Utqx&YU3>Mb=Qv+RlDlT-@-meK~RQ zw$jD8NL2N!M;`ODA-@(Oll)6}WYi6G1D#_s!&tL#D<$#6F4Hj&)y?HHkvyVzIF{tD8%t z;H_oH8uZ*Eu{=t9;#XIOBXkf(d`?bFxJl9yM9A~DxRer+zg82dp7e~5J6l>>T3i1@ ztMnsCrKP23C9M~SO39Ng@nkZYOWJ9q+W(fj`*ab!(n6)9t*tHm=wPc`^T;6|<}-wy z0K%}SNPOnUFQQKEOQgz%{Z)b{@NMvTv@`QYNdHNpb3+&diZE>`NBrSa+3y_9$Il;q zok+e@-9aE+;Y}P|FwRGf-=E1e&QLI}^6&p(9K5-BidiGR#lqTJ!T(pMZain`YP;A( zl3Lh)pssF9p5FzLEcE>@AjebadF2dvv|g1c%XbN17z7{(TwlkWJ#P zt>sa^nl_ixXV0I1d!<}nQL(Ohv}3ycPzXBtCvb0bDb+w22qZs2Wm_Ru_qYG# zz7F#GQD|q8Ur}El`lTi`G_<9qWp8Wc%`ipB$jC^~nO1N@A0F)8Ff?3UTf<1f1C~ds zO*IeDe(O%-v&ouA`)iESb!ITw`fPTR53x+-nMF{&Q<1f*?^qp31!$;IJD9D5%G0(b(NL(zGRMv?JbqL z6SS$_C%#1Gn!efGJMgK5OQgM4@{4pr|LRPiCScwu`+FdfoeLWpTO6uqpc&XyY&f3hi_`}1!m1_SP zJ-!ZCSJ$juczw`a8ylOd1Yq!{x|lYyW7X{l@9WwX3`VxeH^Xg;>^EAtoOMRR;BXS4 zJq#4UzqnFgQyihV7@BObJ{d0^wmtE9=38cM@RrYZSd_>0Cr_T3Yy)+5Mt*KA42rOw z3f)WA=TBFgj-9S;YBV&dSo-}N>j3pdp`s*H2d3uHAXBtiR9&w`ZJUqH&U%`gvxdTj z*}7iHy0#|p^aCR+pm>woGBiSiJc|G+_sT@yF;5fAZ}nG#=mrb6`%gt_|I$_C_YDbo z^$?$Edu%J;t5+MRDx=%T^#_}z0-KUgeq_DQW9;rGUjWmm`PGJcdd%$X>?|x+NAHbC zZA$Jl4NPfXs|-Kb7zCF2mZ6xW(RRhPm1*}7oKZm8-GveXwZPvX`V$sLClDe>-FP7( zp+ze~*M07E=*WAqQ@u!V%v@_y{H01jkjig$7u%LzNY2`45iuTN1$i9QpBc9WQ{KGk zb~v$#my(c(^MqHD)WZ+=mzS4c2;{7DD9l~{eEPh~I_P}#Mx>)P=LAkRgzVgr;bx+t znuv!wRQ(19TtKU2nN|6YYizEZrkC6a$6FN)c$BBR+qr&0tl2E_*P$Zsjel#T+fKkfuFMg%oITg4JcwTj3ggj~9In@d2g`u^OP zGyNB!FC|D49C4{)rqSbMv`W(v#%1lk$B=WH;Q*1y<0r(Qlv`D`{d=N`iPjW;Gu4N5 zJG``V>6Nm-cCO;5onIL-(ubgwPg38st;0{lL&FJ2f~7*n#ombQ z0Xxj;LNNt-d0)M7PStm&L5hcByvePJmr%jL6+v{}3kWE-D;M2oRu5Qw0h72}JDQct zs7cG}*9#+VeoYpN=aSa&n*{u`)Y}Bpo!fo1*XC(^tE(Nlwy) z+G0Pulo}0r>@sEqiVT)GhfjS?ZaCas_?D?kIUn#SQbEZl-V&6gq~z8T2^{8|O=mPO z*_8=b7-aXpQoFwj;Dt4W9~~YrL`8xa=rYv6qP)GmXJLrCdQ?R$Zz{a*eRr!t%cYCa z;-V9FRuwNadDpwMM0)Y-e|%kCvvn@C69{lDqH%e&wrMYjKk44j&k=oneIO~Oq@*Ni z9x8>5f;a(z+?{?o_wC!aH8m>o;+c(j`4A0fi8Kw6h993k|ME7LEvTm5*RxsI(jBh- zwKrQo%`nFd^z%^#)rTb{QJa)=#pA!KP+r2ySvUs}lbwnNR5 z#Qy$rcLHaYnXQ=_Ht^46)A;f3{vyU%T5hp>TkNa zVs+q^J~?8EvJI*Z#Z%Ozj|1~npJ><)FT6AU{-Vyh@0RO(7fy~Q4)&Me+^%2myP+De z7(-wM<%(gBTs6L{3weHgSzqLGY04R71_r}5_^jl&=^elu>zVyjRX(A!9iIxbco7aUC9v=#qr{`U@komiJWR}jQ4+CCvI($NWly8Rd=g*(d@?{t4 zQ$VvKb{YR4%XclKY6<`7dbG z;>PefIl2V{ts&gU^_E8i>eRm;K77a)`)InvPrM&kfJPv0C#gy;d z=S@H=QKfaBBC%-)1qZjd_&MYfl)gQCBmT~cuxcYITQ+eLCTD}ZA>a%!L`0kzQV{zv3UU)Q&rRsX4&m zk{E(zXj;~y5X;Gmii#MW3+2RfE50;`7!ybRQR?@oa$IBwB^g(ScSOZF1bs zq#t7Scgxnv6CRYf?&9P>xUvQ6-DCqd8E*bbZMd?w4EN&VBCKE_)`5x*@^lm%cja+( z^vjnon_Wuvvi+3KRmGTWv(h;7;Os|<#Mll9gsn`lH;h^D3+eQ@~1>3dvY z@+L+v?~+x{(t-OcVjrmEoSmgvPRFKGcsH_Lo+g`GkNK?p=V*G%DK&rgq zyba?kx0U7>7C<#`BwA2Xa!=`;pJR`zG-* zeHk?93K;`lS4Mw>ZUaL&dq{?-M~$znEG&R9?w>=08a&Gk_+KR{(Uub;(}K_J`K_R! zU~Oe}iiRpy=iPu8;Cv}S6|>g}ZWJCj_4f6>>z|vtqx`1Z<|4<&#s+Yx7YB5ZpYKp& zKacyJUeE7dIN%V=A)wjs@+j}}SXf%hxhRpz>?*_k{^G~V%0ZCvyMDE{>f!9Az(sc;Y{|kl?Q6?=9s2-bp?voNAc%gNz15H=YEqM9{jn zXt$eacNNz=?%)R^CnKvYB_k&#rwEgkRgqUvxuPs7BcmcCldntN^$)a7#oCC-{{f&w@5}%I diff --git a/docs/images/FetchBeer.png b/docs/images/FetchBeer.png deleted file mode 100644 index fa0d15f8369d92e9b9276d0e5f99f544d7bc76a0..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3898 zcmd5a^Y`&;MRzqR(-C*H=|3@9We1ONbl z7Us|k0KiTPUtSaZjn6-zv(5OMxs8=QY0yJgJz%I~4(PDlV? zulSF(1CW#Z2j3`wvN#VD7#G?tq^+y&#V7>;gd;7Wr|lz0XY&#=2-^ zs&tn$yNedeU+KjiADA_@f5W%G`6-&Rh-T>;Ir5$q0QOxv22|*#xH7bM>%QrJp zK_gkzXs&|qDzla-QR2L)rOo;@+N zsx$cJ57Um^2TzONCO1z68x7{~q%6j31{@t~cb-Y9PZ(rOxe}atMM07^Y}Z^ndF;_( zh3|IK2Gdz&(~Cksky>wvx0c8H5XAAZzQ58h!157Bh`tF4qdR?9Cat{t>WnL>z3M|k zfYJxtrz)>teew~fa@*Y5O14sg#G5_NOlZmgB1EP1q;Iv;)P&%l#6~HX zv$|GMssfoOlNbpV&x@f*J-UmqCjSzM%_x`Mk`HsdDp+??nl6@xn%W5mhe@{#@4j#_ z^16#V_atnb?jLGI`IA^L?ecZCkl|(n3&G&i7Yb>F~{y~YV}~mH-c9l%j~}V z;cBPZ?R2wa0&VJZhyJ9lvo{S;kC~g*kq4d*+ux4H8>1HL#vB!ol9%0p>k8|&FG+ru ze>ia?c`!mIx(b`%Bwg%3G8OrLN8eC?*-G{~^2B33lE>1h`xX1>No0x|C64RAAx-eW z27oyQ91kVA=xDp@o&YZOiXednH@40n$4ih{N5zQUMpWlP&G!2K0v4h#8Q@sRjJc|h5bK%WzgO;NNrf?bs=!`&PsDd*uCN@({^MFq;KM%#FbDm+RPE~r$;<_l!Eyvo~y1r5A+(A`=Z~Zn|Jl^pH zeN12l`5l!s6{jbuNp$TaSNjL()8i^6)kLu|F;%=^z;{2 zqoe8wX}(2OEM_9FSQzopUK0_uUIFd)cr5HLymgOdj5}nx1XfCp9*e%V^Utby!+;tvv|PWFkSqAi{P&U z)Ae9OECx-0wN3-gdE;$lrOOeJ1;024=%73EB61+x6m{fIsoUzw%U|ecdGvnT%&3+6 z3cOLa<%Js=M_U?DG3ZsU-#Afqh64o=hBkf=CN!sV%*B$kJ=KD z$>CS#1X>Eu3>8-&lmp|fML~VUYnKF=B_UKCwd#}Jm-2?B_ondhmbx390JO(o&H7e` z3TAO=<_mEUTU5TsaW69L!}7s_SR+4W3M1YL;`_8kZKZ7SFyVYMEx#S8pE680 z@|?Uf0QLy(WVS)MW1C3AkhaCtD5zcEX6knHY3{>tS|mllN6hH@{^GkA@*dbN4%t@K z1uj35u|&~ak35Ajf^ym78nGnf1u*l=qwNQ!t-E`!*l#;Z7K6j#Xp zvp!tDAywdN9JzsB z9}5EhqDK-N9JvwSwqWGeJ@5Ytn2iY7*2b|bJGa(kq8)<8ni zEoAwyWRL;KOR+LVx%~7h4T;D&-B8Ys<-FLb`{UrD$3KoW1I}v$ zDXF`CANb*uj+vzKLp=XGLppLc*mBg^ZV8NTjr8!AGnYE9vH{1eP3IR>+hm5_OX1*% zqeIWcp{BafMYXYmKlXo!B?^_Bc6cB{>~@shmyTqMAE#v6ziQN!>pI66^#W21BPV2M z4kfyaUmpSzrk8iOKS_2!vI%!85s_h5pfH~^1GtiPVw*a<4y>h}+r*leCBIabEzW!{ zJ94*_N5aeuoZLqlBjzZL3Nw?gEYGy!jvHp$=4LF%pWo)hTgN&3uGEzp+YDoCtj-a2 z`ts_Hcph?TkM>{i;MaFYJE;52=k_L<8tYs{-peLrn_|1n`{m?(U%lVd8M5!_SK^NE zK-KvA%Q1A4Oi+2QwDho?b1sSK}wYhQKJd9{3Ow^X;U^4*ZF2R z=`_l`<|z}xdOm?iqg{M77v>rZx3AUkCsQD7J^CA^izNDN?)i@6GibiKZMk^An%f=jIBF!g?CO#}+8 zaJ;>*HrY&(|1X2;y?s^tLP$->ukaw1)X}oht$Fdh?^$r*y5(?%={wg{DPyo|_;6U{ zDJjZxBDM>wH`*aHJkZYzT$n;dE{<#o$d4ARx{)r{thx#C(W^Q1F9`n+p#N#*g}t;H z*V7N?otrBYbk{hLw#s-RND#f{dq-Xhgg+~iC<0a7MG-u$dqyPjZ_7{T-;c5v)vXvFnYh20(@bQ<#{Bt zHh+53nda6~UNIS*I?4VdeKQUa;981!qkgIW1fF)DEki z(dy%LG*e>!9kl=Di2=<4NLFN}Qlq@Q2YJY^)IMW0l#ome0B z-cG}(Eoq%u@>qiQ%*Gkrbq4~epq5vG#)7JWOiTmiGY-z{n{xdmL7;HOW=+??t9J5@ z;uMFpa2Fl?**X!1r-q%0sqXscO2wP}ocv5BL6i^B-)Szipht*kD*pS~c%W=+|8x0U VX<%7zF#lN!uz*=ZtIu4y^*?DTfIR>J diff --git a/docs/images/FetchBeer.svg b/docs/images/FetchBeer.svg deleted file mode 100644 index 880a142cc..000000000 --- a/docs/images/FetchBeer.svg +++ /dev/null @@ -1 +0,0 @@ -SequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridgeForceSuccessForceSuccessSequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridgeFallbackFallbackForceFailureForceFailureCloseFridgeCloseFridge \ No newline at end of file diff --git a/docs/images/FetchBeer2.png b/docs/images/FetchBeer2.png deleted file mode 100644 index 268ca71c52c6d0b31013b09748b1ef97b2166483..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3310 zcmdT{c{r478y`|c5iLUv8AOM&jWQx)EQ7IR35CgeEZGLxMp}?$9Z@68ms8Z(I#gtr zm|g}6IS5TNV~sg8h+#6{t8>2XI@kC8|Gn4my`TH}J@@^)pX+|E>%E@$j;*!XUg5*S z5C~+iIoj9`0^tWhe_dz?Xn(T1y9EviTa1GVkH>=$!3l&&AtDe63WY)>5-B_if{5@1 zABr!8h@kLzz7!(F7lHsI5fFjkxjSG2pQojnF(hTDG#Z@j4n@0!Lm(piw_iR;et{%N z3PzY)nFxLn-YKjh-2PKe8w9e)(A?P2A$n}F@NV8i*#jm!Y4X0Mi@by&lbr*XOT^W` z=m%QGLrRo%qt(p4^5BX4jD-GauxjFl^=UM5yj6(^j2wpV1mOfDJE6O_eb51c?_}9? z@(mLGltC|Nb4<&ivhGyNmvtasx^DSmO4B9r#Z*a)L`S(H3$Ni*R=*!4i>*0MO_R(T zFR0Xxx#d2`pE_n#sg+Lp5PZsu4@{)COqT$E7pQEq0KSJ1lyH$Jh@XnSU-xO)l5c`+a$Rm@u z7?n`H_n}ud#}>OrCG%+Ytta{?^DI;3i($0rtP>$O=xGiL&iS`#)HlLq)rlcgO$nIT z%(EV+g1v-kYVBiS+x*S*U`(NdalmDwmZGiE7A-Pp#G6R@Q-qu)*N_3&2%)SKWBAS8NgEgxnRW* zv$+{{K#;Pfx{usZ(9Hc3Zh5@7gY|hJdnNX!dCk|+^>W=MM2`qPFdryh6TIa*7S`|L zu8tkF+!E&Pc$XwCw$YL^nfbuB4Mw+9U5NfXcyC6Rfhdi+AEk$vR6rH30WP95+=J3$ zxs0T>)vo~d-Hd^IAM3h{`yOn60r#MxS=L=0nZ><|C>icOzVO+cmU}euelx}JW7xuJ zw-2m(Rz_N=PML>J>Z((io@pL*cw|{20Y2DNt|RkP&)u&JI)qlakNa?ZWU&|}0R0^w z(^g>Zi)*3@MxL;5ZDXRBtrzNlBek-piqoyGuK1b<2eV>Y6SfxTP99|TGwOwS$@|a8 z>5{PGPXK?t6edyurTG`Id%W%pW}kTD=5v66ic#AzU;!>i=j)qCh2Z(x@fbz6{?+is zJy*8;`k%5bYR-5Uw(8L0ojAJzR#QUcdsziD+^4aM+#IX#1L`%o^hmYHLGBCFA${|z zRk%rgIrp=Gd@Qf@*C>LQj()J{+X!Y+Q~WLZ_r7Z;PjkDBG@u)}#s<$CO|6TDHA_zo zih})O3txo~z3(Ya7=OqhRL3AjpEQp2CU-10buTKASFTZE`P8DnnV&9uByuHOxiNF3 z*(4nQ3BMA>nt#-_K{`8X5#(^IHQ07Q%=V5yTzW1}KcX&=?w26~_2~#5c~!nr ze#g_dHipB*RIB{Y; z_jhbU`AE;nbc*oTL`IBmk=|)z=m0FL(fZ?2M8m35wQu6P z^KzYud(Z;I0=w!FiHNT+bb6ghe?O^a1~sD4yfsv2cU(WS`G9^sqmdap_>1?E3D;uQ z$t=Bxt?q59Wq-A#k+*7%Qm) zHAQ9D1)o{s=L8VQvz`(N`tmooFh+_h`|HFw-Er&uc%7}s)VU}(MqirR^R*@6c$t|L zRZP2IpIrCtGr>Xn6in9pJI*|t@7-2r-c?6}fOXA6aqW+M8*?e8ymA@OiyfqAM#rTu zS>J3N2{%&YN#@UOpQM;CRW7zwU2&$cy*5p)PMD-Y+jKd{u_YJQF4GQR97WDMRey@0 znhb`*GJ{Vqx_!s_Zaf8Vkt zpKTbOG;x(yH2pV@bD@kk$$wfWT@Y^|MS%Y|=ok{@j|YdCt!}nkvKTU4t3DPpi(>1L zThk_h)^A&v@#Y_2(Njm{URJsbDO-Wil$kKO7_EWhrJPW}t@X)1784w|RecC0q{ zsK8?*oVy4-Kj2q8gTc{rI0xR9`VI4`HF_V(EuCH(C(e%L>W(yBDx6UQRLuSQm+J|gEK=} zZ*Z+tzalDCyurKC8N`ndt3|g&`9Fe>4%wvB!+cw(+@49vdGyOgZVda(CkQRY7yL2%gZodrn*hT= z;W{@HxNqPMq;;Rm0)UXArcqYfJ_UKSsSrW@rgx&O)IS(-@lOW+V^KjKWGbf#yxXY+ z+h~d~+VqdaWN!f=D@|4kUaU}EtezJ*c1|-DgVTw_Jb$M9kqr$r{o zDU+6!Rzh%{RB{l_TtC^Mw4O0OJ-6`W-c>8k3w~f$l0a6%M5&X=RdoqxdtKJfeJhzz zSBM(+DYc{zTI>d9_Yul8nChZG*E~mt5QoBWt=M^qQwP=@>CRBX0863AV^NjKcrXWq zVXl$|L$doAL3+Rh)I<`>YD0bQzdR^i zBs^=hm!fQaO>Q)swKozjC2hoB$q_#*GP2aTCgtk1j;ZlF6#P_Vd!zC1Zk$y3B_|tS zjFCrao>2h?Gr!4773ws+`?H6#QUr1E2JoY)U<>_Iu}I^8-TwdZcD_%bdO3%iS%}>N Q|1TisCf3GPMwf5?9Yh&A9{>OV diff --git a/docs/images/FetchBeer2.svg b/docs/images/FetchBeer2.svg deleted file mode 100644 index aaca63d81..000000000 --- a/docs/images/FetchBeer2.svg +++ /dev/null @@ -1 +0,0 @@ -SequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridgeForceSuccessForceSuccessSequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridgeFallbackFallbackForceFailureForceFailureCloseFridgeCloseFridge \ No newline at end of file diff --git a/docs/images/FetchBeerFails.png b/docs/images/FetchBeerFails.png deleted file mode 100644 index 3750f09c3999807db4cebdb889bd3f8dbaa17ced..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1522 zcmVG&v0000#P)t-s|NsA) z00000005Z)%*@QpGcz+YGntv0W@cvp%*>h0nar7)%>T^HW@a;)Gyj>HX3S;)nKLt) z003qH05bpq)4qlP0004EOGiWihy@);00009a7bBm000XU000XU0RWnu7ytkO2XskI zMF-*v1qw1DMz}dc000F!Nkla|Yl~-^~|DP=22uC==5sq+#BOLeX_$mqM8aQrr z?6~2*gyTj>Vp{i-lrP=56V*eU9&+bn*Bs)U0>@HM>4vo$t|A+bqv;|1;I32ebhZPI z*`0Lv#)6ir;f_bsLmK_gJ?otUM^4t297KJ{kQqPYIO@?C1JeOVeQ9(qlw-$Xk8woK zjMGNV)xo@O+#WJG)^xy8STrI#2yc}(XJnudr>CDho$Y`l;~=E$WMC5_$D&;KWW0xe zH$DB8(A_x&j^B!49S%o0;`1Ij!V!*egd-f`2uC=cvhaISe^bSc)=-F`$p1icn_|TU zDaPccs;f%qQOxcwinJTrqRcpk|O;S$C19Fm*DC6eRuB{zmk zG{<90ZVs1-j)#?u5iU_34=EWZTp~LjPBK=wM0Y%tWV~=m;CL9xnBkJd@d%QU!zGd9 z-X)`lOESkjOC|`HgpPZaOcE|h9rq}iC|nXd?o2XWxFmPnkz~qn`GMn3B-4h=PaJn3 znL1p4BHq`j`1Y((E5k|_ix}S_NRqECV>V&O@XGbYQi!7kaB)Rs)t9oPxq*P z5DsvJBOKufM>rnHG57jsLLEtTNB>1A^*LwB@y*tHZ=dC6BuBo1M>*bohV)jO^0Ccce zXhv*fq4$~@Y(^8}NLA}bZ?*Grh8>TiBb`P+jQr!Oe2>YUN@x?OafnAfeBqs|#uPV6{i=e0RN?=>^nj3y*!^t{gWT&=%3 zPR#2%WZm;I>mHdij6?qQoO7JW8GX{ix~J58_UQ5Wk~_`}bH>@8X0RDe$hxN%Sy2ca z&ROt5$*+$i$BCR#$A+%M?Yif|mM}awzB^8=d-O?5>+qLehf9@4?L1@GJ$4&)N$o)ij&LZMJ76bgkxp)Ohf Y13ULDs|#@$K>z>%07*qoM6N<$g3JirLjV8( diff --git a/docs/images/FetchBeerFails.svg b/docs/images/FetchBeerFails.svg deleted file mode 100644 index 9a596e963..000000000 --- a/docs/images/FetchBeerFails.svg +++ /dev/null @@ -1 +0,0 @@ -SequenceSequenceOpenFridgeOpenFridgeGrabBeerGrabBeerCloseFridgeCloseFridge \ No newline at end of file diff --git a/docs/images/LeafToComponentCommunication.png b/docs/images/LeafToComponentCommunication.png deleted file mode 100644 index 13a0ea2f3d082c08faa05dfe874a5e6af8def5f8..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6609 zcmaJm2UJtrvO&6n2q;QdK%_`j2)#;g(xnTCAT4wxG)0PnfCxx$(nU~2S|AjaP9XG} zAU*U;m;QIW_r7=E`|E#LYwtPd%*>uXb8=qY*H)oC&u|_Bfl#Wc-qV9X2-E?5NOlga zs(UH%U?Z}Z*OG@o%407aTN8up>$a+TS`Y}F69Rb_3UI-#XE+GNTMz@dQs4oJjfToS$Qk}W8(9drUF%l6CvWg{d@aM@fYu({77@xp#PjAFN5VClmvqGn zHO|H>VQ9U|r;3gx4;-j5Yj$IF(resRPrr9PIjR~&xaPphZKzBIYIqb{SS}g-xWMBr zK9QNa9m!|uD37LmdFcsOwqLtY?J?PN2hQ!2bn#5VqzL;3N!B|DD5>Xy1dz$g=OQ2w z93|u#_P;hc7zDD@>Q1zmqgU)!B?o)=ykeLoH7(6OI~%$aj)lM#VK~a)AevDQfJg#x z7tIJK1Ym9cKBmqW>O6XhntFO|jW14hp*uz2(2y7)`H&(91_l;;v(DD4r?5!>{l%tyjAk52cgYV{V-mCBcX?5$1Y=H@D~^}VEK@9*y)A0IC=YiVtbyvLTWXJTM5 z2y6Q-aN~QU5}kB0YfoJZ3yVjO9)Z=^ILY!;mW226;qD45iielikjK!)rL_5BQE{;@ zPvXfk3e6x7w4ojv8X|cyy*yNM;VQqTmX?SBkAMKx`STJ_|Hy8Bh+f%UT3YJXlE>R4 z*nX-ZP&j3E%s%Vn*KF*{%E|_&PK94xQ`6bO;d-$1lP7%+cNa$V3pBZTd2>bkKVd0K zsfpZAkNrIQq8Xv#RIIK+($?QXrTzCFeCT6}C%S06)FE6izglVY}5V=#z ziZg!mAV4OocXm@sN{TGx=jPJ|CB5PVxY`sJi~W;t-^hr)CvW+Kfb9jXC{g;<5WKGj zzSy?KsIUeO9*=i*tpFp78po@0?BOsYBPu=C4$;%H#Ki`VrBFqEfUF2J9iN!EN%QJp z_s1*R3+K-}mnr+Y%LM%TgAwZbX1g~-QYEqz&F}&%kx};b>!1zypHv%DuVQ1TDxF4j zWKRYsCj2*NS_TIPuUZB4)favEpw5#>clBy@Wu>=|kCCC_&6_t4O&=_IZUi%7S(y`Js=YEl1ah3B}|6f6)n8DgyK$L@z{eK0#k1cYH_}^il1AT_K zsv-=61b8IB!GGjPl5`9tSm6@<#nFpC2lK`tq}=t^3_GKyiAG%6g>ZR7@oO`LlhQ=jg0 zy}NBaSFh5@e3Y~o*4{KsDH8p)3AOHRP_gGfho?~nSFllh`S$aBC zILw3;%~(UEoa;W@8ZDgSj6rz&yhE2+HD<=e-AL+!!mzJDFz%4>pEpq$SlK1SRF#)g z8$xlE=G197?~=+5QNjsFLUKYEM(3qJxS|=Qp03``5%&>)h9{yTAys#{_#50$YfeBj zLGYC8q>6?Lo)7~}Hq?zx(M-W}m6iZcN+Hz43rLBd<4F~_!~IzQCVnv^lk^ucQ!OOu z{@(}t`~AFmw@v0=_A&{QfR-O{U42i8Kf<~GsP-{Air~KY3+zu{^TyBxND)FFR`$J& zCY2D6EqgsYgl7soy-1Xi7Y~L7Gx3(%XQQ}ZWVtPQ5+{oJHcX4re zZ64Dz;f?a-1s)zdqDj*D(<+ZixpKrQfbJ9dpYG@?FiPQtOd`DbHRr?&kLyEzU%?YQ zbO~S_$v1Rlhb}ndHKKwfpx18!+>ImOzLzxPgakn6HS_xl{y$k?;t>?7)E)S}3Bmvi zmM^{(325_6K=}QK^5m!%dEhb0r^GL57|ig_!}A*bMSmV}z)*4Jl%J$t0HDiJV{ig` zk`PbDDo2hw!K3DeE-Yj(w^|@|6=vJp_zf^M`A~HSrh3g;k0F!^oVH2EfG3eL)38aT z-}fE1%x}1=stREc3>pST50Wp7nJx+QEoyrE-AvG z=aa9Kk9OE2L}h_L?J(a{#?xTFGC;>WxP7P6?_$u zC;^c8LC2eIphxTWXkYIlM4G@nV{pE=7+eoHDthnhnkvNKtO%P(X3uhT`6`jFAKh0Ovxzv#`EHT z_pscSZD|Upx7)V1wn}Vqdd0VSc!W))CG9L-P^lt!9(RAn^}eRRGhAk&u~+r^^ZndD zGNKSP8eM8uJw8c|a2=hZEn7P2Q(?`|%MmYkfNA?Yhj3N^@~;_^kHF;=kn4g)JIS=ULi?G*$9(caz; z*0M5wq@}F)^5E{u$i(CuSJc+lR(5vw3sNcu3KFDcR%WL5eo0#lv(rh_LAh;Pd(R~z zY8o0nGczZ_YmSbNz!lTqBlt{nS6ZLJzlk6#P1jQH*eCC5tE&E*j$myUkBf^_iD9Y* zg&HXI<;xd*&B|n@rQHTktE#K_cXrZc0>_UVNfg}_X%K|9o;#R{03-)p6zUT#EiEGh zL%R}4Scd4Ww??PNjg-c0E|b7nt3KTN&ffXxCb4cY-@(ls(t<{z(yvHI<*Rw<7} z6YPdM!J}Gc*4JGhBL&QBx?QigX`|YJx2>G?bSf4Ytx!9|Mof4(LbY&Ues0dZ)}zJYu8*&; zzHyD)^tYppMp+nE>eaosSy{bIlW#)T<<^;oj=*R&P@v_%kMTvxYNv~pXJ6!xmN618laK5KZ6No-z;@?4GB6;3g5<@) zZeOm7%eco<|4mt0*@d6s9A2az)%1voWejNO^PP!c)&hFy!Co608mi^@&&5tvm~cB%lKQPE1TpPj4@1_Y(el ztI0yP?N>d}G4j{~F?KK9TIAr!NZXGeaxm?swb$sJ>aOP5P0*xb zS)|V+YjdmP6(X?a1pjaGC89va$>3)eIT#*nC|Qnfyci*SgKTn7hYWEYj>L|Pj0~N| zFv%UF{mE1{G}y`5*x3meB}k_qADZ{om6z-CC#4BQ6utNb0oDDZO5wm2IyxF6T}#U{ zz2fA?0jlePI1~eztVI~259$WAI0r(AFJPa}Ql{@PJ?~noYXr4bw`6F2s&Q&(BDr~Z z*eFGFcy#ooJ}YPqKKkb7QcwExtoHY+Z#1{Gw79#w56TJ=ypaLz6@$T?4+}Y_F<*We zoT0tnOv)+;$)iG!b=GY(q@|~8p4NbYXRFfkQ&Ptx6bglg0ET;geSJ6LJ9gmGipK+m zIuRtQtniB1)z#G`tDqEXVowYxutdUmkvUDx%;r4~Kt)V3mh{`oQ_ok3ro?lwlL{>% z0OwdRIJy(NQC=+Q2(p%N-QSaba-Rh9`*rQFjfIG- z)SW(Icrp;?Zu`0mW>+H={*2&v&jlJq|8GzZw*Kr0YfiHN4{7j1krJponUmy;_)eKk zUYp%Aqj!CM(_ie#2VhAS93{~!Ryde_(AKeMqBd~)cGxDpu|*&53lTkQ%gYoeyDt*xvaj#3)= zWCffT9UU!*Cot;&?Yz{~)Q?v|$rk`!?jqh*Hlm=Nc`j&1rOeOIgEz#wI>tZmBkJlz z7(m&HUaFpnY<_s3>+*s)-Zwt_dU`Zhui7834XYX%(P31C@h&<-J61~iu5*yh%yqIh_XKcG%d3 z*eRKVn2KKK6_*bG7i>B9qpC}0De;oMbBLexPx?H4htjUU+>B!{U5t%oI*>bN!Y%Yf zz0!jFihO(tzt_MeerR*BBE4vAaXVPr(^YdPIa|`+SZuduba3MM{o?V5fk$8!Ug>5BU1wxjOJTXhCzNl@HV1Jv|gg&}E_L}ra(G|5V!7F9y z`MT=FnaB6T9<3m1y;S~aDhL~Qt5wC(e|Yl|1@Hfba`Xst{_&kHr%<^4lY^GS0JZ~R9#&|}#4xH$Pw^|r&FmFg7?d0hWrVQMQKHNI7@31&+ zINr6-jC^zWDv*^173iV4QqJVRmjoAFld8O3#b)2{-Bc`8uC`I0O5Ik?SC#DNJTc>* zd#;1|qTgtvk5j?4mn&*9DnULdLN>7ZP;Ml!oWsNGA?B(Eg24#K`=wB(%;e1UeKGf^ zZ24USKjIH7_WOzSJ9jhW)x9EhSJ?PU$(E^@xfhAGGr~bvwQN7gL&?R2(iMW{O;(wkJ!Mg z!}mgo%}0-*+vzZMt3ZQ0?>D|NcqFl_kg|+@!S#$?0b!Goc({18_lF*IWB=i}pQ8{C zHA!%*@PMnrxZj`jJ>-D(;6vKA`l_Y;Q(2ZfFBd3NxXLzKsg} z2=|@R=~FCWf7*JIFm(M393+O%X|Lzp0rKaPd!5YFn03VdUWf1H=M96XBk5$HOj8Q@ z9p5H3q1rSo^DZntYFy`b(&4L8suax`)Z*qZDVEs9>FH_tOGL4Y){dRDQAERQcany? zi7p1?TKlS#8SNdcW_Vp?%hShQUVR#snzHdNTGW~f6FJG$qgbTG2-vw!Cho4+edb)I zKFIIPPvS{ZmS#JfpK>aaZVY&8qHc5V*^f3R`mDB!r`z^2zXdW8{4LN#ORY5h(^pcT znEeLeNqIpwN4uhpIGMVw?j(U|#w*E5yT6ShSx_xqnDBj3t5Kzicvni#Y7o|z8g4^x6c6^Nr%_3+%gs>tFjvZAQfjiyVjbFTR!QM^Um<)UTT zoXWfxjJm&IZ(_0r^A9e3T=d`a+vorISS;qu*I~&mc;hS+9+Bf7zQ;Pkvkx;>U8_Px zZNEs%VlBebNmth_R~%@VlGK8 zXj#^!q;B=B1+_e;qhNNk)O7Bz+tzfQ!!>o+3LQqSVp|Qt+QR(~+IoALHR61K>3;nO zF2&_r{FX`mK2n7M*HBlvf39!AjJugVfLBJXf-5kLha)je;J!fU$Jp8W;#j(}^cJ+3 z;?dc7@&}5ol7j&1F_$l23ogE6ny9MT)?6=li5hBt`+V7@&oe4D8fDe#h@_`eiY4z1 z_JkXMkF2P(tg5koT!{55G;-{(2~&$RE}2@DiuZri_5S5&NScYDSCgMm`D*#Qn8WId zfm>YX0;Lb?<2)MkjbbY=e@wn2s<+&+Sp4Fq+1A^oy?P&~$KPxnSf}D-o*(gq~{< zHE#fwOSIx4?%B4@%#S;ZtuUkbdFY<@?#*CwT(X~}6^8%K=}czxDa*9uSl^7MD9ikeH@B?_dp(i}6z8p}bXRwFBJitJ zz5jnUnf4Ly-F2BdVS$xbz-V#kf&Cl0Grt6v2|3nJ@-LdB84o;+H|iFRWXcTr)niV3 zPaF5st%h{Z_Kb;_=)RLv%lhvsH>3~ye_wgkq4V1MLGuEcS;%#nj*Q}q@5qRcL8)BP zINfRqw^t6MxEe(iZ>zv>$e+&wN0c{HMBjOh$!C<)u1-V=El>7=qfB9*PrWpjlt*cZ zgv2@L>b{In6nai|rmxC&JE?z+Ja&J4%s%*Qsg>l;U2UjOk~O3@Be$Wp0J=5*6>G_+ zv&_XLsbWP-v}rNsG}vr5$a)gtr#oB7$k>e*!;D&l6U_O<94@3{+poe0T6LgAvDe8w znBJmTi$5)qPznEoC1}VkEq-U4X{$#*8f`O$B^iPg*L{EbE4aDG1YpcJc0UOvTH=&P zFLDI|MSMiHGrkKxOSk4-`CE^T^$OlIrs4EV(_!ZKiJoSkzl^Y*Go40Xfi_2)thGL30<7Lhs4o>{hsFLQ15NJWLbK zNW0TY^cQ%b0Q(X95A=Tw8~*_Ykmf@P%+utTqX}^&2Q-|JXKCk<1pn&`0sgbW&c7zl zN!e4@CU!&S`;Lsh;7i9%FQo@wkF34yBy2tGzy=W(6cXnX6y_6#8VCtV+!d7&5$6>Y zln@jwRw6|G2Z0Oh(UZr1|2M(twK{h|a0!2cKJ2lVueFCAMBl;N%gfHgHUv!$oCIk`)g+T5{LLfU}>i#SQ;s=L7 zepo{wa>)<~n^)?4Jq7ULxUIH^8svcb`>O_zfk4jA+)z_7@E=@E3qx|v>^IR*M{|fs zc^x&fN*errS4S(3DDsu8n;CdHdv2PsH2#tEE44GG8Kkhk8ZmK>QgJ3{t`$6aAk)$C zHQ{BR%XtnH(&T3Y8yivg*DYk@@pn4MB9F2o#J@8N?gt-KZdS7UTsD)r8 zI7irmbHjWC9~<;YG9AW7;yww^@yD><9?bGBrmL{L<6k{p^Qgyoo%N%AvO?W_?EVd8 zRx0;kMQmdu@5A@BAC~Z9HJ|L0KMdb=#HL=Xz`Y8J*<5&hU+32$tq2l4z$E!g=cq0g zyOo`KMTL`I0E)URy*R2H4q@t;BA18AXJ>ajIa}_|MNfasX?yJSW%2mZ(wyAOYHTe$ z_q^gdyIgE-g_eI^$;Nkm|Es;@SUFQpKN32$n1#{{R&a3Y8YB7$xxSG``}%cE#CBy| z1Gk87n|$#i_iL+83puk@hm%h*Hu{}g#-Qni*B=z*f?h(Qv-8Edr3o!$d}%p>N;OKk zuEZChP#&};k~z<2m1WoTrZbi|o6Rb9YW6Uc*1!#lNe@ntlWU&gPkLHfI=enM@buKc z^`icltO?|~1(S6WT(%%{etbMvm;U&VrB{Osivo#4m614^8?f}jy_MLxZ}(=H1nYKT z`;&rOJS)Fe24aPxWKpBl(C{LD#T{1SFQkoP-d_$|gKuxT+p_+UVqoopzt69sftS{}eo54Q^R?^@9`YDfsniMY|QbS@W{HA(CvA)(p&Ll<5Tng(u94aCB%ORqLe z-&qYFy2Kn$Ru?wv%+;qpzq}4*oK{OW{fA+1F}|^pu_^&Wn%UjlI<5Snn6W0*)&Gki zEM{qhK4iEEw)64yqerhoQ{KOS)9EDl{yypOS=_{IVAmTOH~#8t_hb|)S8Dd9kx?WY zDeNOHt!9sd&3kxEXJ_-+Ut>0$T>N;b(Jy<^OuA_PrW|aRhIJ; z@^2KD#|;k6jnuR^h3vTG731;gwPN0HGHH`VZk5Qk`iK1dxS;;fjlY7Jt-b#FjQ$KG z6ud`r@D5^XM%VqW?=6)>0)qM|=CdquT{qNx#|}@;=&K%faOjvXreRwh3CilYrF!@> z%X%Z1{$nkH#|>MBs@~n*w}KUVx{n$`Cp(TIS*hwOBaPBwXlRH>$r=vPIP-_m6ek%7 zl@3@-AVUqH5dyT}eh?@Tm>ih-V|X0ACea=OtP}a4A*KJH*;Qtjw$h+w6Nsn(k;sao z>#)qsOxC9YN=miw-v?S-Lj;dPBbt5sT?sAr5@iFyl)dei7Oh+ZR|zc4^1~y{5sXTt z?3d+e4Gj%y#rfQ{@ZHd2XdT}SJv2fSedRSG>D&Vz2BA~u5y<0A3vgBEWV+W)Hj(XMt3=|73>%3@ zywOamM0-X>27c<|K6z4ae0W(@wD`0rNL83Jagr;I-IN6Vy2J)9TyFi}Lv zf3?0WDGM8c)z#H$I(XvP+W|L2L&G=AmxP78!kQYNb4`qo-!3p-`FuwA(vn8u?fHOY ze`66=+}CNZE2%m&4NuvEf`V*LFg?CnsdtGb-U)q@iEqUQ-%G&ZqAb-7mdRyPOZ{LQ8-AatL zw6xGZKH$jRu7nQfa$^xcKfi)>j|zEn{>kw0L$^btiF!sxP9?_Au4kGSzSO+vrkJ0X z$IYN&WMqV}P>lCLBTCe6Ztm_|SXfBo+~<1>Pd!w<5bumg>Fh-1_XO_!@~#--xy+<< zj?t_7+d_XvK>;$q=S@}?oG!C(UX)ckD5$z^CW3S>4+%DbC6QeTKQ?w=ykJSwagxTF znVBi_>b^)@4-XID+`OCL;|ga-p->3U=L2p^p?m&nx>X-1r#x1xd}c&gpX%W47N3{C za)qVc1*fyHNb7KZp_T1Q7_^t*Q4Bw^IDtoLG|dq$K{mZrQxbVvx-ugud->aQ)LQeR|A8BxHvh> zO$*Io6~-dkcYg%MB*oXGXHjsI%ENYcc63DZD)d8b4sPz@GN)K`m@X3ef;=Twv)=jr z`}fy~EIeM2pWn{b*7hWJVZ|TFLn|A7g_~Vf>>_V&PL4Huqhp!q$F5(HkX7b|@Q3-n zlg;tzly&^x3#asuyUQarmc{qb=+60#+VxKDHl^JKTdBqEne?#T#fqdz(zR>X5)%{Y zhzJCteym}&3Wy1ck>!pNkSa1^!BnxtYx>T%pU*~N$QBJdpUi9J{8NLW^o?adGddmP7{!2O^O;T=HXnehM9cMAFselbf40 zH8q>t+B`ix9J@~QDShynX@%psPaN&%>P=d`4@Xz|uZ;H=n)SGDbZ$G{SCIa@|3#IZWAS`U?fi)zb&sl?*iogb}f@H9<0Ftv`D5 z+frpG*0y(ccke9@HppIPethcGDX>tuC~j|WPkC?bG(SH-27}=XS=aOS7RQBxo2I6w zdZmC%fTvs!R9w0dnp0^G!y<1R8WLFKX4GY>@c8KY*$2|usLM$W)^Oi@_tx-d4TR3_ z?!Nb%H#Ie_j2#I(*x#7%6Z<@wm6f%!;vM>=ZKlhWU@lYC8L}VHag#EQ^ZYfZ zf*W3@BR*=dEivZi;^I1U2KXmiJG+5cl)k>k_3OW`jdpi;KTH;h*L;8+slK=TQq&A) z@qTh^_WidX9x4aDW+CdZO@C!%F2j#r6l{jf`Z`wr0&hdp|JgVD;j~?)fVBQ3ePa> zFk|L3XME6T@TDmxo)`PPYpr&p*DU{bVS?sG<(-aLM+?8L?O-lxx16FP%P45ERb6dK ziMahXaB_Ft-KV6@OilYc`~m}ao^#1muInoAzYvDQU`tEiswEBmn__qvq9f8v(NkKr zq?(!Uw^_Hhs=Zl#KW#-wRFpn~YIUxJ9j0}|a zh-2)$yu4goK5}X5>gwj!sfmeG=&E3)bn;Y7ON*`3hr7Tr-RUc$P$(rOC1p-+MV2)w z!f<){>Y5rwXX`KClg&&NdoCtJ0|T$jdF><^2VE2}?toe-8!Ibig71Kxi)(E=IGTZ{ z)0N=1Lo4>dYoWgco;(aRpt~D!hbc+SYNR$K$kcT3$ywod?nBZD#Ai?U_M`hqS~`sw zZW5VnC$l_Uwf04_?Pn6rG+`6IpGl#FZsHR8?WI&-nQjLd)=h(4hB%n|?Zh!&s)4Mr9K7xXRFj!2O0Nv@+ z!0F-ki7to~;8?tm)ozUhX=S5CSflskc=`C8*r!*g$a^o0tU?TP4WLk{P+|)hC(>ul zIIQOCq zjg0OP25~Z;tyA`a3cM6jB#Hc_0fDt)r_?(_fd-hGo2SOde~eLXuoWLYL^)bhfA|QQ z8a1GDyxhl>iikY6VAtl^mc3vuk7xls}!Cc2%N%XHrZbQ`U=3!r`-aJ z>UXuZp~1m>7+ob3f@>nkGid1!LzU|XiR-Gs2`}8O_L6cmRXAZvVsvg8J)qnh<0!6r zYN4lRBZ2+oFYs|PM9>*T<-4B)gn-g+a@>Zli4yU+d{`md)uzc zoOd(qb~vfSQ9^L7fav!2YOs=(jZKCQ-t5%rsYsHZvxM+k6g`)(oQ07QTk9%u_6aT} z#a_ZhUA=)hAo2(@Mh9b(g2MqNGcn7WpgpOACL*C-^BexH)8?~FOOAXlIUUZxW>*8GXpokjP#;C4nHkq^ z%EQ%FH1hFHCu{4!ii%(|GBN@J4fYaaEFUMcozd+ZdAIYyi9t~I@$pfs8+QwTD^{6b zRMb1?i^?r8C=hvIDR2anL?G?yZGDWO8L&(V@g9>1AaU&mR-~kG)>yXHx?tVqk4BN0 zT+r=_?qvi0Y{fq|0`q$~9mFho*x8-$+{w?+7Zwpg-napfHvrBa6>U@J=^;>!DAIWi z+yc2>AB8G6bq7ZPxUXw&Qd!dZvLpflkT?Ucg0YDSi2;|5ngcKY#c@p{7HYkU7MDE% zz;sWKL&eZn$1=-eCxF1&BR*OKC@hU5j(Js?1N1Rwn!&-tvp6^BU1iP?O#~qS>-48j zs#qi|8(R`Up$JZJu2??hn6p=?g%gH>Z-j~ppjsenz>u=~=6hTT211FN7Xh*^?n`?4 z68)+yuPjymUh6K87yF=MByb+<^a|@y zs&=93?&9G3zLQoo2@=^g3Gg|1tGT}skoOKnGCP{v!gH|vBq$Q@-Rl1kuqMC!feKmV z?=68O#sR2f-QJWK9=G5t*VWm{&CvAo=TE@AYfeN+h*=YVOVW}r_~)VD_w<_nf^{Ey zm;L4qR6sy+qg%gj`>SVTQxhKess9n;hv_d$WlTGFt2@SFX3K6ZF&Zpa?ABt8VOTZ{zDAXNPtG9Yg{y0T+c!ii%4bh)c^Mq~s*T zh2d~HI6P+Itj>QCxO>{WI0pRR1P3LBtAK!!%0b`L(f6JW+5w{P?C0z2fVO+keiD3x N+)&q1D^j(7@GswqG2{RM diff --git a/docs/images/ReactiveSequence.png b/docs/images/ReactiveSequence.png deleted file mode 100644 index 7626603f2c3ad9a364487e68b05090fc6e1ace91..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5596 zcmZ`d2{@GByC2#2BqoN4goHr|DT-`kFH6=LJ0WI}C7~f1glyT8ErbS>oopi^(SqzG z`%?D(9=~7z=ehSj_kQy{^PTUU^X|)e-xHyybBmFVlMaF)Mh*3w1`tH10>%+EQ8*|gl_7`_L%(lB3BGyJ>IO&%@)LxhM~@+B7fd~xg&?d11kGDRkbE)(ad@QF z=qrK+DwNi(o6ynm?`3^{JOr`zYur>e^8K-t9;9tJ!`UA5XRoiDJbbX4iTU$`qJ`B* zg6I$f)@3n-#hW*4A>ZG0daMZ|f5r$-y|CxIYw@A^Z9mIWVhxsF9-nU1rjXWF_B?87 zGFM6vc1AD_2(hM|;*9db}Qj|~Oa4LKxAvP3VC5r{k_IEP5JdEP7dHa?=jWCK~fVtU3j3Yy-6^2m5 zpF{%)7(eL=g6{8^?pYN6p9xf5GBT!r5$upNft4o-onqxx;2QO#C$%Sq3{j#2W|-=> zcw7gdpzRYmIq##nt%>JIPwum!yJnXyX6J&h9i18V)R z(mj330&vbF?7xmN7a8knT=8dji{ekLJVPSa= zgB7%31OEv;Nf@oPhTc+;qj7Tb*xR%nji6Q63T;v@sXuYufE6FTTl~Dy{A>_|sVNHw z^|_NUhInky*VgU4?Tb;oq<2q}a z93o|OfJVGtx^t9_SL#&5j{Psroz8DR=-4Qimd3q9yQ$8cA+zba&p<)OC3F2QSJlYp zG3HvI8>*DX{2pw_>Q~M%N=iVMToMj0Dd}iyP-2P5OY&G?r@_TXiq}E;x;;&@N`ah* z>-oa|(y0z({$5hg1nU0K?H{bHE>*6M9esM(HT15j+ADspyZbMtk&*Z!x8X+>(j{s% zIS61yUu8bAUzL8BhpQ0Pi2{6rR4A17w5ADxoQC{P2?eyh;~;b~bbUR%8if)p7dYS4 zo$B>|`x7^>M%BXun;t=pDu18EdMQqxFx_jEL{3jHJ|O9yTcUYEf#I(Se*V8?w^n-6 zTu5r;B}~ALsBNS-eaAD89?xWi`i!QSrzX=h9?IVkD_|=un%Kpz`ZZ0ZgeW`D4@*!z zI@p`2-+~|}?vTbq>}LJ7!uSglgANWI3304Kq^%X*JP-H@>U}90mGN)Nz-W{^q-zHh zPEHasn;wLhP&9WcpRuQ8)d=%Z(80!Ym7Kl~Q$i^Uov$4jSdQ^-K6^w1y>;Wpcb+|={FcHx)4ye{R#jnaq?zwuElzF6R%zRIu@k5tI0T3U|oT+GP} z>7Zz7kx*i~bJ2B-33`@Fzp){KATus`zq?^bM;IJ0$RBUU&GD7I5p}$mo`%yITB*V6 zSurnsM{2BB`anV=A%^+mm1Edae`sR4Wm@qYS)KXKUWG{;uy_X+9XH(Y1F;8NsUxb~ykO$9b?5h$t>>i*w{3k>xZQ$SXuT}J1 z`%iB8n;MDlx`4L2b>qdCOYNImoMwH?y8FgV8=A<9lKLr;fbV#Z>z zr`g&2r0p!@`=wIA5O?*pK|3c4F z-BNFCKW5F%<1x)K;hLtC=Z;Z;m5_jJtH8j(0csXBCbZ?Y>$+CaH`F>kLQPg~@dCd} z)@N%8>wiD-Z8sZRQTMg9=-*Ktqk=_7Jp^L9GPc4-#yw7R9T*fC9kUGtLEHQb@+yGk zUozqK630Sv!TFm1V{!10tD}IcT=H#(Jm{5M@f00JB*sNa^kyu_>C?8rv zB9XwTz~bO>CYt2}(uIHic+MT2XN`DWz#7?RP*CymC9jgw;h;n2NWFihW^Q3&A&Rbd zVZ*+>y1e{Ud+=uj5q3c5jt>tDgENJdqP%MZg~#F-J*!=1?xNA?d-saXiW56*rIGOh!fbTYp4B?}E>2F$g-L2a1PlBb zw}tt6aBiy$Os?&mKYyMxisUL2?)kZ@w6q6Ba3q?gX#dh8wxOB^w&UawxvIj~2zEqSAL>1rf)iD|If5x4TeH%1~Faa}z<{d1UDc?HjE zbE?p+ii+nwGf9bwoD5WO`4HfrmxM{cgVeHPm%gZFBm8!y(bYyGr#0fFkuF5DfJ`qB zTyLpr`+zf1a$O`rvwRRfEu~#MVrgM;l7@n>x^Zu?VoxV^2F z_KvPPV98b#K_$ziBvoU7BXsrl`f%cuXEpm{Li#{-D0HvS~hVv-61+227f`%dlWFpsww#0AFNNsI%&bX6PLd{i` zmBzd*qc!R%fb7gsF>BM&3&6h$zsWp?(px`4B@vr0{(0cVt&D7(L6#rv4<95rqg*F0=%jtG9CyD3p*`*FYYg~K<|IK?DBoM+AI9h$0hIl z{QR-H2VN%;?*?7hcvw_Eem%nwW^DPu&TO*8qE=~twIx?}b*R#PWqG+FaBq`!lyWrKKge$|3u5J6l@`s;^e^<%LyM z+euarZRoFf{le=Bxw^P;adEl0xByq2`IL^nGyU_Yc|*X?=F(8((P6DwamkxEwtaWa z%rXN0bga$vfUwN}Qth*1`EHewOQwQItR7iDJUkq!^)WUwqVVK7n4X`V{m{`dH#?i0 zoa`Z=F5a*`nRO#PS@dqD8(;=oJK|oy!JgSO_U;~6tx$YN@}gu4{xSku{oQ`H@o;w` zQi0Rh*m$otbgYs#O()-6OjlPoCMKq*vl9)U8-G!A{S9|`0bp56OKXid+|ttG-=drs!cShl^kB@Av z?-VJjqN2j|0v=wisi_%|9RqUDx!5NieM3W?0?~N9_FY?DjK6=aiRi=Cak6p~Bct^e z=4+y2q@A6eLpOtsrP2ov9-IwWZ2}Gjv<8&CS5{W`GPMRO27&?WT3J}6yFdOFB|DmI zg{`7y_m+yTf!>3H!+Yt+#t)a$`)P$F5(xxxI47yQyPKMs$Cl%wh)6&zKTY$NWkqak z?ANbG(HQ&FXf~7FoE$tJzwMS57uURh1Ole>=OM?P~E-KM9DY3F6*?T`Qn~SE<_FR7EyL&_LW*hFi zy1Md~x3}~7FZK?pgt*L;S9rtomI3TSf2o63qPl=_iFt}4)}GrV?;c5?1N!VtOqF$S zz%HKOjD= syedR(m)#UOCC~aq_T2Toz+_eHQwn(NpUe_PKI%*W#G}l)@eFb;5)!^J|iv0 zyIXDM8K_!{N*m~)goK1IA$PqBbsoXIzMg+?ojmAzM~ICN_j{rxd~0z~>eBt5jH`>3 zKW|-)7H`~-;}0a|$$9wnxj_Bd@!;xdjFuw6;=6)uYyaxW3EJ@SAVO(Z_^U zg+vlSUPmG?r)YzqnVOoqQ-s~yT=Hs$LGz%dDK8&;Fq58JHC_>PblBI|cV(m5rN5-u zj3_djC$?%oDS-urK#_6j^2&-;xqWv<(&O#|c`_zZI2JUf2_O42nJMwIZo|HFeYs8% zNn#c#ao$rD_ZJ5Ui;If`0|Q-MT_DSQ-j8vp%&Ww_a=5=H!;I7S*0OUYfD-JLBJekI20bZnLr=pZg9f8j%ENeT7q~I??%+l_Yfm z`T!FTH<&{Dr?>uMsEItcK|9G5^*HlI<33)JmUswnTzovoVOi3ZYZG68{Ls`ls#45_ zu^Cp@l?^Qs2n4OwH|LaI!x~=ntdT&a2{K65(dL|WO3n1utK`8i3k#iTH*v6A93+T0 zzGGm|SU)nSw^u*nW|=etKdJW#VQ48)GZ#GDOwUx~y6v-toC#-jZsM~!(a@@2y?nY` z^(cw62{oGEKC^}t{9>@ofrwVapTT;28?fcxDdN~0VbeeND_Sd7y<**J^g2G915LtR z6c-1AZFeV87M7Gmw@*0{f7lTsp4>M=cYSb_juR*_C>Xd9r5D`u3Mm+`E+8T*x;Qsy zTGDbIbim;)o}ie#&ikx$T27LB0OeP2$;1ViiMyhS zadE6lnWaV|;Ec$>$_l#*RN0k(0Tg=9#O)Ed(SUWAv!f&6R8p~X`j61W;KGJk@%N7( zH9^@Nmt$5;n&3E1f|YyLj(|egvpQ{haN1MVqy-euDc$x7nyPU*>H?saFEcC73Zj>% zLu6d&nVz2RQa_*62~N@CJ1%n3eLOMkZj}ogemE6neYTkPilRIj77LBaF(sa|OdQ&T5t&Ko<0x4}u*VQWzIO&STDoQ{GVr;^pb@LQ8hL=%zm zOIIGw6xyU`YAPJ7?yHz_^IU9)tuwKvq~w#U42XkEn0 zq^5S;mk;{+`&)=5bx!+X5|!lTKfalto3oK|yLZp7jEf=c#S6|~)4?c$90C!`OA~zk zS?00Y0VPAj_?C$$KYSHH^D8-8UteEbT+HALavLaza}5%nKUY6)m_&}NZ&{-4)`U=pt{WCWWFa;4#Zc6p{d7F>Fs z$EccMY;7=h@@P*x@PZ^IBqc6MNL@lm86jlkr7z1%A}&fu$V*5>FP_%<9{~54Vlyc diff --git a/docs/images/ReactiveSequence.svg b/docs/images/ReactiveSequence.svg deleted file mode 100644 index 7f33658ff..000000000 --- a/docs/images/ReactiveSequence.svg +++ /dev/null @@ -1 +0,0 @@ -ReactiveSequenceReactiveSequenceApproachEnemyApproachEnemyIsEnemyVisibleIsEnemyVisible \ No newline at end of file diff --git a/docs/images/ReadTheDocs.png b/docs/images/ReadTheDocs.png deleted file mode 100644 index 62891299edb4ece90f26a353f871085b78411f05..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5024 zcma(#2UHW=wi8fk(xeJQ7X+j?387sCg9xaEj&vbNhX5iqA`ps#C?%9g6A%FfLvNx~ zAynzo5kgm_Naw|S-@otu_y1q(ueE2+IlIrCv&&5MZGAW`H3u~S0JJx>H4Oj&5=XkY zC`kxF6*sL%8qOg9(E9@b%HnB`Y|oO`y!P4#Bz%An0HDJG;DCfeF9CqB6acK)0Duw} z0N6Y;YVRnM2xN9Q;hMlHCZ6ztw4(62p{GSLPsT|j0b`4}l@0(Gp4`y^SaE4P|#?NZ1!kR)QtQy7nx(lTq9nnv_$9T{5e?Yb;v}70G zF1j!vu=rzh%~T%|&R}#0aZ+R}QF1}^q6ZlCGM}1HXZpZKP@G|IBvCTFqre(Qe;66H zhO2uopg@@u?E$h#fK1bhZ%hPL?C5yjacN3dXhew^UTLw?VbL7Y0AD!~S>gAK84m4p zcB6jf+Wmsj2huf2w74V+L{-+FyF#Qc5nU$vAK-VCkx#>Chm%VPdwnCyk)O|xpcBU% z!=ORPX48bSh+8QM(+2PV_z2!a|-H69FkGQml#IR|!3|Q@VT%eLp4H+8MycGUA z$4C0nn+d3<2OZy^URgsqoXQ#OL`ych8R7621%5uwt>$gXZBP8Ou%Xq&`KQ;4bOKty z#&bnTr#ObW3dZ@Obib0$1jYBuR|7LWRV}ZVmFucZaq@fnt@lKa&is>K)v8mVjaiU+45xRYbt%#7*5)`zLu?G3R-O1ii`iJktFiP7z8C{UlojWfH}DUo2P0ppJ6 zs{2NbKEBnGKcpjROZQk&C@4pH&%d+%>etXcnLZ~~$Ey4rpgENT&0!6ajU2#VSMe+o|yK_M^|lP zVq%_TY4g_5s28+kC-qr6=p7jW1`rhcc>g4nDhl>a`NnhT#&g3Qh#(AFPPQnOm@7*q zJo-lY&SRraEg)2=P;;#?#t=Z^&x>)c?pffLM6HjyxO4Kum zZnF*ED{Tlav}yvcdqrgmwW=L>T!nz?Dxx8NvS@RZk0b4D=YX_y4NP0KzpgP5Wl!)R zJ$)QN|NMLqh7_hGIF~^FcS!y{A$Jo#y{8nOvJr{Q5rt{I9g|ZQPrk%D9Aa)O3he>^ zu=TnKtPPpfR7?^W&$IUAm31)dNXJIv&jML0iFT~C9yH;mgq&G-Msw-dPfh&ccB~N* zS{*H7)J(Aq(Pqr5tl12B;S8}bHOD*tW@iEkIi+~Y6|9!66JrZWV1VDro;9LK%d<_4 z+B(+ei5YVb>qj=cFhM*_%<;~s#Tg?4eP}5Xmqm1%2N zMtRrEgTJ!^huESEm^6mTn$!ccL4!9pFAn1N2Lg$D9+KQlvTjvBxy|!VJOLBV7{m5O+h|5(sQzudYz zRyJl0(W(HZ%!M+!%r$&cZ1VC9N8(DKOHPV=9F&{D0#B-MhgO_|lh(;>wW!x3lSvD$ zIR9fUApZC)lD}v6OZzL5jqu>Yxms-%AmB}Rqo|i-dazMK`H;=IqKH03`W2WTbyHb! zU{i6grQ%@tk_2e3i+k}8AeWA4fm*u&9*vX`LeGsp+1J0_-^$Mn$h%aiGgrNO zS~0JYW0f+VbBQhPtfpo;P<{WvZ?MW<;z_+o)#tHGxaNiJos3PDtdTfbk&&IjMS+ba zc^LQpt0oBV_iKPthM3or>M!Y}a1S`=D`;KYUcZcl!>nJqtzB;4XKs*)|F|-+E;@s(P zF{kZOUxacJ8LBwHqSNS8RlmHYR&P7~oLGGQ>*%zNQT|9?-ReJ>rjw009eUUHuzz{|g9kJ~gZ|9+oA`ga^d9#8fv)ifEfyLeep#Y__OzJV!c z8#iL`X7%D=QqXe4RzA;57Nohqam~zY&O=|3c>Q;YQ>HNMq{IyXT?mH&@B*?-1m}rP zCiwx~6+N;_$0r@5kyhYK*+%+)-p?QNlpR@=?Tv}vN>~9WMW;bN?*0Xc-|s{(h0P6x zKYmh(ftKrU1S6e0@@}rF%6DcXI1j?N@o_MLdL!VO>C}5+!<{qmUs|v@g;4WrJ*-Y zvWrG#qSLPvK7H(_bur{UdDCvD@Kzxb5os|)8 zcLy3^#9;H}E)WrznEPhvA$6bQeQa*;%^Dd*?$aj^AWOQ#CfiD|0DZROPt7H+ryjHH zIl>b%!H?+>@$XBFk@Q*J15)rzBt`}?e}%%6ub;#uo;0mkOC@ZLNwHS-ysd_nGOd-g7xnoTxW_{?Od=!a2I@8wEi8&EEa!Imi8+ zxdeMZmvM>%YKM*M)W!}ZcMtuCy46&!1471ngO$FiM}7I4*m+e@?@QJ#L)UJ0=~=y{ zD~UCnJ38|j7rp9|){$TA2COavF1aHs@?9@@4oJFxU|IevL1IQED~{p`AAiOZ+Qgc7 zhF$prEA|F3)Q=@4yyJQKEg{=$FO_PD9*x`x zp%#8Odiu{Id#Fm(_3HJD3ap7Pa5Qvqg3BEw>Ga1H+tbVbg?RhXIo~i# z$m(*ra(OJ2tSftA!?Pwal=n}4ipR$sicY7BnxL#JfTIEl*}WxSS30+E<(VkzrW>*=#iR=6aK zuieboKF>OJbPdvS#Ofx2_{b-@bwaWqK04^Z+KaR2mds&|qbrrk_QTISeGD%phs@SQ z*$>;G%9GPXCHy7neqrUSL1*Nfc)@!6VP5ZQzx)H!Pl}GT9GE~PHA!1cGYT2=TX?%a zbq*^(3jSKw^&)WS((x!EK>WGrW?~O>dvOzLyGXWG`bsHyyg?#UgY8X92wNUJS+n$y z9z$$60T%wk~fA#Xjrl5-iGhZ;#A)+Ki&ghm(my-;4&id6uf8yDnFmunIXQyDGaQ z={_h*jIdn3Ctm0-JwrWK*}$(R;h{%^I{z%!9%Vb1vwl6K5Cy&?=!ko4IL3vbP_g^q!@+4@NbjCGxgz?d#>mFMf7?J!$y&hP2=&@)_HFep`?;UE zp>{io0|J;_XxI*Huex}ln3YV}71EbLrT%$NbqhcrJR=H^tyct%7vWSw?+W9%Ufj}d zT_GZBPn*`>0W(vwy@3zE$S0jxcSg5ap803@tP&gO&4%uIM$|416c5eHH7Si*O^jLS zE$}{lgaFXfiaIt>|PXrRkGy53h~R%33;%%%hvg2v+VmEXnQ=owbwoQ zef3Bh<{F&M%`CkkvG?>xWbjRHO7(zwOJGvX)bGG=grXunG>BcVH09nf zl-g@V! z@Qk0eemvGT$rj(Rb#&@_*L~U)swbj{AJV@QXR;H@+&j+QyoEbkF6}VB>AyBAXfo)9 zbO<+lc-_EvC6ccd0!$7+U69p{-p^a*9G5s;=^HLB6Pr%Nez+GL8nUz4`H1Poqrciw z-sx!LS^vLVQpRm*hfdaARIh|_6#|Z}Few~b=8WXPc)!djwlvFd;73gz4NSXFxmTFG zDWvPs-t$ZE9wseT6^xU6dSwxI#{HdX^C^du%qDT^n@!sRz#;W3SpOT)P5p8O1Q*@c zp13Rvupz$TYLi79bV~H6rR1RHieCpzt15E_?NV(?nMWXT8f;JPcEq>ZiCES&zAbB2 zn91LsW2d_0OSYst@LjXWYvS<%#Q|1k(kK?PBtRH18eG|?y_POe8hfSvGGb>wMGQ4z z6koLq=Ryou03;4>#U}80zFO8pMXCX!9{kAf@_1q_aI)5x9Vg-fAA@cb$4S956RfyU z+wt?eR|BaRC&_m6%+`m?$;WX{Y-)iUZSXO7a0UC`FA+E2vqFjAy0|Ee_p$8aFj8c9vmjkgHuk>jxh_o++S=hgS>4ytZoC=_Bd;R!b z^Jqwofh4KW)w5R}sVPIkzGm^PT_gRf67sX{IC?*As>=5g=7SequenceSequenceFallbackFallbackActionAActionAActionEActionEActionDActionDActionFActionFActionBActionBrootrootRUNNINGRUNNINGFAILUREFAILURESUCCESSSUCCESS \ No newline at end of file diff --git a/docs/images/SequenceAll.png b/docs/images/SequenceAll.png deleted file mode 100644 index 2e4ad99882d300e98a82e954e94af1f6c09051cb..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 4828 zcmZ`-2Ut@}u#R4pB1)H{fFd0Np-UHpix|3;P^1}p31W~=q$mV0A|*k(3K8kOLqd@z zg3_fVp(;f{dWUz=Tfg^SvR~%x?#yJ)?(Fdp&{%mwGwVy5dX+*fTh!BPvWP=vFp}`kNMjdl7o`n{l`KM8eT>E#IHWe2e z8>wMm|IN;gdloxu*lM_W9b z*91Y+A|)+7J3EVRojQB|l97o?Ezx7yO4ziJ=~?R?TxnsU=yIbC74~g=oO!{~WCYh6 zY^rXyRgsT;TFA}DSuadN!oa{lICN=gNeJ^{(sL(JxsF(9Bs6V4H6Lxunx^YmHWH|8 zjX)qYG&KDD{Hl=$JF5{~!C&l30M^7VV`Jl1GP6iiU%8o!heyxHkAbVLEGkDk(>*;s zsH5EoFf$8FhEf3b&{a<_#w70oSyVv4$=!YS5yLQp9$AlV{h{W1qB(% z#&^OQOQd9E+A4o+v|ZO1O^m5}f5L273S0A4lt>Z@R8UbNR94C?IFt$@_0OsbjK*VWBwZG9wtwccvqjaI`1PMD6Y4lbD!D*jvb(j2m>p zbj?ObM|)I_t!!Hq4E6Q(dFB)pfEOwv*4EadqM}G7D*_p{x8a z>P0j1R}XXg)`s%Jl4YPWDei}Rn-WRdLKx+}xy%*(zQEgyACoNm5DwcIRTL{nP*W`pHaqBg6k5*?&P7D61mU{lT|^%$ z;58ieXob|^IoZsi@Tk11s>r;;WiZ!x{J82$2=9z2(>+3PntM@Ro<+6iWTpFojVy@Hm1i07Kig_pO7;eXrpjm zE)mtaXEzlEf2f*>#c02xErLePNn-H&i`M zS+s3AjbyUXZz(k@aK?5+uOs!CPv4-qtJ*U@O>yf?HGb<3aos#3N?(#{uyF`JTPiGY zUjNdp5O!(1bPuIeS{kC#i5=w1LecC($Pss)U*=^ z!){_QGmpq6!yhm_m*NezzB}6ao!jaXOUTeu&l>I*BQ*AfgJ-{fO_zJf_ogH>^ZrPw z{dc*vw6rD98-dChL=RITOtx+sb>jaKFpC4`k@6|sU)Oj20|JDFgg$h2?Sk2&+gyhW zHG;l6BM_!JM&she#?M-tu~#l?K6)f$F~w$e8k{q@(L&o>=C=zH^4W+o=}KSBx$&C1&BN{VqO;_oGa z#dq;|`%&9}Rby}G{=)Yx)KSenAyK|%{+a;)$cE$4(^HC9T|Ay6(Alz2ul2z1qEzhR z2LbzN{<*v&?){m0A*MIumel83vQH_kQ9e;CPPhRb*W(UQnHS&_KUXOf-)V>OeVX`X(bq$kLtcHX>aG=M z&fvhH#_@&6XHGLv3P@uN4I^zM8&EX|&oQst8ObLIbIV6}YpEg2kln|3w-$JjZBku> zy`P-4Y>VO4kZ*~I7Ec@=kEgP_9O;VAenLT`hj#QuSG@0@Y$-HDR8r3`qNb*9u3BGTcXf4L3B#d_Rz)tI2R58EV7BIa zn=kYD+|80@l_7Sq>tTEQh^h<)pZ$bcAjTUS&~qrUn?(-}MqidfDL)|7v0cg9U7v5e z084(%OCT2wF9K(C%Bx20^^30A(OPfe?c|*uS6Y6(behC`lRQgNgqs_(ju=cJyHsGY zSluT$0IJemX$>J#5kY|I&9aA(ShlG(4zSBhPFf~z zOea{ytl&KfWnr=5N;^AiWT4v6Ftgo1-=Eb_RJQl?pDuw{^}o?TPQB+C=Ct#!KyWo2 zc)?A@2!Z?2e6XnXj(V$==Nt-5)UBy<4>|p2V$&3SyvTX>tZxB(`1u`sQsn@X@c8t) zqLxVrd-VMLykX9Ola%>!K!!vKHu4>irVKqnl#QgOrE!QZkqOp346Pi%c^Ppl4_4}g z^I-ZiWBTe=46in(aY?WXDy3x^O0ci^0!a7VD7V9P%0t%J*udlxS{)A2zuV7|?Uqm4 zDat|}O0&`MFvQ-`_}=?$bZ~8UgXj}`FKC;%B%5qApU!F4OlD5&Lq2*WYE|#cprE_& z82NH!ZP2Y)DhzCFVgd|`(@`S5z2`Ug8UnVP8Gs}L-uLCp%aoK9EVdHf$q?Vk^Z?9> zwGlKEQM%gn?frjacL5Y0?=}s6ad7;6*2+k>&wb` z8rlJ8Dj`@6j*Qee_wzkbJ7rKDu5C!aEjwW;%A(%H;H4K;9U|}(|A1cHZ4J7!(A(V1 zs!Sr+&_-trenR0-a+f(Wlvf}WV2#tF2UwX-SUPhl-vHovl^XlXiEk!^`7BibCo`a= zBj0ob6!l9alpBzpIb|fZsPRis^`{0~HHQoV*w4um#i88rE%ZMExBw2RxMJ&4RR+m; z$w2_;nv;Lw+;^5C2T~CS@z^iDL%X@pt;ek*AytwJ$Rv_Z65qd<2ohhMPz|B^4cf0j zb+DcOqom0Y-qzNpe0;FZpAqPFbg--T+OzkKhFHT!T(<*sB4h@C{aWm8DfaFZ1YQmT zf!qRLpru9qXrho$(-pb&DMhxZx*AASwbO8`D+`T=66Wk296?(nju`>VHIj}!JArt8 z0p#YwpcsDVO>r@#1Y6BNbpoY(i$yFfET7b&*RNmCGc6+3`>o@kiJ?ueh8NvkT?6*! zv$F>by+p6r%s>A=R)uJJdf|Yg@h=?n?3(RL%s?Ia)mSPcNcEeG!{mCucw(QMjBADY zYyEejn2=SpDty-vA#d77Gh%lAZwftk|MQg!a$C}v^&!5Z|)FVf!TfJfbJ5x5)TtTZZz8;k_r%wFH6QRzyJqTvkXAb%&PxuF6J;7w3V6~kY^Wo2a? z7b8A>D;rz7gIgQOxoeP-C~A$bcOR44^6Q*OE^PW|_p?!+u@p7c($dn=xu6#?U_g|G zc45Jb-@m6u;_kOU7i6MN>E7BVqsH81o~ZSXj^0rhHp$_c@r}gNhK74M!w0k!78NiNx6VmVxT9kkZ~BSNK#F>hfrhhwZGLjTBsVN9jQU9^ zQ6jJ~ynlTBqbO5*(GD|pD;Mg3zVOnoQiE8MovoQSxK`fIF_>T;cbkVZ#*rIqQe;I0 z1aO!P0RA6->sgwgXCol;+b=I}_U&j*kOEXyRo_qA@}1q$MHv@O1>I-6!2;!B!>L%u4cf*W7+(+cSG~q^MmBG^ea-p=FW^O8Iy?E%k3S zJXyrD}|Vf&y^%{r&wIPNfg`fz0p|Tmo3DlatdK$2$(bUZ|9+=ojZ0 z-ELK0Y+m41Q(scjyYy)PFgS0}+}!*_zj6ciX+#9D^Q#3GRaUh~z~%fJNb&r7zc=s& zfBzzmGjy&R8=<1g7(d=8AL9?VEC}S4^2e2zc~7X58B45%yT=6>uS z0&D0}kqln_C@0dYC%^>MSwJ1F4TUmNKe>bR>VK>Attai7cVkb63c;?GI`(#!k&w#n z3}Yc~baXT|6@b34?*UW#TgyF#xv!j|^JK$$rkI!s%`EJ>0VhopIv<5R~+}W8n@C9$$(lKVXCp z)**6Gbt7Q+7n`d_+<+4MV&c{cS&RWa#d#j4#(;3f;>yY%u1>Yym5K*SwX#4yVPRo0 zt9n+-Gqts~8~%r+hJX`{a+Yv*bNkrctpkNxl)}-SaQ4fW!+1|>z;rEGDDOv}e_v^w zMCsI1FSTIJY@k0Y!A_1qV?}%l7r8s;YMD%N_|?A~a2fJX^OD_FS?}vi+G$v@mhI3Rs&z3f4EoxG7qd$0SUpQ(U3kd}t7dZC(4=>Gr-WFrOu diff --git a/docs/images/SequenceBasic.png b/docs/images/SequenceBasic.png deleted file mode 100644 index 1468ef43187eae09dcd60b250585105695404c4c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1392 zcmV-$1&{iPP)6c7vjU;qFF z#z{m$RCwC$m`#i0Mi7Qe7T%SYJ+y4bXM2U`tTn`E9|D_@i|k)u@4%kt5KumeZUZ|Z z@huQ?*xT$70(;92v8LSyW|1Tp+kob9XhIr z&t>CPgRqyf1FkfzhSjhdRvFmd-#-Pdf&CQp-n9mn-+%vpgG+ojp99SKBqCtn56@2wxL`|IHCMj_bW{te(+0N3yr^ca>;zQBZMi1{9@ z4=U{jfBYFd_5D}$0mJeMAK*pb|N2s?t*iIp>Gp&9j&TorsoXxxH=Jc~3D%rXSPyt` zs}}4n{CsbH3%{_zKEd^zPuOYSSoc>O>pz8HfA#+Xc%swo4WZSJ?ScxHgW|$9*DKh=D!wV06e3jw9U$m7xgLbA#1riBT5%6U^81b`V9=*#Yoz@4Ghz;8dk$L4r}cH6sanT z!x~c6qOh;~M^6EUZHq#%-LZY~5EciX=fHNyebp1Q~3V*}*l%3RGa4S1kdSrm$%k9vI=QM)*h2WxSLKYuI#s zX4_#J9EUH4145)+&QF5f8jNHB+j;Y<#kVdt*h?>5;{EW0U=ght|kTh1b5&1VB^)KV5zUw2OF=Z ypJz3!hSjhdwjS74{bNpt4jnpl=+L1fjQ;^23na5$EDe$X0000
Sequence
Sequence
OpenFridge
OpenFridge
GrabBeer
GrabBeer
CloseFridge
CloseFridge
\ No newline at end of file diff --git a/docs/images/SequenceNode.png b/docs/images/SequenceNode.png deleted file mode 100644 index cc8b9ace9846f144d1cdba687c878e8d5ecaf137..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6633 zcmZ`;cUV(P(~lyefS`iHrT3!rDhL6jB~&TWq)6`|5Q<0<6%{cOil87wx>AKuq)Tri z(u7biolry|v_Rn7aDDIdy??ynVNTATnc3Ny- z4+4>Y3xP1)e_w5&03MvR)7Dgj9FzV&)aAy5k@NRq=6(mS6eRgQBN(JWz;)Fr z=EyEw6uy$pqyw}wj=o+K~| z+Fg42)HYrBqk*FE#HMBzA;!g@-~FYDg}KpLuR9U4M1K$huQU#UGn(xJD zTeuHO2>lW1Cm7xNIwN2I5OY>{3!@TndFK;Y#j^s2~A4yW5%--RFCi~J7h`l=}kuj zJz&hD1rj(i7<)ejP=|tM(E=HcP#8OqS0zdi{m!+qxl!rczTciHG@zFYPAIU^*V5{+kGYip zMn?~dFS@`Cgw5-c@%R_sj3;*DwhZs6e^1jr>VGHcFd^@|Kwae@{puB}@NVZy@l?3r zMGk7!vu9yaTDLe$gUi3*$t^MkN&|#(>->EJe=&2{1jhgTc_6yI9lIWmu04iEX>@j+ z!(ueE1W%UV&oDCwzct`6EV8+fGB+-_*&|D9?dHPK+)NwB%F1i8Mnubc^R3tI-saBe zXK+DgbhJj(T2}|ZF*Y7Q-q%#(3g7Qul_5`lO!6{E=p{b>&RFiO%qL)7d3hcCTf0dE zQi4J}k&#&+9w}^|OBXP_eg8OnbMyJx$ef&(Y|$S~>ah=Z;~MhI5-b~_HM$WwAT%IU zO60Fux%CzOkDVhQhiu>39O~-gfgexSQD~pBpxZMtuufAWoYqw#06?I^D0OsWOG^)w zyhqh&*mUZdrheZAH|RThO8Eu{y8W(ZoDuqmyuFiK>Mv;?{Ugi%>Oz zozCdkpC+3#(YrR3XWTKKF!{jnemDCvXxDI$yJ96}(DFjFWcn$S;n&Tgg@{FQ#1K!Fk;T z)o)np*sa>@xsAX0?46>cpKshMR`uF-xR1CvV@F>m?fKMV>FKDn^?GgUvxb&BjL%r) zdFpNdF}vaSqJ~K-%Re{&jp{HHG7`i|cm@#vgJ%d%mEdZ{l{2>YIfyqg>b7$;I z7^^RVH?<=P#xt`KxP7%VWb z66;}d?TxOkE?bN<0zn^21#p#^7Nh`GP*@G95xz>LJ3!q$;vo~$P8X#XSEMw&XL-}p z(=)j4Xmh@Myvapsd21g`r8^K@H;F^g(9rN55lQLiUgLD!NL!mmwxO#Sr{1Ns$g|KiOo>j^X0$nv8qAg8%54ZE{++)#Z{-X-3@{6}b&Nbw!+{uC>@ewTg-Ils` zej|HAn^6JT<2SetBJqueU0jRtBkyIQ(bSn%g3sAYZD8y|Li>p=3sDI>Iq2J#Ug?EWRvs0oM6_ib37$tVOpBni6C<0UwoPux6Db9LWR*h=DFI2rp2iy}GLuQ)b`D$cPID`(BTK#pU(w z)98@R&UuHY&9+{wCORw+cYpccV3A2FOiypTC*~r>^fJRG*@@Mm++r=Drh9(#fH-~s z2D&{`;!Y-vCoTZ_&B^cQ5RCBGmkw1$tUsJ{6sbMb>&tvSzTZ@vgXkh957OAyJ`0Ve zpC87$SoGSpejMUzbnEneL|`B$`P}p7+1Xj`ejh*!p43`Z}kBTtEI$z;3l5M9^Lxv*)vNKQzIj~W--dhrh8&#Wn~C| ze^#Y11r{1-Z6UUp_U37^hvn|&7D$au!%tbRqaHFhSzar1pz1FD<#q;aIsh2FO;CJG z&Lm%ar&r|x@hCPnmStsrV`D>^ zY*g7v=QrWPh7nWR92b84xDBjtwKMo+ET8(_2~!6)qtfM5gD&FkB!MbHVr=ZC+<{L+ zZrj0%Y{4^N?QAj6-)L)VM^CNWGm$J}C{ph!E@7GN5#ltiE5CH+!)rj+{ z--itp6%{XBxFDrlSzZqIq}D^5ObuFSOKhc@Rb;eOZxgcYVsn(6BW8_(*3zvbZtJlP`5CbrBSm z2RqE(wIu;-qhOCrdh^C}s$P+iTI4C7AtRqbjlj*#eKlG=e<--l`W5Xr=g--7b*VY7 zN!@QYyws3$M%;apKkkXK$Rn2CIj40FI#EfzH70!NN4KUaK1>Tg+SgYi;&;}@hKsCL z*47G(i+hc5`Z_uY1mcGjfLD5)j%%x1dESs)@o-A)b)P|)m-J;QnW$BDnd<=Gt&VE{ z6(?k^kH!aq<*yNBckbM2ZEYoKtnynt!sjX#nqzXx%J5icG;tDM*;{+RYzktFRx z6H)vNwJ={?e>TWysd~f1!$|?$A7d5Vc|y+CA8vNHgHrKn?e@>Rq78=dY#%rQl z()s&%wZFTAgTu%ITs zB1I$;2L=WJWkN30?M~8}iL6`)d17*W+(Ra1qe_ZOOMu=me<(FI)zwljL!-1X_Um6k zyT7dJtiu<-v)=01UKtMm{e*qI?xE}_e3d@+d*Fuce68%b5e~SI4m#swG=r$GyLDY~ zc}B)#VpV#&ZBWqLhpq^OasH6j)M!M+sZ_n)waTf|?v<65BQ;##8UR)ra+eD}4`<#0bgNxQG=_khaW0ck0zEGcIe z={P^+neSiY`Sp*MO&eyyKyjp7rkW8Vr^H9RWB0_>5;s*7D2nTn(q*`M@}Z|!*zDk@ zSHD6}pH)`QEaP#*f0>?hZmU;ms`kOwp?V?~dow;hUh_2zZfVJ^AuROHouU1$MfHQM zf&vdWx0iRJ($aTKO!z)q=JYRO;IDQ0=q6HIt~}L`+xPyqxA&#fq0~(1@&%EJy{++D zb6;DfZ5_UL)nI1Sj#I8NcZB5qgPk>uNJ*vlRGKm2bV}-8{{1JeFtm5nt@OR+{Nk+I z==EWxgs&s!?*x^9xi{%RXgC(%<{%y<>loU*sz8|g6IeL%FD}h z_0ehNzwx*MupqM#9Q)0H)lPo2u>d^@sQWqJG&B1^v70*}=(xV;mM}RblNc8l2Lfnn z{lL-5i4QlHpPx@hp_sk8_m~Z`l~A9Mk!8hQFZmmw@VaRca13AN+(J(Z>3hJMMQ}fZ zC+ec1v2nr;v)Br}tmi1=_uq~CFeSDarHvLk=iao5GS~Q}zM8UrhM!WE4zq2@um+`# zrWeeU@M;BDxkNJp9UYx~sz}`>GV=+_AcZumnt&dQy>Y)@;?ZtH?`jboyW%-kVO1Nn zu~OUs4f_4Tx_I%fr-Or9`t28C65m4Hcs>&Ye~q7i-mG-A5d-=sG`|(*!-q%SPdS;h zMN0&5Loe2;#~Z?rsYGkV+@}Hk+Ec85hmdihG`x^3LU{(F9^6lR_R0MGymfJ)udgp~ z0wcB8ScUM=K^(|}LxY2d3$hKJFFGUyhy(&*a&i)^9bkVK(+hR?^bFl-Wl%qu1L({* zEvAXQ)#oBbPg!VPmrUgwFQRYpnl~{_Utiy@>AR_1fL4&Bqoa?HkEds0?;^KE3WbcK zqLqO`?B1yv0JJMtu8hC+(5g{2NNAt!b1Uyo6wWUyI+|ra?g$LoTBEAG5OrzX@|8v= zsI-gTDI*tb%1cU0?&O>BvU*-j+et#Slhd59kMaVL2@l(hM<*mDg|9!H8Y{8av?Hfw zhgw=$)p=kg3Qblvf-W;NECoaa!iBV$q-SoDp&u-~i-8hcel`L6BE<%shgWCjd0Kn$ zs|KXk$jC@|zMy=Hq)+G9uU`{|@0t{t8CY0UJ9b~KZ%;ZCmYS9ZS{KtI%h(h=$W(!= zBL*O60tTm^WK)~a?Vp8r4GD99H$IV;mR46+$Gmo^pZDu7Y3cWNaryf|ue?RKps*ky?ki``NtjNg7#-}{JRt0>d zBSJZ!h8(O__A2g<>xUDJB7(n6cww+YmXZ-nJq>R5_V!xYhFy$F39O4ZdCu^af$s3v zY>d(oVWs$Zx8c|yfha34FX<+WfHaFm@&3*9k6T26Tbi7kes3HdtgmA+{6<`=O3umz zV0_5z*(m4k%owPAVDg9Yg$S!J_ou=8HD~d2Wt&0766P9sIeej@<@FEVPz(KgHs?6? zatBA1^s1B$Skh*IA4DJQL4qfc59PCf7L9{dnFy{lS&M(6HAU%dPoE+2+~S zS2uU}-uH5<=j6hV6d0y+N`S9;p#&+AqpYo=fhUeKHZ~5~pHFJqW@KWLc&F2}a&Azd zE|0g=Z72_bH|JVt{fU&q z2vKDTI_!+*n<3K4`a^alBmAHQ#SiH7Kl8Yp-CH>eav`xOpR`AU`pvGSrOGFSaPwZ1zbm5RVWTF38!{obU=67C>J>k%9rJd}3_#2*BEub|z{a5S~5 z`R2H=`i$G@1FlFHsk}ZHwOm@tL6@UD2Zvj|*RNg6$;~y2gHFAsqF(>4>vFfmj@F>;K)>*498=^Ols9>~q0`dPE~Lw!@!o zL|e43%xAW(YT%*~m|5i)DS=n5om-7gi0<0i2}tST%k~J7?t%>^r=%#d>1*{bj`>7z zBzfN&BW$niu8jq*{1ldno3_~d-AudBWgg+h5M&x`O1OMdL}Gb}8yh~UdW!)y%zw;yzP-m+22yTGMMcGzFG1VOL*8}UCNp<|PZ^)V<@XIg zjFC^iiNhP^U2-^sbB@Ow`M%UaL1}fKeU<_FPcYQW;^&Y+KD_*-j&%4Zi9eRq%mwQXmBw^1quUw(9ZS{hrq z#l+-f+Kw#RK^<92IIUF2q@sZeGtok~E^dia+m~Bxq_6$O!$`fn9h|C{6ze^sft)kp z?l{-qYlow|WmjTmYMP{#y}Z2KRJqX;fB(k#$jC>-PZ9^xRiqkTEkcLmngk*iU$3Q0 z7-x@9OuPzO9E7~4hQ^0y#uSvGb859qcdgFPcaNway(k?Qj)a(57>3>Ey&MHyT!xT-)N=uRP0$j{ST{is*HT73*%lc%U6UIFK_7XxqV9Ign z(je?e`ZR}omeR@@zbZ@c=#z1B&q7g=NW&CbyJ}`{FUZEmCNMD2-X63_4vcM1mV2ju*!%yJ22!O?_@+KoSUl?85`*&~Oo{PNY-9QY`)TFq{ z_rdTJ@b_xKLmKKgA5KKorI=Wmm^OnH0%|5aWCo;k2N0^NPbRzqt1PXHW$7u^xni@E zuLXkg093-1k+s&vC;ciwid%X0$B(e$VQ_wyJMiFeZ(}@-GK%RG1Sh&mZozR8^hY$$ zo1HN4dYn@Aat%MxQ<67}Ibo`@vm*yCxU(cSHa2!oH3mw{L!sXbC2!p5s269XF4ZmR za&dJPPwAm<7NDnmnK9^A-sj@sg2%KRV4 z|6u&zUkOmqe}6uZ>o_K34z76rESequenceSequenceAimAtEnemyAimAtEnemyShootShootIsEnemyVisibleIsEnemyVisibleisRifleLoadedisRifleLoaded \ No newline at end of file diff --git a/docs/images/SequenceStar.png b/docs/images/SequenceStar.png deleted file mode 100644 index 889e95d0582be6f93262196dd3097df505708041..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 4317 zcmZ`-XH-+$w%!Dk66p{TL<9vXp;rw^(WpQufk;9%2?UJv0Md&n2t+~YARwY39YU4f z!4R6%0|KJ7Ly;l`#Dntio^$WJ@5dWsuRZ7b#`?aw_ZoALJ?DxxHNMHtCddW=0K5LJ z>t+DJkbLa7vK-$4kg_1(v0-x3HPQtDN*wqQcj7mUH@tZrIC>n{*K#~#^|)o}1pr{) z--7{2&k#5UnZ5Om;LHn*>|C<^xq=8I0N^~-zpjh&oBEm=>}NhE+*77Qxh4EL-XP3O z&l)p|F<7Yr#g-FFbslgO6&#LMn zJ}f-@woG%eUQ#yyDpXwOhaM}vL7U`tC%&rRXrrl4f51O$kE*ply#regBDE|}?=)O~ z3}Tf&#YY5%M=*s)U_~EbMKQO||GrotJS>oZP|-fh(7jVcWE}jd?3QYqUO5+(3H)!P z)S8-(Me=}+MtB{yCbcedzr_4dn@M|?7#f9rehxge|7p4h)PNi>)tvMVnZSp`IiNZX z48Uxbx@gmAw0vlSCgH#z@cYY&*X)ju5o=iYL82X?CAB=6nCkr@^C@hpdUyNG$GhqV z>AsP(Zs}X|s+le|>#X4f9cVNV`^l$qc~^_@u86Wf%o_*#J}67KeLF!C+iSfKd=!~8 z!!HFQHW!Cy5*-N@iYdg^GOdiM!;i|WiF*5BAB*8 z0Fu9c&Ygz2c9A#l%-g=O<;2R1fL|p4V$!+E_Cog4*|smQX>WA=RdmPn%4 zU{9J#*oE4SwJS}KTiQc|ZyJJkz5*#cWZ&RWdeKe`mM?lj<_b z%R~#q%%*Y9{W(lcNIutoX~(BP{sUkNGfA;HF*@+%t?f#d(9zk}+|JL7`UxT5P@M8h zV=5Cso!3|InZ~awo2S$r94mZYp2zT|^Mdc@L>?#DabCe?G4C@3{+&Yql~B6&qGgdq zJY$;}xB}WRe~Wc?zw1Q})Wa^jta#)YxD|=J^>NBDDxblScExB`aWDU> zwe|HX=mKW7!n^Bhc&bGXLA1NQFhzk&7Ay{V6~M~)p@IvyZ6SX=S4?IYCEvA_q@2pL zyH3-4M3AJ5S>P=g}$8|So(7`<0^&r1kx_N-|E z@QUQlscdjU)>(L=uy#yUsa8gN|6co+@^TE!GPC z!V^oREK^`;ks`%ZC|o=#DG63=;au78SeaQqnSSj05C{Z)Tr)L0dh7*hB5AaW36q0e zy~{~O|Fvd{C6>w8I&`jh#q<`HsD+|(CLBvjC3_V+^A?lFC;7U<^IN}Em8uh~mcnI? zVu6Yc*FtEYaTHB5-;)a(k0Z+U4?95Ay_sNQccIi{cWj>rs%!7*(mx_NK6XodtZAH{ zr!n#a5-u(P?Xe(|WO73^y+%(%PrD};NOES*! zM!i{~W%A&jI}k(Ec&(~20c4+Cj=C1>{z)nNF!pbF3}5hJSw^XH4BK}v2}Ir>KHR82 zfJ6H?2Rf@y01b*j)1-zmKgPxKj6pvGOr{DRJ4f-8?H?@dm&gB>6$EOJ*Hjtt`;v{& zUr?nfRm-Uvy7t>v=`U@^tvZJfT_lR5Y}G*7+U5~a)k3}e!c7`pUYWXaoti02P7_O~ zD^*%xf2+*AJqZ;CNuwm|qKYqs5<~90hENQ5HdFiGVAW4@DFe?q$#vdgo&X$)av9!) zX_;^sY<#hgR*a6jL%Q@A7JtI7#vBc~ihs(kBM9FABYKHR(L2nO!k1Glk6BZ2iG zciO#50qBgfMaC+OzSVaQT@jqH&j{9D^>6!g`xNg-!LyLE+=Iz~ZNZ>pd`Py)bT?4g zYS!E+;*!=PQ+~yxH7f}_hPkNC&IB?5 zkh4INb98HydXiSzcDbt@3&;QN?x3R?OgU>w?WE}mh}T23!w;|1KW43$>aC4S6&VXQ zcWrEH4LoYk>T3U$Rx+q-vf;Jw2(8 zM6uCW-l7+ty1IPQL$ZE)XKZ7@g;i8%xNFFe&kJw}h5$>!r#kBcat4q9y>Ditn5-=4 z|3{5D7xW?igIWL_LJa+@_wqzf^I&BPqf>I1`KSj2awdU?do$qiGa z+{;G#8dqy#xTG+JW$FFN7mjMs*AJSMy%Y9~ba~-o_?bIW7@5O`C$Ovdp#R5Apl=Q=6 zZEQSggW((6oEAJQE97-vCb{Xx)V0Y!!{pyy+tHYe$I_#wVe%FY>nf5lIr#XP`Ui2t zHzlr`Ft{5F5B$>B2;I#;V0V#AnYS4n*b9HeogiW_a_M89_E$#3x;AbFNXwM^Pc5cL z5os5>Y>YWGjK?oiZe%iT#*ANG2%REbgDrIB{1h#x03*}kv}+M3*walO_OBIxIHGQm zW^_u0(ZXj!ndkX0{~Yq3Im}$A(A3)_T`Ri>10pufJQsCFRQx#jCPe?!5(E>X0O){jqcGDIlc>?dPpD&Y4}nPTR#4E)n-5#+}!BX-4WZ-9WapF zeiZ4&!Dj*mF;2_WtlOS{mvJ(PPmdLPcTibHQi-%OlP@d$M{Ni8;M82BShSPv@^P^N zwG3n!m7TMZ&T5}0W&7c|1q2Y1@0Ms8w?kGcW9NEC`EQ{rUE4;q=%4B0tjaa6C4_Dm|WvfZd zX?J?tXyUur9we*@9AwX}Vfy{W#XzAgpW1iwZ-e>t^r1TLK6%a8W7V-4K9*DMukQFQ z+It4VH>&UZHXV9xX#CXCE~A-f4f|ZIo>l)R>QJi=W;$gg3@w`21R*)Gh zO_r;idim;{2>GK-h5L3Vkv8bjQ>{FIf^p%6V-x5ThKYmkmjqRhkrC&4$C%MB!t^Y7 zF5mj~L|H+?lI>L|drwE34akeo0&0f9NuOUeiRr3K@h1aK4`8vk7w##=l>G8VGl3%m zs9i|30y^PYWpg(~XWZ3C$cvqF#<{SQz5ZwE>*XP0{`dE7AmDC^)PVj_D%hY%$n{sy zN@h*>>M*F%BE|OIg)mlOQf=!Ix_zBJH^SeGo+x+0$yT3`G(x?H z=Mh42+)z=A(szixSJ4H|?!m8+uSr^D8|V|#Wbk;k?P35V4dd6V>R~%p?8F@f&$oFv ze!DsVg2OZ>Ilr$jG#eCSA-gYrD=IAp@}kK^@Tcv?GSQHFF)4yTCo!@8vcZI0y)98YWW?~YEff|t2ISp<#!IJU_#~MOq8`KVEymZCDy^gy9@i~4Y@@eNYMHY` z>JklK)f*H$t+tB2CP|^uQgrAp#=%04uqK_96#*fGdUJzpbBC0r$OcrA-48e;Gibmz zNJ6Q}NaTsCghz(Z-(uUgq>yQ?;hvt`eM`g z=7T34G1eF+a<@wbrD1K(N6RBjFUwLDsq))~t?*l;rk`DmkWk`grHHS@*>^$bahzz7 z-J|R5`~$}VN-@@pu6uF-Y}rG6?mvquS_m}DlO|xU9aGBG$Pz6molzncBTmm#`8ZzaCQi{vXN79%>Px z(k)8ADu`t+Vu8C|_u^^MF-AK9>kA3;4&VOkJ;S@d?dG(_a}omD?sTf6m@E_c4O8|K z-{rX1hwyquf`)iLUC4WN-D>`R2D)7^Kz*9@Gp?^X#43TG){?AqHn}QvU=G(7uHLDV zc*}V@cE)EAykkL6Kd2Sg>}! zk!Rd3aDtIGH}24-R4CMHTMg`)p0i_id+a;A8$sdBOep)d8`TR?R}~O&tx7S2lZWKpw=teV4u(O=M=dq;sS2 za#HzT)w0|2L+b?JunhL>`>UTzJIoKgJ^yh4?Ksv@shAjkcFOPB1& zCcV5<-O|)*;#`4W8P8%WCm0|M4sLnaG5?F@w9X8yzx*8gU2mE(OXKe#ky-S}=jy+5 z227m488>TIK0DYd6%AX5#AI+ppLb?M++GTu3f81s=1Op0=tu`)q@Su!+l-f?uE8T! zl_+Hf&P;|2_M+MVdXckL|JjC+aeCN)n(Kdc);#aFLUTM(XNI2p1RWm@hSequenceStarSequenceStarGoTo(C)GoTo(C)RetryUntilSuccessfulRetryUntilSuccessfulGoTo(A)GoTo(A)GoTo(B)GoTo(B) \ No newline at end of file diff --git a/docs/images/Tutorial1.svg b/docs/images/Tutorial1.svg deleted file mode 100644 index 9246de0ea..000000000 --- a/docs/images/Tutorial1.svg +++ /dev/null @@ -1 +0,0 @@ -SequenceSequenceOpenGripperOpenGripperApproachObjectApproachObjectCloseGripperCloseGripperCheckBatteryCheckBattery \ No newline at end of file diff --git a/docs/images/Tutorial2.svg b/docs/images/Tutorial2.svg deleted file mode 100644 index 06cf1dd80..000000000 --- a/docs/images/Tutorial2.svg +++ /dev/null @@ -1 +0,0 @@ -SequenceSequenceOpenGripperOpenGripperApproachObjectApproachObjectCloseGripperCloseGripperCheckBatteryCheckBatterySequenceSequenceThinkWhatToSaytext={the_answer}ThinkWhatToSay...SaySomething2message="this works too"SaySomething2...SaySomethingmessage={the_answer}SaySomething...SaySomethingmessage="hello"SaySomething...BlackboardKEYKEYTYPETYPEVALUEVALUEthe_answerthe_answerstringstring"the answer is 42""the answer is 42".................. \ No newline at end of file diff --git a/docs/images/TypeHierarchy.png b/docs/images/TypeHierarchy.png deleted file mode 100644 index be2c0c98056a071379ba64a9020460136dc30533..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 8937 zcma)i2Rxiv^tP2IA|Z$pqD2d$O~U9w)G!jgg$N-;8@*dCIzjZohNu$+LG%?yFDs)4 z5hHr+kX}`aXK}f(o z1RI&cw<)emZGr7(VfR@!E6-q<+7{fS%YMf?s*IGD3Z{0Shl4?hmU}7X1_lOh#dm!8 z@L>)S6?G+`kttreT;E1jRh5(SDc$DnOin8|H{Gnhh{#Ab!^CcL^t=;!=>1&uT_GWd z3xAD`y&JG%BM&tyt{kzp=JPWFtHQi{0_UOX++G~YQmZqvv$ZW6T1-nx+1U3&p-|=J z8K35CVQ#RUan#ySQDsp|PoRfZH46ugNK@-A3W zbD`9%=u5=Jy52<0E;SNg9z1!B+beDZL~=6iPQJ{WKP*#nEMpX3CnU%}dacNs;(XPh zA~%Sk%Co(`&D?46r8O`kvK zG%@y*8)J!&kH38RvQk(Rzlsd}?BF>#SxA{jvp{OMHuCOijjXJ!>yhSWW`UlX17E-P zNI0cz=P94g38_Gzi@ufEX`rv)(%Qu%yy;cO6y278|B}TE?Ob~9NU#Oi1 zZo z9aYCw`Pu~Tn?%h@HXWUvWo2d2H^g3c5D~)FQ~mt>x>JQoNlB3d3&9`vo4Ak>Ok^D8 zw|ICWj^AqP=p^bFrl+SHb;e&ki+Rg`C0Mq2sI1|@X>V;Zjzg_z1m8*0Lryb(nvcSC z40LoFoRnwIoO$tH(ElEyKPNl;+3MH2b%^Womu<2J=c>>6Ntop1=7KGo&G2Pt$b0{O zZMky7NCQ8BkVS90g#EXBpX4Mn)ZRQatZ}hf)|4j;iTiYx@V6kD$<6(Oz2Gt{RdKwIS^r8Yc zF*!z$j-9XZx}fqEu&-bv{_$9_e1T>`P7ZrT-LJ?pq@|;itI37_ z{F#W^*!O5VoUfiUv9qkS^a_J`+i{!6CjkyUh^Pe~ne2Vb)3Ad3%2#DlQd7(I3-7b^ zEp7{?MvjKt-2^KxOF<>81x`%aZ=$G;ttaXw4u%)EXJ%$R>b~aZ-^%FKF*GzZFnB;T zzp&8J(^Ky>ug*`iweO`6%@A2(_u>VZB5&f0r%yjkI{=vM>4CXCrV5`v*k0_*t*WZZ z@HvE;SqOU=#QimmU;8n*47=@c|`M7H@Sb%k|YD_MfV#HgCNH6Pm^n9y^@|g zOCxg{z?jPQr^KkJsElge1STJ8d3uWN4hMRkZMI1U08Vl~D_RP>1X)op(WUpc6C6qr zaFkb2xO=_3t&M0mFRb|WpO3En*a`8s(B0LE2KZD9DxA989J0Ic5k3F9bNcq}+f!3h zadC05+_JZC1IaKhHI>#Q4*MI^dyrPH_>N_lvRUIQ3->Cd(Dg`XXJ-u!4P&4E=?a_C zj}L&QHBCN|(uniw-V@PAmS<-Ad(I>kYr47$Pb8bxM-t#Ys|?y_W@eVBS-^O_7Q9-w zYt+R-Ai)rgdfMLA1zd|N95wGGKU-N*ah>Gl)|OMbzW4E=`wFZGJ>UEkei(0UJ92z{ zTw7ZU-o-0BuZ)STd>$Osj+B>0-w}hfr>r}&#Duh)VS2uE%Mn>xS*arjE*3{^{x}u- zW@##ZoJ0N#3~;D}dvJvS;qea+S5A@Q6!P&A0au8FEZozqx-=;*CqV$g-~E$ zfT@Uxh^Xh^;pRr><;{K0e(+%9OO^MnFu`P%7)7&V6fB1FyGPm18sj9hXC06n@*wFBBTm7Gx zsCj83wDBaLPbaj)FpPT}CcT{TK3Mo`N@kC3LxhsXhjXbu{Z>T%n6Wz^1wM;$;XqhePptB%>tYt+<3gM%_SE1*(C zL`0A@O!N-1or246fDHDj4oyt-_At`Yj=VPs_#LWKWSCrTE(5&rec$t?<>g3AriX9; z_~ZA1V6vx`qa#MY;1wzEfb@7V{3K0}7k06m92vqJWd)dm&<$kdSb9cb~LR z64Ur2#E_TtEa8}(HD8d7H2RJznk9zw_U*__&KSkBr#&fX5n|SCRQ%*fIlwAQOH1Fp zVOE0Eyqu)q!1FCdH*TCTvo0UdupO81yE1nTSr6_E;Gnm zOg(dRdGcAbw6v29TI<)YLJPoRwUO6w=2vEhQBhNq+V0oT($dl?HmdVI@nIs{o6CwG zMo!t-*qnO5g~@Y3P5plq&~T8SP1_o*}if8r_O zPi^u;sr*A^a3kS(4Q#=f&)-f2bXum^81-6ZO%*>iAXNTu6Vmg>fN+(qo*ZUV|NbuC zc^|O%5Zba7YLBAPO@-Ei$t*E#hdLKRKW=M5S6N=3+&wclomdr2v(y{(Pr`t`63V_jXhh5mdxVcS5NH}mtBwyu(JBIaM?c$Pmdvb?i~ zcbS(BSVd-J{1d0kSW&b$ZVWsJn(5|PRsqgo-)IObXnFnJ1_8@8n% z)7aS90?D%abaixqaM_+tG`1bBxUB>R{TXd_v(>A{ZFjc#kt#o;?jt-hXh%Q=OsL(( z8NyMq$;r3k+IgtL(etcJ{T*xK(fkMvNlpH7afYi0BHn- zuT{C|gAv6B|Gz4sQ1;7fOn|ZiHX2K7{y$yW3Visf+H;r&2X*z=GxkOpo|tHZ_c2p z{h)37Dkdf-Th#g0)z$r0+gn>(m@PS`E2T3Sd+3&j1UCFpFe#&?`^I;c(_(VsAd>TE zc8yRVKoJK$ee#4U`*b)U_Ls(Mgned;9@m&3rFHF}))$nJDAeSVIyv0jlM4z8vTHbU z2|K_|CtL(DGQTqy$a#T?Cl11ZY()NC_&s{FZZKct;*kQvlep$_W@)%7Db$d*6dY$LU#5vwda1buLx42;D~> zYM47ZG2ABf?WK*^+bq+vMy3R1+QJ<>D=RR)hwQXDCnits6+L7<{KDESt(^+Sd)+@Y z3lzjEO}34Vp7OLn;-WAGMXO;EPj>0MvN*e0k(F&9KH=SuL)g*$d@HBNH(em-hAMX+3wRxeD-0dY6U6eOx0fYxS zE+D|6j-jL3dRgxb{M7&-*rHZXkJ8PJoKw;0}eJKKHhiqueHB0ArL_ykvnJa;v!Hi`Rq_uR)qZKV$9W*M*}fC zJ14%H&nn9lv{*`@2QNd?G|e|JX><4EvJy(lpckX}`j@X=8-uhiY85C~Vx9PP=Us|* z@`oX<5!wcm_V!Y3j$QMw+oyx|^IH$fxuYz-P@ZhZH zi9fVcgMLiN^J=Cx5+9!e$v#y=m@dTwjg3bd;OmWe+Jf_ITssOJp5uSxqp$^SSd%S< zUu4<4icwjT^EgP2d-p$c*?cMvbJ=d+nn#q+PUBvu444du7G|u*l}}2lp|o^kVE_q% zK>Y6gQB#AhnoWPOy<@m`S?-aho?dddc>pwNFag>L@jBzPSXg<59?G;9_G_5)PNwEH zSJpna?pe+hlzzR?s?6-igw4fEGLZiQXP^V>1TfZ2p;io3JQvV<~cb&y2rHEr@&aE(>nU)izZk6=(2flL8(R5zL37FtE-?z)Tw$Ujd|Kb z&tYh}@e8F@_4`dM4OV6N_48*zNl8f&k$ET42g=I$xJC+;$M==-8jBvpNVW3|508Ut z=f!mQndG7(-jyOGUbc1(!2Kcz`}^N&BhM8@QOM{U7~H*nSrrYGDTg7D|DpF;*yBRQ z;)-+r{QV*`Lv-uY5;Jr24l}`U6vjyuzx|u!7m|IcwCL+w9G|^N?<%~-28#8%F+^Uk z9WSEv)-qD`q|Jc`mT7;T>N?QS4zC)*`{Q6HRI1vZdGtBugY4u~p=C}!sk@R4=#9YM z%H==(x+3Z3x3-pQYcmdycR$5j*kr5~YJW1hpL_GhjnvEMOEf#4m-}jHII>fc^X`#? z5VnGyI2o_=v<^TwKACBWES{*oW^?G@%|5hf85-DUMS8s0;P9Zknip@2wap_*agJTn zqBls6H)guWZYoqHCbWF$>ggQa?L9fHo;ZnyKu$I%P9$dkVxH`9wBh5Au#$=LtefcU zmRQ+7cClIr?9JuloEC1%}dAxr{Rdop+(B18>rDff@D!DWKfPoZ?Y`wGHS-1Ik`{bZMA7DPZ*T-dU z;&?exR<=w#{e`EW35a|lGR&ElS533yz3P|Ojrc71TdxJvy{?PM!}@kp_SAG@$%UMN1aLwJV5!fdUC z&2X|6q#=jD)(r$w9-6|uUVZeiNRAr9aCkm5Q;9!ZKT91#Ba zkwgCh(M4N&jrS?9AaDM1W%OKfQ;Y7fo=GQw*=uemy53VNx`fAJ892j4ZyRTzg%@pfH^UUCa z2oW@aL_;8*HPs1|yUe&)%rAYKdd4tu!w@2m>-1w+ql)tl7VvcGBAndC#6q2Ndv0ZX z{W8ONUFs-c5oEKID7{Z7vx)7>RVkbmw%+Yile~paHNv)|;2tRiA`IVKk)%LFC&x`V z!@huYezqn^%FCtJ9c&MYfXr=NXSSZ+C`jGj6>52`qcR2DZDOKIgD1WSgmf`QR{GdA zZ=17wWc78h4b0(Q-7bUg3P^Od?k;23v8%Em5_hT6*Vpvg(`}C5c$vu=iQ4cjGPW=P z1gLTYt>z2lHC?5h)OH8ASTy5oQTXV`TI7qzE-oY455T!nNHSvG#p{_bjt$A{($`Z% zIpAL-?hDO)KRk-(?i0azfY8ym3&7fO1ksTqcy$Fb*5c(F{Dw1Z{NhyZ#8_2awx+`n z%I0t`T|(+;ttrs+@uz=xS8#E^ebu+us{CkeaxSrlxkvrD@8%{p=hNqqCf8kBThscQ zriYZ3wH(pS-%b`U2t$_t^-RvUWRM4~v%axk=`BlPqs<&$J5GdYm9Dn4yn{Bc3EE zIFZoRJyyN z>m6Z8NJx^p&1DpAZCC#M^Iq5IsHmtkF<0em^?2oh{(eeFjMSt&NNTCw1I<7F!BWHBeSdEcTJ!wp&FlJ+EbBWZB1>D_L923b{aQRUYAs}2{J-DV z`r~HyIec>gSzN#S)idxF5V>^+3&=6K$B!S6jEp4mJ|;dNAepf`*Oyhspat$?|C6Nn zpbCRUbxwn7!ggQ99lk4CTHdPk1h*4fS_23xkOceXV%D0kcqlbBb#dDxHz&tS(ijeh z+t}R3QQ`z$1a@~-YQ32PFxJ3V;I2X9U@i+J;VlwZM#^TJNTm>Hcf{eLSIu}2isj&Z zSZ3bwv5(7fTN?;tbRWl?exx2%>&>O5rC+B%Uvd!}1zF!;cp7_1Su;o>?FfH$3-Hzl zInwdUXM!Vz29-0cSDN^J8Zx|36Ot8^V!~aLb3bn|lmu>Mve zp9r`q4+*%4;VFTFnMaG+}!wzklnJFI$fCNz?8K|#TnFJIcv z(17EX$3#R$6&W`i_oRs}A;er)-WfOeI62)p_yBGlF{p5XI*`iWvLTu{y}^*6^wf-x z_?ykKCZ`Z8X#KNbXo4k>VFxsL0v-PV&+h;q!hwY-U^5ZeO9hS|0w>wP z$p~;V2b}x_h(uySLPC0a`lCmWii(PAYHFIAnw~v-*4x`VG&D3ZF)=$kyRx#fxw*N! zyL)nS@~@BipFbfFshOw&B>;KCV5)0rp{<42m6gI!K~CQ-!41#?<&ZA`Ky%!c>#Z+w zHhG}fXYi(K{%EHeSoo4?yD)kU&FVbE^N2mH;u0Rw%HN-_S?}3 z!6JZY7akQI6B`$ALP|zdXZS5UlPwJm`c6GZxZ|&)SHE^jfdGO81Tk9d>=*0W3vGK{7*_x?|^C2&`cK7@;LEfDoN55|*!O>ipO}%==S#=Pbu!bEV_eNi)(csZ~hgFQ> zk<)BXOIhmq=d5;|@fanXhM8YIh-2}ZHVrM~#n+EibV#pr#k5D~MA^%Z&GN9izbwx* zm-iQ-6T~88{3^yHO!5tDxbIe4-QzRLLM(o-wDIML%;FIjSpU$p)SrVLQk0y2;@wh_ zXp}iK*AbBR@y(FZ)cgyA?;j>(ECi|_4zIqoF|E^-J^Gor&}$|U7P|QBC)M&> zX`{<^yk)?eiTo4zK^);2I&hVrPH~Mwgc~*?h^*G`i;>Kx1GHR<$9`*z(TFIKr5K(B zm~*U9=@gPir1Ah6FO|o$oFG(NRKRD`tiPP3{&Q_P8T%_n3#l|iMM%;Ts#r-i7E=)b zbSEFUq*+>fe9GX{JX7*O-+BF0rc+M&r-weqXI8V_qf~^ly|c1cbG>ETg>rAVo%#GY zU`tu}ap}42&-sMXHsSp1Q)ku+2+W3Sm{8QlT7I0ASX4o>b=>vh)CjGLl1D+Y9;H`q z&a9VPhSH017p7Kvrk3Va>Q+|u&$v|8nnO0DF^{m_)Eu@cAY&tq7gbG*;hicbSrH5j zA_IFW*6?!XU3si5+&dEFDNgBuz6OEnreYj#4STDp_e=U?#3rymUFz*lcYd~YeA^b;k#Rr{n%~@HNvTzQNgjhmWh=L(-18UIEBYxEC~RF zT7-aOLRimL)6)~G3G_l8*zQ-<0{CzSK^bE89*Yy_6`HG(pxu%i*l!H#5`ZT`#dMfw)aCo$`>TVUZo7sA@=i26KgA?IW4ikRz%v!T2MAdT0OvDoFQfRm5W+Oa)jM4PPZx&B z@KJ2*S}TXXsdjB<@Kg^cT|I`1NlM52%bxK zpgB1Ns78&YCVY>V{z73oW@%O4n0C55Z~l&fZo6N)zv#X*Siqr#d&%=0acdZzi*6Rt z0%OXZ-P5m}zw1uqc@*K5GQ2n~P>O2545r}Et#CZmLDLD?c zoRZiV{e5146_gRQZ#K~ z1Yw%QEA&8KH1n|-s@34q6^Tb(^v+n~***j`>S>qkx)s2QVY$b}1FYti0{7Yp*GA6q z10v+^Gh`=Va;co@z*?F#2)Nm=$wmHu1U>swp22Q z8gdG^5>ei`P3p4PxNH~ms^*?J6FuH@Fd;gU{klT2W5x#KQrib{zzn*_3ycd*S+^?U z9&xy6LD^ECKoArs0d>fYI(XyVcM9O%*)D2l!qi!(t~6R6JEmURLT-GQH$)kLS`*si zJ~e7Lak9Q1vj(zDH$j+_Jp@IFh>jX->?T!BSyrMplFC~@CtOLct`gXaV=C`~uzdtfif^_{SXT$3%_u_uYFUfzxA~{A6Xac$_ ze|`JPoZ#foY5SbokN>`3V^<&2wNz2`L3qZgq|aN&*aCCP@^UHPRu zcidl68ZX`d5MOY1_Mrb|)*V*w;bp!B+gI{G8&aa@5Qs8RfCks_02#4zzUtbbtjEsV z9l%W}lb9k~E2~v(Tr2Dq$nR(!mDxF*gqigmc4dB*p%A$$@8I%=wxBULAMzR35;)RR z?wh}o@cHW6Aye3vuLO9W7RQjo5tY~bm_;K_$H?Pd!X&9kiF#c>xNs~wtGNVHuzrm7 z3mRAMkr&Wp+E9!QVk?$vd3>mzWKlK4U-3|<`s#D29RKwD=8NyEmBKe2%^E(mUT>*e zq`hhVC1}dP+D9tM#LIz~I8DBHPnI0w?lImz_3(+JLir!JTVBN3i$4{WyO^%|C{fKC zartMzyXEBDnf>v$mC}W|ug*bLXXb$?`zm`TB7t6{1&5theV`T@{+2}fDWhx#ujPy4 zrCzw?bD%9SaxTuLZ>g*Mpc5I&m&o#HdG`B3x7P8w)K|JIGJqw`5!{t<#^rkykffc3g-%#ys8- zy4{dglJuh@d41z@XZ>U>@UuRDe=|$r>GUg2Qe)M5NB7UaW}h?vxHR(T>z&T0^Z9vK zjEY0PIk)~=fOI-P(bL`{efwvgz3yHw1MGXkg{KrG{~<(e{%c0-#FCuZk0F-4-GdzU zHMOh$tmdJ64KwN+3|E6>@obhp>0dv1Mm$b>_r@@^pBujqPvl~MzTaKl-?4clISw;9s}9%0G`u!!cARU9%Y?&Y}KF_TCfwS zuxrKM1^VtrnM&(W>Aw1oygwW;)^*a*5tOD5 z@V&0HDI)L%oRkk+tQ~4;17>JrSm6*3Y^A99_IqFRW$rvPAIp5dZ(H63j zMYvH7Q&EYL!K@-{Q8Fmib(vHSN)kdsr;vnlkg_k&&}P23MA*4;`a3*Q4o4-K0?K8e z2w7lllestt$+R$1w-<+WmS-0rv@8dU`a~fcaS&{@;xUFwuPEX?Tl5|0XdEn@^->gH zkJ3+hbX6K4+hyx}VD+>qS^;bIV;On4j1RMt?&?+IkVo~CRBRAbqcC6~27g&sh6`f{ zkb#5&Fp3D}-ZKq=3;b%0tjxmfjR`7@f+8ugQ)vpk<46fkDlq~mPKoQv06`UP0kl$~ zw(KrWH=sE7jxrU*11o?g>}MtCWJ!sqBu5Wi>=;jKZHwqC_o}-gsp^&h5P)1c2sZ-q z#ypOj0P?`~w)%8A3807*1V%PI@Kt~01`)wS_MGF6ie-d)wDbd@SI5=3og`_=#(Uh6 z7WxojZ-`HmIzP@722UGs)5%rPI`#mP%azfN$|$?EM3kEiWld`}OP4QI!UF@O1?X)C zKzWIJo>+yBCcM-N@hJ~h;4TzK(V|_+^vI@Jt+p znJsG>DnLZML8h1LR|jqVdUI&uX_hUf=LNHPQqsotawj7~yLyy#0#QI$c0XEe!XJD{ zRAJKB5#f0BRQ}R=lp2QT5xX}@kpNz8N~$05f3S`|m;OL(%tp>x(vhg+J}7exqSz*q ze&2{k_{a-;P#IPn%S*T_UOJ<(=NzvuVCmqOBQkf*Nx1@2^m#jS| zxQc>gHK`7;YfO$MkF6mac`iA*q4;zSNG}V|musNhvScY2%+YGJ^d`;+NI8u5iz$JC z0ra^&hXf+DxkZ)D6D8NBAYH7?shvGGm5Auk60pb@MJY*m=3LU3#!r#Y>e?YuN(;`C z)?%6fIlfxBxPF!L1O-18MNQ(Ap1S5MB9!Ec%MK?>k+Pb? zhYC^jDB=uKPcG9&Ogk(#%$%J?ZlYWl;A`Gf0e!JWlk@;yq}I;0ksD}S zU8zX-tmuiW(D0G>?;!5xTngo32^LWc)~Awig4DYy9xm%6dkls=v-}j)>V8!nOY11P zcHj_)mw~>RrS($I-~jIU%31?CPHh-oq%q6@w%FSw? z`kUGrLDAX=))#uhqnCTLfBTd9*{H_%+MCv6Y_=`# zQDa^7&7Lq+f8cFyKSbB$Vnx@HlVdOJ*e-~#)SwF`XpWHg)QVh#k6UOx)dRgGzo2Rl z8RA~Kv<)4_<7UyxR89ANn~_VGpn&?8QWaP(0rqLZ2r6{CP3L!%)5NH3=+td607+D> zL%&p!jGa)Bk@Jif&Uw5U_hc`=p_NoGcdkgZ5vQLjlOT>_bA5u?!FAr%{N|A5vzM8d zbHPoZ_9~SPQ^ixaji;GGelPSCVE{q03shQuIKlAjlDi};1(Y2H>EXc93^KaeK?Xr3 z)r*tUc_}jv-kQUASx{|pL!u6v_t=V8tL}>a)CKFgFmrtw2*jVgpCazV6c6D=4O&tZ}ZwwXrWwUMlKB$2vu-0^dtkFs%m#t zfGvUEfgW2AO6l7G+E>(e*XRVu#t(rmc`iJpfIeyJh7>gclp%zR!6AsjuotLMH+yL* zc!|_#IxOvUr<9W02Dz~g;+BB0w+5e%6(@{Jic;6b7|kvZh`~$xmwQw;2tO0v{u+ME z;U-B}A0yiZdL?xJ@X^?&zj|fvvbYn39RcAWK&UIVX#8{}RUn=sp?o?jiizW*-gr=r ziU$Gd5^XTmg&02`TxG{7owp9Q4?C6|O+AQvdv1L6AZS8x8I%dR>b-%IDyM;wYZM5f zpME2gUHZ>Q4k!LbE(AbJ^{H0AXv{c{NVutIRMQ9v)^hYt+EPj}_)PLFQXFGfIyCZT z*6n+&2pBKS`b)yC1~rnA9AA!-#zW{+09J1ZHGRq_?Px&(2pt*Vpjh~Qnx?}*oW5$) z#7ayNA*{d*7viaWuRWLsaFC0?ZGyGuXQJ`H&ra^>A0q4b;NhqoF&d_}QwJfG1Rr<(leu@u_NKCiAmk6r?I#~bN>PGxdV zM;B_%oE74o9{>C?#Q(;9<;pKkU+6C!FfI6xjle=7T$my17aw6#;`DrrJwC-8d=l)T zi_5f&XOAhnvx@~bl(w`2L>^`G^3vzWZ6aIq{4bW+ZZEw1w8U~SFFUd%c4hgb#!vOd za*uVW`tdSW*bl3@qVmC4Cv-(xct!ukiuUyt+kNXnOI#G{tCZU@Yyg9gaT*P6~h@b-Q_^(%Kjt$gQ2-plx99;Lv;H*Pmmz`D40sQ-X+YBJ3;04&RM^LV}}(F0o^Ykqiq0o^#3q zi4aCE+44pG)D=#8E_1FJo5qsN z#^m+h+*m2TT_e#jV`ie#Hm!TEtK0c?wNrA)-FF4m@eS9;>BVQYY8+f{F1-H3>0f)< z{_eL8w+#QftL7mm^s5{J_16p|S;ViW2Q(~eC-NKpWDjioq?#e^6_pm)^jYrlg?KLZ zpyqX{60@q()S#A4;hL*M)@;E~zM@+G*&L~vRs1&J7)IqUdB1IAsow-`CKaUO`*tMX zD@p33?2nDqIv4-ykf%#q^Grk*=>YY>&egY@CUtz7&uyekUn=QK@-}w=gV1Yy!R@=|AxyBD#dt@rsoi{8*4dJO%@dXsIz_-@*Bq0FogU z5KbpvjsQn!9dB)O(!wy^bYkhF5(~_VN5Gq&RN#3Y7CHowwdm=eey9@PPqM9&0HDD|4KC3P|cKhG6qlCxHx%0YhxP7j?69)bG`&w2-f9 zwtl0u!vXauQ^_o*nI(~hhsg3D-jzhK~{LtjGMiUgn;l{wB z^5RP2xYouB0w7Ec`iNrhF;|w6R(J;Q+#Q9Wu-){w1Q1R!0bfXPLvY6wwRgH$AdV^r z?63mEpiMzQ06=B64T10&6-avLw(n(tiIVREr;SU`Fs&K_`ecu&r{zSQ7y_%K2^78d zVSlLt?!wGMycCb83!Twoe9c_u_7$Oc!=DyP*>i5|1!90r%=CSgDlw*^akiRUPsW$?*N=~i+c#y2wDmg zKpQ}Sark4b74@6h#1Ifo zf2Yx_wSF7xua7Cg-;N|d|GL-t+s!hxmzDx>dv;Zb*N6WhIn|2>bo+Z^hWQw;DH{Y_ z=BV|~kvb6C$#oN_O z>TAj<^}N#LF!dA!ui`76k?0503M&FbE`#(QjcIQnZr2O~U(bp}3to(HyX_vxL{oYLxl9yF29rjRe0 zxFKn2$5nY-LDD7Uv&E3=%_pVM8izlg*S@HZKfl;t2RVQ92IJB2OFrM){YN*w&KB~p7ZtI&7)@vPky$POy3ero_)S}Pp?DT>UKnRuIbl{15YbB z{z2qB;D5}2e?BPxjr2uL|IZVps_%dP$)}!Erj<76xz)7&Q2xFGOQu1eu7!8K@qIb{ zhr=&zWR{bHe=i^ADGcbD`cN;nt%#VZ5QfP+51&5jmriaU-s~;Qp8dW0uKruJ|CK8z zhN(H~EWaY@A6zT&%IX!HY=1}8EGd)@>DCvH7|$R1Sb9wLc*86?D5PQJ2NUa`jmtMW z-p2CWt9H1&?sif?>6`bnI_&({ThZGy1-$-6`Omi;^N%LJ^VPKOKHdnTJzA&;-tV3b z`BKULY_Y)V;N`CRwzvQN>a)^^Md&>H2X(*ee%A&Lz5QUF{q25Oc(ebz6S|$pSGVqH z>jsYRa{o|Pg)}i^0cv@t)?Dxm2=fML2#9tY$}Qo{nes`Sc|W=|eBDf$=v1dW)S!=w z+LEP=Gi8gJs_W{u!k#Aje9d)LSD2}F;&SL=@g;K4*q&&%^n!hX#~KmY7P zFFiZT*&whMW1%7hovJ<&ajYT)0THeTb>Hh7v>b=j`w6^9V;5fqN`dkLWQ%VrI1Lat zsH7g0PGjt=wp)aa&=wGC*2wS)ybML-(ZKLN;`AR{ZKUuA6i~X0kRXeLT@K6vLaZV} z98)L;Uu_f|WP@L%!Vtfdgb6Ge8kQ5;M`gv~pmMJn3o7hv<9#96={AiXd4jc+s@D;IXgO6q58h#oblq>K{Bf(W?z8J{Qw zpnB$|*5v_FtpSua4^qhjyWy`|z>PBHL9+dbkR*f3=y0Zp$ZI|k`h^i3ezCV*OwnU1 zbSYq9%l$S5JLdrqcUP17xKZ=>gv1#EwcBW0wp61yU#KWP9vF@LsdHZfu53#Ne3ikn zyAn*Gb>A!0k`n4coAf7~hy)ho2V!0q$uo^3&PIaBZ3qeJL#gD=0;G zju_i=@KekMuA_;Rl(XneGxIEpaE~%FGA|)2MiY2!tO4 zxt4BXLJi^HhOiQV>|)LKCR^5R2plh!7$dj1hWWCLumKe6(2#x~;Q2&|b`g<<0%5}{ zKHo)5k^qiC2c=?LXgZCIc_Pv$(ZB*5qHX;WrZx5%(Vj{JlA~|zB{2G448Y4*rf}40k+Ba&e zLbg@;D1g+|>5Wz>yBn+RpHj<}$vlyKw$U2tEMbzS{h~Z|m!s|W7mI>L2VqTi>en=UR%Kj_Xh z;^+|Z$yt%Qk36&zPZgx=*nWZiJ>vcD1GXJ9bA;R?HIi8e*Oo@MCECNS9@6@$u@t6AOqau#3@?x8 z_38j@^%c2iPrpQRy1SbG2ATk+SobhST(*SSS>pP#p{AjtKy%6Zv1KKzxdsEB!VUWh zk3EF4c1G(Op^Yk3dt6R{`VrGoB`a7p!~s;=6kc(UGXhiDQ)zL=EcWLT9|;Z%7x@oHRNL~q5T zIJvi|s*jclz|#u6oQ5k^1#?H0eoz({C|?v?z!FjI8fas1w>?wtAC!AQSJU|e zCE|f>bE%=Viqb$w6{DlXF(B)LBeR9^Fq4LAUYySSWviQj@PyD*Gm0C7_(WBDjPXMPYU|w zn^`V@^DI)h%20GjRn$mvA`VX+EIMmd$JFy=sHK#pF%|ACaeq9ox+#-uC+}i>9g?AB zw7t%~4@?R@$c9kDJYjxa;DVvPshcQLFSs&+0euu_ zQ1!Z<*Glr7Ks9@z_=bJM#1P(h3gPOT*H+ZhKPK5f1NNsryPKtUeW>GY&J)*tRCrpI z)(=Cbo;cP*eQNxp$aZj}Onh${3nMG<>l`;o!jcklVR9qlG#iZQP6xNhih&611pC!zJ(rry5vfuliO5m=@?RO1JT#6gLOZ zc1+ml(4h&BkX!>8IJW$y$o&tp06zf)ctA#ce)_r?tfY6<9F(;OF%{B=Xke}o6hc6X zUTRTOAcIs|xc6bgc#w5ejy%`0#SO~FsWJa9{b}>&!=pE|68Qd9z$feUX7!D40)xb- z0y~k?Js=7WVIBooFp!l&>;X|5z7AYEcmsD;=1P2rz?*%l1ldOc=55H&*A^^YV*v>o zyFTyC?&@OicEa0hK77G^c~&DFA|nXAlOk3s%E4fiDhYVV%ioCCwh!%mX>a~U^aVgK zw}Hofj2az|!)GJa{Hkd%qwYT^GQH&07i3kZuFtWS`a_fP|oR$YX%H=8_;esi;_;y$c9C4@vcs&DE8r z+XlopdSLIT2qt;EV?fM#$Rl^gWx@@-T$y`7W_QhGjlc{$D z8gt|4kpWEuMW1Juzlyiq3Sxsp((ca_Q|H&6Cw6M)r_L+RTwb`^IRESN{e2CS!;dx# z_P7O*@1qkJ1$r#-`!R*_=K?y4!gyPNfp75+>K#XD5OwGx?J8xbulsB*<*L6gN^{9u zWl5;kN7#Q!EYC;q#gf$g9ns?@Sxpy7&1Jj)WQ9iFqjheucELBIC%!V?g36-0Vi*Or5WJlGqAq}oNWGo!GotTnDu`F3}XKm z45G=sw2c1&gKr2d{EGjA!Hi_&hYUx99qlL<376Cfd^d48mrc^LjnMS@SnDyT*ulA9 z(&d*5^*^1t93)?1;cZ+b6=K+uGf{5UgnK$;S@pryu`^DW>t3~;liS-BGHIY7R^)d1 z81b$n(m4*(FS48i}I$rT#Ss~3Kn6$s9Pn(SUn-vA@nSA@0uAC>Bt$hDNaZR1k6FQ^n>#e_305~8yo3ws(9 z0+1H2%I&Vxm=F$Oka9%c?x1&wIn_bOtWzC?V+kO#4S%f%fT=}*T;iCXs8ha^fzV;S zBO)aUfKNATwG-;ucd78(3^wX1D0(R6&OecYFft81&5 z%|XH=r7RPp``I7X*Pew093kH*n90|XXdPvCV#KP00XkUOHerUN6tM>pY8wUVsP}H} zO#mX7k>h~nfjj^wkAe&Wd-s74j8xuOfW5e@hi;5sv!IzpWIm!Q+06YkCQR?bF$iP4 zq4X}F?VoV0y}*LUT-54tkUqucKpd2`gh2pmY;6$ax!KfDPCcWny)hFr+h*9H)RFH> zxWyXo?N?Kg9!_LHfCj*5TOI_~#Q##|Z0JPveDJ`K+exC14L*^|HYd2}0QMi{9YUux za&Z;}4kbuvYM>Uvm3rC|Vhfr@DcU3#t*Tl?3uF7%{m-hiBzv;-&&%DAl+)lDBot5& zd)xz3oFYxTE_}M&9VQJ>NRtX0^bK&paXIT)q*;T_&>d?7m#lSFqAmkXG@KxA~=3)SlD3vIYzgDPH_Yx-c}w76!$k^Ok)y?awnsY zjr9R}=S%J%pN>N_2S|I@V9=}Ld6Va4bfIh%+^sMCyY#|H&PNf6lEv^dMxz*(lCNxm z#wh;e_kA3qqoH%Ml&H85FB#rTCk*jA?p^_Ofav6h19t8hKSH5lZ}&V0ttHiM?S zY`P*Gx#06PWDjRDPFLGaK$s)K%I8Zaufytz_4I2S=W@LCO1CXaT*VsPI=}n)pM)|PgrH+lYXoVZbvg_h)cKY;3K76-F*qKRLDmBk zaKO<9auKgSp^E@g#B;#DyI_Q*Z!i!*ptgfY01{q>(pkJufhQ5kCNe%t3D?vw6N~_T ztY-q%Itd>`VDnCd3i3?p8{}xYmktrFn?~u9RB4l6G zjJqywQamWqej!2%wa_=TbWewPeWU7Wv)$#*rO$2Cx3=z83?18k<0{C#GPV_9k#440 z*lM(K`P*=Z*T?--gN~i^Re_hoKmMMnd~VcS7dEK7utXow^#H`sup~I?iXPl&yuD54 z``rOE$};1S%00~r%Rr@jz2~ITqX*9xz-_#Aj}&l3>)|D?&&Zcz_Zkvz7$bQ2!~2y- zWK?cGic9!H`%-;ACi$&eD#FNh;CD#F1KJ4JT+zV6U+#_1@)+Ix_3epbXumWZK!J>;qxmHoDURi3x#jSsFV*8}odX(Di>q0RT)UcwFY?La-BEji)i zxk4ERRSr^AN&(B|Se;$xcL~=?MN~5D`X8vq*1MWZ*o)VX?N75p`(MpMVoaXqu|cC{ zQg_SD6Wy(=f*2gHM^;^BQZqjaoNV4Is1SraEhZ1%?3uaxdvOiVKVj3dXFrcB8gzeTz9T&~w}@?RA9&1iw<_-AvG;xf z<&EnNm-u$LqG84Ier~ z7i+y9f6-wHPI#Mik2?4HS8p4&2h+^^72Jgzcl|Tx!Zdz98`}RGy6|hh&S<}D^Uqd@ z(z7tyPQRDF=f6k#{|-2Fa(OVCXZxYqQHy!dvb>w9Ef^*g8%cdPyX?rm|qwl0WQANv!e8_{8m{l zDtaf&r$YPwIFdt*i`ZOdz=@?5GaeN00>yx1T^qbZ$QbB>2G~+S$x+Kp0n_y|BjZL5 z*j{M85?Yr?i@S>k@Y*pEh-TK2^}*nb3%!Y0)!mGQ3%oj;rDwa zAziAIyW$XxBkzC^A537oRSqqH6u^LN)Jy=> zi9ty^fv6O7KG|rLlPa$OPBBIdDS~FvHfHOQV<3g0Bha>ONPBlA?@QwTxE#L-($!ta zokvXWL!j@tsfes9-Eln_o)Oa7Vt0EDG<>hg&UOJRD9N9$=38XTEo+>jt<@=l<>ZJS z`wT`Cq4e9)g4_1PD5Se!$U%CnOk?a+tCYzKC(ef7$00aW!p{>rbV*&$GUwqO|ZNYjtp-o~?lmMg|G2x`wdL%2&aDXmCCS&L;drRDXP(B(VHRnpCABTCC>mzo7-LkPnW2ZaTE}n{ zYw&Y`2rT~PZhCl&q69@5QDHf0dFj*%McVI6Q}l;+LRw^%G6#^Ua>&ji)nQsNiAu$L zP`jc%CpAs25)C||0-5WH(s0mf*S;u5oOKXNTbf0Ci1c+s4WSgUqzrby2+l$*vuIek zEmFhffiyV{D~EGrPrm^L%3(Uny1D=*g@-LiQ#M1$Jm;P31@Zc0sc#kvJEC!1J(5g- zN)fyI>m~_Bx(n>)aWFS4Uh_+Rflx)!@C_9cvlbASmRyO>e`6WR(F2O@#VM6X^(&y` z>>Nl$XqAHMpLV1KLP1DC`P_15cRkwV*c{sbMvmh>ySWmh~kn9|C5%^x_n zN3;nj9!wjbc74T$m8@`xMv?pvbQULyY(Eo#3aH>ZZj|sM8Z91z9!0ntIhX9jkh3li ztmMi#!7{>GB9D1lHIF4PT3)RA5u0-rS8A237;peBG8QT7;0pZVTOz%!rXq&r-Z6oW z0`P4$4WiCij4gn8Oe2`U-6+-4BNGu<(XW~>>Wb_vyl`M3K=PKa;YhX(s&TLnqOnIN zdDOx2l_fKB6OC1Dg;+XreX+g5beiHf17u%Z6@aK7@rBl?6!I_tI&0N1@dmc8dbjmb zPu=o*7~Ih_n`fyef&S7R5&7HYs<)>=K{%xBrGjK2G9z8_j!HRdD5KgF=S9p%QIl;g zF79_AYsE6=VQ6S@_AdhsB9_EFTXUS0q9I}wXW5}*7=#qrE4X%86dczQ(51?B+Tn@i zgpUQ95zDwxO>EBbT(WBNxr%c^AZ=CF!G0Z^Z0p$FGLDEe&PIs{Vt$iL7H^{zH*bC6 znQK5j_bBvE~Zf75l3J&x?J2lz1VZq`#$wI5MsPX% zM;d2%oK7SG6(DuU91cK|K}Kbe5g_j;Xj(kSakO6aYsp zv0280|iI>*vE25sh)j_tT9!L zlfr_m6o6?PVBgMTqt?FA_kejca?w#MA?+QnBzU}1D}jM9Q2-=Rzt0Y`Y>(alqH$RG z&gO^ioW9XHgW72cnJwd5vF9?vh@M1<+Vwh!%rNb6?(#3GeW-)0}V~ky>3aN z`UC%y2e+n+^#7`*dBv+?Pobn*?JS6+6Y*EQy9#qU3e8M?R z`jdCqI7JVKln*G6y1X#u?%TZk;ijyr*wdik=fUVkjjj0EMvW`YCPMz_@`ISFI=&+5 zi=Vzoe0|J0cf~yPnZ;aD;2e)^^0py?hX~u=gmr2P;`!WNCjZd!fyva5dU_wD zGiNuR=dr@A%Jyf!J`R4XzR(&${HY;9e6%ndJ#Y7F;l#>p0hnL#P1Ky#ptv?Jz+Q+P zJg0nqGtVsb@ec3eca4u6rj(tKMV_dD3m+EwG=2H_mSm!RQCF6vX_tiZmIU;c#O9Y& zqL!rimL*ob*#4hV@V^-Z3xSiG{{@0W{{q2L;N;`KOz^*T?)X3L1^=%D!LI)r1ld+- zA7UIL5)3Q~hjNrz=Z6P(7mjI}rGx3;ly&1q3-mwQm8T#pEc}ebZ37Gy93!hZD?MwX zS~lO;I1vNSZz@#VIl2z!T~-snW%I<_t^IV)*lMODz~arDq1N%!Ib-o_Z$=lv$*vf| z^Dhn+8kY6d_>Hcgg5amWAo%ldDfkxzqyCnHe?gGz6a+W_f?(<2Qt&SbTAza8w^I;g zV3C?T1;LJFbZgE1_Ajd=m$j2?gH-R1Pu9hc)P6h#!JJNFt3>Ftm7Ue|MP|tX8o^y# z3n%{u!GD9`zd`WdAoy<({5J^x_k-YWcT3$7`R`*STmw%boZpDUYDPay z2cFxde?#ZbUiz~-@Zyb}w@?@_<)q)BJG03{hE5{wAu%jBMv_by`-|tN~ z9p$huhF=*KET`uFUV-?_zP1_Jq50GH36mTcz9+DoGwXO(y0d-6e=FW<_xI-u$ut2b z#(o@bQ<=JEs)3QUd!@du&#nRuVhpt<4s$6 z+-#G-HLU^}S`l#p1Ym1@0(^fuT#O+dM{l$Wl&*i#dmsG(-LMV7jLFo;&ob!F;(?+W zh4xOgPFtjM=~zhIzM0i0K(HQ^ARmKxKWNK)VaXIl5CIV#1x@Z6EER`#^a;!ovD@6i za^~^@2umdpP!JFhB89w`)AxWYyhytM*CF6~aC;mAH10uG?7*xZQtWh|Xh3+54XAd} z=wt(WUxwe@3CFU9smbBka3C51@zepdrc|GNMz(Q~^pqj823Mftq zy!cGbcu)I$iwyS<@MRi^#(*hQ)+h`pjJO=2e9CSiKClaS2O{1sUy>I=ZtUxz@FbD3 z(=Y=R{e<)r0ZW^-P=3U6RD|pfrcVH=-h@3=LMf+4@-{|tHD1yPxS&B5!Db$HJvFKT z=bNXb^p%7vI!*(`;kGmT4!J*~q{x_{6foL3Z-R+m^cU)07epfguc~;TJ^M0aiE&ub0Z2lG_xK*^xuq;1!;rAwxdE ztG-ZuUlI!dvZW~YX(Ja%0CL?yQ^1ZPoknqqB*K=&y(2$(aN*{U1l4To3ziATXaPcV zdLmrgD1a>AgvJZ{#X#CFU8hbo-nF#PrfG|@(MC(G?nkhS#>+)q_-74y#}XKwN_`iN zZsAdxveEi3hhsRyTXDA1EgS&KzZj3W^JvR zT`eR4Qd_Cx&)9nPf=TSDhHfUDkpO#2>hM08)GR@<5%(p=o{PTwY?1VPDZ80* zoMUp_hoBmrJi1Q-7ibNn#9>Jmmec@CEV6JNZRvq3J!A5-=@{JH(X^7wFLFoDjR7fg zs@+BELq2KSa>&vcymbqb)9R6pcN%+J-uRxSI70qcx$5q;v9&%@f{d$=A$qwx$~9)S z=qlUR+ZQe8^Y(z|F1UzZnK03WayupB`_w8I1Gm_ib1gEP=A^?x+Fu^x+$L2foG(vu3Ro3ZRWWGPkL;VVh!CJl)|B(Ew`gJ{axm?gHS#yO+VXIIEB zTRP}m$~Go9*^HwUMa|QBaUA9~rWX~aJ>YQ$^Y7B?7h4*yTiyLtGC7Wk>p*f%XGp{t zIj5Z>Cct(oZ>QnlsGOn21)?32s-q-HDI)9G6FJnV*d~xCouVj4Dm_zD!q%w4ZKvR8 zkGylXTs8)IZzfKwMFv-d8x}>jdLldQOF_a_nHiE?rB|xW1>0X>XHgO8hg`7y8xD4k z%jwG}#z28_4}5O`a?@P=oLqT!Q1xCmj%!E!S6aRf4yHG5xRX^f^}3|gpUkOuMn#5FKm{bEl=t0(?@yd{&v$+Ay6fEY!}%AO1?+k3$K&~G6@zG!09xx3vqaVF zWLd1nWlc0d_lk-+F+(t;3NQ*D%pkCcBj{aIZk1dN;f?~{6{JQ$Gw+L;gu-x}p(UH4 zlCY2EZe=r{z+tR+9hDlaRBby|B3vuKCyGNv%3TSrAjml7I?-C9_ ztx!!RRu@uWKaWiv-t9dgT`XG45Tth&zZ z0$#UZb5GgHrGPK5eqFgu*H>52q=oEts;mcwPg$YO6-qJ%-f^XSa2`hP)2Lr1R|MFq zrQ9(=&7f|&vN;nlRIF5%mNoqtcvUCOmK@2_Ttu#4cYZP=)wS|tZYu{8mrbqGScIK? zom021I&Oer+fo+iQMWU#HgmlA3)6g@B0IF?xooanqa`S81fo&evQcucyMU7fP&gZY z&tH+r2~-t;;zp-Y`8Z7UX<^_6d9pIv-k&ZzOr-@a8QGX%0tga75hFQ}AkFy(RM!(1 za|fX~;FeM_GamGMki?^vm|xs>!hx_?jh?E_lW;crpxK^((2nkqd+ZC9u$Tp-@UcGO zw$|y)U6Kpd)sep>1xh+O=X6bIN~Io$2z12I3TpWr(sq1R!U@LJP(AR^kckd}>*0>T zU%`|#LnWn&F$kg#=NtWp$;Yhrqr9+ZLxhs2#JkMWj~xdP@nYC_y^`cipx6)|)d3)s z0&18q)NgB?B<7tYCIXwX2qv@y9%Lq1Ax!}RK$R`ulqL;^nh2a`zrgzd6fy6)W+#_W z>SWo#$8Q6)brRI;Vd6%hp$gPat=jq8ZfeCTe+m8%^0zOzE~+8DrOCGp*onMl>%njj zyh9Stuk|1Kf=nRdzB;rHNKf~EN|fU9GrKezQ#%^JSTex8`F62+nCA}2qI!wk8YKw# z!vZPGpnu<4Xw*C0?hfVQ?X%EZZwiG;u=kf*R{k;ixPa%0y)Hu+gm}ihvkOGADHc2- zU-ugaAGDZd`+9Cv+!)TvZWxt4ZS!R}EQF3!57P-C)|X?aM}l}q0k|G!#G1GWO;Qs9 zog13lefqCXBj~V`$FrNnWvuoS07mz`3^(fp+sXBGspxXxcwA&Ond+AVPh6{=_keI- zO?6rCM5_Yw!)AMv>W6u=4^Dx-8%+~c%^&!4u`LH5o_)L2^Ja zp!DQFoR!^~MWXL0D$EHp+=2Yzs`$th%ycA~f^QwV+5hDTO8wV5g84^0u!A%|ND>4` zfWIdHn|L4$3E}C%{|WK%zd3?IVSmTN0{|nx?7usL%=!Nb5`3G9{qdVlzjk^kSN8?q zxqj2fFeH4eKbF#o8+~SxMS_H|BWNvdv8#X4BBX|`zhoe!{>J+{cY~&x)NkYG!EuITMlG@VY1_HmgOBT zG|AE^Z?5AUuWV_L>J<;nhEo&s>44V}~m88K|Q zm3(%|FDkzpSrRHn8XOc|QW7g|quCG-6(bD}vIH{)l6Qgl(yAxO$7QEq+rb$z%Biu7 z@`Xdov--miYClS7CCLFi+2@R?o6Rwv*0VI`52PJw1*DAt1SQt}MyRNYJAk0lBH(Dv zlV0EK=E?-H8>sjm7$*@BCLK`YDt1Lh`^q_AqSjugdIUneR_cWB!SRH zg*~yp-3{R?u%q@f{s3aF3hL(+;9BZ;YOOJK2Jl0!B`@{~~Ub4$Zbw;5V;0pP}NkAv-OI zfCngWZYKC}h6d2WHphiG^6CC)fjn(h_NBF!Kr-PS*i*FEq$VVO2aGi6(un~BEjYkd z8cW;s+Lyx@0@{C89oqKYKUo$>Q$g&epBlh(d6-X~PHU(4DAgA>?xbqJOHpptcN1Zc zXKyIhzGhh!tkE-cn0BU#YuqTn91CzXq~QS5?~YEjLtKaFu1Ov*hyz?dI=t&BI!Uh- zPyOw~5Oq&zYlUK0B)uR$lt|U_1**V_VqWlE_Rf(>030BP4???rJ?dh#krFQUhwaH& zMu;(*yXyqk(`%TeCi`%}{c$+wRR5V~d@R`qCh!xRn&jTQ#Oq{>kryrMkAeN9zRzZXgEuHgTq3Y^zY`4+pN&M*PRewHzZ%9 z#lEXp$6k{EQKp}5OREb!BoCJasF)^0?XOOWJ4f5xxPos1iFj6^o`Pj)0fG66TfMwQ z&PZjm$S)oE%1GP(-w1>89b~{zGl5pKPYP(q-o)ustmG=It-Q$M}EgPyP zcfY!hZ#6r#{2E|;@HA}($okseCrNlHDo3Oj^X`msA?(BPu%@2HJ=Ti#EOc}|oh!zO zDzq$2J-V1FD;X#FG9~JlD>+ru?hEO+WKq_<^YHW_Rz|HW#_Nrv#{!0p>&IYZKx@1} zsh6NuN_hNV;`4%xPOlVQs}r{oi@tC?yjon1tBAgG+u736X0=+rAD*^}^5Jn3HccCR z5G|Y4Ip8LL?8(>K&zKR1x3@ZKo;v1y!EE^q=I_=#TA_0`q~g}OiuM#?P|eX2Z)T4E z9FlipAY7NSYdEQ*H-Cf_56cvf)B$xxErKrR?0rXz#OiX)VqA=>eBV{x+-7fo6KV0< z_g)c0ZTT(wKAY06iB@5-{Cmw;d$RDMPC&jSEQaoiddAdS_xh(f^z_%G(%+90?j=+W z(BG&@`(UT@v#!mS-Xmb-qa#}0{~bNUy<4;&f4et4BT6#)Fh+i&tWro_f6C zn%gUKzNw#@e=!-J9%N!Z{pOnC9rEpGpD}|?vQ8D7nFk*^Dh`{5Lil5T6z(pG&$&y- zzunqoZ(BC{3+?+{dan3z)62lDK`A)-@KTI)0X^@*Ifclo0HzHu|OOuUQTsvhzF z?skdre%{cl;RM&J=W}1EI&;T+%69VF+I_z-=-tY{Y+JmgT4#3nyrn^V8-zQokR@_jrxT>~4zO{XMTIbx_-F2R&=p z_kUa@_IAQwwKh2lY8JOWBvWs82S?|ZR-rzGI1nw+V`K?Kbv z*Hr}D58&bSOaw)F3mM`n#_#y-px*hf>2U=0JY9!b1XCJ74VIKL%Vq<5$>wi_RJ3cY zqY}l46W(Bm83XnZgpCbRX>D`7HNFdUgH1s^C;^ydm>PbcFgQP_N-G;sdkv)}^i$ z3L`OsTVG^^O(B#3$ULM&jtwRx-iMdZw2FgSjASGPKx~i^2M&)M_B)#pWW@ZyaNS;s z+?YS_0vfL(A^;+#6&=|?q&+xR7lt$fN6o`FgTkalRH3^;Y{UM>te|cqQo;y?I*cKY zFepxm-xR0RC?;fqV!m^hZ9|5kCqTFwWwQj?r9u1@!TV&gC=19rP1sFWOo7Aq-XYm} zaR(*pY%qAtuWQlLV-h?^q0Wv|r!td7_9)*QvEX(%n|Mc~+XBmJ8a6%wM#83`bhw~^ z^`J52dd2TxG(vVG;^P;z(I_YcfU$iN#+s+tx&lN6Kmlnm-x-4S!Ock=U$^|zkyGER zB|Nvnog2Xoj3%FEI=Zrc)g+aJ86w)!$dVb1*QAss^oLcI_ z3(_LlT5D8jXhYRr6tk0%$gg!iB0@t_KtkzyfZ0a)`K8o!FO((MDUMN9BsqA(-Kb9{ zIe1ZCoJmn|%5*B2WC}{`JwP+*y*=&U=%Da;7fN=7x<-_Sb`bG0ik^F#<$D>)-OA-C zplK7qupWd4Kns+0QKLB9D+-#=X|$rqd&$VR#&ViH$?Ua(oWoe=>j7oq5H>F!O-$5u z#9cB;a-jgqFj~rYwE=;69^(uRk7Ut=!;H}+bul7(BS`M&^+>J_NqT9;LQR!{c?l&& zb@qfv+GI2Szzcmo6iU}0u3kT9TmWj1JSun08cGV`s0Jlvqm-9IUtK}PMp(lJX~h*K z#0n&CBqwT$Ie|)h(U{@wXd%6G zgz(IvZ;oJj_VpQ@AZG47;humQWBE^;3EXoza8dg;7>b?3bp_?v-+3b90$uHwxNZeu z6VIV#)oyTR*4&HVuryGyQsQlbgaoX-2wLa1lP-r8Ib^6ZjTG}I#M|!$wwTKQqCN+k zg2j;}QxH2MyX%<7>5y%A$n7KC_>5~#;%1G(;xgzqf^+S^U~2_^%8R$SQ^biY3bqR3 zNhl)dn(~{-N^U)2%Pr*^E_D_I4z%-(ob%c)`s~&epaoP^t+3okLy{>dpn|Q@8gI0K zLu%?P(cE+B#*I^<{m=S+vm}zBu3`0GK7zs7vINsdHqGUiGJI(wp@e6ZOmQX8Xk;fg zO4)|7)I>sYq}<1D`Ar|FufG(qFMD@~qRJoKY1(MJL)CEIeRoSwdRb)EmWQ8X-p#AS1@DCP(B*Lkli9p^&6cgYB5_BHM<;&P~A z%Z=i4P{zELC%S;NU(hse0=g>UXghIW`mMsn6cTTnR z-)}J%GQLyGZY+l#Y2vf0AE2pQ)2kS8DHC;4ABIcd;Zv!>HHzdlawWwTVByc+K$KDi z#=7n&Wd(X&QeZC4V@WmgdcaSv;G4MI3>pBlsDF?b!al5&OZ&7l5=G^LOt)^0kBl!a zg)Uj+Hoibz9+g5-)|_(T<}O)XcM2_OPTx>|KHica>3O=*l@Q>AiX^MPN7l;ap+|u| ze41n#mOoj!nW&Q}VUQc58-}0@WzISNzS-vDA=$-E zd;5|DrI3(pMt9A9`r5V=k=ApGZDBzgUGvpjEIJ}la@V&X6&hS1%P9VRA7xwfSkMUm zOk~VFYpmxb=I7x3GySq1Z=tQ9Gw z;cZ&@mmFZI=@b`8YDfTu0gzgtNJj*5GP_rQSwq1ma#|co{aR|Z>zvwtAoZf^m;22d zAHYlV&$x$`Oz&bSIMXAk>eDQt8IN|64}Ei|bNO1Kc&CCIu^O9Q#LVFmR=cNx>|2Gf zEU41bu`;3fQlt?!1*LXLrXXQO=_4m_ySB4Z%i{V_K^MF!7;Itos!b^R$P~mrqtNo3 z!2tqsAd?74ht2+ZO`J8^8tDXTxPTgp(#9;nLN)v<3sGT)qgY3b1ZkWb!;9F1$Bkr* zRB{0kP(w_G-OsxOj0edSyz&Y?-|&XRBjzxYQ{D^P%fTFDo*g8S{bmED51WF&PO3a8J0=iP zZ5l&q8wp-(sxw`xNDv=rwx%feI=Mk}5>WCr^h3QYhz$(?hbbtX^@Bev+S-&<&reN7FW+boO*t}=8ZsL}M z68gY5;P-vuIn|BVAL?(|HTntPx5@H9SK7{pq+e+18t6w{{CGLR|9RraqNa~L9*?#n z@tk~?_A4T6vSXIRae}`;`keE6$nt7xc-kOrI%?v>>hH|sShG@vk3XjGk35)Z?h4w! zArba*W~SHdlPx6?Oqn6)CwjH1&G-?oZOqWEiv0Rb{7OH=d~^D)_3XCaG-oXFXWJ~# zOK(k%Iix?y5tQq_13Q8;M~%d+7AI8!jYJM8}}9sW;E!T${letR}M<;Uo(#yEt7&LEF zb!JbB%*5@oCK=whnVOH6qcpl5-xa^urC9E~wK8ERvX)QRBA;4be@7F>f;%KE$V0+{ zbaO9*Q2%z3|_44CPj5Dz$%x?gGk zWcXH`g{<|jS@USWZ7O(EkV<%$>ET@w(x#w8H<90>)&6fR$a`qmaXFOVUnDn#B^ZMY z70RT_jg;^&9uD@jx$F@22Md1ohWp_Tk+5i`BP__i2R_=_#ZboS$ith0=a6tj47{O& zvEWtF+$58io%t#Dq3J@Yw(UO((wqww1=Fw8-!9B>e>sJGd?WKm;S=xA)DDmCX522y z#P{o6%j!0TFOv8$=ofPaAXkc0BGEKDd54>+9m(i50{mEjepQ=6_I&=F4js~@JL#a8s*%P6ZpAHLGTCg|J; zQoX$Tdb$4aqkPx5Q1m~spn+R|7n{J)5{`yA?#kSZ^kOt^4 zk@{h`fAzz0v)wOav+*x!qSt4s8J$R2@JaS%T7l>X?&RXdFcxGfKiFVntPO{;;KJj} zBrMp`10=c6b_+XWy4bk?4GU)Hz*unhM~Ki77L0|l;F)mW4mRPe;=mTlxNLVCMncSG z8toJIfwYowSYSxcnjSmCrAChpH6{ZPG?D}?I7Ip2JG?GPF0DZ$@x)$omc!}*n3wG1 z-U|`7iN{h))Vjm#g4y=>DxIZV3l2jC?KL{cplku3&~D@qE|dwt;up#|)(=8%UCOBq zIjc-x*JBjmlGF#={^nZAvFA-AZ* zA7Md3N)RB&Yf=LjVJz55_mmj$=Jlo7%xjRBC8MSkdB+6*xH_HBS}?nn#+Ht$0+~yn z?UfPxeT+y8H=GX7GzX4LnEt~QtSPj>30!p!c->+LP!|75htERC961}g_}}6RTE@c< zjY;Wnl{4{RXezBQYpRNh!a>|ZA(I>Pv#;m;&A#;92O7LW zuOQdc?is7^7ebmtp>aN}_M09ip-a;3#~;c#l&usiAy!mDrMGM3}nU%ARK4`5PS)xUH(bKgG#mL zB32}q2*7#_R+w?9io-)nQ^Xq}0`7RqIIIU_OF@WD3ltww4oI-2l2@-_j|B_lJb?p- z)@4F`e}Z=7(?azd3m+k~RNKAiGLJp30Stw_-G|XH_YRg0i`N1bTIQdYSuHw!+N@s6 zUvWgkSnv}|r^3ArwvoGE?~|}#+pmFfzjrA!fVE2p2Hq4r5n}HPZwiLHxHt3D&0_V^ ztXV4vndq`II#Uy^b6N} z-u*6VHK>4#gau6^hTx32XnJVbD9Cs87JHqre$0y01I3}Dn|F&XRB6m!zfY_U-Hy8z zQ({v|!h&6;YmQ&-X?-SM{r_P>$5^?PPCtfQYl$DfODpJ)@!h;F&N01b-w?j|bk(6Z z_0wjDS30rW>Hgq{8Qyma4|i`c<0tfpRHt^6m>71BrJ$llP6(8Ub6guVZjI3=>4Xlu+049MY~I_!>jo~ z^j6^s0+WtcbLhE`#|sY)Y*%a|_s2NSZaaH=eKj0x9_wu1u1HM%=6t?+V&v^T)(9_J zt6K*pJ%@LjP}ARTHyji%RqWKx`+f8KA~i$C`1AS1)AemWmAR_JpLQqwe-O=77S=xP ziY@qUu!kxUPp#Q?-)Zkk`0LlG`1AJODF4+Ah2P5*XMLqh{kPxitA0CE>1lqe{rkZc z{*@^IgQ>Mo=i3@A>KKdwa#>Hp!%g?{i?-d)jX(dVDJV2{WC|9nj5T$RX!35zny}rkD-!KIV{A#1 z1rK3c5HxZ!NFD}VVI~OI!%SxBT81kP21YOwBoAoafky_Ybm~xJWJ01zehjcFh?VQ; zR%gk_oZG-HI0{aCp)6Q{pNS+>u$fI{h8d`sKi|y^^o>1q2Lm&i1LRMi!fO4)6m-5s zU5sq<41rBSIoK2gWT`?R1P1wXI7rJO=)$mXqfTH81^Psng25)(dn5}cXdcOe?zX?B7!+*P)5a&`aE`TN9ks9 zh({8{7ZMswAqzP}SBiyQ!h_rl8Q@5ASBZ-rm!1AlO0`4a=aq>-4QU|g(Uv3ea!V;>dR zVIDb%Giii@pwST!v?l>UQaUWC_s?{=Kvumg$daT9648%!&$Dhq9HT+zc)3OtV$cKV z>+v`EqX`n^Uj{+MU_e082J30bkaUc=6fCz9!Gn~0En?v=6vM^pU*Q=o92|Z)*ApYh zb;e~#w$8*zL@TJGPo3|I4wsV|g$UMCG3Id8yxx&y3NriLx!I`RA%cWW!CQ*z!@Z~m zZ`Iu-4Gva-J`vPih;?5=0t7t^CLIYt_PcJF`IR)T1+Y6Iee;^oBUl#Pvp1!V9Gp}| z!u7DbQSW?G=$L$}p0&WT>4cLWry@dR>OqX4%32^rld*zK)5$O{m9qH<0)S$ICSI*J zqg>CrrCSNa|HBl-%hi}g-uJ*ip9|$kibHvri)~1lp|s4eYwRXK^yKlIMUh;fEc|$? zs3Ud@ff^^i?*^A+j#1O8^LQqi`#gT6fAEK!= zQ##y(Bw!|}g<;%G?Mch<3bK%(2IkTs*TnSrri=PC>Cs!bgE=<9 zGaF`tH%73Wk+}?>5aYhKu&FVL3DzX=ROfJlvMWjOCyeVf$+6e89+fq7Qc}I<0%7l* zgCA78^|C)Hy58K)yqTX@M_vTWg86qT^%hL^MK9i?DGYR!h~9_Te4x}MsL51*Z)E(O>QwhAQ%bpP?!v6G>Qba;}u)pIER) zemw&6@P%9*%ZA8+O3Peco&tC35_;DvCUHYfQRIi_)DYvyv^{9v%78^XOq(paj4YZY z3lgj@X{v|iLpjazw<9#mgQ{UHcq1`Oh&9_<(_+5_s^(5crJ<+|VgTalLq<(1ZILQh zJ*tm2)hC9l*f-KoRO6ujN?JCd@xU=@oAbQqH#olA}Gdm;u$@sc~hg zIJustXJrh!LcaHHeIlXlJZKPy*|Ss*+k*~7k!IFnwfhD2Rt5w6(gr2>TOCMnP(!d- zILe@}ImPI8W`KA_;xh<_gSQ^nPF~Sdh^h@!D)n;pvBU%@XoWT}G$>ftZE{pdtxG~4 z8XZfjVTu9#kt)|bD6aTwC~9jS+zI*anfu*@Pyio6i>u?n>2qvIypJkWGQkb@L){LQ zLZ#M?qTv@y%v`MtrPd`DPnYksG_NSu@@`azE5$1&U<9lW6&8GJQjWAi$+&>-VRepR zAOYrs2VjI|vABIw3#lYdDI1C0OK%-svY`)pT!P7Yu;2Dkv|ZwL{S0#(w=phPRHbPG z+u5JuF*93(C49Yp^3s?JHVprLorR$Qs1UfkV>J8&EakZ)?!~$Qlf= zNs4eT{ut429!1Dlk=EO8mUx{umz(j`pj>Y6)TNPUJY7m=S1{pAX&*nBCu~U$mONL< z@S|o^p?0^8Jv1$774J|2LAON=kT+ch%0sjY+ zLtu}@!F4MkSR52k~T<&!nVOi^!C{v{4tY9Ls(cwup{(T{5ZBY0yN$z-(g4{?wz%9JsCB!pM(zl%Rh;Nj~Pka%){($v~TB&Tv#9 z2wO3vp+O*Pol4F5AAAtAcrgm*gX^Ohr$-`6sxTjn;X~wnJzeyI#0N3W-K=#}vGiF7 z##1mKELp+~&$rKxO;qemJft~UK=v$ouArTxG`-d9#M6tAp9ub`FkT`nXu9u(B$A%B zb*%TpjinESGNI33l;4#PjC{Yi+WmY&^7Xcv#_JLx+NR;|bCWOVF{uyGuckGKJf9-w zKDD1j95*uCh?%Z+p6SJ1{RmWu%PA2*hRqziiU0hRIOBJZ?yc`3{V=0HaaeVhTy18h z`XjrVFjf0(m@$!`|1ux{98c)1WYMhPs-VLePYE^8j)^&GHTcEbyzHunl-)e$t)ool zyvj{Sg-`QXe(2?~f9Zq&^+jEa*Ry!*`J@-0gIE+E+LqA&`Li1yjx14415L9_dpF_;FW4%FI zurrWeTql_G$6T*3w?U>2qWX$LlIW#RZ-nnSzRe!+uHbFnN_$gi5(evoavXydj_0pO zL*3V=8lPg0O?BR0ozd6ro)qP6ye;VZ=r6+xUWLuiRau(1B>j9>R>ln+2N`^ocLqK^ zw`Pz!JhitGIhZF^=HE8+bM;5pBPlPn-i+8L7}al&GvCdGIa z>GnwYxuE;@Kf3$`U> z&9U&AaQu~wsbd+gFGY)@ZZ!KGdvfRVvuojM@2?-rynjsT+Eaf9$Aawe6+P!12Owi9 z&l=q?!WoNm5lu=kT+uE_y=UcAnBmd+tSEnl%B9#U+G?dlE;CY$t;8-3q+-OZW66>E z9V->OKlfZT!V($-!62q=u(F_ezw~rxU?Yey7m{EDYy@iGiU^C*Yky9(Wl!{G>|u(avC3s3abHy6bou0ok@~*n@s!u0ka3 z4CYjZ9_W2+)oZLbfuC5xD8=_P^7j4q}DhA{OmR->4TyK z_pZ7SM{igkY>+Np;LL#aK_S9W7pxCH?3!vX9Qbya%#%RU2ZQll3*5|6SX%CX>VuqJ zelLbOpfE(lvQqI{P=R zsLhY+P)Vl%s2w<)wYw4Yc!riC6>`tHrKyVRAaWBRYWUbAm&0RF*Av6;R_qTDGQu1h z)K2!4Q2Y*@VdIrnWP){kK7A~~jS`@BSt1AAG7sq}+i2Uq`f>$AK*zCDe_dI+FVZ?h zlYa);!so8JcKXAyv5C&9DQ5~nV1ljw9@IjCM_9Z;vgc@PvmCpi`OA_2C%JCNZ(9Vy z>P;?!Ubg4M0j)i~LJYpf*8<#*(++&@kcwS$?|W@D+@otiACeu)L@V6Ks`rY!%Q%Iv z|NZe>J-xz#37Uhvi?j=vR}8i_4@VzxoIJHqM+fVJ;x1Q1#rD9Bc#$W}uE|mX&+30( z>7!uQy&7u8R0{~2q*Ay;eW&wr!y&M z_T6_Jlk|3E)}4LD;cXragiyv2AwbZ+t~Z8NQ$h<%-SIMznNz~=*H(&px-hQ%#uE8i z)f_4xbJM2GxF>BbL0}}!>DkK~!KTwoAxnE8d)d1RbK*1=kpsxHMFh4vIano2i*Y2u z?}|CCVIP6O@Is=-oM_SXsUPoEWl9lvx077f2YA#;xX+F2Bm*h&WGZ;_#2`+z)Rq-P zjGG&U^KzqL_88@90dkt}3r^|l17Y!=DU$t?a)0^cePMpp{C&8{DfPqo>-~C!jk(Wi zO<+WkRWFGq*uo#P-siZuoL>u1I_J!sR~3AS(FE9=)E%m1d? zH70+X{*aOG8To{3C!JwZ&=|!m6|GCxbO|A3CwTVCb?UV1*KXE4p8qAR^xBf+ z)?vcaHQp$d*Up0v7*1#N^?b(O=^FIM*5AZdsN|h0zE)= zXz1FkA7Xf>Q2qO{^HEBp`JtP|a+g<30}yWlb?QpB$5t+s`Hp9m-7SlV{%X4H%l3R# z?znwSmNo7DzE(pWg2_2ICkdY6fqO4&)_89?pS}NPto~(P@{=1k-CABu3)hs@@UGr@ z@HlJnW^a>8^Ud3j?l&#JJ=1bV<-O!;GwlPcYeF-RKm7$4#k8Zh63IUrlAY=6 ze3nEiij^2sb$cGl{D?9AD96FE+trl#BiZwT49{SHFO=xk9j(HqW(ZFV+PQzOh9?FC zPE|X?6N6tk1xOQv1*bMimy5|=SmDdXo_BGIs(te!nQYiw6a= z5q*+o{Y*x9GHERNcpJ{cEW(U@Q0-^s>yw>g%_W0hiz$rZizJ>|MeMb!46wz%rB|yj zqA_sItywLWKO%&5kwi#(x#H{)>;&Ge928Pf8-mBv=Q6XxJV6OG^R~XT#5V6518r@ItY&XpvS12|DBg!8-+b@mvFo z@L(2u(#oJlq7fGoFX$nmW+A8`B2(Lxa+aSB{1TC+kQw^R^EF|;=o0Y(}^m#UQPGfcIyOJnaA0)Hn zHHP&;3UTRZfDlDy=7)waq+|m@7GN!#qH(T9R(;+#Vz1RjA~r}o2QSEwT9ap1~Q*ny)mORYMJ^Fbk% zq+BwoC{8&lihHY%ieiFJqSHT$Vtf598I^Q4(!}6eSH!mIDSPCF-h z9@ zCm9?Z6;p+%ocFP~8I)efmT*4gTxwE092LL)qT5X-Wsxm@Pc!jBU>fWW4pM@!J4mss zS+<-}_u|MMgjWWKNGpSun%0GVC#k3;ZiQ>m=pnu9kV6h~n!(8&NmAT%*yDNurNxlO z9n#96)*YNZOA_NIx)h_OYNib^#q$|wJjEnu>BdF~9vX_Tqu(dWZB3zS$6sRttO}`0`f0NXDbd2s!Nd~fI8ie$~ChFJwv#C>27uT@l(3e`I#JD^6;4y?dFUM5y3es zU8;U)ZBCvcDMxf4%L(S#d*XyC&{sEAC0;?i8IVSeA$On#T2O_ZTfWZhoT*viXiy;s zv+U#+4!}O4*ne94Gjx4VN7=>Tb_OJDWaX8ub-pgi@ov#&B~0&dv4BH7XP_Q;uEEv3 ztU{CmhwKJj12e#DHJgd4|Qsw~O$lwFOcFDk@4b#4QWBEAC>E z)%T2vr2s~s8NC!KyhDB}WdFRDCuFdsDASl8lOz~SAnAkM+-1}K_Y?y&bhj?-H)Bdl zN;DEBpGQIrNdV*H63Y=)Hb_Gq&g-Z1%&LuygT zR+#3MMuUK;nu`VjbNe6>iR5IBo(W3Z+R1qpBy4V9$eC{<*Q0K+WGJ$tcFZ-yY8SMM zf(nA6q3X8l%`(E|<$O4a9hd5sukM3G4(QRy=VdLKS|1?k$HlDAP?0Q$ z)%Q#)F!%K+1fC{Lf%|794udq{c~f$;YN>2YNHcim6)7-wpHiwQ&gxf=8C;ZZYKmli zUqt-ybpAv24O;YY3nUDCgn9QF1k3o|Kc63I<1NtWVtKZ`seSNR?$hF5A_`fR#RqSfe;EzIDj_^N=>Fm}t<*?jt0yjsrn7HA^B*c9Qx>}*7B?EtupaWU zNaK;o@JUG!l&k!EbP!9>+Xj?x^v!ik2@jaLzBj!+8ozAyw)@&Jll_Rm9gyEo=1B{3 zy6o5?RYw_`$$#VtG#Q@jaEH?O2{i83uqHC_{>UQ~7E%d>J;J)@jNM}vLj|JJDK@kh z*Ib$&e{Cr|X}>9U@-SV(EC%@s_6T*6BJj80qrezG6Fr+4D)1*Tjx)LSf)p4VJ=NSv z%N>!IGgvduSs%zqQ{=a?klEt?jl;T}P zFYVv2E_wBUa@a*^IGlOXg}HB2Z!*^HBWe!YYikex=cwrqXQyv%tNo6e zu5r7>-cx4X6(@1-W5|t<4})GU<$mO6ZJ#R_S^Iq-K1gy=Zf43hYA5EJ#0x%Ri$fmy zC%-*EBBl2y8ir5K6U6eJ8Hj$CN^P3ej=0r^e&aXmltAQ-6*+b|%lvs3`Svo`st1qV z-1*b@v?u1YI3B?IpzOpQl0HZ|FP}NDsxz4jh|2Ty!|Ig2nz@72`tXm`|1a2;Cq!I=^7fuwfT9_K`Dyg z7Eya$GG8yt?wruwYvY81Ml@f`&&1LCI|{H+sK7kY9>lo(0MYF_+o>A#jmXt>>;0*F zI4}MOQg?^OD{sNmgQs^^A3YB`58omoZhSt-J)h;JdeFQ&(;Fl8T=MsR%eS`3+mX*T z9NtaNW%<7#no}Nu!oXn8MoQ9=Vo080{0;@(QD+Q;!lhYq{+m<|;ermB&Tt_YZ-+=^ z^%8u7%?#7aCelvoj7dj|6%CmlMc*Fkn?C}D@zT5AjBy@R5%7^>oxS{ov+~r~7-JX| zrU=5mf||L9=;t&C-@O7J!-Qv_GjuY13Pmqhi+*{6Y2GX3x<35uOD5lYpD)t4H$;oG z{SQTTGJ}N0uH}RVJ}l0Si+$ysXQ#rwTwrOaFUpbPup*j}akE6bC@V$DsW{hIqvToH z_?}}4ybh5|1E~-@$c{&6<4RkF_r%Jc^shj)G<3KQnzoEcF#^ryR}d|^O-=_nDq29J z3iy`st?2dXuRSHw7 zhxNP_e-4sp&`Q}nMAOlet-FVc0!$iVVpu$YAQutnqUF(nr@Cp}%K&O9cfI2!xgh)} z6sC{3SJY=Zz^Lu_Un2=T&F(MAqza7y{)3y&fq)B>(J4UKiSq|FZ-V=5=yBrhjse3* zA3FG$+;_Xiz41?SsMkx515HAo%W94j`Q0h{MJs?cgphPu7uhY>VsM!9$$B8I5R$2~qa)~oS;Dx5-yiDUkB z@ZUnALv8c1AZGBk<^c=}opd!xpwP0%f#wud$6wcrqopyn^@sXNFep48rAvD$d~{sP zJw$}!iYEUgZzn7iW@{d2$=f6^#?X}$SuG3}Ho2+ESTJQ;H(P@FQzx}VcTZ{2%kqZy zBzG`DgHe1N={y{JI!mxn=q?^F$aTG0oav1wRe0)dGb|Ju_5?{-LGQVDwV8z&e7LPL zke3^w<5($&w>Uu=YrR+IFNZa)m2*qemR{dO$Y{T1y~10>g>*d~_hkLOQ)ovaG{J}0 zuE{S9?K97HH+-Y>U?ICj5Pz1w$=(@(y^5wC>WaHA5>oKmh_+u?hm+Odv2-6KBt9kT z^ioFC{o7ol?gHp7iudALxt8TSb*|p8<}$(^OMUT>7|2m(Pac$rJw0m%Fbh1odz=bb zOeq9BbAZbWzxV-uqfYj40pMMR2;DlnRA3d}$)?9n^HkD1js<3bxr2K_EhC2w*+K5$ z`jDC-r9Hv_Yd*BV9cC0~$`Tsqg}Ylyy@)Y$E6_mT=+oB;OkKrxNhM^#8nojgaAzD# zzD^4a!=166$4HrSRAH!{JxC>(?S{a1bf^f{ytd1MPv(e|5tE16er;2*^erINes-;#e@zszCPeMYf@sIZP&@C$BZqTm+BXuNW^AX z3$7rUvjopo1PB@wJ%8)^_5LhUJ(-0&6mtvJ)&yKG)Enc`u*KokQW;oV-aQv3$fVIH( z;cy#u!Y!`v%FyqM!RJv=R@Etf2~bRUb=~oB|04T@SoU+LD}G~r(zI2OL*d*@%j(;& z&pr|7^Li6U$>L$QwF@69-s?y&gO3#3;Bfv;Z?3fqsJ#328I!8>=FVHVGoCY2V{9Hu zm7QbdnbzWcx$XPtttT5>?$Wux2odM{r;87*r_Hr4?T=NeZKKTnzMkD-9_{2OR*dX^ zbvj=)S(o`U@3C#0^R1T934X68p5Nc!6}L>&pWSI|;9L8!eSh=-?M)!_{}%FPd}J!q zyZxlCS@bQHHug%dSDQQQ@eL0usVaRM)HD5(*HkJoQohWNYFh>7?29IqKL-c7x69Ps z$1k6_fAMMN_Q4IiQr%1Ud-Ep7(i@0>gu;%-LgPO|VKlzk9CK5Q>@{(0g8$x*goW0P zHQy`b>iHy4=uvr+qY(y$ahJCY^7}>f=$*Ca+G73&g~Cjtm4+}V6kw|y5K__Vf$6(h zxXufy|2zP*z1n`2BLFycM6Lt!-LG-$5x~$pP1_R>_Ra(}7@l=#S5T(`_ zY8*v!3YlQ1&|R(*b_z}L=QnVRWMb1_v=pmJtdOS~q>i%=LZT6Xa-x|8!rkVC$Vud+ zuuwRPjZ8}jd&CN{!9TbCL=z0G;Lg}x2A*Bl)HLEo;)Mbwu+D-QjF9p!Ib({Z{(>BP z9iB566vTo_sEa5pC}MB>Ko@Se{O;+h`=t2|C+e>sfkG5M7(EA`lm^AMk?=xc35&5% zQjiuhK*JHoi9t`s5Aq1-NpMp{ zQy?#3xiL1*;(xJs-$6|_?7HZmJR#B%Dbh<4dhZHM~X;C zs(=*f7>a_Th!p7%stAe*A_$863BG>o{nq-{I(yCRHFNfv!!X0}Co>R|JJ1c2 z0!uWYp79S4LbpO*kg-~a)Rdzmpb6<#n8pl40kDnE zNGU0~&k@p4oYS&ez6lL`3&jeD1B?qojzUAxM1`ILx>A=A5p@ceG%=OD%a~C zAg!CIK<>AXj^TrDg(k6I(f%irqQ^W=v3Y93Hl#!nv^E+~OM$?B=vFukDzTZuQ_|VK zg3pqYzlQTC?1lued8-7a=CQ`kps^@=5FV;#s%Pa^kWnk2WO&QyUR@$%b<%5ccs!H% zT!W~$V=_v{mJOv=xo`)`tDJ&MJF%Eqt!&%6paLeSB8h+o1sqi^Uvn{v&D~GQU6a}x z<++4<8zhgdOFdpF$pQ6@^#Uszk+|eUsexo2N2~)bg&r;f&Hj&M_6GiecMHfJrvTyn?b` zhA~|7ch8u0USWbkTzew3%3FlO1x?kA+yE76>++T_HaNxO5E^`xtN+2huuArW&nB5&LxJ9ntZEj3? z#)~S7T11-Al#C2YJfGp;6r%9sZ-GJ_T)xaHorBafR`FXbDdl1icS|-fTvZU~%L9jt zSU1(#n&fXcBR!&!INUv*m)IMWfyTjd;$#n4^UFCq%P&&_P@qtbDl}3>q@!5hmI~h4 zRe%^q&K&}Tow9QJA+gb+kA%I$gQB!Nn50MRO4Wx$a&W=#boKPH6h>S6-&iXEphDFl zRgB@GJQ;AMOQ|%o3|AoDUWTNF4u#QWwnOUIWpmiwE2M}D&-A4&dG8BOJT_P@W}QDg z6q1!nIF(!}BkFSp-mB}Jc?&Y~1 zR*lc0t@c(=Ao?CHq-Q>f(l{uOP!GX}FskO04uu>jZjMZ34Hm6`4;xi;Y^z?1K9R5H zQ8A@Zou$0rOQd2nvZWXKB)RrFW2F#phQ5d?7>)G4dKL;AW|tw~x-0!~R*hmq9q6HI zY*NqfMLuIHU1O0pEc0s*;R6QmCAliUs)>2d0D|VukcM+?GhFIZIHyE%hUDpWbHMi zXLLzhIeMJ6#v6Um%ITnoFnN&j0o=0``{|)cfl>ZtUL%zdyYmv%KfDr-tf*A==8&ZT zueYUIUPK+AC{!BGpVK-)uyLN8E2O4e++Q+XeJ+X)B}K*3x9Bvig-1nTRdP&+A8s5vDgnEMR= zOjXh?fQA^3p_Y_lZ|k-M#S%bUG;kE&DNdi#TmwS*1SLJGa4Zb;>am&1Q)XMG)r+<^ z{RAZ^h6~0mO=gqZheXgIxBI6IB#&L7E z3Ij-7!DtOPkpHL@FbCB|t5)7C_b8FBgyTCP6t05;g;hhbumKa^I}bxrkDT2DhZ;L> zFk#aT%59<%kVKelgBcW*Amar^>F@Fp05bi+rW$`;PDvr4PzXpNGlTvwN{A;wkH(}x zAyP`6t=pWg1Qeo&=?=X_uLkk~g`Hg;>aO^CLsFoSidmdeDniU2v{GyTBBTC%AEnTY zmV}bBzo$u{!Z9CC^J^khIG#+?OpqPqR|kK3#sta3plK46RJG1FpbT9Jha~wPSlBbg z32r2Q(C=qWe)Bjdc=|*cGK4_E%>(;>OEqw zQHLi&kMyVX$)ppZi2c2@(MbM{%H+v58ET&xH6aCcL7>ccA`9J99~W$e68>`~+!BtT zs|}MFctBzZ?ai(hk*}=jqJpv8{1QT9ff(gs22r z^^fI2ezd-@Z=>$+DiR#R6qA0B%U+NR^(`+=LMOs);juWwDZW7rAzGN{!PHi>!22E5 z{zshykLo_xKCOYe!xow^U-HwI4vr{}O}|D42fvtm;Nssl6D>0`Ee<;dy!?EvVN=~_ zwQY9Gbo!v}>~sVR(G?_;9n8Q3h)xbfDv7DD)5PJQVV9X_>9d88o|`)+Fvq1e$4bZF zH9Z&AN#vz-h*tCzknmK1Mv5goR2$|c*4+>3!NZZ_07vP71(g%Xj{mtFVIk=}NSZ3{ z{v#0%{QrGp?HT(B6dbR<1~KN*hhX;lEWab0Et_Ckv?u!LPXZS zmpMEbHhHqX%{MAv4r1S49W}P;%RUQxat&SQJUe5==XG_45V~8*rRKdp|12I&zV7#Z z{oQeF%kAqN+lU0thh~9BoX`8$C$CA;o%dGzPFQ}kV^noQa{t?{*{*oez<|lUZ(iem zhz0Y&;BGC)zQBFvJkVPo_{Ip{{DMy&7+rF`&uK7~hDak}fm_Nk; z0to>HW9U3+ch9OQb>Dt`DcvdVJAe9hHS6U}S8gAH%!d)<%UPbwy8>C4O03^!-|_Vp z%~3`fIA#MbEj&&JLO?*1P_)^f)wCERvWXr>|XF{KQ2t zq0C04BvKfEXc6*asVcvf@l`y&t+Ey_O0oz=c70vSIz&<~hKn9rgb}t6au20 z9aQ2IepRAf?qiTeNFbGtH~J1s$M|PJN^V}afTt1|#z`t2D`^;!EW&|2YP*GFHDUbS zkVUwZS+doy6XHi;7A`Nrwvs0dK&4|s+XX7UKc(ZhMptPu!<@#nm=Q}19!o8jfcXk@ zJbC9C3}%=BQVTjoH-?R$*zl&VH?7R0wB$1Zsl~Gh1ZJTUTCs!4{!Cr)_g-NwXY<}Pi>$s}4!)$z+qJG%?a&H|4rw%p#?Y;9~e7d#Xl;=@chM442Ysn7Gtx@*& z^L+~XI+aIpsknpiO|sBU`_+l7IeG1X$s6yv{-N{p`GOKaVHHjTi=Sg3ILr}p_}&K% z3zd$0_67jG>=BoG+I1RFUHTOT@hErVoQ#|VB1*{T{MUguGrhV> zIyWMKi2IQOW?M_LS1evP+`05JT7-7LGWk&s<=^Po%aYJa0Oe=Y@_q4r8&iDC%YgdE+&C6nHhRg_G63ou;{}caGOWJwq`vXoVc$5{ouTVunB7`l zQpO`dR6dQYdJpOw6LKHKd}P3UuS@9P)NT|Pyy&rLhqh2m{4Q4N{!4aT1$OV;)RaU! zLHVGV)HhCGzHzd5QeZ24M|;nS$DZP^aR-lwY4jlL%UwfETx zi^{u4V}!xat{pUSDZ!ti9HFR7=O-vfNS#XTb@A@H)49=bf@WSNveDW~=y9{t*YhZo zf65V3=imI3BP{HVAms=nDSUd+!ZKQMuWH#yIl^<5hdDw&x4-8IKdsfIl|wl~KA%_b zggkP)V=i4N`A&1=x`)&}r=UWg^>NPtT=wTzQR>tmUfnqtn)3lz!NfZZu+-G%@!wrJ z0p$oIyyYaRXq~lnRp`?y~V`f?57 zHRBlHcNX|tVlJ^)fi0DH4eQ(9!H=TP7u$?_2t27y^rvwo&m4d4rjVKUlg8OBW5Vgo zldQ*Wv{%d1Cg%p8Bz0V)yYVY&%I5ga?YH7bJuZ(;zsEO}jZGi*;fb07A1kJB7}5K` ziI}DQ(%=tVce(}FCz4C=wlillhM;@q5I44;vc)k)RFS5N8!yZCGsG!|&D(uZa){t$ zO)T&H%@EEklKRGs?1v2Dk)?lP2qQ>+<9`CIJ1e#*7^ zskZgK-^lm3X-Zr9ia%>as`l!Gv)`58P!Fo-_8V`Y+J5xDYRk^TcT(d-Th+TCh{wNk zggxpbe{zH)ZJ@h_@Ys>snQxD~iaYpx_eVu>yQl{!Zr?FIuz6?jDd2)ioz{7e(=<@+6WS~`QFc6x5{`}>MhU&bw+q526xGX^ zB*}XNPV<3!yN8uyf+>GeII3C&brGv##kVCWCpe76ZDIBWRjIF_&W|AlpfI|Ul@>0D zEh+5Ue3)uF9&rE*@PVI_3?fAdL+iu35jLKz(nkCm><$`;Tb7%Hsy+)=+@^-9P?XRl z=18F?jgXauy}Y*tsd7A&gmkg+Un%lZ!-jI#sJ)pdMF|tE)XxMt?#%hw)=G>s#R#9 z8A=lZA(HfN_&DxzHU}`Ce61SGsvh&g0??lqcC2o&Kabo4zzk?@ycd)Cn^WD&<5h+H*)Z6ThrDpUm&L5U^E zi-agK$foyl za{xtp*UIEmmN911?<}lWXlAy zE$SiE@c3a-aJrP2B~<{aYfGQq!u{8t=6lFAMTkD$&zA$q;OmwTd&Q zP?7hJO|9b#A<9*I#&=Qy9WT+A<0uCg9FU+8TToV}FE_ba&M}Xn1Rj^Zl%LsBfKr^j zd*BVn3T6*PZDc-oUtwS-@@Vv91_R^7J#6@1*i5r$eNP4t6eVPW9x3Fyc2&9#qlD%1 z3g3ctxq|d~_wRA%;}RnZdD#_zI%5%g^1=00pB<~G_2bHX$`8JGMUCSq^mHHd=~K)M z)u1*X=L@66v`7-6u&A{CKFDB=nu^N2YwCBVtC%aOmaQ|I%UxAvUjYgcCN~wL<*V6} z8b<4jIW|i#7#>wTb<#~pL z0aEoF&XsP?6(S)TLwij;3^HkjwaQGj^%Uu9&FMHW;5C}ya0AWsZY?{WP?^Aa$&QT+W}jor`G%) zLr$IFtbJng{%K=XwL}*U`@*Moj<bw8Bu~Ng91eYsd6lb)0U{HmEiriDB&j& zb(lRVN+=3N3HiDu96?({lePtLr3VOPt^2}IFlc*+4;m^V$b*11R5`{r{Z%=3_azOL z+^tAKT}+QiB*F~Lk8B4LnS<$D(2ca$yUXf-sT(T7^rfb z>MFsf(#dlG>RIZS8$vlk`naR!S^?374PPuDv34snASXB`1nL{-`b+TYyFfWYD%BZQ zfR4HIij9>su}A_F%Sm$*mC{t-TyF)97h_6~$oVfE<_H;}9HB|>cCqMGTKA?qsObx8 zT1%Z_1Xd1ngjI(*!r=lth$WQa>q2*lIGE1cX32!h~mw zqLRZNty1mUy_Dg{M##eoEGz)&l4LigD{rZ~S=MGW22mdLEs)2 z>=CQ-@KC#G?`WQ&Jzia~WUD4Ask&XT{C*6+_RhJdZ302AIl(`BpPfa~F|}rZgD;J$ zT!R7#TT`N((+1QUKUDo*(4IS9S8;YeLG+q`$fs#8tWt*9Oxg12$JavUpQfP%VIIw_ zm+EXv!^{sO$#*}`%}zb=24@6d=ZG6dM2d3)Qee6Y6jA zL5csf@j+<0_#gMd!|dSB`u})p5cu-}^^E_&HB*Aek^jRZq~lWfr=GFX|ISRwzwikE zW6$_M#0USyeQ^GHLaADu;rADdFVj=)`d>BmF8AlkU-71F{(7AHxbFRPTuazcDt4>B zfX(Kh(DBB!;mU-ThJ+bx@HlvH#6&w(GKJV7r80mEGSx!dt&RLS2fxet&s{_Ue{(|IZ$w zhuy#P2wDH(5ss5QLZSb}BV0Etf;>V>fwZ&D9fgobs0Vq3nVUtBN9c^ce=YMS$s=q+ zKDb4<^)MR`zPy~{Fa>#pZgl!WtYN6tE9p@ZtJ;u9=zFm+$(`g8vO^xB4ap{;;Vh5Z~4SHi;kmM0QYAzG5;Cz@%;3dn2Ji>>2WeKV54>1I0Dnsbp z!0-=`(713S2yPjXn@7dXdSATwVA8!$t4xdxnkjjoeZR63DouNmQb1zUZUn2F4hky5s?}mvv#fJB=#1Tn7W7YZBN*r^a zpqY|8C}^gHH>gukZ9pMRkkucc6szF<(=)yd^^8r=!|qawmhfT+$nn2D!VXH26#Hwx zJwj2EN62TFNT3j@Fo8V6bhq18&XTJ62T+t^gFr5zn>|-eQIUXz;2vJ(HN`Qd z+J&K0C$C)?8X+MYZ+I_hjAx8EZA66l_;hXfBI=?oIH|D_+_*jEm zC$q%oJ8hvmAie*5kYwP~x&Hm*z^h^;H`3mXb|8TaFac;D8^O>jSyXaz8i3U!T(!Y@ z^t&CIfTqt>bO~AH06jp*Pc*876Ub!EgBEEe0>qU#!=^0MY3k_#d%v**so^#T8zF?{ z7&82$4u-a=&y`gx=g7sA1xyiuT~tfLG)TaU*gTGUGhsumv(iPgbjs&la30MUF9ez0 z+bF@h++Ta)dD2gEJxAH!QXWvcLD8yDemvMohPG`aW6W#sa~>hbS#NGL0;Jou< zAwgzVpAuf%I#KHos*gSX#Ncf>&rn3@IVzsub{rgqX*j7#T#vZyYUsrAfLse`yrz|4 z&iA2`SBefvJWHH3J))?5jIK;5^pdSTi?*lI!UZAc2+s>)Cy1@#(tQap?TYwpzw6Uo zd=yb(ijo{%>SL5rey%hQf4ESsma(dNO0M$I}vqwO1R_<^_@rGQn3CU~puuAK*Y2k05|;M?zO8d5+EL(j(Of5nZ%hRc;G?qa>iyf`#8IHL6+um;uE>DR>j` zj}ZV2wm|<%#4j{9RrC>!+o;~@0n6it#3b?+E9!Oy8=yphYw=iwqS5e!&sJ~zLiSg^%(sp12mXq# zT;uj4kX4%FZ-x=cR9!m0x>N@rMO?V0=iM13Q|%}jGpA;eZp*n|opqu@Oe|v8PI6xI z7^-{zc#G0ek#k?7FB>|NJ!_Y69;b%#^4veLApYn(I4~b?25KhIUP)PUUz_<*h)EPcAlV z?5*wXr>X;EXD)mW8cl1Lmr3|^`J!s@_{G}_a=Ba=o$rs2xja!&Eb%{gEgC+F{q{|{ z@wLIthTy4h+FnY-XB}<_a!mPoDyl4=74+ZHb%!1yv|Jov@|~~b zyQ^+X@#){o#r9;pBh0^-i*Gd%&|1w1;8d!2`;JKMD8#E-&`BMD!Vnj~p;c!tEPB{8 zh9)MV@#51(0ZnB5)5(|(OMk^A(s;2dR^7xMJN91cF4QyLQr%2K(X zwq^vjlaWFRKm)T75h4j0ts#=|+0tD%hM=q1Ac!P9!3QFFVa{3rPWSwb7pfs8R1YEv zYoR?}Iq)}0xEZYF9(+1K_|$;CVu+RNU4N6TY^NB0WK7z zp7C+_Fqh6SWp6xU&j0qokg=Gl3S|Nqlp5ACV(q>nrN4cGMMeYEw)~v0db`$&17(=x zfe@C8fqQCF?OKXS$={NXKm)b|4#>;${!5`=%BWC|AhlPWAm0WoPDtI%O!_!zDnt+R z@PY*qw!BjDqKne5UCP`;5^M02@!nw~yzx?t(%+$;@ovNdiqtdS#i`PVXrOhYpUU{X z0S`Ay{zek=NWq-zOw7n&JR30RI9R}^(P3tNYy(Cj3CBpC-s3n87I%cThbqH{7`eUS z#~wMoU4R?fC^1uG-87=$O(HDeQl4R)Aw97dwb)3i8k^Ri8EQW=w>SrkIqNl5*gg%?RVMG<-PPk}_(bSDp7O zjGNx%Ib&+jl0pWXEvnRfL`#od87A`Lj`)D?8!({BK~bI(_4pQ&(53SFJuCsO?D2v$ zQ}Vb-wE_(^EWqf9!QvY*Yq)KZH}c74G;?7B8f7WADRu^~Wur$T38|S9w;H0@801*T zK{Y)&J~9OyL=x7J#*2?TC?0!(EP4@XVuddKejxoT8C(xiw>HaBgG!8tBw=T*+MA%{ z+uq1xE0Z(Z$mYl_OMEiaGY;4`7q*xC(W|ok!q6%LDN>ECvErMvMl*YoHcBciRDeCC zh`qd^xzbU_!;KQ0l>{ZQn1OT+PELLSkyRo4=$cS;J2!~r!`6%5Cw5ox9bP}2<78cnwvjS9NWTB5^r z@~D|nW;4!kOj*_{HYtQuGJa$pPoM&xW}+=hQT8f0z+NFLxU7U-ZfvlewT3iPQk*G2 z*`=@Tyrr<8a5tUn%5XRoGX?!e7ecQ>#AWswYL_O03Jj6+|7p!%>_R zdW_Pim^}0dbH5{n`SKmv3I+G2&P{^!!YF8_BtXW`te}|Pq4s!wG&}Ziro;wJ%qZk# zu0HPGFq~S#3^o)$Wrw{TBqg-}h z-c6@4fWCfRukyNHg`l~{+leO5dFhmpT7|DQwJT{#GJ*1i%?nYr_f!LkA{eBpX2+O% zq;lXkG`HQ0`1*eSIH=Bym zmg2r2`Pq7X({qrnVe zghQwJCc&{QRl*4=&CqcW6I-zmwJ(gJthS>qxLp@0pQU34|^%c=aZ#k^(YfCsgRZcVG#A6hr zN}65yFt4MYCaX!H*gH7~buA7=%JpN=+#9hpd|G#|64v#xC_?QQ-+(N~m>}pli1!!U z(1VVHRTHGW66)=aOCnazgd#ECSoSF$9?z!Q%){d#Zz-IKR5Ip)o`K93VAGo2z%?HsXu}jgyMkqaus6vKUqKxDm9K*T?p3x1-t(D zF(z-Il5skSc6&CzFY(r_Rot{dxs#L{ryBr{O2IajNh`+O9{~Fjf0jihl+hq>^{M9+ zhsVJU7-(RA6h9P7b7Eg+&~izes0(sORxY?o@5WTh{*>k?yj2)#qkxWs2^C^Mz`@%X zCny1oYJ({il%m}LJ?>O@Gp#zH|NW)x=SNCb$A?1)z)Fz4gUEsoiww3$6F$>HhQ34dE}pii{0tEQ%=g$1;< zvr~koQA=E9- zaMKlIkMAvXf8nZJor$!z?inFD?F{j zQR77}?8(PTJvn>A2CU&Tx<&fRuF)M`H=1WRc+R)0DPLJ0@KO!r{<-`0?MTu29&UfX z)%BSs*`uep)O=ob$c9inM(%!pHF3iw@J;_rIa~1tIj5UFeNasI%H{LYU;iaSi0t|Y zLU`p5LTK|}A%w^Ojt~~o{J#Mq?Cqpr(Bg$5_^ba7AzZ=2gP8{Yfe@}>VU}|Cnw0$J ze?tge$Skv}=cv(tLkOQk2;s565W)}CmN6!dG<<6I7#Niygb<4B=3-#fCL359%XCpV z2_c-L0!#=uVUdGiuPcHh;Hsp7>!|WXP8tBgb*?{{sSS@CC*bF zAt8i96uCMuCO95K2#c$sIG?L7jGKyt5YkUccZ5kFB82&WLkP=22qAQ!{w(6w*(s(A zA%tSAk1$ly1UKwIBZLGpQNl(irKTteArzv=Bg9&B4-vvgWU*Z&gz%vo0xr}F1XCTg zd;AZCFdMH8V@RkbA%rae4ZAUbfi{e<0~>!w2v7erLTJ^=%ooFo8#wAZrUL&9A+&-J zLbcpB8Zi<=DD^jlFo)(3LTE!E@>b_j0R#vkw1w+>HnRL3A*4D&LI_b(O~;^Tp zx&KXs(B{8F2owKvgs_O_-y?*^utS7U82(QPq0kX#2qCopjSwFBgAlI#MhJ!B{{bPi zg#QylNPm~H4mcuxMUxV=gb>0$KmbArq2HVr{EuMEroRzFT|$r~F9{($%|=29J^l$H z6!{Awv;(LJ-$16nBZRt$e?kax@V_I3!oe(u2;l?De?kb$Saa<`8VDgg{x^hh4?+m* z5J9nb5pt!!5ki~0WFR?!&?WvIAv^*hgdz|^cmn@_4MM0ZcZp_^gb->;$oxhK$A2S) zhQAR)o!OFjqU@_(KSx zXx^1`G`?@Mz2#8sw9Ysa-@&BHx&rF9hy#PGdvCD z>l~jk;e6&>{i9Db*Be+T-w!;A>p07EGdXQ)bK{BP$Thm#8e`LQ3SI$o({#SFRMV7? z8!|Syj`{zJnAN%0@Blc+5SZLUBtPaIL!W&k^l3OWR^sgnZ5W%eM9d4^+`S=13J>Zm zoQA@KST5GY&l88?LE3hxTg>?!ci1h?)%aVt_&qr=G`Je9-sF{my+$7&oY1VAcG6fUjU!HVWhF~ z3I{1RzVq4er{pfnDxBsy8Q&d5CSVU^O82xB#^Yi4nn&MLy$R<6<<0BGTinA{hry0yw}DUV{xEO_Kv4eozL#Laxov8zK(Eg-t++AM~&~$pLHyv($++d-hy{0Wx#TZ?kmrg=jSzgm)C}SfsqK}InZW4X#L}!_eD<)ba(ZXv zU{Jl9sTz2wrO}ma&4d9NHzd-nPBFt#tcAgr3Gz*5uz`HwMPYy;E`&h}WF{!|BqQhQ z0B$`y%@FIODMzLoLlg!>xMbv^jLFUI81}FJRa!BE<`D}iu?MokCtZkgPaI8znS#s5 zG`Mf+uzOm-l`xi+vA-5A8$84odxDNqde-!6v?-z7oq%h48Uv%~jbR9qA!P>XxN0MG{l{MT-JDr^g-tC_8#fv{CJ;aCdg6RvSUV)}IGYmQrKmws5BoLZq z)GsBH1VS=^+8!p*bSF+uZ6gTL?4T(9LNHVq4k3iE6iEmnxQj#AWi~IGundxl#nAaj zSqRRTAYaFvcqhs8yuCfEQvzR*r6?$VMpnzhNAr6=l5RNRi&qpogB+7ETv1O>kWAsk zcd5_rQMh5V+OY&KRAvT6s=R5Yo$LWl;t(O+K12xVe-9YL#nT{!5F15PZ^7$+pLO0c zjqR?0lGPPqxP-mj?wHEW z5FW@Qn~m;NNc*1diU6>UIZ}0h34~g!>OgK3c0N`#C|8%sfMp)T7L|WA1W8Y&Bj{ub z9S3KVlQ=u`SQ+HjJPX-{NCIKqm3(vUhr=F!1VX7S1XcEZhtMzIbyQpo+%l2EzXih3 z6vvCj&z;iSD1prkBx58py%5>#q_F?p@Q4X%tb_>z(_D}%XG&+sLSrQ^x%bmcvqc`t z=>%GjbM3x)0{7oP_SH=d26GQ|>{yrOpEOwGXnn8QBJnl@QL$mW4!6 ziPbdfTf1bnFr9ouVH}TuG4iTu7HAEvSV8g_6@LuprbII+9ejuoo?KCujQE2PGR3o? z%1==S%}_pMA58z&MCum*g%Ea=y2T`f5Sp5Zs(=u}=MX|j%;e8Rj;!9x{f!WY+(*|u z@^KbA=A6NcQd705+;x;|8&hecfD2(@e<6enWv*NITq%l#sYwXo{vU*}lf9zAIg};8 zn*XB4!5EGLtMu4ek7By3h8I=LGMK^JiA7FSaoH#hQAwW@h0}bm35^Py77?*hmG@~z zDqJ;S;%`vm(Buh~p^4Tc3559#W1+=to%QUHKv{H*y&gy;;C_CO@(VyI_+zN>y?sP--a9E^la$mv%Uj5)6IJq+kXH{B755v`oPbtb zK%sA7HxwSM1Cntj{G#wE*%ArN;h6Ejy+;L6`;o10cJ1gq?icIk`R%n`3P;b2o;*P& zG0+Fau`|0I{ph-jAWpGG{=`(@X?8xfcpHuLa*t#Z6lt#{9NH^khxhk(Z1G`Xt(}JHN0_8wNqaE^n zfsKOBp^gzb{Gx0BN=5%sgg8{JmcWBHtxq>()O!pBt5-Cw_D>07po%Pv!5+5htO@dI zv9rN!)BV}MDhb36^7EQ(?t#!#hBCcsJ${&4ED0eLd~M+ZA%umAD=z&kwQp8@hj z9)H=){i5J%Xsm=CK6COl8#Y!@M8S*D!{+|_R!iJag?fJB5qf*mD%ID)`vbq~My#NN zC~z-}>dd-+Q$}A)?EBtGRF(T?P8InJIiFZhT%^F#698IX znDX|S=-0q8U_@CiUPxd4_y!Pb1k2r*DH)NZ;e{zpbTLEWLGhd)rsK32STQtaywE=X zY&2DIFdiJc>5v#q+unQMl-*RGdB+OF;M)9XMCX(vHsC3I z`d-6rk&P1@s{XA;zThRzzGi-k@xd2oM+Ui+GVP|9Ui%JmojWHo&5VJa;h(Lun}sjW z9Qa@GefQd~or@@Ngm{E*+Bk~{8jsPOkc3NI9Q#RhaGz!BpY`>bn>kBlZx?tuJ;xA6 zcmc824`{!Z0X@M@eu;&_Wh~PK1Gm|LK+Rt`Sh^0F++_9$f*NZvfEIaP%&)fA8>g2o;bk zfnSe-UnK&+s+FK7^85twYXJB)^JmKhf9F@Dad2>OOiWBlN=jB%RzX3*qeqWwYinCu zTYt^f{aSk3)z#J4*Ec*oJUKb}>qF14PlJn#i)(9Zzji)uZEgMf_3KZd@c*)}^4GLc*59>N$U({TbNquJbGOLtY0LWDG=rk>@Eq-Il9Z1DBAuRN^K=<05`v6Sy zd7(*xfGIQP85JW>k;}A-&Gf=sONn1fYz{a3FDw8D&nb43;!K zFn*mmvHGq$qb<&8f9&H#qyKdO>y~%xGlUC2>5P92Z_M{KOCcH~nn`-`0swgWpR8sD0a9E-g59)L-3id3_cgFPWqCbB}Pk&^!9+uRMD6#`{@3 zE&|H&3DfHm@A5|E67e)a8@YFmo#`cpOk0;gB7p_I1j1<~r zyOkx`w+UgiPTD3h;>YVylFHvol8(>>&?AqWIG!;Qr^bFzx~R&{nSK{W?&d~3VjvOe zB$-Z;2lbq9e^^ShKL=b&bBJ?(c#owTz*4Kb`QRw|?)YeCTz1#H{J=Y?^j#|SQs;6u z{)mWBI%WfSNE<9rR+7fj-7P4d_M>T~Fy)NPhoUPgdnICt4yzxEbHkc17ARh$D$U7% zShiZ`ljO2mnp7jQR*~1dCsJH8ShiM~KH)Z_J;!=eMVx_z&~pCT^+%bNw(AX_-}#j`ZywjK zYWpD(b))@$o$4hz2}9lvGG;;o?kNrR7fC`Y#m6N&ngbdfo{n~MU#h$FW8V@TnO!FV zAw{s)dG58Q{ZwEiwD1R>u<7WWJP_>bFevGa3l!oJvvLOIOg#>u627oSU{BzPo!>O&i zX(<%INazc^rnx?NpQ0Xh4hyb$K;3TOA!55Vbx?F$_)ccm-VpMK?OpI3O%xOfEQQR16fmH z9q^8`YXj#TbF45KR~GITk+b*{;kLlsS$Jk{mH>a4w}AAC(*`nI^XV!|eUi%3S>cO= z5}|H-0R3mf4`L4wBreEH31hA($(em#WGisVrc7vIM2o-fZllYtPLOC_x_2(2_p!BS zI%;GPL+xuK)fAT;oLQpw!C4?_#*CuZ@I#svyG{ZX^2)~4;KxQj0vS;_4>T&I7is9q ztdTt}^I(}i*!}<(@BV>2l@WiE#|F^sk2MH*HGA(4UN!Ly%|omkpK_=aJjaKrl;6CJ z+xqfD9(KmY=kju9oU^43{>EOfl=in#EK&} zTh6pFDVY2o5dl(++k_I-@~p3s-!{0YJMz6Y93+5cXr6NoWV(n~xwlWGYrYFu8BK$| zi>ul)rPXRVsjA~v`)u0LnBSZFi0kd^EZreo7SxuhA{NdahU@$&)?gGB#v_flKx==( z7B?VEA)8A8-2?%IIjv!c?Pva(+p=?5-YY>Pnzw@8U|s^e*F&-{q`67mU4!w$7!zQ7 z&)=CGh$D6lZg-u99kG?AZoC~s?|s*D!TQ|E0j4k??JL>GKbo=9iFDt?eo=%oTbvHC zvK-;JF?=yOR|&*hO5c-?cD7rH3KH#6xy~Ga^@oEEOu6@#%T3PcR#9ejMuYnGso0!X zQvBqJFU&8EC#c3Oi52v{B>z~G)`hq<8wu^Dh{!JV$1FRSe!l|kD%U@;n^Eesw!X1! zeQ&+BMqPWH%Yv#dm;6zI#{IN`2;;h3+MlZ0s(Ww69lol>g`hPICdBxawH``7V%CSN zuw>~(6&JaFFxhb$)`i!X-VAanD)Ai=bH3Gcj&?1gwE+=(IY9p{0x`Wm$H7o4pfFKf?}=SYUl^YN`H{`1=}yncRhu9|u$KDym^ ziowI|joLf;%U@q#Oxon%;pEd8^%%I&e-m}|!Lstvt+%!{UoAh`i5R^f8fs#=#bo3! zZqZ}%E->k-J0vyV9+rq-?2_t|>nC9e>ll{ZNo>^~U)+hmYAin*D9D*N)zi z8*Sh1eZ%z8&*;aZ+4tRk^7ak%;ExsZ*`11p_AjcRZ9fHb@6Gh6?<}zfybgZ)W0oiI zO-=kk>Vv00?_{^f&prKV`ZN3BebTR=U!GR%Y-xO5eShKOPT=-@AldF6n6A;U_fDu` z$s^u)-G_nj5(U9z0FetE%f0ZeQ<2I9padWv&mpb)!hz@6@8SL!6*-TG{9)6tOkjy?(PvNf5rb$I_Buj#l20c7=$imJc^zwXA zPEte;be5Rc&0$i#!B57O0+*(TuO!<_(Zl6)9bU1*+S{WFbQ`6FH?A1@4F_qWg*7p7N%}YuPZj4arL*~P=?zfEKA!Ff zTuWHj9j&(czu0^4rzRVIU-!-(T0#p=tQa7nmp~|?hbo;&Z(;;giUlbOs1Os7j*;HP z(0d1|B2^I-5l{gY5Rj^ffC{ML#OHb6^{%yM)|#__*n7^}bNC0CNoEr6i|g~fL{;$( z@&l;Ewq>Y(rkVeIgj#FzoFi7THu=SX8GE2nhi%l*6S-;$CgBE0_@v>QDC7VFa&Rp1 zzy>IYFc)bu<=+712@p8V$|OQ}%?={}2X@gDQ@4_R8Vp?gVb$~a0|-Uf>`C1nYz_`0 zM}+kB>bknyz%l6u>`hjcjmnV81sM{XJLrufSiy-mFpv4 z>N5fnDr&PPcd*!V?)udx=5(*@`BwYM6(e1OLUc?-xJY8&a?aNIEahGFy?LW-G(>(D zbbY0pmwBph9=eE4FM4Ht@s*)qZTfLX%Y!JTj9SdI`9x2DqKm&S$V8SSYA@^OBnO_@ z-zB&gp+N?hT>yCzF?t(dHQj@_<0T$n%I5yq$R$Kst?goU$L^#r6c#cA?l7@$PLfz}v64d?QH@YteZ6W*VS7f`AyK4LwTj0Kp!Zb3|ProG2Dx~D)st?#pA`{7rshM8_elQ{t{}Wf zB1(-eCWvbAIvbxQdKX09)xkgoW=}U27)&pqtBFFjcs~}v~%_K&a2I&#psgx zN;kz8cDojK+m;?^gEF=0LZidU3Uq&k`}09`Y)GwYP&s?yJrCZZbBb+ry;`z=Tk~YC zM?)>=GG@kKJ=NFbpmg)O{0D*yt!IWz1a0fW`V3xXbrMBXFWR-F`Q~+Jm*)DNGafLm zHfwQHY%^wS&_iO+_89Rx=}*N(7^}xD`j-sB0cxu8$-Y>FSK0YyP0Z#uuVvhKqbFIp z@G6Qt3klCZVSp18@Mt`cZSGo68!tuoPznVLE4)lp+A7d;@rehw+i$o~dn&ve_Ovbx zX>!D?dGPCM7}r>~G`>EVvrMt`lV+OnXw;x)@&v*_LK4VCEjirn%5d%Oh= z1%SCR6idLBrgYTtF`ieT8h9uN0#L6&zeypg*FtYJoFJzRgzH1|p4sv6Gik6vh6h@7 zv85B&iOfi-1_@ft2b@WMtPNzs3!usyAUmNl!wZ5VJlk3 zW}L7!>b-vIRXR2r>w9Rh(B@r025rA-GyOu5h(7?+{0wSr8nNm-c)fVbvl00PyR}I=; z$KTH&K=|?1&IV*feL$WDbw3D2_!SvvV7xyPuh~LVoS}ETl}khc)p;n62my;vFf&l_ zf>F`8NHqdffTs5SQ=9ccXiBK=*`p5cTSjGnk1A-{3pW5`El}*nQ&|}$Nv3X+J2jb? zNs$0ysDFHZ5W{k#R!@`5l8^?+u}cQp7e2qn5b1WhYfwQ1gf7{1Ul~IF{0z6Pbdl4g z$&-xxmZti4lz-wi|HzvF8|b+z+`xb!8; z)2bW+xt{vyu!Vy?r+$6{%q$Dq1OwzHpjvAW=cS+K)Q0!)HufqO9d4K;)t}K&OL%Pn z;iv@=M2MkOiYh8bXEvX`3*g&u>_NY0M?%ux8ylMtqyib!^Y;R@PIAF%LIc1zQi}RS zoICa2a8HS6hVlDrH%#rJvp? z96Hs;nJDgF*me3rUzGjqnDvLodJ2C@$_LShA5L3CF_=bYwz(4350m*uhliw2sl7qu z&PiP=ygN_AR9{!@obRnKLU=(0Xg2Cw^S$B=4@*9nhu!26QqZL@wCOF_<}RGnwz3KP zSnvMPwR6@<+w^qe+z+)yyW$1)ON+$ZMW5=kXVybprWa{*AN{Apz1$Xqa%C&7h1{54 zx>iyeCbS&?Bbe;A9Csq*cJ4COXgPLz`9{=oqR`5%*H@ewSL}s%nK+pMt$%^iNCsDA zXPgXUfKuLniIo3Ap_KeD;V9J}7z_dCqJX(*;71DZEB!AlS}eR@F1cT=ykDoW|G;>^ z#bUqf%>J|R|B{1_ChSk-?oSo$Pgnh6qVui)fr&15@2@@k2NV6a@P~>1-2V4il;Kk5 z{?B(Q|8%y>QU@Pfvc61)@NUoe@?kt z_15&_%wQz{wdzv_L0?vXCts^Mt#xxBp2!zmdqyRaTUsbNxXwd9;ka2fZ%F-FiBx%C zx1^AU^P=~3;?{XW8<$3ll?yB{hA8_!tv;=hDC?r|dFuA%`2&^Ln`fpwzk%GBuHmk< zKEBg#QT()PkyBH0VDHb85e~_Ri$yajVW7mRn0ND^AFJYFYf)Xo_Ox zf7JQ==g!vJ5AFM3==%VR1o6i2-CKOze}c|r4wYpZ8jkL*}u>e3VjZ%aa)FVyQ<2@k za0|rv_{1#8ij1T#q$u$^6&^idU3NB7!)sQT6aJu9m(|5bZ6P(tlW~XtKm|lA_c~p{)9z*O3_Oa>;_* zZlOlS*|(*q1A&v2TOW;+pc!|k`?3s zI?hNSb9Aam=M{C2u1ZBJ{W;Ev#jVNIzVzvq=KQPOf=)r+YN7*}imIA-SIwAfxLmJ* z6xDd@=eCCr)~flN){%_J^Q^QVd2c;#vXOJzub)k775|UpjH`;c-oKACs($k8f2g^< zp+He!v|A{Of45ukWG?nt4*UZ#iLQE3%z$ypQToquMk!2mFPn<*Q3$8-feW>KO>>NP zi{xWQyM;qOTJKN0MG=rdNd&+-viz7SjCKn!>NfPJ-GV9YoeJ*CLBjXTg}XWgq#i2q zbqM(x4hs!$e1V9+qft1xe^t>q9FJ4UT(}&3*SKp5CosVt%h^Rf3k7sJaPRzj##slB zZ3?imVQz7#mXhQaVfjA+`ZA8+C6p}bdKZAJ&e9kY>^`b$<8_yX3Dibu26e&G{Fq_G;p-~rla-M*j4AAu9dqnhy~2S3t^5dc7N5)dE*ASbbs1mujF`I(OY z>}zgi`fYX-t|tO4h+$z;#$nn92+nGvAuIY4g=0@}nz*cU$mopYl7?o`iD z`_|2N@k^qzxyW&sGQ<9m=+xrA_X1LjNG6~%ELF-wHk)L`%ENP6v`;irsacEpVnRxf zIReI82CamB&G=wIJswhP2mo?=zEIIPDYfU{iHZjE<3%E4leDXySY1&~6q&9(#MEt} z+ogezrk2ryHfO^G2E_;L4PJ!4Hf7~oE++e7lp%p*namjXXZ%ckZ_&#vL2pI5E9qz} zA>*$pn)q&kVM(Q-GTVDG3lMGy=J8>=8RUf-)kuxMH`ISIw}g)bwZuS=E)!YMv>c|6 z-5M~1c)c@@1eiA~Gru!qKEz(~3)mnDOp};EHbL_cDvo3q&!X%*zjrCLJ7={k6QBZ9 z2CU;uJUkEy>RV0%sg8c=TfFfr2-oCeq(Es?6z;~fqww2a!)g9g-h?hk!A8pJ8Az1> zSugU@LCO(CQoTcPE{shAs63Sy@lx|s_oYKvemoKq#0P*9i?qBC-{G-?6-^yu|D%^$#S2qrilTU*$ zD^-6jzSPlpbS=YLQzhe0xJ()Hi|>GeTgu({K{OP1yusDO)RYqQk3dkyWxL_}v}V^_ z>Eo$GM6Q6ehwl>n13gimX(mST#6_h5&*yx)4cWrrd9i_zVQ5(c-&Fkho6AmzuB|s{ z(9M~(+4qj#mNTYtKTj~Abia%bV=3&%tQfNwjCwgX7Ex|_)3Je}V`qnZg|s<+tf_mP zS#m*Amd9A_E1Y?&bM-4vCqz5F>3-d~4y|6hyXyL=;7u;@pyqe&8lM09L@(m1Y)Zlf z+v7jq-d9z#r^l(y*KnQ9jg#3{;7MrSmXB!;m)2GAi@}0yZl~td}5?jKm4uw`tP;( z^tOp7mRG$mJpANk)joARX{D+C_vcf0SS;?DUqgPZe;ZKKK5ZEIL+DxH7gGAkndEyv zx{ieD-rWEBLGW~5_xZMsct$3ga&UJr!0&BJamPnNosfac^o_(99ZNc27KW3jH}je! z7Ofs#8*9k@S{A;&dfMvRn=!Y|42R##mmj&m-Rk_-n*Mt|yynad-=pu{`{cPhH6HWW z`vY|j^iTIMyD!;1di?T7&t}bW_qBjWdr#lcw;x#%za)qEOge0DIK4Psqc-$wNj`k% z)g#eEIcoqj9uFN|tGFjj16aENH0`tl&8@r9z6K2M5ZB~;MMqB7;~yr4xz^s4Awzv5 zSP>&($z*6(04ozwm)TL+l0w3Zs1Q7^MdEKsC7C*I00<030%JRs1acAp?;@uSJFQa- zr*g++cw3mIGDL7B2QCt*lmqOVAT`U#k+3Xn${(VKjF61X5;2@#h7 zRtUjfVN{opg2IoJX2(pt{Zz*JbS1|rCS(H+3|gm@`P4xXUr_*2io{ZZw@s2?MSz|H zq&iU+q`BFbN;n-v!HtE{$%YJFlNWEyv=JpVs=FpGI=mgFL5$|Z|9RRJ!zc?EA=Mp) zxp8QJ*?3oQ@P=U}4X3UFZTRd<&os%m2R)V28LLv&SFEjnIHW_2?hY|SK6c-*mh}e*S7mc*xOO`0W!~B_j zdo_6xa;zg3qNT`t6Z+hYM)$1hQ~`1~0`N3(a|(1prLd@3Cvo{FdFtzBZaMPr>K%?@ z_P3MuMgkh8#zG;?;tj?=fXdVPlRAa*>Mb@7BtYKQ!N15d*XeG=veRI)?6H>H_9np! zpl-dfaGWjB9D`?>(A{m(=G@VfMFB`rs5>foQ%`tnEWIZX8X{?{_Ay7^Hd?G#i=Qna z&MWo1qj1)tQ#^-s)EGxU0qeK=nI+7)X&AtYfuKh0_fa-NefN0~q*6~UfWrJNiH^G# z67s@Ht4ow5idQcdRcTeT=R)2e_OxaLHP1-g=b}Yv;z8f}yN)J_HYajqM)gLPh11X? zAIK^$s^)CE{g}SLO~&k&{9214h&dgjp9(So>!qR@lgQ5| z(Pn*?`=EwKt%_!B3vyE;I%y5RiyUb>IPMTOXZ5CnJ<%Z3ZIPNIaH=(+kl!Eb1vSVJ#Xj+-MmFNgnA3sUe2zKQ z(9CwCw>4V0a2)R4(`xc>@l5C|yyhZR$c@kF7W6+XDAA~w*m1rs1ekH4J zZl!U$7sC{lnVXQZo(8X=#nsz6{BXj@GNi&@#d;wYsHOGp1}l&Yifu~=`zqi`U|$fc z$GAQ9kYmr3{w1v9>%+ny^lWMhk;4(Hx$2h8NXVvC4G#ih162`i$ze~*)z~aV=~r{{ z%8};H(*~ho9tKV7&gO&2&4yH8zDoAFir|&oT#A)njO`UD%0?-bYTb6gB ztkr<+)R-kM2Kj5Xu*^Aszubb||DGmE8G)(UQdg$0Ce^Yj>cMDDn{6r^^Qvlt)%jV- zFlgOE0Q0xqVlR#8qi+jxMIZ2XHT^8CI>BF68Js_USafCuDN|uC+YjaJv)QAx9Ek*> zvFiTG_`E)3&4OxcYjf)0y*;=AX}(Oeuuzm)_h^VAdqu9qS~MW7bVCvwfr)k-f_BER zZcv(eMCzoQDhHqdgo@k9 zrdqUWZU0tJzrT^KzT=l&CA=q{omVbnzU=8%4v$_T|7K(9VC2*6%#wCwT%(?%P3>XVnvL|rDsN{a8(p+|D=LY$S_pQ!0sBIG_dF6KY7=?H@P@{nCoXqB`zo-Dw!GNx zkZZ3g@Xd`~Lw@zQltsmDZso|Zgh6Rs`A--OBHyhdQmV z_j1-7+w;q7t|B#4uAzH7xLUh8L4&tVP@CjOK>}sfYr6BXCj#14+67a7|15)abOx)6 zIyh%zGC&Eu(glN-OMG%1bQ-8c1>p!lIS!c>cnZt-wiwelO2K=l0+NU!dOZpJ)Wo{GlmqQQg{&7RdGuKqCjE*W815T1~}b&r?)$WDfav^ zr=wzTi=cIMKRuG-(Do0g<^(kZi_|o{?kRq9k`j>D)olK3F5hN$_gAW^mTyN`T)&zk zC}N^_is>PTzj9Fs*hNv5O;N7xZIB}AGm~y>AP9`f_ugU6GD$${?2}J{&fX)1&=A(C zM&~rA-jhEQS}L*-BUSv~q_27a3IjFv0y*%hGNm$d{ioCl!Ps)}mXpF+QQ*5jQ~?7S z>DOn*fb_*Jy^D4ciZl?H4ZP5A0Eu9%vzC8lZR_Ni&arX*o7Nw|XR)zh&Cz}?qV}se zGoD{13!hZP|GD{AYtuVWXh>WE?gx*{qtwGVC(yK$nl8=^uTpTT@%%R+<@57z^O*1| zhY+QtSf(_^pJNiDkZ?}Oonu%jzc)7=#uPUreMkVBblNT8mTVRBUc=xCnWWK5B%k*) zz5db9qNB1}woK1PkHu$4c)fKTDO99p%??4uX?GXR#@MT_OCOkwb1&?49~S?ZfkwuE zg8d^Zt!A3M-4LbncU0QXF2QgbMtGxN1gbx^Tw>&6h|@gyN4f!YSMFrSbiGvZ*{SWD z(`u`j^*>eV#C#8J1I^nZvX`#^mYS-PXf0?in|uF4T*o4Z@rcR1RwjE$PGYj7;Qi;R zuP1~>ZEx4kl^n=@-ykJ%OhQYVYe2Rd3q|!SXwQ+ZekiNgE6EfW$1`pUynQhDq3?v+ z*BjD`mUDa^^QAotkHjH7cn34C1-S5nt(>Gi{bM%oM_swa9p1%r+LE5rAHAz(y`~rA z>K7+eKKczyTy|Tch%8+AhLYbXgOM2JelOt^c<)bMJ4-Ghbl8LT0~CbN>af{}b46JGtNK^54y^bLO8k^W$GM^V`3tnG72HKkZnZb4Q2@IHe`yd0RMlfJ1O9lg`-eADgOM;<|EB-}R73*oCO=~_?r-yDIxc=ax zXVc|1dg}G&%cmZOv)>W8(Q?JU{|@6x`bKMj)${viHT*Z*f{b6)_?}L=*?vv`{i8Tm z-ms1zn~O~aR+kyJ=gRtw#vS?7YQOg$f0-Ao4uAB8PG4amk{)mx(=MdsMWVU}{@J`% zA00Sy2hSq8KsDG~W_Qy;F>Fsp>Uw1%8Lj!$GsW6I(-UUv+=@zbww(N!ZhgrMB}_aE zTg>z-W<;+qlskc^Jl3txWe2|YUb+`d-zbi~@>=n4+mm+vJIs~!92Wzo#@joU<~9DB zWZ0gHdlH59#?C9nIa48$#kF3HtCfZ1UCGkwXy?`PN=uk{c}?lmYGqL_d`+^RVS5%o zn07X;ZfEgbspy=GEv+4}pYpBC2eLmkT$3A;kr>wVmCYWtWPe}x=IRmIx+#^Rsx+kx zq%IRLfdq0+Kd2CI`CzS4ouY!lm_w9Xu3voc)yKMuli9V0#4JH0+(L0`fg^@ z#N(Q;m#j|DpnmCjq4KE~HN1ypjM|Cub&rpDsLJ=JXZW4t7XLG9hnds-l9i3AjCnhO zM&V9({iV;XrK$!6_;Dt^OmKbz02SZvLX7|m*&x&uOC_hs8dC!y?B*kS$r>4WJ54I`fLbR`ppz?t#9xexJ9Q8!r&l^8c> zTD?&x1)5(#PkCdlFM{c=RcASmi_^$lS|do^C9_fDHBe@|mI7z)tNQT)*m;hc1u$wj zfbUr?g(0ck0~U1t_?rhtX!`7IZ>v!~ygQxxt-aDud(iBav|cV*O~0oc^z`2B-Cl9k zGEj`!*sq7959?h6YGBkL05jstL&#TY*dF@2_~eh7TQ=6ygf0{bLcG-99UfzCbi8U|7^Mg zeJ3mFe)vKXGe85TbZI660AqI9r^ez4yQc0n3WE@F5-~NDyQTI?S4R|i+(f`WEW_a3 zU|1Gipo#i%AZeiRz`#g2oQb%evaP@*_cR_L9UUjOpxFEsOjLsNQZ3Va#cn?Hw_HH- ziwpOIwhtx^cw)8Q5=>=__AaQue^5}5m#01@=#PpjXN4N zBYSYxL2Q>8mQm~OQRdt`K*zJ@-S~{2N(Xu1U6;}iifA!QPF)v^y&|2_1&T3b&H?js zv5a+e+Bt=B?O6{n8qZl8J9b`dmPs2^0L@f_!Up637?lK%W^KAAX7bQ7YifamU>|FT zhYTopK`oKC-YP$M4t_iBFc#8Hj~rdEGu_msbT<+;>~_-6!`GDf%q6E|7_!AH18#YL_Jlb{br=5bGAW^3Sj>NXXf2@En0~Yqp+pT&JZaGlR7qL{C%uuNjg3XKRB) z&YTgN$vXcLdbDqr`S`{N8xcu4N>Y0+Vl)~RLOp-rF3rV#mGAC>=gUSKdxm(f%>r?Y z71JjYqe%}Mi&d+<&1>|TXk0;T21=yt;5OMj%Wv_z5u~OZXX!GoZ%CsBQeB6-WF1S8 zu-if&C(!-6`G9G)p4A7I=f&g&Xa4c(??%;}{6ybu zk#{Ol&5shOe(fS}7g(ZOJ#MWBj(NOq^lEO`IkrZOzdpS}YL;I}_;PXi?evfJYs&Nl zjxcuDLrf00ySatpBlJB!aLh#ZmO#EnKXIRXRoc?;B>XwZ>&ATka`P#x^Hz;S$3bdyQcH|B>(UC=fi)_ z){K5DIZog7E&Dkk_GtIbKILop{ofl7yn9u7^c~8~@9!_dlNPz*pVnr6?feM;`Xv1R zY&aMk-cKa4wuCX^E`Dn!4G5ADj$xdR{M@)(#$vY)w%in8yDr#rOSSkG()i}F78o4I zxRXql$hd(ng^9P2wTsCZdInkH!%b|)E!fU2)nIp7N0>YtS!+>eT7;r;kgS{$_9b0R z$qxe~0&oDrbXC@=0AQg4+>8~&RT%Ski_SC@rEq zNFdV7aZ**m;y1m}`T-}TsGtDClo^v?U#~x8EdF&nMw^y!fC$yDg-Rk+b(>J}UT9Cp zc)%|{L?kAOdixZ3!s)Dw%{S<-K2(wl_RTvn4!6nrok3)RG6bSvBbBo?4q9l}SBkpo z1(hO!Z+6fcU7!Tf-mZr#LDO<8G6bB&KRBZ2C6soIqt}dMd^Zy<@(m#y@s9*lt20nP zCnO(7#}|v;{OpJ>DX>26uf8$Sj5RT`>{T0{S1Pg#FSSkjSqhCY(YMr(4nLHEHc^m5WXO&XyP!bOu1ifuib|;% zWX#^`ss0l_hyVcD1(OB*zyk==WBtZ_evDrLf!A7y8R(1|Lc}qU<9x~ThDz4;24{m| zF$LNJ2u3A_5Pa~=lmtYK0Lh^+(nByfHG4nk#3(zBI7?RrKb~=N(=E*h61$pq2Wq~yf$baI#Uu;5%h{p2KXsJzftL#rfJivUg6Qhp6Gsq+5e1GtblX77A=FNGsPFtxm+bd1??E@?5;rUaPzI!+^X= zR1TwG-G&k>sFoSDJXct1+M@>N!z}FK0Zd9@Qo5mOq1C2BE}ucGv*nl8@P#EkXsEtp zDhgqcW7)&_(pN#O_Q_8=Xg<^5R!`|i~?2PuKQv}P!G~p?ep@y$}^{slq znILvjgyZ~Er==;Y%oKTP7c_+L#`8whS5LJ}9|B{EZyeXiSmIxqSDoF?GgmC%cP{tw zFE{7K2PLQ_!h zcQm_kHJjHsuX|X=OFlR=bkjCl%)T8Zy$8LDg_vYFUMawwu0ZKF0yS}sG4uEwXv+C) zQv)X8oHRatq_AJAakGtvS#4`R(*BvL!7-qIbTG@fMGPy2ru?ioE23TvpiT!+HEKZ@ zA5Ch2UgtRKd7m1`o)M+IHNOw#wxE_-ZkVTTo6etp$+^uJthG#P+uBnm=ySZmwI4R) z;OgtJCO^<2%CokkmiT~kQ?2W97RP@+>IJlyu#dzviVLM44z`Fg+gzd5~PTgw40EFS8SATJ`o}@-_qCqDoT?2n|ho z6JZOgxRtmQ-q$-e7TUSvyBp1VF8MxiOVQ)&=#1a8wf}^=&Yn27O1f!^jX&J8snj#M z)~lJ-GZ}cpERc#&%Gb<_P^J>hM(-b#cIXQ7e3^s{|q%%h=OcA zf&aYe+!$r;E}!n(@txW3`%sg|+5`5Z7(r}vLPyfJ4f+g6q3KhxcD{}h{g%lgbCwZp zf8)joFL_L(0UWQXY1g4stAX}~&P-~jBLVoTmVRd0yneI)EqOGm>Sdf<74T|?0VnP z@;S+9nOe|2*?3|I2iXE-iBOp?0MgZB;%~NT2UVdeyBHXW8#uCefgq>t=Xt3A4!{fR zJU&(#B2&ad164547(PJTPy*1d9sU}>WVF!>s_IWK>q_N1Sy4=EmJ z=#7u7+9hlesHdj9R_yPf)UgJuIW5F(jh@nc=G6xx0t!i*&3Fq1?)Ya`?&jayy0@Q+ zi4mQjzKSNSpn@p(rA8jM#j*!FR9MKJ zBUb&Xxy9_yKf!08$@+ zi9_sW1;6TVGsc$x?`?iZwt-T_iKau4t(Hj(Ce2Zc_YyRlqzWiwn{T4tMn*%HImh_= z6vs|ErHw~^w#|;wm^8A1jA=pUe=Et>zIz?m=A{@{P6H%1&g%5uCOt&8_r4fHy+%Dm zd4<3fTA|?&@j;vur_LS@x1nlML# zf|7}hyPWKdZGKmKw509}V?#tOz*yg3iF8)&1b9YfE-z$!w8b;F`D&IB<6p}2uM`<_ z>crt!KY|w2hudZN7C7(_JWP|x_Nn*iyE}-!z0tV>f31~Ik)T_IHK@zZv2>K9^u;}y z3!ReEvSk>dC4cR-wqG({>uf&ja@XA?{n>QF6DMvZDhs3f@8TXG$XFUkGVpyXQScOG zyR_8xW7%3n!$520nq^fQ*J>5-ytE^PA2<_Xxgr$2TG}a9uD#Y{z5Lv7;6d&xsdMc! zc`e>=xwBKcN&8a+_$dzg>2cVnhn=4aJLgUeudnDH{=8296ifRwZYkBD`}v;xXPdmW zciNKkOV=0N)=SRcSj=5tb-TVcy}mBTvrJ##)c&Go{N;Ptm#<-8_T1LhN(65GljExW zi{t)pkWnjv{YGHF9oT1Z+-_k1`CkM5t-nz2qtpK#$9)<9AK2~2)Zf(hzelzV88zqs zmr?&u%BaKtYci^GiMWy%~J2BSsQ^DvoKd(PkaPkhL3LgEZ3U0|JnsvF9Q3XGn3tKwm zKU%hwc6HjxDEB&x&&TYrxtKy)wEg7yJa-^#xjso{wZ)k|lgHFa7Fa$-FF; z!Lr+!jK3sP63CJJpj@;x&sx1aLh+Aes?ZYZU0mmLvW(*|$y9=dyj2C%mP;3Qd^a^L z;&RQ?qbOxi*Xr-6tX1+SPBU;P7cs8t!CQ9~=_WcOfRoQDjv)XLRy^$jMM2XKfUp_h zdpR9k<0zcJRdyJK9~>L>@4}DxL>ICPSjZxSaA_(zLROQCfxz%1dKBdhyh10>z=&|` zNA(Y0oDQ1696R%Do*ae2J6Rx52Ja*z8b*k42cjhycwx)c>uLR2rjdZX$v zXznXKD2Y9}0&#GyJi{>~L<2chx;F4{*n5au5Sa-A1kO00eygvKDR28zGd*_sX8AW=aM*vod*XNYQ`1P|p^k#i)SW+qd69D(? zVUNIiNrTFamyQlFA=X16b<%9#1vJDbwqEE;XJFwRAbZ!d$kQKo9w|gsAmI)Cc2k{_|&E50Y`}gE1%E6o-FVZ`AvOS^}e&sW-AIIELNt-8JpRM9> z(G0mIMMFwG`mCe5(C=r_l%rsm?*Y>Vq(d}RX?RVS4S2Jiv)yIlQH}4hb*bo08 zdyRe232D_r<3nt+s6g{>+d3KPW$~tRn>usbpia2J^P;&G#l&738#(7C=t4NqT%7_Y z%xV{Pb2ac$8D&W8Ia=s}(c(u0TMJ+HK^8t>k?ezDymHtyX5@$70}I`QSFZTHZ+xY6 z1<<#jBi%iI1A&>$L|*e@IK;men)yf6nODYizcqf;Qe6fF`e-aF(Gd6oUF;Sytb)Ng zk1dHHfu4`%kT*Wv52ItC%aB)3>yYw&AQlQLd z*i3_aLd*Sr$i;t9^9~L?x{k@#&S^rVd$Y)OVPb4--sq8O87=-ohYqO{1PbNRbo$|7!@z6Jx%JdM@gj$h)8ab0WU>d1|#3IBbY=-@ulr=oxV_cOSs_z{kw zV#Z~&sz|T3{PA%vN>jMP=L^^~Z+n&>G$$}p-_h6KeZ2Iz_5Qs}UX|^yKR-T$&$lb2n zXUXW(KRoD#YoB`4`OQnhrqA!iOY}pbmo0Bk83w%Q7MKqE(K)Xr>Ib@E4_hPLkQ%fIHuYiRwfxtoc1I%XB_hjhh#*vJv@Sk$))847pXENuR{Y%>#5 ziVfSU{Iap?As_m}1^m|dWaCr7%(bx@q3<2y8|#$g*Jdb??Y{dP8_Dw5-yT2y<5|>~ z&4Mq)`EbbY_>(W&4g06pu0wvlWBu~I_m0~aL8iUdA2nYzmBTjUhJLvMk79{_l~8^F z!iiijQoKz9kCGq~#8VCg*ZT_&(W7Cltm<0}$krsfb{ZJ&f(#e8h8iiMIg8W=JzJ|G+P^|?VM3uZ|~DKqbmurkJu zs}@wmLlyiC9EdJ~)=)+&oELy9*V^9MwmptB(+9QoZOD-ul&eZ?5WqHkNl$G~mwj0y zG=;@bR0AMUTKiS;?s^;mO3RViwN%)Iam=j+sXzrxapEsU09pf5g(wXYT;Kt>2eUQD~wRZNAn?}ssskT#6p^os$RmJJB->!l>gF=H&J1S zLH$E#9l8RwTA@%$Iu(qVxBG)H2^7~xuzdjRH;jY1$4L@y_ZFPIREj(<@rPjEVvCR= zfns*T52C@W`ICnWW0mWpxksZx(O5ahm}+Cu%n9USejsGWK_NL(rRBB<809|@JL8Zj z;IFc}Eu5YVC?Xs=adxGAaVjL+`2yq;A7Q{>w<x0Ox@GTSm1CI}7C@Iriw0 zxY4SPMEraNtL$6?7nr!cDVu#BD&q%^IBM$KVEFnNFA6A51LuQXBnZi<1&r%Fj?2b= zB+BTeW2_QBd3zosSDGYqC}BJwl$nf!fjEYY8eSAxeJwy?5F4`Zb}X4hh1nNK4pgObQAoEx(8W(4HH_wF_`hAs zEjH#1q11ENMHS@)rm%>%Mly6zF-avbP}RrqE@$Cg#}V76Bo?sicGbdN2Li^ckVQK{ zoj$HR6b)4kKAA9yzu83jHkK(M866y{-dcal%PTeTT8x0dVV$F}mo4zXTbrpxXE#HW zeFD#p0_Y%AM@e_oTKHvee4hbS0h)}%XHZ!I?`4e#V6KEj@XL(op0aD{Pos})C-CfQ z3I;L&CZSa{^VUb@X_H(ApEYK-Ktuxjhame7#*I+AoMV^N`G9nexg5BnMlO^jhQvh_ zP?T-&|1im|npZpRb)SnAh4TYV=I{2wL;~2nzm(zcLq)E<67F_aQX8kTB+JbzrNYSM zwE?6;Ln>}0U8zBL7@do6O;kex!$B&xE67ii327nu8HetNr|1=J%O(auP38;ICXg>j zf$<=ktx3 za4zs3H}|e}PNx+1dn*Zfsv-h%Sk&%&V;%iqfcYfS6`DKQik#Lfn|Nv}W>5g{Q6A)# zNi@B`ZY+wD#8|H)XXcb42E|2*QJbVEP5VT-kMd6 zqbhX`A|GZU6+E);sOx<(CTn_NQ4x7C#o9EVIyHWP{;C9*luxeBUrjFKQq-7eBf#?i ziVR^i6rctN%kG|*Ah13y_hwQUmWozSVKhr{8wYbE0!<=nvBiPO>=m^#N#&Kw)g1o! za6~KuS+jWjkapa;c{T3wkLpj7gmB8Dr4c^IOx& zScQ?*lHOL48A)LoUp0Q1q6%MJE?=B-Ey&`7BLrxNjUyBKlv{T7WThJ2`;bBl%5!D9 zX6giozPpE38>PXfZd8*{r1n#Nwp#;DUyRv?ZJK#`>u`R#y#DGCM4n+>@zvfs1f>n< zr=I<@l54eabnnKkRiwT?(7BT+>#Kfi2oZbLnjFw@9HB?KX|p zFGI$1()8Bup_<;evHfQ9DsA=kfkr=FIzvnAxp-v<8}W5)S}!tlIWo+rveWOv0YyV& z2ZI>+oZ6;zchA~Yx@j9M-vrJpBgXNFJzw|WPvnEmhI76yh>xwzL$$xyD{u&zH$8Rw zHy+7MwQ%dzFJ^arYw60Ge8lOmGIXSnc_c5>87k)`z0rVY!{dG}Jb3-n0xklLom6KC zs1H`u)+KT?4embsD354Lj0jNs;F3vjh&qteiMY}Ja;|_oUw73+V^t7Ot3V2Qx~L+s zn{ld~N*e9(bUV*J6aAcQ(^|N@-frBJ>+K?rQyDS?pfpm^gsDZ&7uwwe$ReRKGyp;; zG{F2%)C)irsR~C7^p^B(VO?M)2caqedSn3Th;ErlDmi{3TnY)5rz$~aio1R3)?63^}hm?sXcvN%EslAL; zz2J4P?&+gBe%XV*eNpAZ53+%Yv&OWxo|CM@%U<>|k(8gyNM-#jDMCwsH0!aQQsxox zfGuz~82X`*1x~HGPssvDEH1g4-b!UDQKw!TF^e?Jw2~f{RK!FJKoDJ3{3fKAdVn|r zYLxLuLzO6%;s|mP90!#MLnJkMeNo`G9#kF!sVLHACW3uqcw^-VI%Whs1bb2_foHJG z6IvQR@s-WxW13pYI?oNe>xWJ}1j~>1&gyB7To)0OW)AJJl=`QJs*#1?rsy*?)O)yb zP9|LF^EVPSD-AO!Lqp~A1I?vvxq-<^O|4J$Z|u$*vP_r~B^xv@Vt8xcAZjPL$H0K9 zU`&FDS^z5>3GDQO3Pg{x*Q*wF7{lK`V^_TE(3PO(4o*aq+*^PovXt1Z0g3*H_Rh zY5gYV>ig)V_a6RgcW;m?K8Km_4Qo2S{~A@FM*iTU_gri6{jv2As#3RO^gh7Pd?35e z+11~wEtm^2pL_WR{6OiGmz(1$oxhWW=YNZ`dYFYqR zWhwOTn$;2noFyuchKrBNhrYs`xMr41<4AX12}_rc8*p&hU1+#pwDa?;3hqQdHWuE< zv<4d2fLVpVnT#S#FiPT>_^bTS5TjRCf0g<>OWx{=;V-G#n zA!sbPif!Q5DG9p{b{LCEI%;N^#qWr$-qJQ-a$Sh5SD!)<(lnpDB*vLb{8IZ3+C|a~TP@9G9LdW$w_4as#|)}fsrzqJ8fH`BBP(y+;)gTXr!Smgw=gSn zovl7;p5j_(E_`eK{CBD;Seqd>mJY-9K5JO=Euxo;NZi?SjFZAcWZ~QfVHQRs2k_$q zWgK)f`00Kn7+z%8&hL7O|EYYuiiap9YEKr7Bt!M)E?l?f6?k5;cUWzdx=dWC#kT?v z;far*6LZse2{cx-!}Zu#XKHr4<(=(maHN>yEV3uR z+E$pO;_5GW-;3?R8R$4%^hf|&baScKnX@JikFiL!Uk-Rq6JFD?#xR9SADJf>cgyhS-7`DM@h1`X_!ONAGUIh#L?YS<31D+GtjW#}*=yB>7CF!@A&f{2@$ki_` zq1EYD&G3@#Lws2pISmX z{)vSrbUwG+1CnZ@-QWzQ%^R?6RqXw}!#h~D@0MFn;chsFuQp5+h*_w7D$;R;z9yE? z)w?_(fwu;~!S``XWJ^hoEX$~+yVv~)mn+hMFb!L@MM?|Qmmau;-Gmb6ARtWc`Eu^! z;K5JI8h&>-n_knvZwKt9ckO7bkT)OuSnfum) z;iusZr*?Fe)K2CI)(mX_vi)IK?duE8lihxa z1>_=@!o*8+zwNQ}cp>om7c6{VPNoB5gDekjvMc5@#KUSPY_eP}JD)uiQy#YjA6^t` zumai03bH*i0i$wR1S`8*MwVI%v#&9n(EY?0@X*R7~+PgqULXZX_z$#Q<)DqO( zD_NsM76z=?+(Iab3-Q%tk(z`haiq_sh>D9?g?WfZLoj(F*b)~a)M+5Vrot<3FA<^sLp646>h zNA>p)AKTPIV5P3X!lW;;0jJ_AYN}z}Zu%@xxTgTgA|6EMlIg?2Pc%-@LJc9;^-CSJ zupO}XyRZ#MwR6}pMgn>q=6at475JO9cN$vr#H^tlW>XwL1-YJjA819yu>?peRC>UN zC~O$k^&TCBU~92Q!$@VU2e?lq?iblaQk#d-KV}V!+rvGJY$e8H#HNULUEogk=Cf9- zTD!xPXfbamiL%x)(g~6G9AN1!5!eY0sOYrk%AmC&9`bkv*-fWr98tOCj+VbC!y-;( zp>NArXTl2phRS8UkzPrc^#UR)m-k!Nvx$qbTZRC+%wfo7%{_nJ$q-%ymCG`5R4%tA z*s3*Ie~FzZ>KP@EkKs{OV_&?{`CT-JYHU;y#bZ7x=`3}ntwbGH6)$5cMPtx2otjo`TzCgkZ z+o@%<=sXWOM1=^O#GbCr5zCNaAMqrnVhH;fc)83nVSb#_vwLw^)zm?NmlkJKT+gXd z^v(LteVI@kbTL#3GE$Qh8{8eWc2~F%Az`hfLHd+pTdbNk2YAjvk(;P_)=;O0PvJ>x z1P9?H#I_0FV8*3=4%ejKOuCSsp{LuWwO3j&4 z#3A&_i|JD3D*}EP~1$P)ZIOTH~_g6Umy7)u(wM08ZT4EeU4wi(_4 zk08$*&+7dckRr*7u3&S4~-dJOqm*v=8dPYqJ zp>HIJ%d5D@vGAC24liD@Igp$)t=p=VdbSz9;Z)<9ch*@xCC6yxN$`M1Uu{}t{)~3| z$H$kjZm3_1b9v^u>mxE^SJO+lIc>QvM(oI=7E^OoP`}J1eu^xy5L>#pZe3QxnD|v5 zhh&jj(5&or=Cbpv>ib(uN~{ zs5K*`rNLQ(ayOmI>!$Csn%I~W&7&YD%xc>uo}ZmTF1EqWip(oT*`L9GC(fJi=Tkkn6AT$^k|hu{00LUOROK9d22&H z1|!%4l^T~nSIt_Y>nqg(%Q56~&nwuwLQWwX7LSImREFTw;M-g_4c%#LKOucp4Y)~* z=DpSJCW`zvjoUe!h>-f751v|IeHceJ*_ZV2=sNfp%Mv9b3paFr)k_QB=P=k0)wuY*8K(4nqd!wz) zqLgu+ZHMm?YBqil?&QC?Rz3c)2QF70Nqm@8CGe<5_VbQ{|smoV37{L`D zL9=G*N>!l6Ea%oo5>c~MRNwpvm?iCzf?9045o(rCL|8^Xs-)aU$+GBrCU^#9&LwR7DI z0X-^*?u%Q?kGJ2>-RkCF$k!{Y+shLJKgV1>74u^AyoX^9WZV-8`cW&Bls zoID|#qWybSpIry_d|kWxw*HGA{l@F1O!Wr59Qt-i4Qy_g+*CWTKVTp#ZD8Aa$*p>W z&hX#{sllD?63(@QTLT8yked(q3=;H)R@62fQj8MiRFT4@oW1pIcn2{iR%)27M_;52}B;3w?PG zeHntjfK%$Aod0Xk5^!bWKa0!1b8(sZ_j4ubD_4roawY8#xl;27u5AC0;7Y}423Oh} zaDL-TWt1zGX1Q{N$(2&^KXIkM0fiX-l`GqR;>u{(bS}xST&cw5N{9luQis8n2q)l5 zdrl@-#vv$IdZAqD8W1SYyfGhnPY86qgRO~+P$D!Kf_baYcXo4^t-?&n-u4s-cn^CUJ1zagxhie2}SwF{> z=_psm)iJn|%=J55x#LH!bZHQfw3PXgD_s~|`H4#r{Zevg7x;Qt;PYY4-1PrS-45GRc3AD`kJhm5YDk%H(fcnf#|*X@-Sm{}rxu`#B>6G9GUX?(wBh*5l``1xxsnElwteHu%d=eR_d8sP|L@_-Z9(kEZaFT% zU04F%4LIfbD*QC7r?_E{3ZLI`r$C8E%^Qerv1}7g`o^AZYxNDzT&Z(XpkToH=aw@y zc2OA;Te!ALkv4g`?evS>a@+dt`uV^!apXt*2ZIkQ_4fsg9UBS6gJfAKAJr zQwrzaFKg^Ac&}g?Ux7&EzP(S_pDqh7yS9$vD((36=Cb#sj@x^VT2P)vA1hl%- zq4Zc>Ez?T9wDSZN^L+eWnGWP*?cYVAxvF{S;gqz4K2lz^yG@f3J=w6OfxYgvoHCSA77c-v!yiUfT&wu8w?u#d^_l}bBd>5Si z`8DF8!(HHato+IHv9~zyXK&iyv$dv-o!~tl)UU@?#;G^%tMTcD;0jE`%ape#Hhk(4 zTRKxs-SRfhs;Zyl>(RX3XCk?Ie9&KY7Ryc0EzE@!5px_)- z#`tW)`5<`A%0T*j9MNYl9>avnPrK%z67RQAb#`SbTeR^~I=ZqXzuSCWQb$EXj2vqj z9pGn~<|l&3Y#4xK$6+E3Hafyqv{G87P8}?<6>*r=*NxX4^)FJBxYM{oMAQ4_doi%G zV5zf^3s@l^CoXK{_r-1XZZoyZ7)W^h?_Jc`RRbvPnxJ{;|xm|!R_zD!C>(-{aiS2~? zlDZ|&mj|DH?{$9~*?E{@mE*AY8F~3}%PhxmRkGy^Dl*Wup~XNy-*H*s08*i*X*CYh z*`aqH8$2X23lQrDw+K+UTNBANFtk(+#hZunr0c{=W8}=>>&Ci%nf5j8T*)GU~)5_p+bsp`LDIBx&@lfwoZ5%X1Sw8Z`{-)Zqv zEtm})fn=DbtXOA=lTZ|ZmvaQL?XWy~XeOCsQ!gi$W{4+@EEOMTbRk zj_C4R!V+~G%Bk_*1L_YvAwDzM=>A%+An4s!;|Or}6MDi>bCCCiwr*K{+L z+6Y#b(FG&Sm1UPngDepHlgXp;@)J3n45$omQx^-&9aSsr>AOgZRx8ym*a^N@=u3cF zft31#m8FNHH~wX9Rg@32{R##eAgY5~uk+gXsLx zJQIrfFtIV$PQ#Ll+(WM74Yiq8$r_6-&WYNRvGirmBkdBgy(C;(!6>jwxCq<30t;Ok zNmRSts7~*xL@wLpK(0mg80gJzU2gNsg<2`zlq-1TO72wtB8&W2(-+3d2`YxUiPNS| zmc_%4q|9!u%taX4y7NI8^?{Pr+=K!74e*}aUfkj#=iI&=@ni*47zJd+j6zsL#4xn;AfXc44K?YPdJt@bSW>i%WkaBv^Jk#Q) zy`@NeHI@ODnbW#AumNd9@C~&Zhr|dgnz_Hx%18i}jkTjDg{!@fovJA1VnF56WF*5| z9|wk(ZYA52iYhBhcpB8zl{?Z*%Tg$$iK(MfJ(FADFBs?2{KT*)p1f3 zU$i_?pN;INN?Qk>`FuO7l_m>4K5`?y)M_`m@UzGK$|FM+(}gIQcGD`58w1jgwIzu&{TD~juQ^&;y&L3PrI=2bb$9US$g)6 z-&z=2k3exQejHO82e=6zgWb7-!Z&v`70;r_4K-Qf@ z?~yx{GG3pj#>r0uifOhnw@9N;aiT9ims~&VMq3Znrl!Bxr0QST_u>#&FHbT2+_915 z(bSQ(eO^=1I=8r^TVH@Uiwm#u{F97C4?A|O@9@Oa8eo-v?FQ@nx~=+GwM!X`4jfVK zUo&sOa=nyA>VWxJKP_ayu3gerbkJsOU^L`~lb)nw>Y&4cK`i^=z8;CaqC=Jr18eMi zkMs;GrVfz~yiji+@`~|r)))>PJF?$uI5c(GE^9cl2jo&mzDs z^#|}@x0Qb_R)S$=2?Hye7;Shb^kwWHtb83d8ZA3oEad+69D-I546 zrv94t-?Xj#2P^+qdH6qA`NOvIAFTWbE5F}X{)3hO72C@H0ai|D7cY#D9607ufmn?d zYsM(dQ;P5ucA94#f9F%AT9U)wp{X&En z^5S(BEtR@a;?Ls&v4Z|FO+W-YQ!RcsZfBtPB9#&PTIm4H@LSf*<@-ZLeC>5d7OCgV zboAjuSM#N8d$%O!_^8!GgZstDC}%g;gjo+&a&6!CHeBn)%k91|ZjMIv$++%+rHI%H zUO#Y*KlKFn&NWHcd&^dp7VZz+C+_&n_Dl2>1DWjePjGI_vBR z0wJB(wPM~b5P2*+qjazNV&|dZ$WL;TyzQ+uF>a6Y?GzL>Zr{9vKYWL4hNymx>$G6( zVVmy0Au?|zik05k6^w1=Ii)BUB6_Q+^4@KPxviX6kLKa;9MUd;ZKd};>Y=p@l4@4P zWq29hX+MU$m@>~w#{0?8*e@Q(w~igT^D&@D)V=0ojlsdCHy(c(bFbx19S=RPPkWQ< zQ6nt+Cd$3~+0EnAE$2VKJuCgGSC)6?mgAzy)N|E$*`CjINH3boJpXY}apTOr^R>7W z?kApD@dkI_?5WSbRuj7W3)_>I^lKGgJ_mZfVSCQ`yrzDIo_`qcV5hwAmR4V%6A5?N z`qnJ9y?d?JJ?9$R%c|7cnn}xFt|%*w9jtgKyQls#j~T?OR#$eeZ4u1j3eAhRudtd{ zlztnY{kDpJc-%;t{l4s=65r32 zmamh_x&YqZ0Oq7p#l^WjYj#qp6b-5E~G-wIR$!(=%T>iq~P;(3IHOSV+0Zs-hSMt4gZOZ?7tq zi%vlZx~f!VtSU?6zpX0$WW)l%suJS~PDy|}49r!fs|PIU2X`;Bl`8tSs!Xw3)fgH^ zOhZ?d;)`O$wIc5Yz~VFEFI=<*6Rg&2dPQat>cKs=_!Yr@5WWMd=#9ji!F;rpkK>GR zW-wh6$HMMs(ofQf5@3;pSe{QrzOp3Z1IPzG*i2%z@i>L~9cvc0kUXa$353P&uuj7f zHumT<6)O!R->ul4cKU7$L1YAUtkDZLZRX4&F9>5Z*(47x6IErK3V5>3vskr|hndp58S@GuUq_Xpe zNoDWw*;_eg4LM|0dwFSD;~N^0J|0P~Sy4ir@%KZc+YR+4$>^Rk1nenEDd0GfBy&%R zoL^w(`*g7aM~mFf#*MyH6!6?Bgj#{N%I`zdVSF@3)>}FQ z$n-VNui2IVu`G#~pyOT{&GX%)l6UcG%i#_5VaB8qlizmKP?f`g+d*FC2sO@#U58|< zn1ICR#v8OGCvJSmSSUGNG6Ge<&%-ZD~n3Mm{s$}qEKc2)VjP5n}< zLF(bFW0m^b4pRl=;?~Am9Un#vZxRwmk#{yJOEJVi*N}}mnBuVcw@a?#8?KPjQqWZ; zF)is)7FboL>ad@u#0dmkrkQxjtEydnj38C{^VKn#eARZ2IhU^_2UTt)Cn41@?XFZJ zgI(yPQe%&HqpX)@s)!2ig+F5)vB({^Ul+JiP-T` zi!I9P-4q=Y8(KAW%06B_n0xv9uF{h;$=nXh*q$O`mQX&%zgIgz+q-^-q&cmIPAcm@ zz`l%0W!@vLeh=!|QpTimAbn$a-eTKQA)D0a5oJ5Fk-K(e;2kS#FAq>%IqMX9)!rw7NhC~gG^)F)2KJQlMYGbg-us$KYC^0`~If>6rqzd}PL91;(Dzi3@YALQbg&mW+n-Z9?#M@O3Vm zYU8wnpO6I3X0WI9j3{d{Q5+g+!1kIRmB*M-@_9S8)*Q7u9J#EAakCufR*@$^SgLwEQ=OeXx=1z6PYCQODXpPRccAf`oaxb4g{a>`1u#Qh$MGjabwj;fM#J6U9!&)N>7w_R6i5B1RZ-uy8~} z;Ni+Aqp(~~81BdgY#PMdVeTmT3`>K~-8N8`H3jz+xX8~IkiqMuTVBUNypXM9E+UWg z+^@OxsuOx9!lLv+qmgf@QP$zX#+^-P1D-lMXazm>C9Lz|ozOjclh(Ag>4u^Vd#&UR zF6zx^G@hOn*85~x$5@}eloi}2iJR6I9=jnjhRBaECvj1Xo*w_;44(g$Fp_$FaEzzH7MOz&UQb7E8K zfL*}AHlG1oA0GkHK?{(F(+3<6_<=lp9mvDiOIp;jii-~IDd;`M)5oXO=UE^fEPc#R zba+kHF>p*hIQ3`<*jDx&SzR`Kl0LkFeFSVP1NBDEDhlt}5lakJn+9%guhZs+2A7F!(M4mn-#~TUAz}tIAZcs+20F z!C+N+dTv#D7F|__Ml)8Ge!mxitNggC)NBwSSWX-K5P@qlR+YM3a_Fj3soTzdHUe+_ zy;Wt|!XHV9nGTMejYpT?%nRbqopC0 z_j1JkSF#e1Fnz7pFC|@KRa|W=*p;~~eaMa6)LWb#4^+_I%zdt< zkyGGp)Y>KM1e9B^d&j+v-}iJyl3rV_w7|s0<91q-=h|A`V<+1TeqbR`>(&UTlfn*11iC)Qgn|V^Bv1I;zH{IRA#L|N}`*Aqw04m^-IyC>frIp zX>e3s@14sMizb)C1(KI~I!dcVjP{AA8mb3gj>!&UOE1H?(s@- z>oEbJnKPf$XwlFrgwCZ)u*%93wZ2|DmutF%Y0QuC?Y?yK? z3{Hjvs}v{0GBmpaV_3S*H=7=hf3r#jV3h%=RbHHif3pBr z=r{$DQL9vDSmjlhZ&n!~BNhm(Qrr^+rv&n>Rk|6&1T*;YB3to}Z&rEUYSs1ZFvU95 zDkU{zB)3G~GlwM?NA$U9FHW#Bv-Ud4u*!+ARtZPpky)#x;}DqeomCQmRpO(VR(a?< zt6bDV@}7pozFK9`oK@DH?rI?{1y<>ZS|xW5nQzW2YqCuRf3nKX0KS!|RjSCWh#Q%; zN<4e;y4GW3b5?oDMDJ6`inm{_GW`du>}NmMo@3UOLsqtzmz6bcv5NGIPjYLH5}JsA zn2lN`0f$;;7_dqU)G7%~t0bRa;Og76Sb+;zW#3sYgJkgBND9SQ3`f_bI0lbkm0mKf z(lO}e2;|C+Aw;VQRwO+cj!OkrY4pu1W0+PMeR`=3YL(_#%n^oFdIPJ3si;-nOBcYW zc7`5FcM%)>YLz5v)c01|nNpsO^f0Y*Q`&pF(F#oXo!qjB_W%WkfGLjn%8aCDyMCI4DT{^y6NReC=D!73MMo!&gW0b=Ig;;2=s zF|9Ig)+&_~ki@olqtVML;g?i7i-A>+B%)UNg<+K&A{bWLb&1Xi=f!bA^MF;-P^;vB znb=vOVI|M9G0(I;T&1bvSjVtRv$T{M)GE_}RZ`;w(l7V! zMy;~^F+zBfKc5YgNvgJ^?Y_v&z`) zzGjbe8fp=?hIQfD0_l~-h7}6HDjiX)oN1M%s8zm9N}b$Ox^pPrlxdZ{^;p$P!70=#mp!?{o|LBz ztdc}6K8#wWb7jL#O`QtivO{f`n?p*Y7pDNLoX@mMasPgs0No^pRa&A}+0X|2GpzE` zBdx)BaJ`aYm26at+&p3L(j{K0FY?M9fmN!aR_V2xc+ETdnKx>c*$k^J@H%U5nQ77$ zyu-QnGFyh5JZhCQyJ2athj%n;U|6LLI9>*4 zH)IOF@{z2AWf@kv^C|36At&z#6QZF4uMm7R+zkE=UD6JHLXzZBtMtw*Yco+C!8QV` zbpHsOQD?34XymeMp{P~z+Gcub&sn8f&Xjgpv-a)h46Ag~M6EJu3+%fWwMr-qwMxu1 zjJDrUVd^Aml{*<$IoZar$}91SwsTgAyTsj!S|yu*#A;X+jo9 z{hhTIb5_~Gu*xH6c!*(az$&{Q99$0n!e64uuu1|EwMxn})G7}EtL*p9J#t3oBWjfg zxLJI-Rb=cREH!6XWl@oGo!=5*mDJYI{yPxv7H31W6)sAt=x!U|-6b^}-&Ng3bgJ4` zKDH(n%8e&tTK7XzpX(LSY_YsQ>wjDezfI!((SiVs~lR=Px3iow5@-iTffOfpzo~R<#3m=>ztu16xyl1oZ|j2!k%7gU%=Yw$~1>OCNMy4?=NPNxh+c?Y$mK zeFE$IybGj5S04+|8(!CZEYN2-wDxFN?QkTxN&9dZ997>aGZMFLBzW6M{QBX?ncoU< z(qC$opa8!DeW_tADtn+WFaKJx1XlUagOwbAr&Xr@{Z^^^)hY?IR+;vPRw?s?Rkr;{ zSfxTF!z#_-?+S1w)G8Hctulvcm6CBkS>++{pk(A%tGw}(RYtlxa7lc%N^p@Iy}2`P z019wu~t3+lC@Ms)bfbT)A(mo(ij%k%?pfHa_t+JeHl`?1n-pjN~8KzbG0jtdF zNc-6;RTx&8{fL#+a8l?vU*$s8(m;H8|O9;}qF8*li|Dix~J=B%<2waQFj zl`_>31z6?fIjc-XtunfZVU^JD72q3xv`Xs+0SU`RKNjHD46Cf>Qb4Ve*lqWI)+%rQ zu2l;DXqCiStBm@|Dx-hjDu1H@U;po0<>p^oWvu>O0WR|^tNghDkNakoaer!+I4r#Q zUn#)Nf3`~JpRAJoHw$nJV3imD#40uQIqh+jg>iFMY5%=dq6N4r(<%j{QLD^mSY^d; zTP4J1=FReb0dDz6RtXAA#)Fj!KUt;Fw*q|l2dnIWLvMVu%1g6W>H0fX`QKE4uLK2n zAMP)=N*D8~N4&mDQ&K$3T@2*C@R6&G(wANeHI{eijN=KsDCQ4FmExbKlPTP+rvw7whH^I!ngu=99@zTkk!7z;oozyn?rT?eij+-|)C{ z`E+!u6DYuqru{sV-@bC5?8fw7SaoI7@_rttDxoJnQ?bp|DAzYzZob)as3JmfOp6lU zl)SSnW!ELvMjOK(hfMbsx45^T;0$~o^6tGp#IxF8I*^u5DmTK7DFhu3d=cyBVS@Nb zhcyTGniZF?BkHAFaI!rQnke6>$s=-FIjFy0rNYuoN%)Ly&_L#)na%cNi}i(r2hWXM zad2JF={^04IjZ#GRp( z7z=P7?jaAM^bU=~X;; z?;D<{yp1aKPT=PCEYYc*pjdtCUwX=uYkTeFX=N{(7VigE-`Xj+ht-lYr@XoZ1KwQP zRW(`8ZGj~HfiF)g`bed@&!&zO z2n^cq`MB{Ddtv%)`#t@&{qFSr+J4J`_B-ZR?YDuSrM;gBjJDr0G+4P~w*4kD+HVDj z(SEDXw%?1Vy@q~jzgfSv-}2LlBD4L5DVrZ0pKZT8VQdHG`}W&dQ)-QexDccL2A@OG zcPbII{oVuGZ;22O(0*euQjGRnuG}Av7k6ftaFJnCool~U{d5%UVJXmlZvt^Q+jGOxQ|+ix1$e#?ROTRdFlH`{L-{DB>M3)*i1M*FQA zA@jBUo(RF?(f0e4AV!u9*E8GisbKJirnGC+90!(;U#`+zpdxm@5R_Cg@)6h{ls?d?e{wkH2rpTp{LRU zX4`Lz&{Up|U{x|~VtBedENV>!+J5VQZNI1D(HAONp@psf&q4b=8K;V4wBHo8{Z?eO z-*Pr$Ju{Ij--j(!{nmaHbAM>RA8(1^D4uPOl)-vrV6OeH1?@NSBv>}e7tgle!Jz#%${n35 z=%HRzjaDoAa0zX{sR^G#1B)q)_FE!z`Z4lB2yMUjkA^h1d0)@8MFOviov?&ge}ex&da&~p;!d8-}VKAp#5$rMBDGW(g8;M z{kRgjB$Pvkh-mx$613m=%Xu@&-iBB3w9?$t{6&2E!{rx7LHmu#Jqy}zezg5g@779Z z$H@52wcov$>>3k6`@Qo?0cgLMdFdO2_WMc*`2Rv7CWptM@E)W6KE{4U6^FLpd*sDz zRM6xYeqOP5&Bw%_T~x(%)V$q(ThQ`OsSX4~&j(0)^D2eE~Q zI>#bBXWMV#WF*a7p9{3#swFnIMOVGh_M0fDa|E>CgiM*p$P&k@11~cduQ|T*NqjqK zzYS;GZ{9@(g!qz$jP~0BwBM6?O0;um`<<4ULOQu@j|m5({Z{0-SQdWSDCt7~NR2xu z+I|y3`+dZnwXupdrzQim-xiGayCm01cBMn2+MY$5`-E+mf4KVPCSkqfd2l>U2DIN( zRcQMSzA}qO+iw|0`wiYxo^8L+fX6FaKhc}CRmT0eI>LQFD(*I|f9Vc`6(!n!tKLvH zJD1l9%aLJhQSK2L7J2fmv?~#q(Hp!06$e549aQG-oqW$BRS~q`MrA6HdNZ^AmTY!u zj5rF~?}j1=uPkV;{f-tYbX}9*aVrXaq!JfA4%%-@f^=P(1!%v!PRW7x8}d_OwBN5s zwUR;mt;T4-p~4wP`yJ|8F)`PEx93LBfcBdVD@IeK>LBA*|J)d~{gzA1k|WQy-^xX^ z?YB6i{a)4r%Z*1n+m%VVz+Q4X+n*LHWp^sP?xYhz``ysy6%HpIN84}qGGu96_&iV=-K6>Ji7}~ zY~yWkGPXvP_4EVI&iDD3cSXr4t&!69l1;jl*z+LZ?RVX?1s&-i{U#<45S&GvSMHN-2JN?D%O}Ck zKG1#}g13C08reM!aHH9p-%`$f%GE>reE9lVRoeQxnpB4unx;o_$ip#3Jd>+$s66YMu=mon<u(@DhaPkY?j8}aAa zFZ8wjUiOzVC74v^KwrwBFV~?jteQS zT^;nHO4=+_CX-R71gF6{nWw=ScXc`pC?v*d@Fpfx4x>z&{@rPCR`fJD^c$za)fi0q ztJC0O=xOkVT4j_emBC#dPPJQUzhX+ITL|U5hbom@I_8-24$73pfGOo$h=!b8b}#0b zG8bjaWE%6X&hIg$|Bp-=+8`ipY5XHohBEK!a4VxsNdk9uW*@42_Hjf6+sg zY*_G6CH_BxDc|hqiXAS^>Vrm2L%r_pn=Y1HAGJp%yHfb%fh&1ywuW2Zv~dm=X~;WV zKWf|jmc5F;vhW1=QUa^(qQ_5 z+j-dQ@q#g>SQ@4;VRZ!syv-RZz4YqI$!PuY10K!7H#ZEDE8krn+r7v0y8PJcYr@%k ztWPX@`u?m^iMs0eHpQnBSZU2mTAkxM%d4f(_S+q_-|L=AFHpYM9K>k9WzhCJh0%V? zq3w4eXusJX|DU$s&;Et>yYN4t{r37*`nPM*hSlKnLlm63BTKZtAIUaC!_r~{_XZ#Wv=~JW47Pr-}aPW z+ix{62>RN7$D_BvLHjN9tM*&<`}RBi&)RR-x%S%?rh^ZqU)yi#KWx9HzV0diw)T7C zhdt%j_FL_D+HWA(-?!h=f7pIY{dW6pjgkHr+wU!ZP5Vvw?e<&s|7ZK%@PFEV+x$1T z-=w1ddHZeqt^HR2SK9AQ|Nq)=;@{bR3t|56+wTfkq3B!t4c<#euYfb#Z#Im|*F9w& zv;8*wq5YP_VU(Edw*uOJgWK8Q3OL$+)BdpiUh}_dzjNl=?`}r>ZTvrLzoj9JHn;-* zwf*jZy&uoD-vkV}c7xv1v7c?f!54|l_FMKh+i&@w+HdOIp7Pi2cNE%wt1|YK(tp-| zD}L90tNm8{P5Q0&Tlx3fZ<+7gZw}1=sQp&_KX1Pk|Kr>5rmKI~o|4LFzpEMNblyN; zCjSzjgy#PIv#0c5?)%T45?O#av-gI{WM=n?yw< z0RLxC`M)~=zU@C~PxZD=# zXy4h3B^Ov;E3I~Zd_VhGtd#=mzJrEOwCL?zdgQ&Xemdo^UXbVOA~@TFNy~+imWrW- z)WBP|RfDHnYRUv*+&;3d@FVvMFI~~t@+WzQ^YrW25XKEQdA{IUQ9fJ?LUM8Hi&f@F zhvWB;>(*U<{JGz{rqt>WowHpYMEX7GUdp^Dx1J^~5et2%-&&p3xxFG}fZ z5S@LbGX1&X?N#6a___8YyN#%fM=G-p1n1CgLHn&?%s2oph~eG_4uD@2jdBd1ex;u7 zbYD39m#Y-x*QD}*N6*&3FKfoUI$T)QBgpCwuHL*62>3|s=9#|sK4m;;Lp2xcDfjDd zK9764f9iX)ZD-RO(bv(}j=xyEeWqovXk)^cPyMI#Jnls3)n8b#{F&B4?9DvUcR}MH zUp{O1BDVPa!n1z)*h;&P%1?dXf4RSWT>7cE@+Y6^F#){^tle>9lF!UdbG@mTPmU`s z@%_*pqxVaV?Po>1FYl&ar(~60J8|f!@6Cb@3ph_6^@EW#mf9N28#psR3^9%MW=+FE ztuQO2(_h}r-u-s-*)%>ksl?HJ_QJE1$`4;Bl@ot9sdVtO^!u|(<)+z5rSKx}k)I}& z65l43iqnWPb5cp5Z2slDN#*ztlS)%fsdXOWOTM2}lF>=!J}{{?3i0}GQmN4G&l)ej zi(O)m44c~TO)BrBlgf|o;aGZ1xD?{2MM5W)L~F*R((l`(GKV>-3=G~qKPXCOc2X%( z9=g$5{1jtS>B^W?u8&6&x+PQMgX120b^Ur$Y52R7%1`XjJ5C zNu|KIb2@jvn^e-lrt+srWe0Oo$@<+nog@Cb)E_35Hgl6oVc95!UUX8)1}2r)qd6qz zCY5y&xlTV%Dit(0Qoy8=jWR(>;AT!L@&4Oe;`TnAn^e{%_LulhW4@i!`C(G2cJkn( zWDa%4q%t5T;K=c&>5%fp?oYDCPVSDvew|cO&`IUJ?mH$#O2e;{O8(h%I*Ug9Uw}y^-x*aR zV^T>)CzZ;KNu`2~7;SOXYQgY@=HDijs%<|^DxZ2raCFX2Dp_q(vcROWWOh=yQ)6uy zV^TR1Dt3lTdDx;q0W6Z8Yqqi}&FVh|-=P zCzUJXt=04Hdt|V5r9k88q;e;7Qb}P}f zm{hX1CHR0zH zmkI#5I-U09G`(;sTQw4#rBaY5uc^4|Y)jS>VVfH-)>0_~S}J4j!RK3!^*+i6EtO6< zOXX;hUUEe0}Qh2RlABhPNS16nHc8r)J+UwWqtf|g2atfjK| z&{C=L%w|619%!kYtF%rofF4;Yqh%@_?Mh#4;4GCw{@b9XGAD_1rr{!JsocR?DiJ>| zm78nQ>7b=jA7`mVRP5s{mBC3(pN=e*BYlzkhnC7ptff+Y)vLG~XQ^y2;Ia67OQjTO zsicUy{-A-&2Ks#z+>cHoqsDk& z>QIRMr|DSt{Gh_$#AR2oxBOES2DiM1~&cga544d36G^_{&nM zg0)o6-+Vg-S}JGWQf`5k$`v`0RMzV!uAZ~!?gcHCS9%U4Uo3)_$}0_|=2K@MOnFDo zm^uy!_f3%<%>0OX60bX>HS;Lld-fugS4G$C?G2ozQmISWsCx*sROVKm*Nt^LJ&PQ` zS}Nau=VF~Ez#p1-dNI`kS}HAuPy+L>B^Q*3IL;m{I8!ZXEG_72aa{0N)EQcszP@NO z#BO{58Y>r9uFqP@vs-#BS!gZcuPoY5BX1lm=_@X3pynLgmUumug|%iy%a`vvx?Z7Q z@g8!vlU(ulSTPA$32s}_3UCfRScxR_i;@Sk-z%{mt3J2v|FBg4pRLo$12Ba+OJx^; znFKJa0OsreL9y~b-QWMWmCFCr>HMcor)G z4hn5S+>ZX=l>GkhcYptnD3$-65a*xiOEWrgsKx{ zH;0`Fr{n|5oCew*YPu##{NtJyy*`lAUwyl4bFZRv-isWKfGZ0GwGz{wB7bT9?w%Dn zz6;brEN__;4?o5&G5X70vye}{Pam%0B~*N%89tfKja>4NSWDSyj^g0l;gndOFEgzV(}^Sh1x zKRyuK?oWOk`bt#ykm1Ir?7Pn=T|1aPj(Jw>&wkW$Z4pfW=q%_od+PF+r+VgFK?$w% zf)SSePA9jO@xL#f$*>rXk^hj?(7m92`J3WK+GjiM(+uY1?)WKfUs&UR(Az}pW2W1_ zQonvg?@IpQ>p|NtoK8ORT*UXQCm!#8z9>&0NdD0N^y6>SaR+pT!}q^^8Pa?6tgW&3 z@#3q3LcC`(CpSyHms(5(+RhJIcA)nI6tNi+3`IMNig7;#NsZh%Tncn1`Kf81U zZLSU+@hQPB9l786ly`lvWcx}+|EWvo4#=mB!SX5Zxc=6q6Yb5!fR+cIf?$h( z)1^}kcIlu!a}yEyu29TDf~W<^r+nc}h3nF}`>RXG>SveERU4P{g@K-jd`fEXz!hKd zPF$DH2(C+~#+T44=u&pjH3qk0{6F}Vzq)j?{#}<&WCQ^G(WO)UTbGUp7YiEXQ_j0$ zyL5n`e9Bw6E}hq4mrmp#e99EVvmG`;LTD_Xl4UoFg%R7O!!jQH&PIkd$xxHwelU(t z`QaCzvhz<}I$)K~!7o20woB*5&n}&tzws$)dPML2-lgMk#HU0@4fn7zgM3OhET59F z2t|Ixr)(-zr~V6{GTNIO56h?I=QTjZu-y%Mk%)f!kDTPM{WM-((wcNl+?d<=>Qp&LY@io$d7JE*-C+i?cPT{?5FML|uh z$%lMOeJr0cr&#O5+G%63OJ}Ee8po$hYKl0=B}7 zOTh9e??ha#GS>FM8E+QQ}iB5BZeN zSU%;lY5FEltyMwd*+V{Mb_d~h6MZd~Pbrd82RAK|0Qr{wk7nk zwG1-pZ|xc`gM7;EY>-dsa!#m4Hga4R%cso6@hOXC;&o~A)nfcD+1sj~iH+%C%m~Iy#NW72Oyua zB(;D$vzG(pQ#!SC&gBz%{nn)uiQ`j>#gT0VLO?!c%xgQaOXuZLm(ErV$fxv7!}2L@ zK|W=!XR%luvIWbhv?Yby2fK6-uTN3o_>>NnB4{)N$fvy08<;x`jPw(GM;eZV3OhXS z8y#VIbm61>^W*!?eRvZ_Tjl(fNyF<3sT9m_eOT_qZyLvGY0nD&=2s*b#7X7cCuX= z#-XRoxGo*x4R6I(ET0m85~)b|hT>!=H^`^V8I0JT4MWXH%X9XHVfmEvQ}crI4^bx< z>_rwdwK(P5tThf6tmhW=rx(=P9_o24nprKHnJ*ffdr%)N>dh@$PcK?(p-nxO&RZ?n zYq4KwgR>kg*@VwIf0&~ro4;4i>5K2;aj>iw;DVN4@%6athow|Ht0Z8%zt68=DV5$Q zS7XUmp8m$Cl=-iM-y$agIV8Zw#>UIbD=I1~CntyE0F=1_Wo2beO-(&LJu@>iYinzJ zdwXYRXAcjLNCTkG9%#A^^tl0Z0l-`!upS0{jsdXlS1D-xUKB1wZv9YnKsi`?RIb~&KH8nM@t*u>MUH$$2FJHc#oSa-(SXf_Q-`Uy0 zU@%86%0K=WR4LQ`_Xof4ICP-ueJR*DE>O3_2uR-{ZKtG=g8&6Ws&G~{dLb?XAyLZP z8;$HC=fBbn=dQ_Djzrk6DF-?g9BBXFRw-Zq-w%FE{|bI{|Kw9z5Yd=4BK(;Sw8mxw zsBT^Vv!62YPkhRyzXrb<2sp@!7NRu`jB=x#zmF}%>Wl0lV;xnE7vs$)T-oCtY{nN8 zt-W{I6K@3?FD2V+5wInL(66P`tLcQxjE*nvnNqT)TTVa;2OtG)H z5E%RxI|_c2!p%C+czl&QUS&XKF>h|`7j>09O0!u-ABnHns=N+~I1j$d&8? zgWqzQ56DEZ!EZ@0_)XeL{Ahn_e)%x?orwo<2}#094FD8`c#a9i=Pb$m=is*_Huz29 z)lq~Eevd!_3om#Q8F0*6hveS|znT6u_-%F+{BDQE_jI!#TMwkqW$_u~Y@mAa-j^sl z8=BnHP0BG6+-f@Voyxk&+StYiKEq0VlkPO3C23&hs(HYH^}hzc`yr%1gWrPx68t{? zm*DrnAHnYdT<{wYt#Mz=3W2QSP$PXfVtWu{<@dqA1#fX60%g#Yh{TBSb>SZpl^0&cnQG77?P4?H|cL=0ZFY@#W|u@9vKg!C2~ z##D*8MZ2}wKy)wy2EW6hPzJLh28S{RF!(JE2EUOODCSaJ@S6-9{C@SP;5V(%#5nc{SSW1e^4p$lO~rd@1}MPlHJxwnA#Tl%J)2s{O;|Dx8EEjQ?rRT zJ$slnNJ=FYKAgy*J(cqM_-upM_p;kT1jl9O2|EbXExf6@jCt_MwH~Ne(%#7lI?cMP z-hD6TWQ~2R1RKM!iF`T}O)5(6Hp||1S9@q|zsh35sxYClJbj{ue-H1Mul@XFWH>&h zwhz9L16u4j0(OD`^ix{;|Kw8+=dge(rP67DfI%4sx4T;;`3NliZW;5^`dpRrW5Z_i z$(zxkFZCIxnV!*9P1z~;;`o#q)-2@?Ut9NoD1j}X?=V`fczEfXe%cTGpl3q;dCWfs zfPPBO48+qMh3(j{?hE)CZk?uW1Bsj8rz8cxJ@cHV$`X7SpjPp%Gvg#l;O$3K#)9sH z&*ryND}H$1sMvr0?&PPY%}4HTg5O_ZPJZqXJh&TF@c{qv0ddvsHjgC1A8${c`chQU z)>v5aWA^f?Z{wS7<&A;|i=OX@pM&qi?#tZU38zel&w1`@i}_q(&jg6j=-YyE!gw?Y z2zfiS|1RF+Cu**KTptYGarVjsoir*>i}(jjj#y+Rb)|=$<4=1f+=e9$iA2qdNJOJ) zMO2Lt5NZpEAV{o)!YFhA)MtYy?6Sg07F3LWB-G0+(u2zprcDbG)PYH$V9L&Tl`5Q) zAhA*hBIX%!yC)S-2I2WQgRm|eQ2-j^f8_B;fxl8 zI>?hK!iXb%eEnf)mwSjOr!T52+N(md5 zrtAPossNN?fN8xS?V)rT2Wu3C@sB`#4stGnO+dmkW{qP|AsuveBBFK-N|Gpg6O=Bq zeNGv{1lpnAyDX9bj1P>0D~9mlqTr6I_e@-aLJy_OdGENM;6$6VBw!7=MX(#Ks8J#! zXNAYZ9hM4~K*fN%r9fje|6b_J zIVgWq2;sIQbCQa&E4gedB8aMjz3t+^Z8J{ z-0}O&2ysh<@kWZBS`A~$4!$^&o;xRvIBEh<#;KQjL76~%I0==gNfPVaq1bDO1~wDrk_LDDc(oL7m=K`smjJqn4#CKlpBjUP|DB#bjJUH{{F^%@+YMW zgxhkrRuR{m5yEU*(dvHH)cF@iGuGfK}QUNNMq$P-h8sL&f1-1=5ru>?1RTdFI0}7bv z3{b#iwM&_3lDujPxm=VJRf8bhw@bFDYXt79#BTkVdpf3yCF}Dh(0=J1zB;sV1nUjmrr1*785|MOEy|4Z5Xs-O!vZ zX_>G~D^ga81x=PQkMm{f-nTSwwsbs9fpt`O#?jxWSN5i|;#F=zG=``K^nmJRPBpAV z;5E|(NO_oxXUgVh}k^B5^CY@iGq2dS-RRD4;pGg3TC5kZNN+@w<3EBuEf*Q>9 z3#Br7LKa;-t6I6S%|GH?NV1|m+|^|l(k%suukf&>)#%@Q;vbzHnjNV3ytB(Oc<3cn z7BSca4lgcZZfrcq2J$JvCh(h$*mj+qRcIJ*sOyMVqzN#VatyB>Ed_Eb+kx+E(gj#< z<+JQs!y698FgN_>PlhqQtaJ7z0K$ky2r{i6g~z}TuY`)}`0{T7IU(M~bLbQj0pZL- z;jN!0O9=#wPRE2^AK<}pD-RTm(yg&Gc&qDi*9gGfud?KuqXNN?V z4T9>WJE&edql-VqN%W86>p|R4LqbS}g@xXr3z~Ue_}OLxj3F@E#228+GQU-a==3O5 zG|I3tOcMQ~Z~i&=qYLoR7q45o<)|l(9EwF9lIK#uC-L27;!(ZUY(6{gGa4Lf_qm13 z3Oc)?k5`^iw*$mm0Bw7Y7%E1YRDr!2TMW)GZZP`@pwyY*i^ZBO>9&CR^N<~!$&wiH z15(LeKtu)mcz#;0Pk^F*nx;J*1XrF(WxdOf_i&2m4QR3y?IkFj*nE@QoWez2PV$PB zo4$?x)ke<5;OvR%GuQ38S;{Hyg>kW)vor6?aBJ1^hPS>O?Lo-DMa#@ZSfLmvky?yn z%;EFWT8$_6(ek(6sL6Zqq%Y8-AfLW-37)))I#{r)errY;x#T#_e!C5BX})|#arwSE`@M3w+w`(&=d$-S(o>%Dj`@lr zmD{a1E8zkzc3)S((r>+I>7bu7@fLYh`fBR*D&y>G=E*hkJ8s$LYl**1mUwXB>>u)_ zKPUte;{(LR#8gDU2`Ye^nwpuJnUfw6VE&VQ`On&A@+IKey+5?e4-vrE*dy&SgA|iN zfhobsm(2hsn;xrRg3e1&zN}HeG-+d64Kcm<{z1yb4EbUv^Dwh@ziXP9)n}OZFAkMW z%+4%k_XAen-2e2q66YUc=l}nH;UA#Sdi(hL`3D3B1&4%&g-1k2MaRT?0|^On$tkI6 z=^2?>**Up+`8kP2MFpj03t{S<$F)vlE6nm?$io`uJ z>q{*n<^YnVoH})jY6^yRPkIuanBeAmo}+qm*4APc^)y!}heMY(vnzn)RG#fy87^8c z@>3FpbL#OMc@?L`O8NTZ`HaX9Zq7I3@ivs}SDxBfQwhFTaXITDhG>Y{*7{qVH=>W6o-5rUVce|&qoIZt2i`FQi-VD*>=h*bWzLTs*rJiyAR5~~X_{Bph4vAPCH*2MZIO~`l?t?|VK-CH(D z7K^KdOG!5QMWBpYJPy5d<%90E6zA7BmeXA6KIRACc`b519es?4E7Sc8;S~Ngvf`EO zPy^$_tlID6E4i^E-?(zCRZUj&QzzWG^DAv8Rts~z_qYqo15MV7OSK3&iz^Bz)=Klz ziPpKRUlgzB*H4?Mm$w|VTPM8)tQ8%VXt)gftL|=um152uG)8WA4ohrQB8RA00D!_GwCXAI6-mJ-35^a*6oOI~C%ZgP?CG+^P(Q*-JNs%>pL$!-D!(< zBpPCI>q(36jt5;sBsbx)1XqPPe+o%_3NN*3Q`GLRn7n6Pg_=;J8PD;`cGi^{s>>i@ zaN}CbDKl?$^Zcpz>PGM>er_u!dtE#r6PP%isYU~!A@SYP$BYQ?ow0dA2(ggj3aapl zDl~{jkBCs3L!sSH5CFcF3;z31HJMXDbWbi*&xj`x+~Py*CtOVYXL#S$?^o+hp11rw|=G9RiCMj(bk2qBM-%P$@#&-0$z+ zLyde-q;@&9PgzG_qp0P%^MR?7WPz_puV3K3PK-*R5qVzh8FiVUn~9nT((}f?a?o}s z1N9}LH%4&%p$#=6U>ttpbN3C~@?;aLoJDV=UY=P2PmMlPq2b0{dI~237Z_OXXsm9P zOr55!Zgy%Eso_qP9jPtCC2>Jb{eD)sngYpnN_o2T?9#W?rZrFr48=%Cx-4&l7lp$k z`WHfE>i8@sd^cv7~YM}iZb1m1iEonF} zPq~^n*9KkLnEc~%myqLk-|;id7;;crdL&j_T`4l@>Y-Z zi@OQeiPpuaHMysQL-Rk&3Grw2^N@Rv>9f!YCv8ddP-pDga~phAF`nY4e=JoivP2f9 zc6XL}Ug}xUOl3q_-mEc^TMuJMRcJ)0wKc67dN0q}=p=fMe0j>%L5J{~)XVS%#PHsb>yT6En*H_D`+LJ4OFJ?;s1?N= zGzB}Qvnk0Xn|q-u&rL1GvKXUmRM}Ks1bB4k@blAX5?>ijeHv6CeqmLo!TO~Nq^?MX z^~QzR`>&X9i0kN+t_So?9Iq{}Q@Hg$*l?W*(Hibo;dws7;$YNjtox)`j!)FObxhY- z8>+sh0dn)2r2E8Zp@c|o*v+dpri@b`T!h+4!yH1~=@-)dn}$z>I2&GhyKxP#_!VT+ zHN&VHu%@!d4X_*AoQ{)FEC_l!=d1Fb&dZ+Ztc;&(DO z@cxg4IA$JE{ZpDRN0qKCT3-@2r5_GJ zv~9fcJt5Cc1tHXmTpdq+D9mKfL=?*5f0kTk8Vk6hKbnv7PuephOg06?gfqC`{{0nioK6Y4IuDP;Sj|_}lAq z%2{?FUXX6-f-)c;yh^ZB{37}O)c$nxlSbuD&rKxV0|Z>6F_YXL#rqnv1JRW!rO z75Xu+wgRurEl-5&)l){^b{yUrC~vMnYtAumIxa7^163~}S1UmypY!?N>FwT9Ha_@0 zUZ;00WfE;siRjZyXQmx}6kM+;^$^Mxa>zIc5n2F5TL9dJ-#7<277366Fj^Nvyf5e5 z{P@(3yk|u9w4w#Mt@+P45^B40pwOy~2*|lc9@Na~1|2{Q?r#9q@`g&?y25#NjQy!E zAteGrD+IgzN%Z?H^f6EOrZvaMFS70YSv>wl1=QKTca4Fh5mFSo+D zt}OuQ=%BbQ|I5)*&`N)eY8bIaa1E940Thte5P^ST1@P!Xauh@Ei3FO6h}}cNgi(+z zePF_dT~^=Mj!HXU6+UYOkwd{z6tFwg`WhlZ2HE}t1i(-t=ZGrdi$ZpX*o*bz7gZw9 z$WVa)U%7OU@}>i$cZm{4!SGxZsMMl5rBEhyq3WFhatN5vOjxQaOvu9EqDYib=4tah z6?|jP6&v<7E-_4F;C5rsU8{)m*(wl=u*bBLb%{vmIQQUgs7RwXs_7h%se9S+G;uqu zBhNp^Po7K~9w@G;?x?8XCuI0iz97d;t5dt%iBN7U4seK*T{Kk^g7mNpS?=mr`w*TL z(`_8#kTzzQRTDkM_D~6R028c?#uJlL5mnKwh6!&$MP_2Y;=v--&T4f@56z3^srVFj zM??2u5o$_WHGzI^iF|6pA`Xe-BNpv2zt(9Mf+a?WxTD6n@>P(lq< z;UQTsFN7i?f?H7POkmPl@ssE!>MbbMmaycWt}+|DMy-EBq|}-c1QG)Pivg5$;gmB_ zns(`3J)Hzl%-p+t4|z#3mdL{`#EvS_n@zbP$K>|7^4%c9u#1942%vXN%gv2Y#Yeq( zMsj&x?~--2icpYYT>AN!rU^z$yMzhv0!>$91YM0nt9spS9o5K;*$b@!N?S$CMkW0u zl+Bp31`?1z$bor^sZi;G=V~;742xr z^9zO)TTlT&e{Vj$V^La4CXRLs8i;p6Cl4@|ftVR-eu9Z4whI)9roEDkQx`ciJ?bZb zkn6q@bk|u$he`Wv9CErQM286S$_OqPDdnb?a)vu)58v+{jHBumJLHO#n{WKt7!kx` zvO=)pMJmY#WB9n5q$yl_W>56gl~^|v5Hg)j@d5a__QZ>LtpFEyqt2RRDw*z zc`9LYl-wJ=GY8Z{GRa6$wpe8qV_oP)Qh!sK;9&fhx+HxtJ{rqunENrj2#sx+^~+d- zz1RcUz+CNWS5w6O!4-;NR0(C4d>+ZozgNgIT~}qz)V=0 z?b+~RWNMBOB&M7k4ydVddUCUu^dV2pODnuAS+vejQ!E*6R=G?o91m0IUq!YTBk$lX{1qHJbP?4*0&FRLpSj3YMG(+X}M2Gv8_uDfNEe~dg`mH zAF*nC(3*=>LX~ecHK?@XM~jYK1!zWU&&xunDI`5$TI_wu0`BsC`A!8r0>s>pt={xX}Qoua&t*A4Fzw z6y6ECs4H@2=3Bg0_Jw0x0F}_0J1|uzXlgg6m?}dV8@F} z5X$S7X`K#iNbHk+qycG|)DjO7=XEdRZ}GB=&I#bvF34@ zk?xCn6$?R<7UVKDV8_$^Ipn;ndwUlkznt@!CnUcx`H`q*>DF1qMg_i@~lI4K-9g)EF!)`8Wl z7P=EiNo|FkyX9VS5!$f>>r}69p>M4>k5y#mdmOr>KeLZS_ctR+;y6mrM6Mxuzdzy+ z?e^p98dvtv06U&yvlWy5314-gm>L{aG!tkd)aOnc91;Zu(aOTxpw%gzAajQLxDfq(YwYouPkQWj_PI5^94$_*1u>2M1DeN1?vYL$sla&mR8(%&zrcfyv&A(!EflgI8OCAx4&OzNf(M;&bg&{MojyNLNdR)VZ z_7l7e;QQ!p7|ca-m?ZBjU zAnSQ5$7Z1Lm&$>kgJg7I&U^9iVNFm9*n-TNzS7bJ*YTuB<7tCx5TEA@GBEryBm@S5 z`#!T^ZH%t$zAORo|J=aPI`NlAD9xgXA_*N)WFJT`>y9H<`H+$1U zwr-A6cZ*D3GL9GXf8U)Fo-%$`2{OqKS^ps>j(FQ%&^=*W*_8=O=pF}b0sap=i$;v1 zb3#NH;}aZWP&#A8wQu}?T-;$BEsnf6bg(Z<6;22%fx*_g1k4hYr^arkmYojcOVHrS zy3Zf6@k-q>@nlg96{zdZ05sscGPlBORTc6|fP?~a$InEe4H)@xQ5==DsE?wZ0hHt+ zy5Gg;Ux^S?K;GVe^_6x}S)i4#W`RTqa+XjI-rajc@hwr+%v;C#9LLjJn*QOBd=X+j ziGgLxQr0eQ+`>1DWZIS=v>_Efh4iv6t6!M!6j_P$4%l*9AtGBnVYHYu$sb;R!`Xvh z4c-tIoh$~-hJ~*L3CODdSQb4A{t%HR^8rya z?-byBtaYQqe4|WpqfdSV{lV9;cX}hQbK^zZ#_$LK=jQLz6yHzCzkgF6lsNr9tn>X` z+xvGX!^X`&#CUs@z4`D#{(kY-58LvaLHBY$d2H^IxqeLF{64+;b!HPdwS_0_0lmES zL5B5+a4iSsw%SX<`OAD3(IiZ;TXuRxh?{m~%xnr(@D-5gcT*hh&HgK8~2lwicNYanD&S!xnxs}>`Vhwm>c^im-kcX`OMCl9lsYkmEX!2 zCrY^1iuV?A`t8Lqhpjii0xIu z%yzE>O$xa{AE#Y4$`<~jaSoejMVC@?%OKSb<1Te3k{>RWxpjRwv0q<7(F9!~lHZrS zIo>5fztg*bY?UgaY|mkcT}ca zCOesHL1mTgiD<=Wc8coemg}s3_3rGgUEQXSOP)RH>(}b-1!Z;RA@>)rU-)rxa}K|m z?s~<`%hU62sc(*VdHu=i#%9Zht(}7HPhXS1?CuAA`;PJW4mr+s4$Y6-u5?CynBp>5uem-teou%q~bM5MApE~PO-%mC=txpfOG;F?WXNNIp zeSfvZQsGF?8Q$Hvz1SNuBdx`J-e-k$d)H;2o(u`LZdnUs4x{P?A3 zylXk?q{ojhUtcYsd7SY8GlPN9&)kN6lSuc#+jc>C5`L)9^dw#Tf$$t@>;^`HYbmf)m`49_-r5kW>*&f%|ZGcd&#HqZ1%F-M)MC8g#xGv zl<96PM5%Hd$?7_1xff&g4U&-b2G@!}ce2asVuFSh;ZmY?{Eej~?O?`EGW+_~r4)y! z+{>wlviefda{7ZWO-cmH#jDGizI3)LS%DlA9GM7$;+34pvplQ0cSP2>@)EBVujV_M zG~-3tIr6L(=JKo+(PhRLgR=Uxn=M^YJaZr{br*kXYpIiTbkCtXcnCnlBPROcZBAClffS)uv{w&6p##e} zc^$zG1xQE>pa4A5t52#`2LSLKra1byKcH?8h`x~%E~X_f7EKk?yacr0r+eu9!l7Dd z>h;Yzq0jJJR_BWc#8SSAms;*iOQcG`0rd0RYX~J`f!6gUQhLBaA;qTQMi()EJB4(r zXroTkE5cI%n&c)&sn3k>W9}}8;7#=1m;7k+U9yCl8&U^zMO{HKlEC4}EwTn!CTc2R zq7^>mctCo69~A8e$>N6i*2}n(7cNkW4+%rWPMWl};5%&uLb#<`6&C;lPLXa%pz54JKY9 zqe}wrHSbu{Y_S6~bevb~d!2gtmK{dwE2W!*5}aeFW!{eu6_LJoPD-Vg3aC4C`Ex`N zCPWYXyAkY!b*R)wIjgtw_mw21^<(Uvs7DPB_VTyt?)VKV&o5K)$VOW^;m_`;DYr=U zYgjs8zq5VvncV$RsrOpxVKL@x=S@Iol9QiI81?D53_9EIWAaa^q@_~jcfdz(WUGEE zVi6@Opgil0KOoCSq%y(LpcbR0>2vjrUb2GC(_SZA{S$2Oy5*vcMa!J;b3oeqMjZ@l zjp$GC>YSH6z7Zx=;pk|(I_6t-VdzFwS8Pnr%VM7*?z;2ju=a0sE(Q{(ovL2HWJ^2y zMt@*WE7Ix_yYbaG&!_657fwUEE<1WHq0TheRAm0m#e-dnOi$i3RMqrWW*q_y;_udhw*U z4#%V#J4l2OwG!e20H2K@sYs-@L{k~~bL<yi(_G;n`HE7E9n>RSwf65#P4OA ze`)@Tw-v^`Lxu49{uBjuptkIKVa#=h!z`B_nDyy=alp@kH8^ zj7e%#f`9vIm8lVNpqZNFO(T2>bFy$d3+1`?!MrYE_AIkdIKyMYM}fR|(rhdsct{H< z!whE%$FiEo5;~Aj2Zd)Y)W#Sq4WV&R*brIn{ahsiqf$k~1tQOvb!g!86FB3&Y_^mb zA0MzWa5^_ziY6}Hb0Ljc&un}E_YrIe(SunRRZ882YkQjLg@|!gt6qZZW!%?IqE0nA z_t5AX`p98s2l*@1Q29mg*ZiPTaDKU_QU1)zJKgpIx|W|Ls=z*Q6=_&HI!4)9;T_F?r+O zrwHKy6Tr6!zE4pCG=MMoJ_UsUFz{@I0t{pT6FFcZ4Oq)#Uz)=7f$Zx*#SNg@0cgDg zbUFh=?!fQ^V9F0z2*nyAz*q7g$pEGbz;xj7Q(J%IM!+-4Z9)4C2+pB`mAJK>i}P${~_#h9OaesA1r$a7Za*$QakQ z6v>&v&E*z%(l!e|cNZJRn|FnMxmd8Thoo?T@n{?d+&ILH` zjdYvha{KjYKZR6dMx8f`Z*nY7N9$fwr6FY{=n3qx<{=BqckYooPNm1)X*+nW(LzX6 zla9Q9fg@S=()G7DKc%!>eMTJ<+*K|wBz)P!Tp6wVFS8u~=UI*h!Di^dS(*S$KW>V5 z0A>!r%;RR+0KR|t$60Ltb(TbM7PMs~ZWa#($~#TpjT3cP^Sy)4a)uSht)i6cHM_ka z92{i$%5H(T&P{GfC395_kGn{TdcK=1b3=RHwjm(CuXB@-ik|#d5dL|4J4O@Dqv7a} z77FnX!=>St2n+~<@7!QU5Pa>f!c8`g+hR+&$=>58`@8M-Ytis-{$)5rMok0kLK#QA zxC$=R;cyodb>@bt!n8_8chDdq@57y|-bU8Tfc2Y#{SzkP0fS59^~V{_j{ z6YZgczUY7NVZcoy(z`+U#5D92jzQpv*EEhM1h?V>cxO=o$bXm++=r>SA;Aetaa9u) z*sX{e!p->xz)S;}MeLma#qzmZ91FF+5k6NGy;@vfPWX)PW`v(YtCNl;(Me5ohq852 zuA>;&$qRipwKh>E1y4%q1D~5Wne$48zK@QZcj9<>Ek=;KhUrCQ20ea|jGL6u7lMcQ zw%*=`et|(g4}ybq!~6mw&BH8XOcJ8;$;b))lhtW53_@%kxVxwy%?q9+hx2m&!@S_F zmwvRUULlQhv%DeT@&w)I>Sju?MQ-;PwGhEi+?>RG*~w*GE6-xDk3(>Fd;lC&O9MK z)+Cgik~lFng`UYbTle9wsei39?>|qSf}1)Mx0Uk&tYxh6XqCal>m>G8{jXO!;D5Zz zhf{M7I=7ltECp~=d6<)v(mNC2Q#cai`Mq|(0G2BVDd~^l= z?xeztK;Zw~4tKaoa#FK$T+=%BuPfg8+lq^F{#x;$vp;+9aodH-%Y=r?&ybvq(HS3~ z(vc{F)G;E$G9fwTLP~n7dPcfIc7jQsd3I7pQ33&BazO+!EgeO^VdC9p&)*N}!(A`> z57*$=;)6#SI6b)W3vkWX&j1W=*JGbH8%O&coc`aOW_XEzzy3m&gxI@W^}lhK|7rbk z*TBxl%hKOG(14yMSeKF_`~oQv4R|rg9SIVN91}B5GIMehFXR>C>lWo0mKJ9hS{Bt* zS0xgYl$9rv(a@4-wL0bhu_1ol43htFF~B1L+zp4P0C*+9tpFbF;1SS?Jq574VH9`& zgO_COpN@9Cl)t|iC`(WY`18eZ{WnM6zr7fyexYb*TDo9e3d-mUghaI1vjMy!X+*YZ zdH9C;Ma2bbB_+D$`Gr;H<(Bnz6(;#)q}4U0jMRB8y4O0q4UTRQ@F91&Ib{C%dK^9i zz{3H2e767?ux;ou?n=!5`M&r!+v4y!hnG2n_jfl4${0KnEvit~3BPU-qr>ZA^V2&u6L2AN|PKA~-1o?%gG8NPaXxo%ZaNv(O6 zWs^xmYZd`HDM4|4g&JkI!PC3+{q#o{<=1mU{vR$1_*^`E_=68c@StotIws};%)-$z zu?1kBIbr(lV}=7UU)M1EpMO2@fBnEq`TOSt;sSV4P+3yHJtw3NFN*4K7v;C-#P6rZ zUoJ}2!x&Fna>`&`V$$Rb_yiP=gxHfbFY|g)DZW8jWtnq)1_6|c@ zdPV~Vx(i3wgY9UODB=`N(6D@*602x}K4s9D48jwBVH5uF9VbID`3OuQ5>qOGDHp?f zjT<#Fjary?3rw#o=6NV)G6yr2kD0B(%r{~dnhy=dm`@9sZ#$TSeGKN{*A@Ez_Q$c- zc1jCXKBj=qoM_Ogm!icc)|YD%fCrnECgozl7tn9FK<4Ju-k0KHOI&kpZH=5v=!>_%qyXR>_SK#1{2Yn-5&tH|j9t#?O?OHee&V_EA z`9AeH{e7~lG$)xTuF~E^kW!tnWo0C%ym#vOJr;&JIOOLy1RuaR2fnyn2l8-ipy!n}&Z zyh*{lEyB!HVrFYG^9`7#cFg(!W@8BRc@eu%-@jtM@BRuVzb`ry#55CD}AYIHTi=nQci1Ay)^|>!x<JRovhNOUl^rn8cUXGo~(`-%#VLP9PkdX zpHkemxNqJz2fm7H=kwc3Hy>0?pi*zE^4X##^oM%vJ0ryloYj5e!(ZCh7zj~BPdHT3 z=m?QrsJgF8CBzW4et+l~$#fv)!^;l@chSnXNxb~zeEfq%0)xZ&L&KxEBBR4&Q>jBud6@X*yMe?)v4w2>5fj>?kA$pdW8G> z1qX*B+Mer;yySWPCT4U(bA006o7tE1&liW5`&WC`pSr|EP3*P6Y`{jwj$ zm}bJ`s+HJ;05y+U4>ln{!KR+7T9y4IghAAHs;4UFSp=96IIdO=CIq;u{=CsRG)Nfj z*QWNA{-1WvGpgxy-Qp3E-jx~@3{6@LDCmSENdA>JY6)gLN%zgnyM3*l4+V1>}2B~x+f15AE z8|MCLH_!%gx}VMJgXr-ldn}@QqgbxNfwQO$o91l#QnRWngx^Jt>1f{mPay$(7!AS$ z$pjc!fTRWtr@-tD6bnE)J3ftkhs5X@NR0m5Au0PKBnN6_3YD=>PVWp5)B3Xa*xp=? z(U+AadaG;hl+{=iv=MfJw;`E(L@pwzPyw3#&=2#kP$r%NM(ung}(j9|rjItN?-n zg!w8EzVq;q)4*YW0hDNevvQoEl>XnW1S>{x3s&@{bd#$D@I~{rPv2%3V=_<`LUz^X z-sRdVzGX<@n`gi#>grW$Eq&8wR5BRM02wDf{r*=k7NI=C6sq@%=2_u+KDmBH!mG=~8LO2_eIK3e9s6U)fLTp&sUjd}CJ(Q?pBJ$3+&+Oq5~&|wRC z0p74iW-4s^SD`j-do|>KSkKRp0*DDP_5r?A0>W1un$Ej}nGZj8ShxO7%5kI={imd` zM4LCJ-_A9#uF&LH$bpiG5C(;Snn*FQ_0_U*?X;J8z6QWn8(~Q0)T# zYz-^OC(NMzD!W?oI{#!I8FNXa*Va^;MKq6DOc}G$gU)b~fZtU5=jV`UHq1G9mPhk> z!RpvM5~I@(2MSDU_I1H7HY1e^#5@vXBHc9K&F5zl%27N43KO6)0ul<~JOC`faNG<6 z3PPaOK6-xfcS8B+g!0$s6Y-Dc^Shu>90d8=^sv{ z8tx7&ASyHGdVVJnKJyTnZ-|Zgwqs>IYS7!^Q8sF5HBklLXE^ufll6Gh-HVj}PxApN z0aOLp5C91ls1rv(_%RUvBM5(dn+BlscToA$*!0gq<#$#N&F5HFoIk%{$dxa#Y>7#O z#|oDE+ZE6n#WBiBE7%b)J6-L2OIYJgd?gh$E#uP=Ue1eP{bjAb)tkfU4uaXi=UE(o zvlCLs`>t;sN7vo!^C3RfM8BjDk%Nt_M{PJJJmSFH3q>`fM1$if7yGwOJJ8=*0sma6 zO*#}6z=42r35YAe@~{42X9je!|3X^6vtn~hsI~cT54G68w4da^(iL^ef2k{fU}aek zOEaC62G;syP)YkaZz|^2s%U^YG3`SVEqen>W|;oVRcZTLMOpz%=Qf(RX6@8x5!GYn zn=?o>zsjCfoo#*hX%O42_;rGNe!e^+F#XkH@`*6pNqR~BEx9RVEN}wgXfb^L2P*0R zQ0g#Ke=l{o7!K+-;Pv3~joabQ_{fw1p#kiu2!sb_W?)wbwD@g@akuACcYq@Q_z?4F zzxs*40Hux>@NSSyt~vEbsbi5t7wMG=yc^`py`STv0u89WV=~ZYBiF5oMcnjb?A%0D zzPQEO{9)m0A~7-#B#=`7g$-+^fHIV*4|SsX(PMh?Ef{7QbfP z1Ut`$VbxhT!wHF8`E765(W3X2%!7BqYH8+()H~Hwv^`P3sTb(TzDv}*LP8A|)_z%w za=}s21@f;X{#x(*q0Epw0D9@|dOS|(zLv)c5!?rQ4YaSw!byv$z31XHwQii=AXOqJ zbGoAm{XPhCMCi!(m#zO+je{b@ClKKiN$^1JSgDDx(!tldlEl^-oN>kAA~CWFQH1gy7@y^ea&3lCq`bosz6bl zoq4-KHkFgBS2f2Kygz(-N@_ZCqLNwqB#Ip{ZHvT}xX%uDz?g zv%9aLw|@vdI1KPPKIJnxJzJdmVb1&g{F3$J@~X+o+NRFN=P!*PclHdozky=+$gkV6 z%Xkq{uPbNJu+{r-o|EO!GISfZUAN)5W_M1?ft;5P-15BdW{NMyfvYG68c`Q~ z!-`wgP}Fv}HS_k!esvP9CqdeUM{|uSiXsrz5qsX-;WyEt!F>Ik{aL*EM&qp|*@OA_ z>jTd!m*xx?nfGSh#g*ocV(s3yCMsj|e&%H>ix7mi(v?m!S3o4cM@_%Rf4o7&ny1iq zurybXeP!Z0aLEpWxVkV|8$_*@#QNB=KRA9nCJzO-UK~tR8}tB+S*@hiMgBICh}i0T z=YyiINs`#zoKa|so%BF_>)xKPxgsg`2;Yf65r_6XNme%LaEj$>rxlrS8Omc)nmFze zF#}6`b8wPme=|SxnP(R;88d+brE@buFbAYw@a2J{ixD%-@U6M` zz{QA6P5M;*aAo33ap2lQr4@V6DY*q>PAChk3v`MN36ecU1q-i>RKKZi0%f{hTSo`% zvrfc8cI#`Su)eFl32ZXM7zSfSGoCP8rP6ff$Ff@wn4e0DW{5voV8)#BgF9bxC?LmRdIqaw)fL~lg4-pm=R&w=Jn&slHf#9-x*1}YQKNsvH1u%h5T zF$#Km@Gp7zP#yRr*iSh4F~o{jLa`FEXyVP`k0H!z4b#r(mVP2{S{FzA2NrF1Z0}PC zkJ)AFts+(UVwsF0NJEs;^CNqOU#nxs@?2bV5lyqg!s0^NgG&n~lwr7E%FDlns-!F|PjAQxxlQb8n`1i#sP)wZYdo8H}-4Cr!N^9TWPo|QBO5yL?)`Xxvt2(8YS0;;YKb*5;Y(QeU ze@!r5o5|h}X3?@=a$VqPR)<{k;InWz-5NznP=+AAglUVve2*%Fbc4Gik;u7qY5vlK zu4Ks_T8Y5RnLTMLsQtE&m$UjZHL{6d3(o^U6nZiwb6L~;#IG+|$x=!)BzxsN=w;A% zFA-EI(;g>F<-YokYg@W} zarR9|k#2Jcmo0bV@aBWQM9naa{z#!j*PMKf>DiIb)K5|8T zYStIeb#Cm7<7|0!jj?3Mj?r9unr*tl7+h>=s`%b-N#kE1uXZ=)bKu+etTsRNcRrXL zmwc_*w9b#)3He&A6KyPwc4Ub6pitaPA4XZGm%i_BxrX?? zH`Gq{=WrN$88GE_Jw%79oGD&Yxa0b(VC{aSaVVV1>3yi=ei?`I-LlA21fR4yIECaP znLe~P2#Pofb!m1u1=JtHOr!7U)|;GGe8@}}3qg`%luVw(Ok+)<4rb)n@V9liI zY>!&Q%@UnGNE=XY6ZYvGi2Y&3m*W&l<`Rv3)Igv#Oq3k1}IB8uG3?JUOhNVW)G8i1UEO1Hu_prUook3L8&rij_d zek|;TR*meRz9_x2-n$Inc>(UudTUg?Qrq8QX;(PO&D!&pB2r_uz8x-5@OD{aNxgw7 z+jsSy{lwzh4VC~3f^cqhaG^$iYMTQNI#|4p6YdOlXyeOkfp9>$Uu;0cPLEuINa2|` z&&w_96raB~7{AG`Tt8gQuJ&F9!g)KE*@<1tC%%MD&vMv_?Vc91D4VgAj`O((Jn^FE zEXjwr&e|58!Jc(Y*VtxtK}BI%-NX7^SUr8tTxIof(QpL^SVmn12i@!Y!V<=2Wp=4P zB3o$3B$@|N&K!^SPvJ!8Gq`cSswpk6ON_POwaKJ@182@<+pc(B5GM5XQOSneSH^Nr z?AP2X_qDHXbxm*tW8gwAQ0csvQG7)V` ICqQEV13e`tp8x;= diff --git a/docs/images/t06_remapping.png b/docs/images/t06_remapping.png deleted file mode 100644 index 3eda28258dbfc045002dec72989de3f1c67fb82c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 7496 zcmZvBXH*nhvvyA)ham}wB#|hfBqc}~K$I+poP?1qAd)jU=#T^ihb(bWlH{CWNCOB0 zl0m|NAc$ni@s8j7ogeRAx7X^`T~F`Yy?a&d>Z+$Ab+jK-k+YBk06?Xt`cM}DKv=@r zObQ_&!8bzB2p6cmqLv~6RK!x8KO-W@AP?QgNo0<^tfQ%~a&>hjC@5%YX}Pel zaB^~TadE!Ay*<7*MtFX;I#66(EG;cPG&H2Ar`OQXke8Qt^b6ZR*N4GHO{RffSK94; z??`HUz0+X>g5EqDPkmSIcbf>5+mpO^b%pJ1TP>Ae>yH~r0?|`YsFMO$m%lES^P#Xu z6k651eyx@A;L(%I;5V-ninoUr3&Cv818JflkvN<+gVWbzc6Qd4!CIHQC1IRe< zk%2y;38D;9O6`|V59xxZt7rnc8?mY#cTdJMYOv}8=(v6>VXRyT_p&ZG5*mjB&@^zc zDnXSD#C?+h0CaFP0l zC#|4!M;aR+kQ({qg^SV+`<5t>HEi-eQr4h>@o<$+FD%81ofduty1dSrWPVW{1~{#) zZnYPG1`fFUsrV91;r|W*4c4$=3jmX%*M7m% zpq%f{(Y}L%-Y$eeZ~*+EI$N@ts=ofn^tW3WZ*$~Rk_nwUBCX(O*f9*&IR#p1flK(*TWxpI4CAd%fz2c_G=uAz?g;+%CeU9GAvnbU^N;@) zJVE$;zB(E#7HAZ22nEn&JjiFDsgybKB;QI+{lNj;D>nmJE6%(~nDp$x*2zzT#|xZw zd3D6?VVfHL3xchC8?-!@W@>G1Y>MzRgOZlJ<(3{~r_AhJGhwm+$wl)XTK}*DmhPW+ zG%ydwKzxNN44XvbU0-Av0Rfx)b&t(gMbSVq|6z#UHke`LmwEw^bbZi!Q1+);BJN{X zLX)~Rl*zvAt01*!3URq~vca3Tha@l>^Pgye$7m@wk(Dw>SNtr*V#?H;-(PaOcCn~C zzo85ee*4_3-KmmmnYh>?vr^xfZd)g2Pww{;olY$dxEJPO!upxNLANsE_@9cTgD;dh zB;MP{%O1r=1I9(7MdG$8;{lvg*NY|AV!$b768&$1{v8;zhqO`hdwnMR@hatS@_I8y zWs}Rhxg?HnuN#zM#Cp)aHtAx5LTirMc(mmNt^mpM;T;QnQ}1VtRVxG~k7AKMHyD4T zFnOONf&%?4x8K*3?6YELI>l`%H*!9J`}aKj*1^o|eS^cr@*MlN0&%x`pVz;{r;U(# zR*%Nhj1O4!$E0ixnL(Mg_E_-X+sQ*5mT_%f;Gzfoptj1_Ji1``+VX+aLs+Z6DQjOpGw}SG| zVW6FX3FeoeOWpB*u2GMXOq{NtN^443QBuG?qaAY>O_c@v1335dUNucY0vx2058-kT zNSIY&64wI8irxiM=URN1^>Ww@$tfW*ywg zpBjB8(+xrpl}=ka(sT|Qa7b02!R4CBX)37%ZC?dt7fzX%$ymG-TeHq=EI)+{Vn39K z8iIwaPu#QRb&kBaV#P&wKJW1KRW;In%NhPao0VabqjQXm$$sokb*o^sst7pX*!ALk z$#196cE(~jC_7&M2xEvm#1#~Sj}1j10}3s>Jw;~E#Y#Ph77x>5LGa`Nd1`&-nj81X zyFo*p(M4BNlDLqm)lBXRk1K!H0{gZfz<8|3!pq#kx2Xn?+vZ-FdDX^1gaONYxZB9V zo{+7LS-S6O(+Fj=(z~TeClYXfmc@N14~UOZzK}<}1kk1)8y|Q)Gw|_KY=}AC+Bd7+ z%!N%(q&y%ie*dFu45vB$XBZFi=A|j$-{|t+ao|4@0xL{(e9|WzIft}ezlPNw{;(31 zI@|G@DHb5U8=Nw%<|uAbuI;F&761}yajU^~YqdRFf?&Vepp)x-Z2M(3>@M8nKp@S7 zmDlCnfC*RAI6&d9P}6dbg8EiGbc_OReL3l4{6p`{x|AA8#*R<8Hrg=(*^frxfgb1P z@ncl6JTw1`TUgKcT6JkzI<}c~l#F=pA@9&Bz^3m7gtRk!z4i~iy02iUL8yL>jIc8k zoLQcsHZyBDBr|!7sm_%d)ES;YLxL2E-Y)N(0Hs%|$Pk~SxaY&v{1}TGYCQV+!eD)x ztjA<3E_RG$LqKDdN7SE1<;M}>1uq)=KL_u_+klQ840o6Mh`W0f;r6EYS&rB8#spA| zvpU{6%{kzYCIj%L;V>g5p_8s8AiXm1e%LvRPS6>G9q|30#a=>fjWYv8S|YygEN=Er z#*5%Ak-InKr#@6Mcp=?b<&8U20=qzlwhc7a!Sg6ldGM_5g?{=8naSM_<}1PrpK*1W z;oJ#-w5-forOt3<2Xh^7U2!GL&z)yNaol?rNAP42qdIQqnfmc?%%>b8kwST8f&IFx zl`2@6Xof0i;7ibpV;vsf^=q5{%s&LM0-f(+lpN$J?HlAxE^lRtrtI;j4#x-zYergd z#5Olmyr|!aP=N?e1F3c?FHOZ!EavtgdY2~qzOa2dm-9qXW7a!zY@vMqM^$Um?G9!b z=t~B5|K`i#ze*Rtt0+;|%kBnA9MbWyS=lsb3G(h_vxcyGVHcOL^c)v+Yz2j25fxc=DXi{Lt5sX zRuMVA9jCa?-#y7eLbsx6#f59>E9h-w45`~ zg>;&+yU&AsPb{@A4X$@_rvOp%VPQ{PD!|PJu+_?`Q#r(vtNkkeAFD4rh_N7?c)sgp z1&pk=5q_B8vsLxMKnt-n`o|mOIU|%}d2Y?UFfV?%6VBI}{|{`&4$Exgx`476Tgm^0 z?0a(e=u1|Hbig|0)DGP%N8SZRm1ziXN?U*k-A%#Y@=hjxO7{h2U#XKbL*neOu_>eYZ)R0y`~7|7RDd zZ#3}@7C&K>&2(qt#F{<#4P`&mWnF6Z2^cC0z?VSh{VB8xs_gy&na01O1h`3j@f`5E zDFtP0x7+MeWJV836wIb9kaLn+xc3lz4zJodf3(MAv2v_-#D>(e&kGx-TnraBDmouCBFD>(Ma13{?X)+%{-lb5IfL51XN2zl>zVZ zu|x9%t<1feCrwX>Any?g{+xWOFwadWtdnS`CBqDffB$$-?kym#XlY9ZfBc|MGkqZM znWi`TX#{uskd_4c`k8tAU6QmEop3I36Hb%cK{)eM-n*bXdn!uTY?0jZqy%3T%r(tb zAvaQOugSx3^3wE)*B#pMAQeHHp&W?((VP1Hw&_EU0ZuX%47ZI^=k?H}JX#S<^y`$w zuY zL%hBiE6>~o?S&iNGhaRTvQYsPM>cyX9afU(!9XqjQwPu?8D1SZx&s;G;G-p=dI95V z#~|Il2oh0!u_Ztt!h|jK=O2cyhYdE7)84V1NLr{AF9-7?I=-Xp28YA<<6AGT5-dE# zlzBRJMnKs8{8uP-e` z8&t-9(WO!5SxBhfo?UuaV8g7AhV7TwpiPorQ|6Ot(PQs*lH$CTIYLK9BWeH*hAtg7 zg63qxr+nHXjl9njHMRT^k>+Y=jy_Nkcbca76gJ;||8Lz*trJCe8b+>oBK(L0(6#Q=|B+4E9RkxJlf8S>G*GH$PnWW<91d$otgO+~t3wbJ>9Tr6Xs z7D`lFt+LWBMQ~wssH|zOiqDzz5FXWaN6fl3@X0r2XpiZ1;Ds5{0S&c2ZxWtBN7|(aj#Qq zsD_NkA;{W7I_R)+#oh60GVFM~Sue_;zbQj|N~?ea-C*@4#^2a(z{w@yUViOi5k!rGE()+F(3@xpkJY>L2ECZwRvf5zeE8?jj_k&Ruu#m>m=rOz0 zxG{yBs_S0;;HdU@M*5i-X(piTUUvNOhvS8GDhl?n`-j~lR;*nSlSW_enGSmpYEOJP zPPKWy%=+qtERW9rX5Q2G=fV*ts&Q6!M95xt4`Vukh+PWKa%BqtH$Xq#k)5sgJ9`uk zkTKAc=|1>WA->*8D)G+F5SUW2CcFOf>qGEbJgj-}Zz)Y$o<}UEMNQ#XTkhdFCK8i2 zJbO#8%E_dLli1aaPL9~YQb>3Lz#Q#b9Frrco%s)y*0l2t?ns8g1{8-Vnehn~)SzYH z+f@kBHGTRST`h!0%uD}k!f_ynCSEwDwy=p7y}uQ&Kjm<%zFu(<=ON#QQZ46CrVoQ8 z@*O$~_e$|)pdHPI3Y({NUFUl&_)mCsn#OBDO_RgnGw6)kro6zXMNSZN8c^}WG>kS# zK6=fhhwuwG8gDWl_s|6PFem9K_yd$O&(PE z#y;VOAp1QI%3JA)y(;OE9~rGQFI8)CO@M-IL+;^0zW8;@pM&Iqa_{cL9}7z`Q_7=D zCS1RwCR&4AJ)hT62tOu9z+O1EyPl3t(F-F zeoJ6iKS7}<2ef#TmsfM2%ZBKgko{)Q{65no4`UQa5ez`-bVK(|?9T|%-Rt(~h$jo~ zUr%@bIgfu6yEJOx!{_5Slz>U%^9GJMc#`V-*(Sqp^E!ua?;V8*$!~tw%aVlDr;^FB zdtGg2MfN32L-Y??#pI_rA_>V+ag#?ky9IGvw4c=^DV>NX<fw!$(O3Kn1teRsNe6Jbd#=dl(jG51 zgw|0=b8Ry0f#^|)uyc&0{4knD1fC0(E0=gvUiBI5yvMJPgz>Bl~IIP-)b`R8^XTdtSuu4`>!dVRRUaj( z-NOif;s{1|Ol1hau2s`j3p#rn2nF)~hza}I$G>ZhRgnP5Vg2Ibe~DY&dRaATl_~nqiiBZF*2xfZWEJSl=sH#R%}P_2?J;s2CDGU8-`_I#5Ss znIFvv8^4H5kKu%u-!OQ+8mzg+f%VK}r~X{hNW(>@ld@0G&`X+%l8xktV>p?}5Irl# z*hz!m8vCvyD~B>mmo5*6BQG8i`z5^$Ir{gkl8_c>E>yK zL>WJdVvNdu5>>ykC%MxjAN7sC!?`VMju)94D(kh{JrU76Ra8sq2%B@Zv=g0K)C-Dr zbpi|@sCc~&XQdC`Y9*$ZzzT@-@GASmEVW=cBzXg5hP(AeKi30Ln4OU6=axjwQJBD) zl}UsWZ5L^-EI7JbXMVInE(CH}Z%@)r=vNnw3J?%qwAJjF^KZ=XW_S#sL`x6q0{n-0-8$^7` zYxDm9<~RStYrw&4_u=93W~2yGz(wp|o|CBF(!SV;7R6${5%|?dVsMP=i`nKd#Cc%r zx`ymrioJN%u4Ni=_5q!38v3~Z^e^eztu6QrD40b&m50We6tQX}V+3n*zQok*wLaA%1M;M>RZ*XaWuuQ!g4L0C7Z6SNM&08co_a zV(Ij@ZZ}iuND?>RTdlNvyMvgT5Dx_-QX?ma>tjz0RmvV%WVF<(KuS|FL^I~HaMx6g zJXWK~E}pB?j@(o;*R9eb4c(X6nPxg7`eHEvc?GCc^C z850i$aqi!A-V1NDn|mQo;}p4m-4r>o`kGujy@L$sYm@|vCm9DAzg1a|wg246K%8n) zlVRWc2Jv13_v&%YN4A5$Z5{H3(LHMQEW$V8ylJOLx<&>}S(khnM)(KuatY4Z43v zmmWx$3E_zGjH^ft_*=XIJiX)kKt8nk{oF~qF;R_ zEEIyZbTGO3h*X0Hf`iT?MkgSmpQTaiEM8-!_tz5h9X<@pV;o&;-o&@Pdg;2zhc(SI zqLhiFwKfJmvt&<%F}eaRzZUKsV%b>+bLDh~20>v(B$+=FCmm-3v$0L{4cY#+l_+@{ zC8W@!Rp44qIc=MF(=49*Kob+8)Gl6g<4W=3&Vi#z7_B*^v<5?T3XfQ-hoLyb>PU{U z@8?L?rwx#CFN_7kyGSyvtHUspew`5wJK*I-DPl|JK3gyGz8~N_=3cVXbJtP)+u_y>9@y*Fumz0m}vh7cmT}opi z<9KTACFZqfVWw;_o6JwP*U z+m?bK{IKr{(e`n{q)p$fPi^TN6o$G+Wj*>|3=ARj_-{fI;Q*4!m_;v88RO<58_*K# z`OZFJA>UnA#LiL%S;i*)iR4c(W|TXgzF63#iSruUX@Xo>Iu;ZRf2epsr6c>O_eZZSO5>9y%Ht67lk81Xz|cDHaGiz{zOGX^Y`~}0bkHry79%u z#ib>U(uva2()9H7bvI!Ittgptj(XqfvAn#zpP!$Ih{znv?DF{JEjsPjo{#) z2uq#}V`F3HgVMUXawib*F1s3wsPl&HJAI|4r}BjY&)Qa0Uek1RKKetzEB36qgD z^YwimvAmDOgbZURi8*_^v$JE)lR=BF#pQPC%0dtYJ{LBcYq)fcalSTd>eHuBi+wuJ z&g$ih3gq{VSw%obcLNhi;l@Rtg7B?`YrmTPEGjJv=_RvxUd^|E;@qvn0`w{~ME+m$%sZ*hg%~@m`cVVHv$jx8ji}C1P3W z?Vh~m+0t{iPoF*o^?teIfF~hf`}_Nn_^?G!>X4hIcS*hGiICTZhPQ)oFK_Q;`jp2D zmxz-oWcr%3rFU*tR^iA@k=?TfhdS9V?k(doSrO3%CAp$G{qMV4vx2+{W=~ zBQ;%A_v*yso`>YW^X9hJSS~+Mc;`V=-(o6b4s>uq(EY-hb1vhG<5b@~eg*R(ed76@ z!kg_w73mc`0lw;l++z1ZKZo-r-Q;w%S!rBUT(u`^a{1y zd13}~+dos~WNVi5|IeE(l+*OI=d;hgeszCqYbSW-d?Ym1{kic$Gd)2RjoRgG#(!wG zYb5Gd;00%-y1(&J+(5_m8z(cnQfKSJ{JTK_4UU#8h0ZDAITJN84-pmbq~OyFfBeU| z4DzH2ch*QJ6)0xM*x)SCN1jB2a z<`?JRu{@%}zTZUbahcS9brt9@jPr5dmM!F%uT-;6@hrlY{DSB|d! z877M$N;@~n(_(2_KO?4HlYubyv4enGl85PbI!f$-0NqJWpB!^w5tk{tFtC2C&SV)` z9N4+S4}X9dhf9p*bh?1O-LP3k&r%EiU^ix4-$)}dk=HuH&OTwPNJpeZz>682_+Myg zo6p@j)y;b-^wC4G-@N)JtQ7C;b&gBRKK zBoC&hyDMJ=wn#Yge!u+aF6A*dvxeQE{2t*}SNoHcT4cX6A<>hYsLn7n`flKITdz>o{`_SKm^RT1%++xydIO1fq zpVfJICyb&zQe}i)V82qu>ZGc@VBBA$=#{%Tf^ftyJkJeR_>gd!IFrb`W)aElMJ``>km3oVBfMQW=2-Y8bE zRQA%7G%jC=*T;oIgXP~49T1(#;`GVm^jWK~OPGo85}a`pV@XRDhiTIm%D|E3G&!*U zlY0J;8gxTe!@l)6A>6lU(&jvexcKp2x;)d=sH*B3k08(WDt1)fJ%RJd%U&zu)mL@% zzLlsb>!a8`_T&$7vxZOV;nJaz^egho?w?NB^mT??r|^$wTC?>V=Vq9;Iy=tKbU51U zZYiJ|O_O}}59IMj-{A|Bk{SJy52%=WjNXQlafW@B{U zNA36V&t3;Y&-pE(JVAWx1G3it!5P(L`?#^?KiE$nlF3t6sy9sw1U_u1{kIl972kf= znpG+;eK|{!_aN*s#|EX_J!!j45Vh8s%h5DP0MrSu#|%y zR`wIGAW3~WcfhyO$o~X0kxZ(*?yLduOFInNNx~R|Ae4?Z@I3q&lpKfHGV$#oU`3Rm6q{yg{Nq@bA6X4xx)YoYkCPxU9aGpx-dy6@i0M?&xl zLp9N1W()lD)WozbVECKxr=2qRSz$bmE94KA33)C1Ih@bKPp;=9)co|oR2_|ZYuKi@ zu&?Ag%FuM2Kc!9m;kDGH@nNKQRdX<5+ape!=+WpaJ|sK&}?Z1A&w+~H-U}MeUB^4-* zs>LofVh5QXm9}qu0<6_sgB2-fZL<}N$p8F^x%m-u+mtrb)p4ivVYcQ^+n2)p13>sC?*Kd0Vp7amGqhn-`01CFmUz!q0cAh{7x`E^K}CW;oI z0CgvZzu<)(*lZLABJ~Du(M`P56Y2qnvtSj0TVJ7TDia8b4_R0MA~ zn|?#~jguf*ASRLELT!}u!+WDQH4Lw6)n*b&1L*zH6y6}?f6kBe=&$w{h#(*PZ`Z5> z3iYN=A&V%dQyW$`#v4}ru(f_df!#e7zOpv-tUzp=WMNiiLb3qP-p|U;oA`I2Q#gOy zJzX8`37(cH!y}b!#P3t{EFT83XTYDr2;|0|;B#0)$MFViR3^zHFyxYc?@>^UqTRHX z-zr{-K+xNLrfuopRSzqT`lnX^Cg+GQBn(jd9oeu1vy?t1d1WVuC3V-y|P1l^*# z4)l>lL^0K}`3edm96CaGE73;ZTn%Cm{5`s|OMnwbp@R79N}>HFqUsyQH_E=Rs3u;0 zH^`5le%88Tf^R_;^0-s@40FJgxI|s2=IS>zB_p|+EW(a&u1hpQEuVxe zxxJ|s33e3MlFIDmd)VOa_weZn;tf$R^VM82$wS&@Vk4?7mibXN7X#pTI*Ew!Bxk(> zLUPfh_vTRSZmWa}H7VZ#amx^iKazab?&IA(W>3cKeCRY$AWIYk&c4`XvCJl~w(#Dj z{^AUAGiDq5IP?dq9p%jCfAe|7&BEDl>E-4NuBBTAV*%J&5ZZK2|MR=(ZZS2tT@vqP z+(;(!MK2a680@;DYw}3-%h$CsF!@QrMv4RSiD?T`F8xeZx7^G?87zp8puRBctTbhj z{g&T?$DUV|{tdD`9wSGi$6>+?Sa0CzLC_89txgq|{fv3(?e<4)40@sz zQ3_?Uccery;k-;)`T^8}Nj*BJ+}IUgf`Wfo_Si5yi*6Y(Szk_ns4rVM3Ar9r$}muX zH76IyYI^8O=n1)7B)2#)M6ROB$&f`nBU72L&2T7tj?(DbLDBtn{^<%wWNic;8ZG7k z6&4eMeu78-Li=IkGB6TbuHCr2GiEq%q9UhGsX=)A`s&(nfjvGU2rc-56x599 zQ%q#?PtHeZ;**hh!b_g z3bz)z#zCA^!(DQ{`XU%%rXgR_K|BEPV!cfE$&cX0?SlNfCuS_^=yg0FNJvD8i1{h= z#L{wwQ}uZKZ!vaf0b^or+S5Pm=2k7&PEC=VwOqFhRMIfz`0?X~E)I+)50U%k}2NAoxr&=y^2PapPaX&9#_6tRrxrOu8eRbeUW#vtKB>5D&R@^Uob;io(bZUd9c-2;KoQS12kp%dHU>W%f~utx4Q_ z`qwr_arj~emmZ82yZhr8tCm9!>pGDGuhSsnc=Twq4hAMvmU0~qnX3DFwpqZWrlF(S z?2HK|6kch^Mg4sER9rug@^{W34ktfq^t0-gcWA@EklnWx3@lWgTd`bCmv#bvluirP zYB=lK()JNPEkOS8hK!j=slCPf1vhhG)cty@N1cwOg5ix#r*URezM;>09c_6yjpG*= z*)=qiiB@w_?O9;)IIWhsHvx;kTmm{=@Z`;qVIsE?@y4x|NCUjoW^JJiR~XH1#+IwN z)la|wVX*vSZ)NbhIKl^W5kW>~IB{01L$g7YS~R|5VkX}LhR>UBXjl8j4-!TB@_EPr z#K3l0HHwVLg6xxaxoRoi97ryVPoLyH(Sx{jChS>b+y7mBPIRp5v?~wS#-fwvXPlCn zUuy=qNCgeGUFK-j@CmVVdPhu_>||bTp*v<=t{QJfhE8|*{A9Sa-RC9UqC^>xRlK23 zZ3{4p%6+s*$s#0!4n&q~&1S~=Y18`6i=ff@TQix=-|QTDD;On**uKpR$N`N7#|pwx z@9;oPO|4bI?@goU{9E53$Hjhst5@NOKfJ0;&ocABp$pHs&wdI-UrO>9yxF0`AE#kp?`Nn-zYf;w@hvM`3q)n)L+sT3Q2xbw@2~taxHQHSI&HeCKEH!dHNVX|mhPzw!y z{?AM&ugPE4yf-6@E_7>N87bOK>+8qj4D3oi4&Q=C#~<-A^VEchPMv?sUy%PdaPrUb zD}yH^*#<=%P1iqYORBvcCv5K4xDiBWWLyL{X7T^jiKo}~QzWp2mo@e;e4z9m(4DMp zg`aVrm3TCLPavwJElQswNi&i-(iD$Rd67fLN{DGPl>aSBiKeFXXHMAY{&fp5YOyTp zyZWzdHT65|)92Z^%@ZigXJqs$^F`sx%X*x?cjs)^jc3ViGor?yot+}zkacs%;rNO$ zKjTlU!~CZLEhypN`+9-@iNvlD7ZT5Wf9O>y3R4&yt_9B|A`7fj(d zD?{4T)wB{E1UL3m+G0Bs7$$B52dmjXv19l=vy23_I3Ih-R^^6BP809R?B~=?6)uYi zLg~oD&*`S2UvVB4*;Ch-0;E*q{ll4$r{zo~#(y-T^%R`9&U|V>I4z4tWV1~>Htq!h z*fXR>HfJR{7+S(DQqbe-(1e+uDD2Q~0TauvoV6rWMDfWuJQwPka3L1KllST*1g`U` zFub9AWvur4)-zikpZ2HV$BN0!QZ9Rq=EyzqjexECX=Dp0h0FI~bgiBcOE{k_;h0>6!MRx?25;BnEH3?@pMy$suX{EZZhJs z!m}rMSC~e^B}?+ez;Ifk@mN$8WwCAdo)14zn@57lVugXTIhmX1-tpk7wl4UxXM6xic{ZzfFN($y} zrM_;hYHgY`^qnU$%6?83wP4%y(Z`dX&4NeNomJ4DmCIj5()-3wqNvQ}Q?bv5_4eLA zxbkI20xL zsy|S|M4VM=ps(ZZlga;1mljDD4D!?pGe;Vwy#518m?t-4Z{XVLUquRF9?Sn$rT%Y; z>i-@9SOLC4vFiUn{Qn$i6i#7Hl`q%Mf;SjEh0xZPRJ1}MzdOQ|OX#$&KjIO|!QeLa ziSm~;ua6xiQeX7 z437rC);g&#TnY3SbqqAFWy1Yl8OY7`Naq^0vZ7pYbj$MU4H-3gCg0qDFErjNp@IFF zoqZdj@TXP3ceT>Fzb@P?tQ-IL)VK9@@!0qgT*wLPgim{a?9_o+z_Q#=*c zYlEAIgUshoqXx4EIAgz^buzB~@r*2mK{U)0ggFXB;AtY+qJ_UAXP ztv8CRH#SCYFI#BD{aAQ-yj3_aondx1q*8wQpU!)tKD4*jnC@{oFZxwI(mOidzy2~g z>;gAltk>*jX5Ki9{N36bDUa*!f^Nd2}9a!t_flg>R zK2$<~tsM6of;(EwXg;K9v!@O;Qlxkvw*QtqIom#3LSusL1l*6GY1mt>FR!Okl4q_j zCtAAyiu4#uNzp<_fY3*vjD?jxGlPhZ&IAvIgg=W-$34RwiD&O~a#nx-v{oZ~SUQhZ zm5K^V9hNFz;`Q|}?K(;)9W}4a%o2U1O!2u@lbozM)*ruqrKOyf-b|n9;hS;Wv?9LU z7qIn#%Rjua;m;(q@#rGt-;}FO0>fz05wtltfOAk$)rUp~C^Goyk>;GmuDMOFtpx-I z_9egYOrUP7`26|ts35EJwKnTy#OMe#MY$wXJ}cn*#KOvIf4-5!!lI5mZi+7@66e}L z-xu$3!v*Ck@$gT>PTs=!_*)KE6 zfU7hq{R)&W1~&(XR$zg>{ihm25hB99IM}LEcte)83i8(IIoa7SdY=_*g+DxDVBme* zkakpY6`&dXc-7*acOf5CMhF42=i*}b z@p1SIjfmN~8+}86eSKeQp}(GM?;p!wE%)~e-rV$gh~!{Eap!ON`91r3OuSvtC47GM z&CTupqN7ph`}O6EKP65u19W&eXEZOt%`2+=u_d^}-`ySe0ZU1Zg9+!fBjw;Po+Xkp zI^qWHXJOH)Mh<=Be zD|&Z7K}Ctcp*rcMuyfqEvRDlSALsgXEIgc;jmnU;k`X}h;7V!W$s{l^ooZZ6;>bo3pQc8A(;7d&H% z?(U^MJ?7!k4Wf<%V9}=PS77SR6cP@9ATffff~=QcDD=eDqF7s)Fk5(B1q#UhOo+$M!SO z+1$x|L!=CWEVVldzx7snjP}1Iw|fM8qOvkj_BR#mLs?m?xWAEre9!D332x!*pPQpk z&1+(tTpJ8_*Ha6Fi>sHc%ojG@P&P;8b{cy2SNo`uVZa5|v(f1uf{yYv92`1R*&3fB zRS`@L=8BJ`rBSQV_&@Z1_>iv06X=5(Jb?6WYj0NZUSod`smiF$eRCw{_irtNFHTMv zLId&z3w3?7{VW3X^nKk7{o~`I9=+GsRz+}TMxuuLGb-_$@Xx24Ma-oiM{@-!ujWp# zuZn}5DEKfz#f+DiU1QWz>x!A7XzyS#J)LW*zTx~af_kYwHI;v*Sxtir8O3&^!1QnW5*JX#l6tjRb)_{tV1o=E|`GPC)O9&N1xfL zs2s|}O}=|rS%!6P#{BHF0j4<@rL(sm9T}k`l6zL5s>+_3YvOXLc(XHc)!{c8ux~J% zD{gu-vbIJMn;};O-|_f0n67q{)}P4mpppAqnb8d$(POT!uix-c`t4f~KYt#^H(CJD zBr!30*`lOYg@Zlw&k2&6zu%zPM#&y*k$nz^NKm14D=H}wAHN@?X!&ZQRN{Vh zG&|1c;!8n`zmJ!fow>PFKtOyq{`+2@aA_38_h9sa7*Y$94yTP%xf{Yh35oQMeQRlL z)@R4tH{UI70kgQez532Y_j}3T&ntd*flnpV2mE$-O&y|ra!V)rjgo101V3N3kN zBhQd%H#XGKaBqY}B8*zeRuA)XKfd<3y@=`T!~g_9lq#pq-`L&#P%`+>-<`~Sn&|nu zzTSQoFF!xns9iWN&BM=*sQ8hIU??;?SCsU8SZXiFoM=EMGLV#1?>$$1EcZxu)UQW# zxn6&=h&bseT3fqq-W3M{w6@BQ8&wdz_xJy~TM-=CN%GMd>F>*zC|^z9XAKgEg#)sG%b!-|mkSlr}VQ@t$&;jqOwPz%Wg{Hx zWe*M5Oq^V&=qhJF<6bcG>OJm~kW@wD-db6wsgy(;?*X5moX zfTQ{Hn4V(u@&5Bg6JFjIHt9f+rxx~$DiORC7Z6b4(E)@24feC3hkI|eFPA~#?%C4R z^{J*&)f)zAule)-&G!jhzfHwzzA^tk{5~|4os_J?NYJcYlKb&v(HJw>ABF}uZ{JEZ z)}P^b$P>x=ww@0zU36MotE;Qm^xR3H@6^^E2A)<_e7T=lu(#S*Y7*-0)j;2*0*x=8 zu1ftAgfFDORJL6lc=C(zzi~Q9$$NZHbiJfQM~4i{6|3ZJy`Gst5_5~7MP~`x-cSDg zC@Tf`Ui(k5$i+uCUK4tG=>5XF3TRbZ`H3P~)74pmRvfO1_>?b7 zo7Sxkrd?_F_o*hmkply{NQrd_9vd2Q_qM6%+F0UH-*A(dw!Ix04JIQ@KHSa-II;YA z-dIq7f4dk}u{R=A@|vAD+XCQDh4a>rWfhH%%E!cphRr?pn6KG>ehP|9fp<;T3<{eY zl{U2Kh0xF1pPm1Fp{J(;3#Y4_3z$e8B~|Mv4)zdt7y<4RC*%_Oryq=J0OCbPFdrMr z;1w5HC`vxOwOT*Ea(#xNb!*=F3NyO6K9x6jLX{hPcyQIi?p%^I{v>!-U5W7zY7UQo zm%H4DVu(JG(~Lv?Fqlf8m@-JroiPYd0Q}l->FtdxSyeXHh&(j(aHw{m4*He$cgX*= zjHX(4f>8CP65}N{1-13w;_WlTf&%@(z@ovyg>T5iyt$CF+phcldmKPO@S_KALUD011pg4^Q>Z9TTx4ZJR0mnaj|*mOqPbR zF$DsUzO_wBdOCZ@eLMSIXRCFko7?0UhiYh}AlT0~j>cJz9L}z4X=|73+Qp{!j+`J1JGS1ni>Xu>=y1FX}RhDz{U5#pfV zuPp}_7G@`SGq?rSq{_8Fb9BU6ya+u1E`T6NFJV&mP;KA7Ff{P%`Dy$@KW><#tuG$M zsh&isBSFla8Sydo-YYPQQ}Pkt4s&{FD5{A?`lIT_th?sT(euerw7{L+dGFB6z#Z+T z)Ks(rz;WAyAN3z0%|@viI!=!JCBZYAEh>5Qs7I5pDky_AHP-=LfplP7QV0u+l!C%p zZ~CgXHXZ5RYe@r-#=G@`?)IM9@#=-3({H`A!tqFKf6ZsBLAT8QOh8BeJ%; zk>+xFpwgTzR{CWUX?R$?z)T+p2k;VVMiF2uVV57fLmBVu>kW&UNN>ic1>ZW;$Rd2+ zOUQ{}Bl2@|6My~sQskA6eyH4GBOWj_I>@%(8zbM{AT3HTU^7ZiE#{-Lwc5vDEXRkA zP*;1&#`^XQ*Z=6RWAGzcJXUleX82oM+u9Q)N2i0(l$7zXutGrL5D10QJi++5;m?z6 z`J8bA*H_1n8Z%Q8WxDntx1tgA$;u59eOa?L*U+MoH#I!UwOef$VrKa^S}9<6xw|n> z;+!z=;w*Mc5TvOq!Rh@ehkpX;A0F=Hik5?D8w^y60v&_j+64rdDJv^=p7%{osu7}A z44wgEpl@%t-4gt$rap2H=F!x&>*_iUvLd%rYQWPj&f}t)cnB+~n_E4#pwq(~@9L{V z-(zxdxl@pfI4$`mX6WZ;8zp^!r+j>!k``3abk)Br$N`uL1mdl9L~JoiUn?Xzx&sf3*ZBrF=5hC(gi#>0mswj!K^t4gXQ%GQtW9M$mZqRPC^zD zk>wrt^z~!HQQzp$F%cs76nx(!yo)Y^z3Dg*`34-c$t>a0{d1WgMoBTl37U<<(Fn0; z=?}1wJr9?XNnh*ewhQ`l$W~4bSYj5yyEbExk!oJEzha%lL*D-^*Pe2xw0t~OZPffq z`)tkWx`Iv5DNhK$u*2u!>iF;VbxCC#Jqi=k5`N9=jW-Si1cF5|(QHZwMBrG5F)cdt za6UnNV!GbI8l(H*DJc-LP6CzG+s&M5e6GIc#l;D>Cv1Xjc5N*QI82kaZ7y*=K%p@ck` z$~^#_zt<5H7iTEdh|Ciq-dIjNYbyLyUOqp8F3#Uh? zCm96%ns07xYinp=fV@V7GQz9?&Lb==shIUK*W^P#QO}!Fcv)Invs<&9XR0Jm*T+l~ z5EqLIPghp46clVWGWI5QBqGcR%Cmb{esCipzL&FDdw7^ADsKEf>k>;=gT8E9^}Pp3 z^Xu2||IjTwQ>zaHesI&{y_Z+8**asnz;w2?jYhb6OJj8Zx3#6JtQ?gWY~XU#@b|;e zKUxrjh1?lh9|Z_94ECIkZW;-xYGXs9NASvwY-&l81V8bW*QJ%Tv?d%bul!a?U;iAW zjv)D!ms{`cBTY+f>*4-VUM?yoW>`6eiEJ)r0_Y_rp&=fPDH(W>r>$>i#8&snXr^>8 zFMU53gF+dEgm}R-4{IY}nS!Wz$j>RV)Ku9oPF1iH{!>zA2W-G&LlqfioiohME{c#i zl@!mVq$AkDE=p9e@%Q+6V>{0QQ^tTN);}y#^^|`uCC9G02BHSzzli@cNv*F<``qI{C%@S zkw8g%5korL#JCeP(-N&1U7&)Ex!Xfm_?GvfLDcLc@aPhi?JG<#k-(jqnvevVmg7Mf z-r32z0tf}5rxCS8xrBwI@;i}Bcs(jf`q7aCY5LXon|O`98_B>OXUBamHvjD{G7)a> zcp32ex#QQ3UcRhmeWl~Csj2GLJK~^baO&>PTwANw5sDi~d$My@&+6V>TqfiQ;j03T zHvv|GLX4TJ`sqhQMTNbnOgX&lt@q_ojm0}roPie_e@KY+7Mfq(gLM`ORHjeNk~)1+ zfDHNC7Rb%t&@;+4yCg}+$HyWj#v(=!9>QYu*Qb)ks*2Hc(JncNSV zORaVizC3%Un@{eke)U9a$Uv=lb=lM?~OcsM-+?=e^USPqeX2 z$q^x@q|E*RKr}TqCnu+fi-Ut>{<$)d914=_+qdOK7F#i-G{D_&Z~F!YJ|73(N*6GS ziERR4Bju7%Rp(KVC)3e6XDZRTs#25zw+a}`t^1=z=8tFT9NN$O`N;?UH}(W_)SoQk zfBR!-=mel`fB!Y`ooeHj`3c_GKGC|`!yE~!;|oW&(3-0?yZdck{3*0nFUk~RVq#%o z;n`VXef?RzYHN8}#vDnS%rq}|-wgZz)`KPI`qOL4TEj(Q+k}FWz-bgK97Mm?69w0(PKiwT0}?~*ZdBBtganv2 zn`w%rtQ?h?=uIo@soBZyG@yrKBe$%~C?FwExrCD|*z-q=wLNO>3V!FM zZ#TE4qLjE2uJmhn*IQd#0jL(s_7*+>=7HV^7MGej@pPp(60ly8z_+5m2WQ1nQd3iJ z!oYNmn%#!GdFh4LSVLfK{2&k}g60QIDk8aF^VyY^ox3}p$Zoxgj`Fc$U3(zVg8W0PT)K2ZsRXk~)WQod zrOBuzZGDr5knH1#W$n51X2&qDuX)Yh&3R;d`^)FgGn$#LN~M(gm%@1j1qFF|2m4;I zO0>g+Ef%c{!pxe=%Lj)!See!bbtQ!bNOO}*)O!?djM+8zDS z@bJ3iS7jKbS>WAy6zy%T3>@s)KymrYLMDJ^WwhYw?rvjmpAbVTLqIs8=C1Uw?DZV# z?&hYYRo&DaZn)>!dD?e!-9-~JKFM!3O1%j*Hjn~{dktM`NjVtIjl{pwIw39SSxxEe zJnqxDGJGvW*k5^k9WyNLd*jg*6kP;li+IXoFL$hjc=hIh>zxLB;H9(3MgRKBBjDCH zHl{6UscByPoSc&ryeBg+^8%Nw>CTVUt$1cZ?*&VFT~IU%8=Ih^VRey0+x}j_-d+HB z9?ip*43NfUCq$v{c)YhK3 zxS+eapo{qYnzywg6>U+uxOjKdUks8YP}}I~kkj(N&5s+H6%j)A^<$2Vv_V5Lb$5&B z_an;X1ujR+G9Yfx z%%g!}s6-l&ITMrFG(TTP7>#Ih^@AW;yw*qw?85tAhugo+m zcAAZzBnrK*oZ=z-GBnf@ad^1a|8;6gVkOMpUK%H|;b7aSJ0yG#)&+a1dwROl7}~ANJ#b6^Kf1S`mMbWwy+@0 z<5E^)d3kpLAPJYcRo`GG8@hr_NPlmGt2+!gdC?5@2A27o)y5^ygsz0!{t=>lb^Q>}fB3BGHni+ITpMm(#)1 zds9UppNlm{LS#>*ckk8noa`y~_6kRbYKbsYaS%Y<26cw1Lk^&|AFwPu|TtaRPn1< zr;Cec-@bKrc1EpRRVkOG4W=!@gUYWWBGi##N6)TFIeTVid_YD{2`X}|tkrcf zIFNie6a#luAdCPaMHaES@w(WupE(~HmQ&|Wsl;UxJISTBv7W;tI*26owb7Z6o_=#{ zOa;hAAk)qhCe+l{uBoj>MSTDC$?5*PC~}JTL939zzzI-QPDu+xWq9($oqyTZE0=uF z|2t;VcJLv@&DB+>M2nPIFX^Lbz>If507=BM4$cyC3Xqp~JVXStO112mUu4Mp8&QH} z;a$FyUDWQQV@_^dJ~npi_wV0PA#Z{oUu$U{170m4@CVEU=+JQBOEBOtB3dZqFVP1oK11=zN+u{`(E?Vy@lG`6uW z&i4hex{5)F~(+p(B)jY|F3^DSa2&hCteVj$upD{Fo&<#y_sE zD6ttp$@SnMDndsE$UF-R1W~z2ky@;&rY&CH^THyVBMQ%O)bpV?PESRnn$XPiOUIaj zqP9=Pzw??kXon0dy^7c-ls7OT6)vq{OK=tS4;Z?`sCMGOEvGC2HAWAVKAK2UT zhd>6_2g1Un3Hklsn~Tkp4**h8^BRb+77AAQ7!QGJ(e@TuPcKe-*u&Hva+Sex5|+#K8*>t7l`Ixs%Y z+FCm8&4Ug-ezqz?<#9Uoh{Z1|+zTWUph&Q>CB)_P33^jgWId5u%n_aR(PRmDj3~1B zPab}-bQrJ49jtlZxncji3vWQ&KU-A979GKp;V`jYdgh-Tl0zpCyhoj~m7q+)Q#if;%+uTkFy@6AUtle&?#pq)Ft!!vG_kVn-(<;Zo zZ2yLz;(yU37W@YtcJ%izvZnqys79hAJiKrc2het8?A(8~oG5Xi?__5AyRP=&DT8#b zw-?+Gb0pz&3h&}(Cs3Mo$Sv5>L%u75gVOklTr3*e3xVjKBm@rbF>6nS{ilSXL4VNb z7FrW>iOC3cm4UOSa&cDO+?WVFW5Q<0$&q1f3x0ft-=@bpDUx$ATZcM<9}$m39$`kD z+Q0~^6xX2Q1R_x+!w1DRpN3jcKTYcWf?JZ2@#-dZ-n`~ZK@DNT$=BIdQ2ALne~G!i zJ+b`i6_$^hMw?$FK6#v%Rd{LeG$Zu*rvG%vD$am{B-fEh8I%wM?q9neC(|IbN<%-Y zdO07yFUXaoInT<+el*e8HZgg??EYF)Gplxu$L}3px@ykw*{T%hfhtlgT&{r50I~6=WXy1!I7+ zUQx&V>H3C*6rP8pT9Z=N2@nj(<46#+6cn%eR^_zNP=7}KqQy{dty?<{Cx}|;XF1TL z%#oYI1PwA}yZ61HTFC$d@8aH@oA%*1NveY_rjvM>WxzJzx^C^ zU8__YdazJVO_}{#U!Q@}QU(g@=1U!qv9$mF=HnH=_X34P>D?U>IMMzg&BW!I54E*7H5vb|4H#OZng-3u}pe~CwHGP{FH+H_U zP|%Br&|J2!u3`y_SU(1NQ)`6KDjFM$9*6RVo&2I(0(Bx_oa#d%pI@7$1p&8J#Eqt- zj$$ieVV10^Z{tv}sxAZ1${u%EO)F58RVpr?W96>?n@f1Ol}d?Q=XWyXPQcR&&+6$? z{`@Hi>IypIuP3!4X7_v5PqDEByib7ZO#qn~8qGr%140DjzlMqVIaGXPGoIP3m)+m+ z1^`nIsC`oh|I>QC*YX0O{#&5!$&Jl@7a$ZDSdI}EiNL{8r$wJzlC-w42(XjW8h=J4 zXT{UY-)6@r105d9?&_+Yamdxhl9gS%<4bw>PVZRAN_`}-yKv^}=yJ!CH@dLCpntfB z1^5jj-|4L%Oj6Yvy`-UG`l^Q=xsxZO_UqTAqi99=!QyUa)}<5{gnepfzOk~}RB(4U zOOV6kh7XZHn#+$zlA;Mspuyd6n@&|ePcHQYL9aN?#`+Hm1kS0)#7vy^{uM#BPeuOF zok3n;9ejNI6>}k@>}qs0>+$oPv$J`58;^Jz+>w!Hjo2#?l~a}DbSnTIq^%5pDd_D5 zgei(FaFf~xfda`u2ciMMvq7b2Y&-w>SRY5>Xo6Q{e?Jr*5gW_h+V(1rgOVjtc^xyH zRq~PUSXWibcSrkbYb#bAEj3LSpZOhK%GE$rI#<@gQn356IrgyvK?TR_+Ha6Dlf3_d2Z4o>752^nG^M*Q+^AVnG$ceo3N{L4mWkhve)$4w0`8O+k&c zBp(R`TZPyCMz}Bi`^4TFe7|GVYnB4{K($x4YlTK}{^Z8<)LT?#K`Y2~9&ngSlD}>!Abfr`K;0TE@T6CjBKiXz2OR}q6sUmy~?2pT~t7CazD7J_UD z0!j%;bft=sML~fehzdb5hF+v8BrI#egtC90_Uywx-FxmmbI;s4GjnFX?>C>N+(*HH zi)O)|d+OT4q086AzRbF_ac|42t5J!x!a|+5tK*rYr6|weV6Sgt6192#D8`!hS`LC@p0GTRW$2V-o;UZ?4J_*w|g3XF`MB zCj~upM>>m)@%U`8;2wW`&&4wv8m@6hG3CY0cWiupIsJ?C3oR;P-6}O(T0$&|HWRnP zT2s+!Sd^Cjtmbmf%!~@iIPEWWO}P7s*5d#)pim#c6dcWEX=zRb9=e%m+sl^*fU(Lo zFU=kBk!a!I=ejydf>lY6B-Gxi49s-l5E}rzPZf7tj#krvREzx{G!{{|BT+t)RxTKk zK^GmtG%~|Q{2H2sgbT>lhF%WlQ3fxmWo@mk;!zG`csPVct2=m*1s>ft4h5@k2He{g z)i3zoOxVTq`_@4fruKUPx7f#*#(2e@CbOzx%bxAxaN&Yu_?%I|z48Az<%#Of7 z8-QzhE=h*s6U~DhzbJ3hbdiRV}iLv>@*WbQN9-vWT$pG z797eLv4z5FM|f0I|8atjLD9DZoH(5`1H?%nWmJoAm)`3|;QDxYG`4Q>GQYV|4viq7 z#2PCV+|BBKjoonh+aFi8dGouS$e7X|NiQ!d7|{wN6bGH9a+qR2&F1%h_y8LoyBkY~ z-<*@Ol=?h+FJKcopKLrPa&lmeY-U#18$yG^$}{-QIr&>wh0MA-Ewd$hg>W3;o6h{y z12G2kGj(?Bu3N;2e-TB0o5@bsUP8a);eYCt)0)Z8Z^U7=#l`2>JZbdnZ#LAM= zNVC~>?~+q>eZq?|+Tg)_$CW}!y+ `|T1!Asa?oQsQe<Tg%Tl3-pRhBu#pL7S;_DRBoMbxeA9~gM;U&FGDMJuqJ zv}Nl-$!*_Z)+3CUN3K973`x9p?OG|xtCwo`IYe%vxj&#k_sQ_g69@#5t^$!NDMgZ3 z3)t-Jmhs`?VUftxC`m|=undokq!ayOV)kEqj#!3ovt+%U2K8*esj1zjS%KhJH#e?f zwtf3=f?dBmjJLHVjijn#Fd260=3I%T?;ajN*2|{JHob!| zXNoF%_6*Sx97>VE=e)Xu(*OjPSm{G1H%(QfWDcmu#l=C0Pa|eQEKGM(Ll7($n-QO# zHKVDds)|Y`Hmc5xg-4a!aI!K9Oo@A=^Z7g;yRx#NCz#z5uq5mhhneO( z?v%q}ZWI<4-oCBcJdD!l^M))RkO4$uv8}DG8P%%g`QD@8J@vl+`jEk$kEdS?!>N`8~Q_WVCX98jw2=!(tZ#`ISm8=C*SN@ zEZp7i0aC-VODKa|q5L<&$PeANf>b{F^VoQJ=_?3S(x6(qQvH0X6w^~@DR4muI08-| zw_6{-`#9d%bdQlK0k4O{t=dX6Kdq)W{afJl8NVR^i~nC>rRu>v6hQ2)9f{>uKJotm Dj8EZq diff --git a/docs/tutorial_01_first_tree.md b/docs/tutorial_01_first_tree.md deleted file mode 100644 index f1c60b60f..000000000 --- a/docs/tutorial_01_first_tree.md +++ /dev/null @@ -1,192 +0,0 @@ -# How to create a BehaviorTree - -Behavior Trees, similar to State Machines, are nothing more than a mechanism -to invoke __callbacks__ at the right time under the right conditions. - -Further, we will use the words __"callback"__ and __"tick"__ interchangeably. - -What happens inside these callbacks is up to you. - -In this tutorial series, most of the time Actions will just print some -information on console, -but keep in mind that real "production" code would probably do something -more complicated. - -Further, we will create this simple tree: - - -![Tutorial1](images/Tutorial1.svg) - -## How to create your own ActionNodes - -The default (and recommended) way to create a TreeNode is by inheritance. - -``` c++ -// Example of custom SyncActionNode (synchronous action) -// without ports. -class ApproachObject : public BT::SyncActionNode -{ - public: - ApproachObject(const std::string& name) : - BT::SyncActionNode(name, {}) - { - } - - // You must override the virtual function tick() - BT::NodeStatus tick() override - { - std::cout << "ApproachObject: " << this->name() << std::endl; - return BT::NodeStatus::SUCCESS; - } -}; -``` - -As you can see: - -- Any instance of a TreeNode has a `name`. This identifier is meant to be - human-readable and it __doesn't__ need to be unique. - -- The method __tick()__ is the place where the actual Action takes place. - It must always return a NodeStatus, i.e. RUNNING, SUCCESS or FAILURE. - -Alternatively, we can use __dependecy injection__ to create a TreeNode given -a function pointer (i.e. "functor"). - -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; - -// Simple function that return a NodeStatus -BT::NodeStatus CheckBattery() -{ - std::cout << "[ Battery: OK ]" << std::endl; - return BT::NodeStatus::SUCCESS; -} - -// We want to wrap into an ActionNode the methods open() and close() -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; // shared information -}; - -``` - -We can build a `SimpleActionNode` from any of these functors: - -- CheckBattery() -- GripperInterface::open() -- GripperInterface::close() - -## Create a tree dynamically with an XML - -Let's consider the following XML file named __my_tree.xml__: - - -``` XML - - - - - - - - - - -``` - -!!! Note - You can find more details about the XML schema [here](xml_format.md). - - -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" represents the name of the instance; it is optional. - - -``` c++ -#include "behaviortree_cpp_v3/bt_factory.h" - -// file that contains the custom nodes definitions -#include "dummy_nodes.h" - -int main() -{ - // We use the BehaviorTreeFactory to register our custom nodes - BehaviorTreeFactory factory; - - // Note: the name used to register should be the same used in the XML. - using namespace DummyNodes; - - // The recommended way to create a Node is through inheritance. - factory.registerNodeType("ApproachObject"); - - // Registering a SimpleActionNode using a function pointer. - // you may also use C++11 lambdas instead of std::bind - factory.registerSimpleCondition("CheckBattery", std::bind(CheckBattery)); - - //You can also create SimpleActionNodes using methods of a class - GripperInterface gripper; - factory.registerSimpleAction("OpenGripper", - std::bind(&GripperInterface::open, &gripper)); - factory.registerSimpleAction("CloseGripper", - std::bind(&GripperInterface::close, &gripper)); - - // Trees are created at deployment-time (i.e. at run-time, but only - // once at the beginning). - - // IMPORTANT: when the object "tree" goes out of scope, all the - // TreeNodes are destroyed - auto tree = factory.createTreeFromFile("./my_tree.xml"); - - // To "execute" a Tree you need to "tick" it. - // The tick is propagated to the children based on the logic of the tree. - // In this case, the entire sequence is executed, because all the children - // of the Sequence return SUCCESS. - tree.tickRoot(); - - return 0; -} - -/* Expected output: -* - [ Battery: OK ] - GripperInterface::open - ApproachObject: approach_object - GripperInterface::close -*/ - -``` - - - diff --git a/docs/tutorial_02_basic_ports.md b/docs/tutorial_02_basic_ports.md deleted file mode 100644 index e4491641d..000000000 --- a/docs/tutorial_02_basic_ports.md +++ /dev/null @@ -1,258 +0,0 @@ -# Input and Output Ports - -As we explained earlier, custom TreeNodes can be used to execute an arbitrarily -simple or complex piece of software. Their goal is to provide an interface -with a __higher level of abstraction__. - -For this reason, they are not conceptually different from __functions__. - -Similar to functions, we often want to: - - - pass arguments/parameters to a Node (__inputs__) - - get some kind of information out from a Node (__outputs__). - - The outputs of a node can be the inputs of another node. - -BehaviorTree.CPP provides a basic mechanism of __dataflow__ -through __ports__, that is simple to use but also flexible and type safe. - -In this tutorial we will create the following tree: - -![Tutorial2](images/Tutorial2.svg) - -You may notice already as the 2nd child of the Sequence will write on a row -of a Key/Value table (the __Blackboard__) and the 4th node read -from the same row. - -## Inputs ports - -A valid Input can be either: - -- a static string which can be parsed by the Node, or -- a "pointer" to an entry of the Blackboard, identified by a __key__. - -A "blackboard" is a simple __key/value storage__ shared by all the nodes -of the Tree. - -An "entry" of the Blackboard is a __key/value pair__. - -Input ports can read an entry in the Blackboard, whilst an Output port -can write into an entry. - -Let's suppose that we want to create an ActionNode called `SaySomething`, -that should print a given string on `std::cout`. - -Such a string will be passed using an input port called `message`. - -Consider these alternative XML syntaxes: - -```XML - - -``` - -The attribute `message` in the __first node__ means: - - "The static string 'hello world' is passed to the port 'message' of 'SaySomething'". - -The message is read from the XML file, therefore it can not change at run-time. - -The syntax of the __second node__ instead means: - - "Read the current value in the entry of the blackboard called 'greetings' ". - -The value of the entry can (and probably will) change at run-time. - -The ActionNode `SaySomething` can be implemented as follows: - -```C++ -// SyncActionNode (synchronous action) with an input port. -class SaySomething : public SyncActionNode -{ - public: - // If your Node has ports, you must use this constructor signature - SaySomething(const std::string& name, const NodeConfiguration& config) - : SyncActionNode(name, config) - { } - - // It is mandatory to define this static method. - static PortsList providedPorts() - { - // This action has a single input port called "message" - // Any port must have a name. The type is optional. - return { InputPort("message") }; - } - - // As usual, you must override the virtual function tick() - NodeStatus tick() override - { - Optional msg = getInput("message"); - // Check if optional is valid. If not, throw its error - if (!msg) - { - throw BT::RuntimeError("missing required input [message]: ", - msg.error() ); - } - - // use the method value() to extract the valid message. - std::cout << "Robot says: " << msg.value() << std::endl; - return NodeStatus::SUCCESS; - } -}; - -``` - -Alternatively the same functionality can be implemented in a simple function. This function takes an instance of `BT:TreeNode` as input in order to access the "message" Input Port: - -```c++ -// Simple function that return a NodeStatus -BT::NodeStatus SaySomethingSimple(BT::TreeNode& self) -{ - Optional msg = self.getInput("message"); - // Check if optional is valid. If not, throw its error - if (!msg) - { - throw BT::RuntimeError("missing required input [message]: ", msg.error()); - } - - // use the method value() to extract the valid message. - std::cout << "Robot says: " << msg.value() << std::endl; - return NodeStatus::SUCCESS; -} -``` - - - -When a custom TreeNode has input and/or output ports, these ports must be -declared in the __static__ method: - -```C++ - static MyCustomNode::PortsList providedPorts(); -``` - -The input from the port `message` can be read using the template method -`TreeNode::getInput(key)`. - -This method may fail for multiple reasons. It is up to the user to -check the validity of the returned value and to decide what to do: - -- Return `NodeStatus::FAILURE`? -- Throw an exception? -- Use a different default value? - -!!! Warning "Important" - It is __always__ recommended to call the method `getInput()` inside the - `tick()`, and __not__ in the constructor of the class. - - The C++ code __must not make any assumption__ about - the nature of the input, which could be either static or dynamic. - A dynamic input can change at run-time, for this reason it should be read - periodically. - -## Output ports - -An input port pointing to the entry of the blackboard will be valid only -if another node have already written "something" inside that same entry. - -`ThinkWhatToSay` is an example of Node that uses an __output port__ to write a -string into an entry. - -```C++ -class ThinkWhatToSay : public SyncActionNode -{ - public: - ThinkWhatToSay(const std::string& name, const NodeConfiguration& config) - : SyncActionNode(name, config) - { - } - - static PortsList providedPorts() - { - return { OutputPort("text") }; - } - - // This Action writes a value into the port "text" - NodeStatus tick() override - { - // the output may change at each tick(). Here we keep it simple. - setOutput("text", "The answer is 42" ); - return NodeStatus::SUCCESS; - } -}; -``` - -Alternatively, most of the time for debugging purposes, it is possible to write a -static value into an entry using the built-in Actions called `SetBlackboard`. - -```XML - -``` - -## A complete example - -In this example, a Sequence of 4 Actions is executed: - -- Actions 1 and 2 read the input `message` from a static string (`SaySomething2` is a SimpleActionNode). - -- Action 3 writes something into the entry of the blackboard called `the_answer`. - -- Action 4 read the input `message` from an entry in the blackboard called `the_answer`. - -```XML - - - - - - - - - - -``` - -The C++ code: - -```C++ -#include "behaviortree_cpp_v3/bt_factory.h" - -// file that contains the custom nodes definitions -#include "dummy_nodes.h" - -int main() -{ - using namespace DummyNodes; - - BehaviorTreeFactory factory; - - factory.registerNodeType("SaySomething"); - factory.registerNodeType("ThinkWhatToSay"); - - // SimpleActionNodes can not define their own method providedPorts(). - // We should pass a PortsList explicitly if we want the Action to - // be able to use getInput() or setOutput(); - PortsList say_something_ports = { InputPort("message") }; - factory.registerSimpleAction("SaySomething2", SaySomethingSimple, - say_something_ports ); - - auto tree = factory.createTreeFromFile("./my_tree.xml"); - - tree.tickRoot(); - - /* Expected output: - - Robot says: hello - Robot says: this works too - Robot says: The answer is 42 - */ - return 0; -} -``` - -We "connect" output ports to input ports using the same key (`the_answer`); -this means that they "point" to the same entry of the blackboard. - -These ports can be connected to each other because their type is the same, -i.e. `std::string`. - - - diff --git a/docs/tutorial_03_generic_ports.md b/docs/tutorial_03_generic_ports.md deleted file mode 100644 index d5d20df08..000000000 --- a/docs/tutorial_03_generic_ports.md +++ /dev/null @@ -1,185 +0,0 @@ -# Ports with generic types - -In the previous tutorials we introduced input and output ports, where the -type of the port itself was a `std::string`. - -This is the easiest port type to deal with, because any parameter passed -from the XML definition will be (obviously) a string. - -Next, we will describe how to use any generic C++ type in your code. - -## Parsing a string - -__BehaviorTree.CPP__ supports automatic conversion of strings into common -types, such as `int`, `long`, `double`, `bool`, `NodeStatus`, etc. - -But user defined types can be supported easily as well. For instance: - -```C++ -// We want to be able to use this custom type -struct Position2D -{ - double x; - double y; -}; -``` - -To parse a string into a `Position2D` we should link to a template -specialization of `BT::convertFromString(StringView)`. - -We can use any syntax we want; in this case, we simply separate two numbers -with a _semicolon_. - - -```C++ -// Template specialization to converts a string to Position2D. -namespace BT -{ - template <> inline Position2D convertFromString(StringView str) - { - // The next line should be removed... - printf("Converting string: \"%s\"\n", str.data() ); - - // We expect real numbers separated by semicolons - auto parts = splitString(str, ';'); - if (parts.size() != 2) - { - throw RuntimeError("invalid input)"); - } - else{ - Position2D output; - output.x = convertFromString(parts[0]); - output.y = convertFromString(parts[1]); - return output; - } - } -} // end namespace BT -``` - -About the previous code: - -- `StringView` is just a C++11 version of [std::string_view](https://en.cppreference.com/w/cpp/header/string_view). - You can pass either a `std::string` or a `const char*`. -- In production code, you would (obviously) remove the `printf` statement. -- The library provides a simple `splitString` function. Feel free to use another - one, like [boost::algorithm::split](onvertFromString). -- Once we split the input into single numbers, we can reuse the specialization - `convertFromString()`. - -## Example - -Similarly to the previous tutorial, we can create two custom Actions, -one will write into a port and the other will read from a port. - - -```C++ - -class CalculateGoal: public SyncActionNode -{ -public: - CalculateGoal(const std::string& name, const NodeConfiguration& config): - SyncActionNode(name,config) - {} - - static PortsList providedPorts() - { - return { OutputPort("goal") }; - } - - NodeStatus tick() override - { - Position2D mygoal = {1.1, 2.3}; - setOutput("goal", mygoal); - return NodeStatus::SUCCESS; - } -}; - - -class PrintTarget: public SyncActionNode -{ -public: - PrintTarget(const std::string& name, const NodeConfiguration& config): - SyncActionNode(name,config) - {} - - static PortsList providedPorts() - { - // Optionally, a port can have a human readable description - const char* description = "Simply print the goal on console..."; - return { InputPort("target", description) }; - } - - NodeStatus tick() override - { - auto res = getInput("target"); - if( !res ) - { - throw RuntimeError("error reading port [target]:", res.error()); - } - Position2D target = res.value(); - printf("Target positions: [ %.1f, %.1f ]\n", target.x, target.y ); - return NodeStatus::SUCCESS; - } -}; -``` - -We can now connect input/output ports as usual, pointing to the same -entry of the Blackboard. - -The tree in the next example is a Sequence of 4 actions - -- Store a value of `Position2D` in the entry "GoalPosition", - using the action `CalculateGoal`. - -- Call `PrintTarget`. The input "target" will be read from the Blackboard - entry "GoalPosition". - -- Use the built-in action `SetBlackboard` to write the key "OtherGoal". - A conversion from string to `Position2D` will be done under the hood. - -- Call `PrintTarget` again. The input "target" will be read from the Blackboard - entry "OtherGoal". - - -```C++ -static const char* xml_text = R"( - - - - - - - - - - - - )"; - -int main() -{ - using namespace BT; - - BehaviorTreeFactory factory; - factory.registerNodeType("CalculateGoal"); - factory.registerNodeType("PrintTarget"); - - auto tree = factory.createTreeFromText(xml_text); - tree.tickRoot(); - -/* Expected output: - - Target positions: [ 1.1, 2.3 ] - Converting string: "-1;3" - Target positions: [ -1.0, 3.0 ] -*/ - return 0; -} -``` - - - - - - - diff --git a/docs/tutorial_04_sequence.md b/docs/tutorial_04_sequence.md deleted file mode 100644 index ce711998b..000000000 --- a/docs/tutorial_04_sequence.md +++ /dev/null @@ -1,206 +0,0 @@ -# Reactive Sequences and Asynchronous Nodes - -The next example shows the difference between a `SequenceNode` and a -`ReactiveSequence`. - -An Asynchronous Action has it's own thread. This allows the user to -use blocking functions but to return the flow of execution -to the tree. - -!!! warning "Learn more about Asynchronous Actions" - - Users should fully understand how Concurrency is achieved in BT.CPP - and learn best practices about how to develop their own Asynchronous - Actions. You will find an extensive article - [here](asynchronous_nodes.md). - -```C++ - -// Custom type -struct Pose2D -{ - double x, y, theta; -}; - -class MoveBaseAction : public AsyncActionNode -{ - public: - MoveBaseAction(const std::string& name, const NodeConfiguration& config) - : AsyncActionNode(name, config) - { } - - static PortsList providedPorts() - { - return{ InputPort("goal") }; - } - - NodeStatus tick() override; - - // This overloaded method is used to stop the execution of this node. - void halt() override - { - _halt_requested.store(true); - } - - private: - std::atomic_bool _halt_requested; -}; - -//------------------------- - -NodeStatus MoveBaseAction::tick() -{ - Pose2D goal; - if ( !getInput("goal", goal)) - { - throw RuntimeError("missing required input [goal]"); - } - - printf("[ MoveBase: STARTED ]. goal: x=%.f y=%.1f theta=%.2f\n", - goal.x, goal.y, goal.theta); - - _halt_requested.store(false); - int count = 0; - - // Pretend that "computing" takes 250 milliseconds. - // It is up to you to check periodically _halt_requested and interrupt - // this tick() if it is true. - while (!_halt_requested && count++ < 25) - { - std::this_thread::sleep_for( std::chrono::milliseconds(10) ); - } - - std::cout << "[ MoveBase: FINISHED ]" << std::endl; - return _halt_requested ? NodeStatus::FAILURE : NodeStatus::SUCCESS; -} -``` - -The method `MoveBaseAction::tick()` is executed in a thread different from the -main thread that invoked `MoveBaseAction::executeTick()`. - -__You are responsible__ for the implementation of a valid __halt()__ functionality. - -The user must also implement `convertFromString(StringView)`, -as shown in the previous tutorial. - - -## Sequence VS ReactiveSequence - -The following example should use a simple `SequenceNode`. - -```XML hl_lines="3" - - - - - - - - - - -``` - -```C++ -int main() -{ - using namespace DummyNodes; - using std::chrono::milliseconds; - - BehaviorTreeFactory factory; - factory.registerSimpleCondition("BatteryOK", std::bind(CheckBattery)); - factory.registerNodeType("MoveBase"); - factory.registerNodeType("SaySomething"); - - auto tree = factory.createTreeFromText(xml_text); - - NodeStatus status; - - std::cout << "\n--- 1st executeTick() ---" << std::endl; - status = tree.tickRoot(); - - tree.sleep( milliseconds(150) ); - std::cout << "\n--- 2nd executeTick() ---" << std::endl; - status = tree.tickRoot(); - - tree.sleep( milliseconds(150) ); - std::cout << "\n--- 3rd executeTick() ---" << std::endl; - status = tree.tickRoot(); - - std::cout << std::endl; - - return 0; -} -``` - -Expected output: - -``` - --- 1st executeTick() --- - [ Battery: OK ] - Robot says: "mission started..." - [ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.00 - - --- 2nd executeTick() --- - [ MoveBase: FINISHED ] - - --- 3rd executeTick() --- - Robot says: "mission completed!" -``` - -You may have noticed that when `executeTick()` was called, `MoveBase` returned -__RUNNING__ the 1st and 2nd time, and eventually __SUCCESS__ the 3rd time. - -`BatteryOK` is executed only once. - -If we use a `ReactiveSequence` instead, when the child `MoveBase` returns RUNNING, -the sequence is restarted and the condition `BatteryOK` is executed __again__. - -If, at any point, `BatteryOK` returned __FAILURE__, the `MoveBase` action -would be _interrupted_ (_halted_, to be specific). - -```XML hl_lines="3" - - - - - - - - - - - - -``` - - -Expected output: - -``` - --- 1st executeTick() --- - [ Battery: OK ] - Robot says: "mission started..." - [ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.00 - - --- 2nd executeTick() --- - [ Battery: OK ] - [ MoveBase: FINISHED ] - - --- 3rd executeTick() --- - [ Battery: OK ] - Robot says: "mission completed!" -``` - -## Event Driven trees? - -!!! important - We used the command `tree.sleep()` instead of `std::this_thread::sleep_for()` for a reason. - -The method `Tree::sleep()` should be preferred, because it can be interrupted by a Node in the tree when -"something changed". -Tree::sleep() will be interrupted when an `AsyncActionNode::tick()` is completed or, more generally, -when the method `TreeNode::emitStateChanged()` is invoked. - - - diff --git a/docs/tutorial_05_subtrees.md b/docs/tutorial_05_subtrees.md deleted file mode 100644 index 32c849dd7..000000000 --- a/docs/tutorial_05_subtrees.md +++ /dev/null @@ -1,138 +0,0 @@ -# Composition of Behaviors with Subtree - -We can build large scale behavior composing together smaller and reusable -behaviors into larger ones. - -In other words, we want to create __hierarchical__ behavior trees. - -This can be achieved easily defining multiple trees in the XML including one -into the other. - -# CrossDoor behavior - -This example is inspired by a popular -[article about behavior trees](http://www.gamasutra.com/blogs/ChrisSimpson/20140717/221339/Behavior_trees_for_AI_How_they_work.php). - -It is also the first practical example that uses `Decorators` and `Fallback`. - -```XML hl_lines="1 3 15" - - - - - - - - - - - - - - - - - - - - - - - - - - -``` - -For readability, our custom nodes are registered with the one-liner: - -`CrossDoor::RegisterNodes(factory);` - -Default nodes provided by the BT library such as `Fallback` are already registered by -the BehaviorTreeFactory. - -It may be noticed that we encapsulated a quite complex branch of the tree, -the one to execute when the door is closed, into a separate tree called -`DoorClosed`. - -The desired behavior is: - -- If the door is open, `PassThroughDoor`. -- If the door is closed, try up to 4 times to `OpenDoor` and, then, `PassThroughDoor`. -- If it was not possible to open the closed door, `PassThroughWindow`. - - -## Loggers - -On the C++ side we don't need to do anything to build reusable subtrees. - -Therefore we take this opportunity to introduce another neat feature of -_BehaviorTree.CPP_ : __Loggers__. - -A Logger is a mechanism to display, record and/or publish any state change in the tree. - - -```C++ - -int main() -{ - using namespace BT; - BehaviorTreeFactory factory; - - // register all the actions into the factory - // We don't show how these actions are implemented, since most of the - // times they just print a message on screen and return SUCCESS. - // See the code on Github for more details. - factory.registerSimpleCondition("IsDoorOpen", std::bind(IsDoorOpen)); - factory.registerSimpleAction("PassThroughDoor", std::bind(PassThroughDoor)); - factory.registerSimpleAction("PassThroughWindow", std::bind(PassThroughWindow)); - factory.registerSimpleAction("OpenDoor", std::bind(OpenDoor)); - factory.registerSimpleAction("CloseDoor", std::bind(CloseDoor)); - factory.registerSimpleCondition("IsDoorLocked", std::bind(IsDoorLocked)); - factory.registerSimpleAction("UnlockDoor", std::bind(UnlockDoor)); - - // Load from text or file... - auto tree = factory.createTreeFromText(xml_text); - - // This logger prints state changes on console - StdCoutLogger logger_cout(tree); - - // This logger saves state changes on file - FileLogger logger_file(tree, "bt_trace.fbl"); - - // This logger stores the execution time of each node - MinitraceLogger logger_minitrace(tree, "bt_trace.json"); - -#ifdef ZMQ_FOUND - // This logger publish status changes using ZeroMQ. Used by Groot - PublisherZMQ publisher_zmq(tree); -#endif - - printTreeRecursively(tree.rootNode()); - - //while (1) - { - NodeStatus status = NodeStatus::RUNNING; - // Keep on ticking until you get either a SUCCESS or FAILURE state - while( status == NodeStatus::RUNNING) - { - status = tree.tickRoot(); - // IMPORTANT: you must always add some sleep if you call tickRoot() - // in a loop, to avoid using 100% of your CPU (busy loop). - // The method Tree::sleep() is recommended, because it can be - // interrupted by an internal event inside the tree. - tree.sleep( milliseconds(10) ); - } - if( LOOP ) - { - std::this_thread::sleep_for( milliseconds(1000) ); - } - } - return 0; -} - -``` - - - - diff --git a/docs/tutorial_06_subtree_ports.md b/docs/tutorial_06_subtree_ports.md deleted file mode 100644 index 9db8cdd31..000000000 --- a/docs/tutorial_06_subtree_ports.md +++ /dev/null @@ -1,113 +0,0 @@ -# Remapping ports between Trees and SubTrees - -In the CrossDoor example we saw that a `SubTree` looks like a single -leaf Node from the point of view of its parent (`MainTree` in the example). - -Furthermore, to avoid name clashing in very large trees, any tree and subtree -use a different instance of the Blackboard. - -For this reason, we need to explicitly connect the ports of a tree to those -of its subtrees. - -Once again, you __won't__ need to modify your C++ implementation since this -remapping is done entirely in the XML definition. - -## Example - -Let's consider this Beahavior Tree. - -```XML hl_lines="7" - - - - - - - - - - - - - - - - - - - - - - - - - -``` - -You may notice that: - -- We have a `MainTree` that includes a subtree called `MoveRobot`. -- We want to "connect" (i.e. "remap") ports inside the `MoveRobot` subtree -with other ports in the `MainTree`. -- This is done using the XMl tag ____, where the words __internal/external__ - refer respectively to a subtree and its parent. - - -The following image shows remapping between these two different trees. - -Note that this diagram represents the __dataflow__ and the entries in the -respective blackboard, not the relationship in terms of Behavior Trees. - -![ports remapping](images/t06_remapping.png) - -In terms of C++, we don't need to do much. For debugging purpose, we may show some -information about the current state of a blackboard with the method `debugMessage()`. - -```C++ -int main() -{ - BT::BehaviorTreeFactory factory; - - factory.registerNodeType("SaySomething"); - factory.registerNodeType("MoveBase"); - - auto tree = factory.createTreeFromText(xml_text); - - NodeStatus status = NodeStatus::RUNNING; - // Keep on ticking until you get either a SUCCESS or FAILURE state - while( status == NodeStatus::RUNNING) - { - status = tree.tickRoot(); - // IMPORTANT: add sleep to avoid busy loops. - // You should use Tree::sleep(). Don't be afraid to run this at 1 KHz. - tree.sleep( std::chrono::milliseconds(1) ); - } - - // let's visualize some information about the current state of the blackboards. - std::cout << "--------------" << std::endl; - tree.blackboard_stack[0]->debugMessage(); - std::cout << "--------------" << std::endl; - tree.blackboard_stack[1]->debugMessage(); - std::cout << "--------------" << std::endl; - - return 0; -} - -/* Expected output: - - [ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.00 - [ MoveBase: FINISHED ] - Robot says: mission accomplished - -------------- - move_result (std::string) -> full - move_goal (Pose2D) -> full - -------------- - output (std::string) -> remapped to parent [move_result] - target (Pose2D) -> remapped to parent [move_goal] - -------------- -*/ -``` - - - - diff --git a/docs/tutorial_07_multiple_xml.md b/docs/tutorial_07_multiple_xml.md deleted file mode 100644 index 628919531..000000000 --- a/docs/tutorial_07_multiple_xml.md +++ /dev/null @@ -1,128 +0,0 @@ -# How to use multiple XML files to store your subtrees - -In the examples which we presented so far, we always create an entire Tree -from a single XML file. - -If multiple Subtrees were used, they were all included into the same XML. - -In recent version of BT.CPP (3.7+), the user can more easily -load trees from multiple files, if needed. - -## Load multiple files with "include" - -We will consider a main tree that invoke 2 different subtrees. - -File **main_tree.xml**: - -```XML hl_lines="2 3" - - - - - - - - - - - -``` -File **subtree_A.xml**: - -```XML - - - - - -``` - -File **subtree_B.xml**: - -```XML - - - - - -``` - -As you may notice, we included two relative paths in **main_tree.xml** -that tells to `BehaviorTreeFactory` where to find the required dependencies. - -We need to create the tree as usual: - -```c++ -factory.createTreeFromFile("main_tree.xml") -``` - -## Load multiple files manually - -If we don't want to add relative and hard-coded paths into our XML, -or if we want to instantiate a subtree instead of the main tree, there is a -new approach, since BT.CPP 3.7+. - -The simplified version of **main_tree.xml** will be: - -```XML - - - - - - - - - -``` - -To load manually the multiple files: - -```c++ -int main() -{ - BT::BehaviorTreeFactory factory; - factory.registerNodeType("SaySomething"); - - // Register the behavior tree definitions, but don't instantiate them, yet. - // Order is not important. - factory.registerBehaviorTreeFromFile("main_tree.xml"); - factory.registerBehaviorTreeFromFile("subtree_A.xml"); - factory.registerBehaviorTreeFromFile("subtree_B.xml"); - - //Check that the BTs have been registered correctly - std::cout << "Registered BehaviorTrees:" << std::endl; - for(const std::string& bt_name: factory.registeredBehaviorTrees()) - { - std::cout << " - " << bt_name << std::endl; - } - - // You can create the MainTree and the subtrees will be added automatically. - std::cout << "----- MainTree tick ----" << std::endl; - auto main_tree = factory.createTree("MainTree"); - main_tree.tickRoot(); - - // ... or you can create only one of the subtree - std::cout << "----- SubA tick ----" << std::endl; - auto subA_tree = factory.createTree("SubTreeA"); - subA_tree.tickRoot(); - - return 0; -} -/* Expected output: - -Registered BehaviorTrees: - - MainTree - - SubTreeA - - SubTreeB ------ MainTree tick ---- -Robot says: starting MainTree -Robot says: Executing Sub_A -Robot says: Executing Sub_B ------ SubA tick ---- -Robot says: Executing Sub_A -``` - - - - diff --git a/docs/tutorial_08_additional_args.md b/docs/tutorial_08_additional_args.md deleted file mode 100644 index ce2aef333..000000000 --- a/docs/tutorial_08_additional_args.md +++ /dev/null @@ -1,153 +0,0 @@ -# Pass additional arguments during initialization and/or construction - -In every single example we explored so far we were "forced" to provide a -constructor with the following signature - -```C++ - MyCustomNode(const std::string& name, const NodeConfiguration& config); - -``` - -In same cases, it is desirable to pass to the constructor of our class -additional arguments, parameters, pointers, references, etc. - -**Many people use blackboards to do that: this is not recomendable.** - -We will just use the word _"arguments"_ for the rest of the tutorial. - -Even if, theoretically, these arguments **could** be passed using Input Ports, -that would be the wrong way to do it if: - -- The arguments are known at _deployment-time_. -- The arguments don't change at _run-time_. -- The arguments don't need to be set from the _XML_. - -If all these conditions are met, using ports or the blackboard is cumbersome and highly discouraged. - -## Method 1: register a custom builder - -Consider the following custom node called **Action_A**. - -We want to pass three additional arguments; they can be arbitrarily complex objects, -you are not limited to built-in types. - -```C++ -// Action_A has a different constructor than the default one. -class Action_A: public SyncActionNode -{ - -public: - // additional arguments passed to the constructor - Action_A(const std::string& name, const NodeConfiguration& config, - int arg1, double arg2, std::string arg3 ): - SyncActionNode(name, config), - _arg1(arg1), - _arg2(arg2), - _arg3(arg3) {} - - // this example doesn't require any port - static PortsList providedPorts() { return {}; } - - // tick() can access the private members - NodeStatus tick() override; - -private: - int _arg1; - double _arg2; - std::string _arg3; -}; -``` - -This node should be registered as shown further: - -```C++ -BehaviorTreeFactory factory; - -// A node builder is a functor that creates a std::unique_ptr. -// Using lambdas or std::bind, we can easily "inject" additional arguments. -NodeBuilder builder_A = - [](const std::string& name, const NodeConfiguration& config) -{ - return std::make_unique( name, config, 42, 3.14, "hello world" ); -}; - -// BehaviorTreeFactory::registerBuilder is a more general way to -// register a custom node. -factory.registerBuilder( "Action_A", builder_A); - -// Register more custom nodes, if needed. -// .... - -// The rest of your code, where you create and tick the tree, goes here. -// .... -``` - -## Method 2: use an init method - -Alternatively, you may call an init method before ticking the tree. - -```C++ - -class Action_B: public SyncActionNode -{ - -public: - // The constructor looks as usual. - Action_B(const std::string& name, const NodeConfiguration& config): - SyncActionNode(name, config) {} - - // We want this method to be called ONCE and BEFORE the first tick() - void init( int arg1, double arg2, const std::string& arg3 ) - { - _arg1 = (arg1); - _arg2 = (arg2); - _arg3 = (arg3); - } - - // this example doesn't require any port - static PortsList providedPorts() { return {}; } - - // tick() can access the private members - NodeStatus tick() override; - -private: - int _arg1; - double _arg2; - std::string _arg3; -}; -``` - -The way we register and initialize Action_B is slightly different: - -```C++ - -BehaviorTreeFactory factory; - -// The regitration of Action_B is done as usual, but remember -// that we still need to call Action_B::init() -factory.registerNodeType( "Action_B" ); - -// Register more custom nodes, if needed. -// .... - -// Create the whole tree -auto tree = factory.createTreeFromText(xml_text); - -// Iterate through all the nodes and call init() if it is an Action_B -for( auto& node: tree.nodes ) -{ - // Not a typo: it is "=", not "==" - if( auto action_B = dynamic_cast( node.get() )) - { - action_B->init( 42, 3.14, "hello world"); - } -} - -// The rest of your code, where you tick the tree, goes here. -// .... -``` - - - - - diff --git a/docs/tutorial_09_coroutines.md b/docs/tutorial_09_coroutines.md deleted file mode 100644 index 5b214dde3..000000000 --- a/docs/tutorial_09_coroutines.md +++ /dev/null @@ -1,171 +0,0 @@ -# Async Actions using Coroutines - -BehaviorTree.CPP provides two easy-to-use abstractions to create an -asynchronous Action, i.e. those actions which: - -- Take a long time to be concluded. -- May return "RUNNING". -- Can be __halted__. - -The first class is a __AsyncActionNode__ that executes the tick() method in a -_separate thread_. - -In this tutorial, we introduce the __CoroActionNode__, a different action that uses -[coroutines](https://www.geeksforgeeks.org/coroutines-in-c-cpp/) -to achieve similar results. - -The main reason is that Coroutines do not spawn a new thread and are much more efficient. -Furthermore, you don't need to worry about thread-safety in your code... - -In Coroutines, the user should explicitly call a __yield__ method when -he/she wants the execution of the Action to be suspended. - -`CoroActionNode` wraps this `yield` function into a convenient method -`setStatusRunningAndYield()`. - -## The C++ source example - -The next example can be used as a "template" for your own implementation. - - -``` c++ - -typedef std::chrono::milliseconds Milliseconds; - -class MyAsyncAction: public CoroActionNode -{ - public: - MyAsyncAction(const std::string& name): - CoroActionNode(name, {}) - {} - - private: - // This is the ideal skeleton/template of an async action: - // - A request to a remote service provider. - // - A loop where we check if the reply has been received. - // - You may call setStatusRunningAndYield() to "pause". - // - Code to execute after the reply. - // - A simple way to handle halt(). - NodeStatus tick() override - { - std::cout << name() <<": Started. Send Request to server." << std::endl; - - TimePoint initial_time = Now(); - TimePoint time_before_reply = initial_time + Milliseconds(100); - - int count = 0; - bool reply_received = false; - - while( !reply_received ) - { - if( count++ == 0) - { - // call this only once - std::cout << name() <<": Waiting Reply..." << std::endl; - } - // pretend that we received a reply - if( Now() >= time_before_reply ) - { - reply_received = true; - } - - if( !reply_received ) - { - // set status to RUNNING and "pause/sleep" - // If halt() is called, we will NOT resume execution - setStatusRunningAndYield(); - } - } - - // This part of the code is never reached if halt() is invoked, - // only if reply_received == true; - std::cout << name() <<": Done. 'Waiting Reply' loop repeated " - << count << " times" << std::endl; - cleanup(false); - return NodeStatus::SUCCESS; - } - - // you might want to cleanup differently if it was halted or successful - void cleanup(bool halted) - { - if( halted ) - { - std::cout << name() <<": cleaning up after an halt()\n" << std::endl; - } - else{ - std::cout << name() <<": cleaning up after SUCCESS\n" << std::endl; - } - } - - void halt() override - { - std::cout << name() <<": Halted." << std::endl; - cleanup(true); - // Do not forget to call this at the end. - CoroActionNode::halt(); - } - - TimePoint Now() - { - return std::chrono::high_resolution_clock::now(); - }; -}; - -``` - -As you may have noticed, the action "pretends" to wait for a request message; -the latter will arrive after _100 milliseconds_. - -To spice things up, we create a Sequence with two actions, but the entire -sequence will be halted by a timeout after _150 millisecond_. - -```XML - - - - - - - - - - - -``` - -No surprises in the `main()`... - -``` c++ -int main() -{ - // Simple tree: a sequence of two asycnhronous actions, - // but the second will be halted because of the timeout. - - BehaviorTreeFactory factory; - factory.registerNodeType("MyAsyncAction"); - - auto tree = factory.createTreeFromText(xml_text); - - //--------------------------------------- - // keep executing tick until it returns either SUCCESS or FAILURE - while( tree.tickRoot() == NodeStatus::RUNNING) - { - tree.sleep( std::chrono::milliseconds(10) ); - } - return 0; -} - -/* Expected output: - -action_A: Started. Send Request to server. -action_A: Waiting Reply... -action_A: Done. 'Waiting Reply' loop repeated 11 times -action_A: cleaning up after SUCCESS - -action_B: Started. Send Request to server. -action_B: Waiting Reply... -action_B: Halted. -action_B: cleaning up after an halt() - -*/ -``` diff --git a/docs/tutorials_summary.md b/docs/tutorials_summary.md deleted file mode 100644 index aa4baded4..000000000 --- a/docs/tutorials_summary.md +++ /dev/null @@ -1,64 +0,0 @@ -# Summary of the tutorials - -### T.1: Create your first Behavior Tree - -This tutorial demonstrates how to create custom `ActionNodes` in __C++__ and -how to compose them into Trees using the __XML__ language. - -### T.2: Parametrize a Node with Ports - -TreeNodes can have both Inputs and Outputs Ports. -This tutorial demonstrates how to use ports to create parametrized Nodes. - - -### T.3: Generic and type-safe Ports - -This tutorial is an extension of the previous one. - -It shows how to create and use ports with generic and user-defined -types. - -### T.4: Difference between Sequence and ReactiveSequence - -Reactive ControlNodes can be a very powerful tool to create sophisticated -behaviors. - -This example shows the difference between a standard Sequence and a Reactive one. - -### T.5: How to reuse entire SubTrees - -Reusability and Composability can be done at the level of a single Node, -but also with entire Trees, which can become SubTrees of a "parent" Tree. - -In this tutorial we will also introduce the builtin Loggers. - -### T.6: Remapping of Ports between SubTrees and their parents - -Any Tree/SubTree in the system has its own isolated BlackBoard. - -In this tutorial we extend the concept or Ports to SubTrees, using -port remapping. - -### T.7: How to wrap legacy code in a non intrusive way - -This tutorial shows one of the many possible ways to wrap an existing code -into the `BehavioTree.CPP` infrastructure. - -### T.8: Passing arguments to Nodes without Ports - -If your custom Node has a lot of ports, it is probably a sign that you didn't -understand the problem that Ports are supposed to solve ;) - -In this tutorial, we show how to pass arguments to a custom Node class without -polluting your interfaces with pointless Input Ports. - -### T.9: Asynchronous actions with Coroutines - -Coroutines are a powerful tool to create asynchronous code. - -In this tutorial, we outline the typical design pattern to use when you -implement an asynchronous Action using `CoroActionNode`. - - - - diff --git a/docs/uml/AllFallbacks.uxf b/docs/uml/AllFallbacks.uxf deleted file mode 100644 index b3ee7bba2..000000000 --- a/docs/uml/AllFallbacks.uxf +++ /dev/null @@ -1,181 +0,0 @@ - - 10 - - UMLClass - - 260 - 120 - 100 - 30 - - Fallback -fg=blue - - - - UMLClass - - 200 - 200 - 100 - 30 - - OpenDoor - - - - Relation - - 250 - 140 - 80 - 80 - - lt=- - 10.0;60.0;60.0;10.0 - - - UMLClass - - 420 - 200 - 100 - 30 - - SmashDoor - - - - Relation - - 300 - 140 - 80 - 80 - - lt=- - 60.0;60.0;10.0;10.0 - - - Relation - - 300 - 140 - 200 - 80 - - lt=- - 180.0;60.0;10.0;10.0 - - - UMLClass - - 310 - 200 - 100 - 30 - - UnlockDoor - - - - UMLUseCase - - 70 - 200 - 120 - 40 - - isDoorOpen? - - - - Relation - - 120 - 140 - 210 - 80 - - lt=- - 10.0;60.0;190.0;10.0 - - - UMLClass - - 720 - 130 - 160 - 30 - - ReactiveFallback -fg=blue - - - - UMLUseCase - - 660 - 200 - 130 - 40 - - areYouRested? - - - - UMLClass - - 850 - 270 - 100 - 30 - - Sleep - - - - UMLClass - - 830 - 200 - 130 - 30 - - Timeout (8hrs) - - - - Relation - - 710 - 150 - 110 - 70 - - lt=- - 10.0;50.0;90.0;10.0 - - - Relation - - 790 - 150 - 120 - 70 - - lt=- - 100.0;50.0;10.0;10.0 - - - Relation - - 890 - 220 - 30 - 70 - - lt=- - 10.0;10.0;10.0;50.0 - - diff --git a/docs/uml/AllSequences.uxf b/docs/uml/AllSequences.uxf deleted file mode 100644 index 0dc50ed1d..000000000 --- a/docs/uml/AllSequences.uxf +++ /dev/null @@ -1,265 +0,0 @@ - - 10 - - UMLClass - - 480 - 150 - 90 - 30 - - Shoot - - - - UMLClass - - 350 - 70 - 100 - 30 - - Sequence -fg=blue - - - - Relation - - 390 - 90 - 150 - 80 - - lt=- - 130.0;60.0;10.0;10.0 - - - UMLUseCase - - 190 - 150 - 130 - 40 - - isEnemyVisible? - - - - UMLUseCase - - 330 - 150 - 130 - 40 - - isRifleLoaded? - - - - Relation - - 240 - 90 - 180 - 80 - - lt=- - 10.0;60.0;160.0;10.0 - - - Relation - - 390 - 90 - 30 - 80 - - lt=- - 10.0;60.0;10.0;10.0 - - - UMLClass - - 760 - 70 - 150 - 30 - - ReactiveSequence -fg=blue - - - - UMLUseCase - - 690 - 140 - 130 - 50 - - isEnemyVisible? - - - - Relation - - 750 - 90 - 100 - 70 - - lt=- - 10.0;50.0;80.0;10.0 - - - UMLClass - - 850 - 150 - 150 - 30 - - ApproachEnemy - - - - - Relation - - 820 - 90 - 120 - 80 - - lt=- - 100.0;60.0;10.0;10.0 - - - UMLClass - - 300 - 340 - 170 - 30 - - ReactiveSequence - - - - - UMLUseCase - - 250 - 400 - 120 - 40 - - isBatteryOK? - - - - Relation - - 300 - 360 - 100 - 60 - - lt=- - 10.0;40.0;80.0;10.0 - - - Relation - - 370 - 360 - 100 - 60 - - lt=- - 80.0;40.0;10.0;10.0 - - - UMLClass - - 410 - 400 - 140 - 30 - - SequenceStar -fg=blue - - - - - Relation - - 360 - 420 - 140 - 70 - - lt=- - 10.0;50.0;120.0;10.0 - - - Relation - - 470 - 420 - 30 - 70 - - lt=- - 10.0;50.0;10.0;10.0 - - - Relation - - 470 - 420 - 140 - 70 - - lt=- - 120.0;50.0;10.0;10.0 - - - UMLClass - - 540 - 470 - 100 - 40 - - GoTo -(goal=C") - - - - UMLClass - - 430 - 470 - 100 - 40 - - GoTo -(goal=B") - - - - UMLClass - - 320 - 470 - 100 - 40 - - GoTo -(goal=A") - - - diff --git a/docs/uml/CrossDoorSubtree.uxf b/docs/uml/CrossDoorSubtree.uxf deleted file mode 100644 index b5a5e10ad..000000000 --- a/docs/uml/CrossDoorSubtree.uxf +++ /dev/null @@ -1,299 +0,0 @@ - - 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 - - RetryUntilSuccesfful -(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 - - Inverter - - - - 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/EnterRoom.uxf b/docs/uml/EnterRoom.uxf deleted file mode 100644 index 74afdf8aa..000000000 --- a/docs/uml/EnterRoom.uxf +++ /dev/null @@ -1,298 +0,0 @@ - - 10 - - UMLClass - - 260 - 210 - 100 - 30 - - OpenDoor - - - - UMLClass - - 390 - 140 - 100 - 30 - - EnterRoom - - - - Relation - - 300 - 90 - 160 - 70 - - lt=- - 140.0;50.0;10.0;10.0 - - - UMLUseCase - - 110 - 200 - 120 - 40 - - isDoorOpen? - - - - UMLClass - - 120 - 140 - 100 - 30 - - Inverter -fg=blue - - - - Relation - - 160 - 160 - 30 - 60 - - lt=- - 10.0;40.0;10.0;10.0 - - - UMLClass - - 260 - 70 - 100 - 30 - - Sequence - - - - - Relation - - 160 - 90 - 170 - 70 - - lt=- - 10.0;50.0;150.0;10.0 - - - Relation - - 300 - 90 - 30 - 70 - - lt=- - 10.0;50.0;10.0;10.0 - - - UMLClass - - 230 - 140 - 150 - 40 - - Retry -(num_attempts=3) -fg=blue - - - - Relation - - 300 - 170 - 30 - 60 - - lt=- - 10.0;40.0;10.0;10.0 - - - UMLClass - - 770 - 70 - 100 - 30 - - Sequence - - - - - UMLClass - - 740 - 270 - 100 - 30 - - OpenDoor - - - - Relation - - 680 - 90 - 160 - 70 - - lt=- - 10.0;50.0;140.0;10.0 - - - UMLClass - - 890 - 140 - 100 - 30 - - CloseDoor - - - - UMLClass - - 770 - 140 - 100 - 30 - - EnterRoom - - - - Relation - - 810 - 90 - 30 - 70 - - lt=- - 10.0;50.0;10.0;10.0 - - - Relation - - 810 - 90 - 160 - 70 - - lt=- - 140.0;50.0;10.0;10.0 - - - UMLUseCase - - 570 - 260 - 120 - 40 - - isDoorOpen? - - - - UMLClass - - 580 - 200 - 100 - 30 - - Inverter -fg=blue - - - - Relation - - 620 - 220 - 30 - 60 - - lt=- - 10.0;40.0;10.0;10.0 - - - UMLClass - - 640 - 140 - 100 - 30 - - Sequence - - - - - Relation - - 620 - 160 - 90 - 60 - - lt=- - 10.0;40.0;70.0;10.0 - - - Relation - - 680 - 160 - 100 - 60 - - lt=- - 80.0;40.0;10.0;10.0 - - - UMLClass - - 710 - 200 - 160 - 40 - - Retry -(num_attempts=3) -fg=blue - - - - Relation - - 780 - 230 - 30 - 60 - - lt=- - 10.0;40.0;10.0;10.0 - - diff --git a/docs/uml/FallbackBasic.uxf b/docs/uml/FallbackBasic.uxf deleted file mode 100644 index 8143437ea..000000000 --- a/docs/uml/FallbackBasic.uxf +++ /dev/null @@ -1,216 +0,0 @@ - - 10 - - UMLClass - - 260 - 140 - 100 - 30 - - Fallback -fg=blue - - - - UMLClass - - 200 - 210 - 100 - 30 - - OpenDoor - - - - Relation - - 250 - 160 - 80 - 70 - - lt=- - 10.0;50.0;60.0;10.0 - - - UMLClass - - 430 - 210 - 100 - 30 - - SmashDoor - - - - Relation - - 300 - 160 - 90 - 70 - - lt=- - 70.0;50.0;10.0;10.0 - - - Relation - - 300 - 160 - 210 - 70 - - lt=- - 190.0;50.0;10.0;10.0 - - - UMLClass - - 320 - 290 - 100 - 40 - - UnlockDoor - - - - UMLClass - - 370 - 80 - 100 - 30 - - Sequence - - - - - UMLClass - - 470 - 140 - 100 - 30 - - EnterRoom - - - - Relation - - 300 - 100 - 140 - 60 - - lt=- - 10.0;40.0;120.0;10.0 - - - Relation - - 410 - 100 - 130 - 60 - - lt=- - 110.0;40.0;10.0;10.0 - - - UMLUseCase - - 70 - 210 - 120 - 40 - - isDoorOpen? - - - - Relation - - 120 - 160 - 210 - 70 - - lt=- - 10.0;50.0;190.0;10.0 - - - UMLClass - - 430 - 290 - 100 - 40 - - OpenDoor - - - - Relation - - 360 - 240 - 30 - 70 - - lt=- - 10.0;50.0;10.0;10.0 - - - Relation - - 360 - 240 - 140 - 70 - - lt=- - 120.0;50.0;10.0;10.0 - - - Relation - - 240 - 240 - 150 - 70 - - lt=- - 10.0;50.0;130.0;10.0 - - - UMLUseCase - - 190 - 290 - 120 - 40 - - HaveKey? - - - - UMLClass - - 320 - 210 - 100 - 40 - - Sequence -("Unlock") - - - - diff --git a/docs/uml/FetchBeerFridge.uxf b/docs/uml/FetchBeerFridge.uxf deleted file mode 100644 index 7c3418e46..000000000 --- a/docs/uml/FetchBeerFridge.uxf +++ /dev/null @@ -1,592 +0,0 @@ - - 10 - - UMLClass - - 550 - 30 - 100 - 30 - - Sequence -fg=#009000 - - - - UMLClass - - 430 - 110 - 100 - 30 - - OpenFridge -fg=#009000 - - - - - Relation - - 470 - 50 - 150 - 80 - - lt=- - 10.0;60.0;130.0;10.0 - - - UMLClass - - 670 - 110 - 100 - 30 - - CloseFridge -fg=#009000 - - - - UMLClass - - 560 - 180 - 90 - 30 - - GrabBeer -fg=#B00000 - - - - Relation - - 590 - 50 - 30 - 80 - - lt=- - 10.0;60.0;10.0;10.0 - - - Relation - - 590 - 50 - 150 - 80 - - lt=- - 130.0;60.0;10.0;10.0 - - - Relation - - 590 - 130 - 30 - 70 - - lt=- - 10.0;50.0;10.0;10.0 - - - UMLClass - - 920 - 30 - 100 - 30 - - Sequence -fg=#B00000 - - - - Relation - - 850 - 50 - 140 - 80 - - lt=- - 10.0;60.0;120.0;10.0 - - - Relation - - 960 - 50 - 30 - 80 - - lt=- - 10.0;60.0;10.0;10.0 - - - Relation - - 960 - 50 - 140 - 80 - - lt=- - 120.0;60.0;10.0;10.0 - - - UMLClass - - 1030 - 110 - 100 - 30 - - CloseFridge - - - - - UMLClass - - 920 - 110 - 100 - 30 - - Fallback -fg=#B00000 - - - - UMLClass - - 810 - 110 - 100 - 30 - - OpenFridge -fg=#009000 - - - - UMLClass - - 860 - 180 - 90 - 30 - - GrabBeer -fg=#B00000 - - - - Relation - - 900 - 130 - 90 - 70 - - lt=- - 10.0;50.0;70.0;10.0 - - - Relation - - 1020 - 200 - 30 - 50 - - lt=- - 10.0;30.0;10.0;10.0 - - - UMLClass - - 980 - 230 - 100 - 30 - - CloseFridge -fg=#009000 - - - - UMLClass - - 970 - 180 - 110 - 30 - - ForceFailure -fg=#B00000 - - - - Relation - - 960 - 130 - 80 - 70 - - lt=- - 60.0;50.0;10.0;10.0 - - - UMLClass - - 540 - 110 - 120 - 30 - - ForceSuccess -fg=#009000 - - - - UMLClass - - 150 - 30 - 100 - 30 - - Sequence -fg=blue - - - - UMLClass - - 40 - 110 - 100 - 30 - - OpenFridge - - - - UMLClass - - 150 - 110 - 100 - 30 - - GrabBeer - - - - UMLClass - - 260 - 110 - 100 - 30 - - CloseFridge - - - - Relation - - 80 - 50 - 140 - 80 - - lt=- - 10.0;60.0;120.0;10.0 - - - Relation - - 190 - 50 - 30 - 80 - - lt=- - 10.0;60.0;10.0;10.0 - - - Relation - - 190 - 50 - 150 - 80 - - lt=- - 130.0;60.0;10.0;10.0 - - - UMLClass - - 570 - 310 - 100 - 30 - - Sequence -fg=#009000 - - - - UMLClass - - 450 - 390 - 100 - 30 - - OpenFridge -fg=#009000 - - - - - Relation - - 490 - 330 - 150 - 80 - - lt=- - 10.0;60.0;130.0;10.0 - - - UMLClass - - 680 - 390 - 100 - 30 - - CloseFridge -fg=#009000 - - - - UMLClass - - 570 - 460 - 90 - 30 - - GrabBeer -fg=#009000 - - - - Relation - - 610 - 330 - 30 - 80 - - lt=- - 10.0;60.0;10.0;10.0 - - - Relation - - 610 - 330 - 140 - 80 - - lt=- - 120.0;60.0;10.0;10.0 - - - UMLClass - - 940 - 310 - 100 - 30 - - Sequence -fg=#009000 - - - - Relation - - 870 - 330 - 140 - 80 - - lt=- - 10.0;60.0;120.0;10.0 - - - Relation - - 980 - 330 - 30 - 80 - - lt=- - 10.0;60.0;10.0;10.0 - - - Relation - - 980 - 330 - 140 - 80 - - lt=- - 120.0;60.0;10.0;10.0 - - - UMLClass - - 1050 - 390 - 100 - 30 - - CloseFridge -fg=#009000 - - - - UMLClass - - 940 - 390 - 100 - 30 - - Fallback -fg=#009000 - - - - UMLClass - - 830 - 390 - 100 - 30 - - OpenFridge -fg=#009000 - - - - UMLClass - - 890 - 460 - 90 - 30 - - GrabBeer -fg=#009000 - - - - Relation - - 930 - 410 - 80 - 70 - - lt=- - 10.0;50.0;60.0;10.0 - - - Relation - - 1030 - 480 - 30 - 50 - - lt=- - 10.0;30.0;10.0;10.0 - - - UMLClass - - 990 - 510 - 100 - 30 - - CloseFridge - - - - - UMLClass - - 990 - 460 - 110 - 30 - - ForceFailure - - - - - Relation - - 980 - 410 - 70 - 70 - - lt=- - 50.0;50.0;10.0;10.0 - - - Relation - - 610 - 410 - 30 - 70 - - lt=- - - 10.0;50.0;10.0;10.0 - - - UMLClass - - 560 - 390 - 110 - 30 - - ForceSuccess -fg=#009000 - - - diff --git a/docs/uml/LeafToComponentCommunication.uxf b/docs/uml/LeafToComponentCommunication.uxf deleted file mode 100644 index ca5f6103d..000000000 --- a/docs/uml/LeafToComponentCommunication.uxf +++ /dev/null @@ -1,109 +0,0 @@ - - 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 - - diff --git a/docs/uml/Reactive.uxf b/docs/uml/Reactive.uxf deleted file mode 100644 index eb60589f3..000000000 --- a/docs/uml/Reactive.uxf +++ /dev/null @@ -1,260 +0,0 @@ - - 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 deleted file mode 100644 index 7b1a773fe..000000000 --- a/docs/uml/ReadTheDocs.uxf +++ /dev/null @@ -1,153 +0,0 @@ - - 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 - - RetryUntilSuccessful - - - - 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/TypeHierarchy.uxf b/docs/uml/TypeHierarchy.uxf deleted file mode 100644 index 34e0059fe..000000000 --- a/docs/uml/TypeHierarchy.uxf +++ /dev/null @@ -1,141 +0,0 @@ - - This is the type hierachy - - 10 - - UMLClass - - 490 - 180 - 100 - 30 - - TreeNode - - - - UMLClass - - 590 - 280 - 100 - 30 - - ControlNode - - - - UMLClass - - 590 - 320 - 100 - 30 - - LeafNode - - - - UMLClass - - 590 - 240 - 120 - 30 - - DecoratorNode - - - - Relation - - 500 - 200 - 110 - 160 - - lt=<<- - 10.0;10.0;10.0;140.0;90.0;140.0 - - - Relation - - 530 - 200 - 80 - 110 - - lt=<<- - 10.0;10.0;10.0;90.0;60.0;90.0 - - - Relation - - 560 - 200 - 50 - 70 - - lt=<<- - 10.0;10.0;10.0;50.0;30.0;50.0 - - - UMLClass - - 700 - 420 - 100 - 30 - - ActionNode - - - - UMLClass - - 700 - 380 - 120 - 30 - - ConditionNode - - - - Relation - - 620 - 340 - 100 - 120 - - lt=<<- - 10.0;10.0;10.0;100.0;80.0;100.0 - - - Relation - - 640 - 340 - 80 - 70 - - lt=<<- - 10.0;10.0;10.0;50.0;60.0;50.0 - - - UMLNote - - 460 - 360 - 140 - 90 - - Note.. - -This is the type -hierarchy in UML -bg=cyan - - - diff --git a/docs/video_MOOD2Be.png b/docs/video_MOOD2Be.png deleted file mode 100644 index f44586a37bdf4385a25e9faa75dda218f31d95bd..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 171741 zcmV)IK)k<+P)Bq${&Eh{Unn0u?0cSb}*rHyDB85yve zds|sqMjsq0C@MBKGg2ZQpo(abje?(uU|3aBHa0trihe^tK9rD#O-oHvQ&LSJ98phC zsF7~4n}DT{Y(6|ZnucYfi(^<*Oq+yTmXLiuH!>z6Ag-gGNJmL%WL~9_abaIvmU~ZE zQAd}6RZK`jP)tXlgXSVpa^uYzSlg=$BCetw36 zdV_s*pN@Hog@ABrTeG8*dw6w$cxINAm9?gqh;B@La9>|iLq9Soe|m05KQx<)a<-|Q zl8km_R!NYLk&0H? zpQ17;BX(j-bXqzVMnHdPOu5D2cV|{EMQT(-HE~`=ZCy?(IY6zs$h5!Nv#zPRt)Y2S z7HL#Bfs2$HJ~?-Uj9pAIzsu%gXmr27z$r^hK0!y0gKHl(C$qM>hW>VZgKVc{V*OFV@o}R zJS&l%sDg7=Q$QvxODkl0blvLwnxwVb;OB0HfkAdegJ3pMlU6Hfa6e2^IA%G%#?mG} zScQmNL@*Xvac6RLLWhM#Cs+tWUs(72AZ$(^mPH$6^mSvA&h@okj zd|7y%Qczr)Wwf}3o^*FF%F|=M#dW5hsM5$TxRS(iw&AmPF!I#|00NtsNklG^lPQ)eold7+SNH>3 ztyU8a5oIZz7*r5HX717@kC*9brcl`uwgaScBkE`x9fGK-d5|~ zPFqpycvtn5bcl{}ggt}}eQcxKZYb@{=Kgjz7RcnR4!6_6m*=R%fj-F|FR4nsUJYlI zI`&E%AKmGq)w|U8cDrpFck2qik%})%-}9qoG9Oar!voQC0Bk zR-jV7uFAM91X9PX)-f%-;eOEKhL|Y(Xy2$tltC4EgB(t$+Z{|0P*Nh%Wblco$`Wg1 ziO4#m2OfAp>Uz!!G;v8Wgu7;CUT;t7C00naB zdKWlpKmi|OifQ7OlXDq#&{J4~ta@j6uiLJxYNw;%jI_G|3Ll0~6-23-a)y`{(9-9t z-Fk6#wK%z*PljF5oYO6c>N`hN^+>_(xvn%+29&=EFgwJbuM@QOHbh{7uq~*&N4qXq ztN)BQgS11_ou9t()$s7(;DywyuX-;eBeBSOv{>16IX%SFP4^i|1XeDS&8}Nbf+AzF z(=FI)vocf6k`OpLvlw(a%uc6xm)mOcOMd^T(;pg7%@Mo08AKJWPWW`KCbgQeaHNdSmSwD&VzC6e+H?{dhrmjRiKCScr3=o{>yy8o*S+^Xa4-H9xg5++SR4b` zgK4@46K{2@x;jvz0Vgactb-2)QaV)36}2yP{qTbT3?xohimFn~%J>B%nvb9XDDcEY z32#!FCUhW0A-wXdB|5@lZva*G?(S9xJi(p1U2+rd6F|ITIm#r-o)}oc6mE#yx8A+` z%JvmG9xTcZhtut_b5w;hq7fCTtEY##NI6$OZJw%!Fq|g-xzbkQtN5$<6d_eGk4B(@ zGH}MIF=wV%zj^zq{!jeA3sYZR_e$a1^!93g@`lSPh+-KYRkPv>xe?7|vi)91&z#T^ zJi&6T_-c$4A7_CctPB=2#XTOGOg4ud9sJ`ynNN&Ze*uQG`^;8SuG5R5%ie#hO5huJ>FvBPV63N0fAY9Hc9~+2DgQ_9=!49Mk{- zI}M16$?`f*b|RjLfhY@zl2xT-v*HF}gYY|`8>sm&^oPR{QVfbj%5pB6FG0l&V$E1W z@<|c5-9bd*HyNeP8Km6W#tNbwlBE``1*MiCszH%ViD|)R>7lC+UA_9yL)a5Wg0UyW zL0)x_N?V?TVieS|Aim=wE|CblRv7GJG2+}zBFF$+6|0migiTZBxlO95mqvzo#Otj2ZnAP+?BQXi)DhyAc~Q4+jDh%9XVFcFzKKD zL_ET)6#CTm5u#U)>ac~lb4U`_ght;Od(&$VemNYIT&@7}lzurPg@XaJB$;q~zG=P5 zINfxk3Dr#a62WNFVs_{`6BZUC8LP?Wgxn6iXoz|Gtw&Mc45X0C*-Qb+Z?#E2cX}8^ z%@;<7!A}SYRAJ@WXWuT&idc_`5)oiw*lF{*t+5Cb6^Bb9dyAQJ^0)7n(zrc8=kV)1y)Qj;pBWHP7JL6QIpqBspsioKQK3Q9h}S1w1& z^bNvnU3mnBn-#Ae%rH@Wv(d#K_3M1fo=8akpd__ghDYVEUcGkr&;}?WOEI(rJ%m+& zhE<2jpzC&Vi2v!m#Eixbf%NXZm$7;2@=NdHkf9v_1)`?WSVq(*7ER0&A;nZt(8ngV zFQUE=$)W%h+Mi2@YJWPKta5-RB0cPRWuTNJ!bl}|(#gVrgF$gfL73HMO9D?_bSdhi zE4tGmk{AW-qRC7am%o0+W2>%K_HSLuY;Ro3`udA8c$8Dz_8mQ<+_^S|hqzT9k#izD zIy{9l0aYw`2?9)Lq|ZL%9>&Zau;%{?$kaDFic@X21p+~rKMS6Mfq=>7b$UP)T#Avh zgDKv6T$Bpg99o*hJG&+~U20a~gky#TLxxM~H1TTEWb-2Aa|b1}0|ki!dlWRA8ZXSQ zp*R7PN`WI5_C%D`>UX#kaEUTJiu?jZ0Vxm#F;Pv8D5-@`vH_yPcq>%pEC@v16igkr zs*P|mC$Hz?!5B;`QFG-hnPgdMOQ6T5Gv&qt_{GR+b(7!Vh}j$T`z&#!3BVg)BO7oS z9wqW9Vu_m}f-dg&OAr(FBNIg)H8(XC8k?D$8@sr0?dfMGCsC!i%w-8sahWg!R%mc8 zG$9PMK3f^DM*4-2ugB5DmzOvdGjcD@ryy+JWvaRwR6UQ{M)t&H(M|+?SPvK|PNZo0 zO9`Adiu~xgg)g^x-dun&Kw)QAlL-37lx2?GbJ6kjy z%?e~O=1{dVL|bdn6Bkm2T60hC%TXO8rYOf4NADW?eS+wCKU zT^JN^4#i$L707F%O9D|2xBU(e?z<*`SaK3sv9d4VhDT{YVL@|q7>XI#CTl z)Y{t2Yg03%;qeg3<#J89mhd6&0!YA+)+vDao5fg~9H$8;m~_#o%yX5JeWIAobFTqC2hK zhP$oJ?KRnI5|V+YoN(K2vfNnUPS8zHO|rPilSXxeGK8TfJ1;#MAaU0iQO6nx1k7f{ zegSxt*XnoO;R;R6rV440!vLWzK1EwX%1~i^!0EG6vF|V$CZfVx*eAn`8iq$nxL$(^ zC|oVa;t=(jD5+Mv>48Zd11-2#B)Oi;J#!-%r@+teNtTMahFY(>Z8i^h!jB_>qM^s5 zLj^e@+PF#NLd*`jeY~Iv^^KAov_hlwmcEz-9oJf%%4r_;=+fe2%jvP@nW>qTnVFT9 zaZu$Q85nRnh+dm*U?eab8lJhdaP67ND;vxMm(@{p5Ntg_STR^){{+J&+-qY4AfZQe zVL&23+dyC7MU_Al(+R9wJ3F^-p)p8Ub*KbTgw*~43qTQ5AO3|qeYag9cPd6Fqs3x| zstfftHS96awtA`rg0$R34C*Mm)w^4J9lVR8z0Th5E^y+y0C0m;rCX;fTaWSZxu>V- z8yVWpYI1X@n2ex|9g0LHj{5jIW}Y|l2v!)G&88eXVr=rZA~TRm=%H{f;IyaA8LW5bO*;IUhoCpR{=R;(c_$Py~WoX0Jy z4hAzk{v+LiW(fVWa=QZF0GcZZqFgqAu+NKd?9CaP5hkn7jhpI&$M$1U-=&r{A9 zvyDbwX$J8&4=B8>LzVyrs@CdSc z@!{>aQ@X`3VJr4$b>%8i$Cd_ODGCHyXk1L(?uoLfll}c(CdG*qZO_9baN4RUnP{{K zo+d$5J{bvDW#WK*Sqs?uhA!dqyMl?EzL3Zdd!LI-7vI{U_vD4FAB zPS3E2&<{9u_ba$G%A0v}GU{>=LOf+?5Eb5OpEN2NIfq;?BU7y_nhVFvs4RB6SlaMK zR+okH2*gzpmCBG+J&!Y)apv8gn#*Q4qe5WwSZmcoH7mJ2$5dQalwzq=$w#BPByQd{ zPp^t+EPpP8Bg3PN@;T;pT`rp2^i72rLR5Lsi6W9#9$RCgNb|D=CMq?XCZen~ zl^8LI%4KuOWU`U0YD6VkL5YZJk_&~&pe!JY)v6IuHLCX!QLzY!x^~TVTilX>M@5Q6 zluG~YdE8QI?$=kV0WF;<-L(wioCvzOKCUO4Bn(+R?IC*T+Cfy)0uAl2fJ+`*^ z*xKWBKx&zZnn{I*{e#0Wt<=mi!olU06vEAoCsoX~uA<6MrKSk3tZZj% zcMC;vFa?;9x(VTcj@A|gf;(L{UA2yRpuRq$_{A14->!eTaPk$I&W9Ff+e2?I8jbvmEwIiM15z8nqPYs2%*C+C5W0Y zr0srO#4(+yc&rSda@lP129Odnya||8?U;#5#K@x(aS+9quZa2}ji_oYvT*Ii7q5jZ zL{!TYjz;AMUE)bOi+d{WDV5F5N+}=BA+_~Mu7KI3Aw~8Cp~E8gAtZF5 z%xbod!u?nd=YYxVb=?+@EUd%6;9sabV3zmFJwuP&fB(?kLp-Miai!zDu0DYU;&Q!~ zqEX05{a{-a3`oZ38Jv4$S>cYXwgY&8lte*AWNyM{OhAB zCp41^gfx5F+U;P_)>KE^>Z&SHR~Nb2DS3r54PF^291&IdZbxn7Etsy4*rFL5eld#B z4We)pOzw2PJ!mJ&au&f(G%F{nS>$ZHTRo7l?FyXeSXUp@7er|UqN80?(C4t*0#4lF zq}YvQHcOLDxpLg%4+cDR$HijrO{Unb0}qf1Y%!K4@|jVO3je_(7FB|y|FX2-{u z#|tAMDh=T;;oJ@2Mu)$eevKxTNup3MI-?`$*U}>s-k_A-7`prJd!D-e>izJ!$LGdC z?qe@LefJOrc@*Knh2UgB4a<@!(m%mj7%{~{zZWM8^8#M^jSc!$HW40f6I~3Kcz|Mm zwGM{ZooItT4Wm)aF|-jgQFuoa9cWcioIzv3sc0p>PPPD&q8i~I%!i0mcm{~_s;&AF z5!E50R6dGWuo5ZO>E&L{P$8n)0QE=-2clUUJc^0>RS3~nF6|uD>y3z_J#kB*Rmb!`h@zXOjGrdU z_gT&YCV>_QL3oUgo~7H!XVxSAK9|>Q9l#ZyPCIp?u#yB(4lGVh#1+ECTA~&RXdcyS zF;OKDwaA(yEt68?M3jGKW@2X0@0}W+3XwxGQBL+enuaH$(xVP?N5+YXVx>bPqXQ!j zr~Sh8(%pC8{?yg0cg@X>pprNYKv%}+=Tj+kr{*qkwf?T5D`L*r5QT`?2>m)d)Q1}Y zOH&@V9o%@p*EA{-fQdCpin1mNsS>V#?cR>Y0xII^Nl~fAN>V$h2!K4T8nL$rBv>jI zVA8<*I{=DuvOTqmbyz0Bwsif_ItfSvq=gB&4B^4!y9x{`TW;HMdJDEiz)7;m?!9)4_+Nf`;m$S zc|ximHS6*M!nSKqU%NOqcH@SqRwRNFaFUKGpK5}r7-%7r(mkqIKF6!^$if1Mx)6+8 zEOB4$SfMzMXDq^DGQ55(+PRSHBK0MR!8Vk)Jj~WblFAUESQ4oOQ^Fu_DGs3nV zJXPip7;Ck~zCy_9MM=Z7u(@>m{p3+YmoBAemS>>rE715juo@SSs6g}MGc#mhk6nBE zZsv=lLlgno#ROW+6Yr^BkDYiJaYNVAm5n^{l+XW)rb)OIx`b3ShTww9P#|o;%+@;} zekk%V63X%)?xN^HaTO973is&2SpGLyVN?)h`Dz;-rKoiF$nG-bCeBzhTq=fRnbndk z(;whJqrTHtVN>8_RSp(&bbHgIJ`E{{BU{R3R_pa-43!gg2W)_l6QYD5BC|65igyN7 z@6^=}zn>biY`TMrvts1iJaV5EUnU^RsFMEZQp_C4yo?GDqXuQ5K`_>CDr2WWK0z_1}9|?JKVe$I>_2svhmvOhfc*s=~Fo;^X7MAdqc%oKQGr7aVhDH>CdIms|h9*g% z>8`tmbZOc9lJ)@V0&roE;>iy54Wjg)mYcg~q3I~HC{8P?Ow`p!7D*Qu*EE-!TbUZX z(0^&_(%kseg+c$^%-lSpz5tsPh|yw7B5F2m7c~;HC|%ApO1RSC)J$l7^YZQRsN0u@ z)=*8vCkviH6p+G7J2(~=F$j^^zQ!(Hd=dV2_gx4Og@d6%=smF+(KAo5C`F`NRh5Wp5Gr-0Eh-emG&Eq07dnoi75iDyvA@dJ<06*CXoh$-oFQ1~y+XV!17D zGW&d(l^PhZ;g1hU);qitu31AgJvDy)@yD4cwx<+`LVMxM0X*tq4Fjq0)L{Rmxzr1< zzV+4ztmmJ9{`&Rn!+3suoF1=rg>JJX$jjhA7GpjN9z_yFHNzJd;Bprwyc`2j$R!&@ zR5*g-q0An|7lzK!UH9B`&(J+XL-*WsJ84KTcGnf+%VE=qa`s1VTnvwagHRArq1j~P zfRN#`*_>VY-kA$o@qIduHs)WF8cWNN-Xo%B6{DzU;4ZDI!6!Zs!Cfop~DY z;N;B@0Tk1PQ3t%B)!SV>t${gM1w@Iu1vUuiL`K!!BcRm7)?qO$XEw``ViwniTIL6# zRgko+)Vt(ohl<5gjA%sl{hBCiWiumZGg&!PC7!y7Gyx7MVQi@EV7QZh6nmDU?wxQK z$4y{{Z=8UrC!BGJqd=CnW0UF;^#@3a>Xzd?Pv<9h-TkhJ#TQ12!WTA~F?VSqqHK4V zyV9U79!D!$^UrAzmOxYY5$?QHuI#^02?i-i3^RBR?5^CYxJ-<3)&>-{$QT+c$RZGciX)_+q%4}y?WnvBm43%h9yIbLSG^P`U zgMYOA9nI<+{CH@gU=e+j=m|xGmy}d9# z9P;aP&Uw#yhf;Suj^!snB!h#e-I)_#@SyjfI(2Gsab{);MB$E!Lhh8J+7w^JGZUps za;bmwD4-%^FO5klwzLaI&Z z+V$)Xq@W-XREgNYrIPy3};Nc=Z(l28gnn z9YvA-OjI%x^(=^z<38}hR251d1u;zo7BfdD`B^TGV*|lsxnk{k0LledY+a;k;;S}- z0#OCZitQrW!=duTmet)52+f^ao!MO8yBfTOR7!bsD~^C}9XM@~Wsy)wgh>sJ?VJDc z&x@Q=u}Q(JC`Y1_#;-`O8UmHWLtbA~%gQQjjK^=Lm#|(1HaBNxV16T&WhVN;C?2I3 z9_45rL$~8tSzs6i#!a>$7DGf4AIE`$E*!GJ(??S?GomUeh=LS*QnA`glpOZ~64{LY zDP>}$bSW@BwyLzf5+7r8qJz%oOm$e&G+KC~hKO=dV^Y2(hr@<4q}5b@sD1(#MCv(t zaso&pyxWiiyki5njGi7PeLy-b^u3DL>GOr0Z`o`%EqH>g#uQx!e-De%Qe<+wUC3NI zA|NWsrqzO|X$-94Q&0uvg{~F?swO)#vosGPrU)jw7hc6I;ehH2!eK#_`%a1kOBp{1 z1Xc*W%__5Dg#rRm6!isu22t=RD)!axKnlOV5l_$!qN;=b+-KoYAPPo=nKC`4QAI@s zx-1<)NMp9KQfAD$Xx6Pbg`SanYOb3eCi^IBG|Z;zLzLg zib51;)f_#fv+ocf>T2#Dd)f(1dV)@b9D5x~{y@7k5U~2t?`q7@JE;=^shiW0n68m= z!kJ_b__QEu^fUtmj<&ZaX7Kth-6Vh z$&^hb%k{jp#JdiwRwt)bX{< zg)p?%+!Puc90|-IBf{Lo zMJYW9jKmeR$q^sFkHfyrndvyH`}CoU7m-I1Eh{5 z=`B_JTA`AX?95V*;=lu&4ud2P@wOn!AQ6>xCq98qO))cB^flf#+O@DKE5gv0z5uUx;b2&w^-0PnSs57_X~Lt@ z&ZVV_C_O7B9knE_)}3qa1yLoaOb}7{+QOs+77|VJMfNCRQv47sF;&NL;*hS45kCeH zegh{!l?$Tkh^Rq6MAXNDAJ_ZtY#M8Bp8u92IjOTkk#tM(-4@IVAbo`Fgq~T;_~<`l z4O%qVRH37m-DwH9jE%vA=;yaGIIURf={b)IH4hKX$C`X&@u`cHMnMFSQt7)?crSuJoLG(`qVRD@z7oWjRMz|PL>Q^t zMX=Iof>oO;xcS@Sxp1GIQb%}qF(sH33sTlfn?>(L3Y9?~m7;SP^{F6=kpfd1OdgFS znHvv|j?SKDG(HAWvuoRk?_g4bDw!w=s0#{J&}7dfvm@F%gwb0#GDSq1qJu36ec33Xd`nQPw-# ziKtRM`WYjMrsO=PvciaoLzooJZ>dBbJzPsf(S=>gRUUMie1a&q3whMD>{0mgx(w<@ zGlX;V3sR_PsmaJsOUXh7Qh`2mhmK6jZg>0Lky~gz>M)3^?T}1LVM=x=Ip$Mx zDd_^E0zm{2-5pXbOCZHG@iBlvP$DWD6v-CFI4K&zYJ3Y+LwzXwnqz2VM|y);ZkHG> z8pDE1eMAWs4}{cI;%8=0(gvofL4u+_T=(rmWt_G=Xqxkmtga4DBZv;+W~HVkfJXNi zdV>Hj+5uOnEbr81(ej1593@pIrkmGe^P4lF<~Xt_kw@W#lsFGpnIt|%*vBms>v6il z2TOUBs@))Qw|lA;n=J5Pi&e0Y`2UbfWbN@N^$7;#wO4A^AsY=sZVrBK%vJ_ zLsRBSW>??j==KIgHN4sFjp+91`zKD%Zfw9|=o|%COw}I}Oe#|!OPZW)EH6hIO?fox zgB{hA=Vu`X3Ws?94Oo#7Jc8Z#-@kC-wXWX7hf7LvklGL*^%{7hgVfqxS~ri_m;Z4%uJ?9u_swIWlfP#XN1%l>Ff*z zykEWd9&g^!Jtmy%PiW^Py(s(PCO#OT%}8u^x6d5_OzZ4X>(gWKpvCFc)j-I;iZQsr z5-s94RaSaeN18`Qrct=NxQsMx6CF%jfOJ8J0GWwOREUC+qz+AOVmFwTx!4p92Llzt z<|2`^N5l}bCcSk^THyU!&7+`8X9Xp1LPe~h8%6q1Q)i1wa+trB%!;Z@LqS2Ec%*32 zGLd9*SezMv3P@3P0!iR$kHP6U*wpbI`g4fDhgUgZ^BK|~aM2?ux*M9Dbeor++0WKd8r z2%@s(H7J~ADo?bo2bOvzp~uB+wPIYw9dNnOK=xh)gOxyw+S|7v6|Lpr5sLOGY`6K4 zfb*ynl_sDWbPU0lS^||L4fsJW%~e&+g{rXm(%5pt$QW7(dE{gh%Tf4}Q%E|QD78^m z5Veo$J9pTcs~6g40U*bxi!Z(eoglsR;fH*ZC=divEWs7L3W=90 z;_!oyaYzgStKY!Z2?Z)e{Q2WRi^xK6w&)W$QXwrufh&0KY04thot~@)Ud8Zn+E2Dibw6&P1upyoD-L z#Y$mDN!{z;ZdGQZ>>xe)~$;$zm3hfAY6j( zci;76{f{~+;ad9;6q0ep8medu0V>wo?cPqiGeniX^@}`0HG}Ks%-oExa&=^7b+u*5 zR}~0_YF4I^UtzU(X=!Q^(cVWiPQN@AZ{~dtB%;*iD1G`o1#Z)!nHViaQPd}|?9vl! zliz>@J)~1m9LrIFk8z_eq&*nzyfrwH>?~A<2AfbmZpC0ApxJ3syP3KKDftgno_6ho zq&0fAcCSTmOfV(z%LZ1YoLG?3AjNh#$fg{YBs&q+7i{dq+7sr(Eg9j0aL-9JO%Pez z+dxaIFTkP5RbG1a)mI;U^uY%oe3h{R47-Selsf_jZ^4CFfbvxcpZd%*_uO;OllNS> zKot%yen_8)Pk0gE2LfBKzy9)DAPZx%G|87ItF$hIwpfGdrzH&5l$H`v{XnTyRyHXU zLD8UHCTf+0ts_lkPr;)O3!)-;VyyfjZ; zXCxRb2crd8rZgHg`C+v4(QvBPv_Jt)YLYDikJ?`c;ANt4GEyoOKm|MroRp}Kg*&E6 ziTo6MD%=ee)%uW36;?ka5ye!g{)7{k7EeS1s;jp(80$SQ);!f(;H3yKy7# zI+noZ<0~noONlaki}K#)NN9RJhH2fUDN!ny(OOgkK9=$hh=}4l#tcOLv(jM^s2+IA z&@n(nSyClH{=Y}5NU36`xO|>u4LDPc7B|)U$f9&k4Hl&G2`R2jI80V=z*b(|c*gpWRZIQ`*|w_1gIO*eISK5hZ0(!rhW$iDhZ`}+k-^k9|dyp5IK;T9?CW1u+dE2F5dS3*gW#}#pP zdPZ7${T^3Ea({ho2VPpDSn&!c=(vkLe6VlLVKnre?^!b><{y}tm^gWFBBuyWEfJNX zx0xeF{g&zLi-^iFQ@<}Zw$CT64W;fODq%Se zfNDa6L$Mf!2c<-5os%Qhjx-A5J5lQU=%T#9%lbE>QngmM&+c}&Vujyt#=@nNFa3@7 zBBj1x#b{Tt&u*`DJKZ*&(PA=akVa(?QOLR3o>&?Okn`Hg3xmg^Q4A)K^dP9Okt~Y( zui<0(@G!-ML>Be-P0W&I0T%L{NA3q$&?C^JkG@1gh^R(}7f4{~8K&t;=yiAx0fmM& zjKPY5RfvYdKi&U!PHS&1YTA<|b}dOCpP)j*hV(okrmX*kqC)75x zOhc(sE9Y{55_+ZRNxb=QL}9VrruCVvE+h53>A#>ulJv|a>RkAkR&AHM(L+irXKk=sBSOpFDZWS-6tO?bd?-U3i}-6dwg0hFxe zWqtx%4?R>@QF;`%1*{Mh3a}^Z(6bWYjq@pTQe*LivY!ii(31 z=O@+*5>KA}=BKk~uU_M*&+0}ZrO7gwTy4QfD-o5)L_JGH)w2Xrs!QP_2YO29gi2Gc z68gz$)N$M~Pkg~irM?K|QDBJ<7W2eHg4F5p04VT8L=}5J#Rs)SJidS_$!tfvyUP!v zSf${pAIi)L7E_6jP-5XpZbFK2Z(q~!*kHq0cTM+n2rWsW`DXNv$I-xqeOTs(|BPQm z^==uy6RKH?HQU90A#$Uv7zsu2oIqQ0`@G(o?qQ54562*4YYHdmqDM^WHJ9CrgzO3n zymG3A=YJ*&-w{maPU-QwwvHl=3ryEFN51RqWF_2h=NC9u(!`pApdt55**kA#scn0L={dZ3mtzF zS&u>h>o(G3x04tqxYHQ|>hZ@PXNLk%MAR*W6j{`6F;!_|%@#4tgwR?Md?p<^6w8=T%MsSWiN+n7tLJyaxtkn|&Q4v?g z5k!5}^e-w{5)w2V_35xSez1oi*w|PrSnK)en{R&l>G?HoNq1g(#_sIRcN4L&Be!F}qfGA#Q=sv~eHA*@<}sJ!e#g(w_2t=b0Oj+}}UXe@8S zKFIqjt(DlSaWJ+yGu%8K15feg&CS^IO2cvt(;(}^*ef$MJQZs;a@4n*D1%Oe;Q$K3 zDWh|essgC%zZ+_*p$W=n!izP9U2CRf#ikZ%?P_s-WqnZ~h0DJam4(uQ3C(v5M}cfa zyQ_UE)&SZO68@2>J?~SW9H`n@O|~?r&#f~i&`t>{2^M2|B8Y;Bs$%*5!{4nyTLk9{9z*gS@45+3_Fk>^lEFdL>8zVjOY#yP-;ox~u!$90eo^?OC0#rBO zeC@T@UUSnm*IaYM4L4l#IP~&;Pe08b^{MzdsxXoE0ER!0efQ}@x4d1ES#q>%oN5`O zV^^scQZc;&wq)rr?Q?+DR1VW@>RTQN8$@ zSR$pzCGqyR?Fn@7+cwsM5oJOI|6EDb!81S8(Rz>($ zb}BJyvATuH9$Gh}O-GuAgHe$`1~*)v8HD|!C==CruEokci(-- zwKv^#<&{_7aQ*d{-*?{?FTC^08=OU{M8&_w-7>JE%Pyu^_!&3vyXCG2p35uw^0jdW zi^c62Cw_Yodh^W}-+b`|l_j6Q`g!QQ*=pyln#68RK3mKFrfS^>aLckeur238y4%&-+16SIqEMLtQC%oZ zKq8T<-WB(Oi(Qh&9%V^%DPoh_>ruto`{CSWa$zEy3Vcixoi!lJBbQxzBPg3=>AeVB zJ-LG}m*0;^_2GU&R0%walF;M`0c8VFCbO9XKWpXCG;cJ{dsQ^>tj0ccNBpu3qAt#j z(B_;|X!>j3+G<|yjtyZ$%$oJ3m6q7_@R(x}3t#0#OPc`n^P@SJ?wzYrqW*_5h{MNNMe+5wq2klJ*}&spiBy zarZg)J_#fkeJOgKG1X#p&|e@WP56_s*n;|m#ccH==&OFVk5{953J>TDq6fmr9H{hX zAf}3o@U;X{2yrx!gPB^e7)g}vLI{+K5Tr9)eJq%knrgiXvK}F_02YyT`DItU@X8yX zeWzwm43l)m2`{=ZP>dAoyBKdYj?E}h_j{}V%$YAyfJXsRkVS%BvCcmKJPHWs%W0G5 zDopT$D6|nKNknyZDLgSz?PV2SCh7}0t!k=vUttq=aD{vDDo(<6~zk6 zLQ+PSW5KC&`&-I)KLIMQJ;(y7*VwwC_W*t(obLUQ^PlspPh z72iojA%)76@~HM22`Cnb>cz%W2>fc>JVuM%=q`2_23=;C8GBvix;-uq_evp@Nuj)C zKM{pxV3S$OqnwpvOH33@Y79tC)4%GpK25!VU&q(ynwRI7r!Wb%^hu~tT`cS#3j05GcXJB?1T#3##6U1S0=I2g8SY3im;vvzuv z{?cL}IzFr>?f&%qw_A5ouj&+kRk1ZsH(n@xj#n(6PUae{?39f+b8 z-Y`9(X~K;(3PeGDhp^_Nj~)yc9PC-^GlppuGcnOpuBUHhK-dS#L@j_RVNzBc5?AyS zVbSm80cZlo)hDAROzT0aqu+eiM5YSFc6UT;mKlX#6W3QJ=fL4IWhr zqL4=&ttW#L9>rwrA}RHf=Z9ccrXHC0Q zmu@tnh>0==Ox8+`n>Lm;I8qYOgoHgf6Af%qVd5&oVIrb13Vx7*I@E)>z0ucJ}%3K2eZ`&VcnR@7+BGzbt)|NKJg{h zEuMV+tq1P<^gDUyEEz4eN)e}rL{$tx4I#zGeBlvQyqgg3|DO!wx`5>@BI>8-&z>)~ zqvGl0RFA&-YqzjRsYLNgufHwQMjjP$b7i6t?TL1BDM!B8!9tg6HM-2^f!U3F^=nr% zQP1C70HU(24p`Izh-xyoQ`DDDQC~lzK6!J+cjmW`B!vUMUatUbK$E|nN0Y|($1}f~`OWa^0?7ZnqU;Ci5xq^F?xkdlfSTgpYFe{Jonkk6ziCVku`$Y z2_H$rzs)H*N$-gzg@~zK2q|9KHYZNC0MzBNP5jw~+0FhHTw}@E2G&wNK&lE0nTR+h z3P6da6o7)ECYF5h5VRW^A!dpsavW$Ch;~bt$sZK?Vov5#qz<}z{NQcReEsB0zW#aN zWRb*5imr~00#N6VQvDwe(k-Gp^6LjhH-F;l^{;;bLX`V*3x5D-sznv>rI$<|hEBLh zVf79hRXH?%$m%RN$F(CI>jP07n~)0JY9gNKNtaWad}W(L6Hju9BCoHGhP9b=tX>@u zL>*)sMMNAxB595n-$2?1==M0pP8kJlD&@FTMyaN-NsjRS4nb1%T!GeupXnmuK!6+oOEIm21 zcJ71cZvWbs-h_d#)K{!FjWpEg`7h6W>pVgVqk*_X6eJ2|`3ezM;K~y>*zx2yxCd9l zQ513;Fmh0y266z@|D2EtgyGT^tC9y4SlF|WiWrKa>Z&0=|2Q_vzr{U4RJdNOR}~2W zpn3+p7ePXQZy+gD2nK?oOsyuT?5TEZvvhiFg@`&mi~SNXQi%wA4<0=WQI{lY=>nnfk0mx&4Zi-H53}x}H0u>q?qc^OZQ;N2l1aRh4ud0K%OI+9 z)|gvvRxGwrQ%DQp|0w*vBpK#jw87EBAPS+0=R2W^{!LUlD>-sWdTYk03Zf7_-?@%* zkz!_c+Nhm=pGgp0hG`vh(hpQY+0GN(`7WjRU}2V zv*?sGMWxnALZs6h&MYol6bNMvJf_J9Q_jj7Ue=R2@1* zTu}`G&U2_$d*QzI7P_+iz*Bbw``{6yjYbhY0YTJ^xqsm(6GhSU!^hmn1TB+9fWgxqf6wHj z%`^$9T(q2nNpfjoi)BtaL}5dRUogQ=A18Rn`TO8`A{}L7T&*sJrMzAYt!q+vBb!+~ zu;3#_L`{&5N}AfK4(4=Ei5L7#fXW|_+ymgdw^mkHl2${ln0D=a*Sd)hAkv4pMp~)W0~u`TL9H||HRVL()}olc;@S0goH3#EusnqOGkMj#eKp76;33! zT7c`!-2m#VAPT{XD^w3JOyH$s&zd~r5ye_|Y*Y<4YA;ck)`1a(z`YUF+PVyZV(6tdFJ{J|fB)9_`EJiO#OXXK{-@7{Y#zqE@@P!rV7fp{!}-^H$Oei~Hz!-xY~_nE79dWHU7-TZc2; zG2q*wxHL_>5Bs9YsB5BOop-p}Q8Q;(qL%@1!PnFjLO(LEL5W+Uk8DCq4T1`zPS_@#cQgYL|$DPPjCkV4?=A zCk>ydW~s!vRCxs8ZA za@-?|4b)yMg@TD)ZXb>&TPc?+0TpAVf+$D6=O>8TPn|*?8|4c`RS=nA=a80(Nbl14 zIbBv#TD1aMmNvH!AR*+5(-{Klw&qTv!W8pM6^SP(O^zSv0Z}X;DGpQJDyGsR&AkQ3 zkcYSggx8mFY?P4W@!{f=g{wCn4D$Ke+h-X`oLvwGb^!Emn7W>ojZDfweA<&kj;CTc zY?yi_w-+cMJ47CedyN;ai7et08JYfgd3f58<1kV|DcFa%98Xdx%S2t7I^7y;;s4u; zw`N!LSS*>(Mbi-k-Lna2i%C$Su%@H5pO6xwI~4qLqZM8R(9bZ48(%~ef=sdoF;h?l zU?HJmjv!r()-R_z=YUCB}$I2it0d5+>#$U%A?UHUraoG{OVsTw-GEpKl z@rDbn2!K)^$`*^gnt?s&hh3tMA3uJAtO=Z1$38W$2%>DrY&JE`gor4JP9}IVz0{OP z6sM+`Deug-&pb**v58vSYotCovuIV0k+?riI}dCDur+6vDi;26v)d*cby(=&)vE|h zFj2CMCjwnU@Z^SNS#nCve4>2$I0g4m6`;+AK2bdaAI3vS%&7F~5;Gtie0;tbE-zE% z0fvL*67?VazFX@lODBb!82Ar+5F<+w!kSbfQ|u#U+!P!#k;3l;7Kt`q-37Mpc<0n#U-ZteeQe^$JQYYh;^>}BE>S2cpa?qb6fRxV^{pA5 zWpkK`nrI55C^At{6fMc`RyoN~v5x*m??ibg~PPHC~JKrR0 zJE9ZIcxb!SPOZJ~;M^QpC%)iK;8>na6jw}?p^OyPQ zu3?-LydcW=@r1mIV1h5lfRXlett9l^Px$L7{)h3$wNY5>$Yg-3(q0?2JPM3ic3%Kl5QF7hBwC@P|@bGmfPmC8keUR)SrIIX2 zC8Pk=h9y&cGGw3)3A=-MqeV>vx(c19AO>k$c!XSq{$iM|=fNesdW4&k{P>?gp_DJY zMBoIocBy*@VtrIK0SkpVpKGJWtDP!{s#MRy>+2#Pg^LbJ@l2`~qp%hBY1SLuULV^i43%X5(OMISh5LBfauA;@2M zxkHS6!k97Ke>|^`VW=sVR@B(D67oaiu9d1OHMMM3nU&p0xy-pfpPwE^AfXSgN?1$R zi}4;Yk0sjK$mM#_WH?HHxxQ{%~fn6j|f7R1p_qtcU@a>N*O^S8Yak5dIm4d07 z0=Sjod0Iyuz^-^AD(@_#Vt8=y3TV&KQ>bB9XzR1O(u%HzP(N# z61)SJO5Pp)-Z7ehs+;K3G`}!6w{PFv+;Ro?4(=BVDFO=b0aJO+lvCxjRECHuIV_*V zxJm40s?i9RUEX>TwZXv4H&6aOiV3;{$tl6RV_Y6#^LPSVyPQL|T)jO!##e}aKJk@+ zgAQN!h@eDlT+L{jPn2(?+dF2qDb+=>oZGZZ4}6oO^U}>X8RiDU<3(a`a@y%HNQtvg75qO_mx^_RiLybID)(U7t#$QO@|%b55J=A%RrVn@Aod^CQd+gCJ=7Z$#~t2vGQ4 z#DEtdgJO?oqhcUg$!dm@GWu^`M{#j_Fp=m}va*HfMPRRuy16O3(?yO7vue3)JzPYe ziLinZjyy^%5i=^uUiu5!Ix|s`j8az>+ngPl0#Qi{o^P(S`&Uvy>}V-+1qgn$L?9=E zl;Oj{mda&{qYhaad5J1Ti4;*R3{pbC#gXF4d#iJya#m8d?U<>ifXWaX4{&0ra8!*j zoR}5fRnN(5Lk>jn_g$JC_1gem-*A-=} z7_DzikB={qjoPi7~VPTVsmx-d5l1rS*)lG7bzq5+7nz%RuUbf$VB-> zksL%=K0>&=_k+EP>}1Uw3i>!iF$i0-Y-E*cWLIGy1T>=YT)3W&_DR{4h48twBNnl@ zJ0>v<0n&gZ1>^mF2GU6Jda+o;n0T}W6gj$tQc>U{Ch#E>MMp*nQ}{gJz(b3Abo|kq zt@dV1CG#!OpF@Rxfi$($3`L!ERGO|3LnVb4X^d`XdK$;@dJU;`%qk~mAp~LIs9djy zDQ!q#-Q@RqYbl$EG6@hu#J5r`7Z?*xNm;>nnoLwolgUa6b-SwN;HRb>qW<~Y`*I_& zTu$lxy-TnoE>RqrAdQ#O7^6S8+#Z){iCk%dC$5#n)|Z~Xqy(s7q$4@}Y<*#61+hLs zR6KEO2>oieq)5GrH-7T^&g?_Y#8v3x^Pcg#=V4KI&%N)v_?c5gl%7rHlvJ9+npn+x zKs~Viz~##hQ8v!pE0cy1p>>NFLf<8flDp%`PNIAX8^sR=;_N`EiT%MNCHf&$m(+#z zO~%pWpp~O}a|NdbLe5h0?g5n>?DnO!ROe1EM)t-kA}vANfE~K90rcEC6vuWJQ8f`J zYb8AWG+rLX;$EWSA|~z&_kB6$Xs>(-{V%)2&HY&4oT;+#(UyN=ms_4;-R?wI4sBT9oP;rG_uWse}ZCVp-5j zHaUVfq(Y9$Ws6x#NSW=Gc8MQg+9p*hw9F)|x8&NW9tnPB&I%^|?NNUGyfzJ&yEA}E zTLUyv7hHWB)Ag&y@UW4^{#o=wuM<|9428fIDVZ|+i#(z`qoxLuB}(C1&*EzqMrAOXFLab z?sH#GoA@sZq7<}Hi69P&{8r)e0}$cF2eR4_o#3WHKUn#}59s{wb5iZ8J7A;sA=bCg zi}cNSM0G$EOf?aO7{&-jf8}{f&Js0ww;LEMmsf2}acq=Kbz%YzHJs|E-f#qD}T+?7nfu%}jG6DcDJ>L`M+biz>-x6j>u(R7{ zwFGf{eL{B~^`FM9#VOk)8O5DM(Jg;(F@!?6o_I~SP<^g>L=9D|8#4S#AE;Oy71jl8 zV&ClV+tkr3*+N&;t@WZLBg=~pNW^y(FM(PmhR7hgbt__~UJ0vZ1!YKPzA@G=KoQy- zkNIn+ggrT|J!t{IrKF}!XJ4~$M@luf5YZE|T#K$ZN# z8l{|o6^qk|SwWVwcQk9;Vl4&hBV0dCb=5@~j<>kdYMN#w`%&`i5M@Gyl#0V;s%urQ zz3InjJN&)h{^i;=Q|($R))e+CB7{dl)M4zkLp3Wi#Y8o+9th7ZtBXa-ploOUcip_ z@@B4FYLr#P&qKAM6b?!CSaCy6q8c8{Agz+@j|9M$WS6jNru}OvO7WVd*+!d3q?1<0 zT4jZ86vs8`znz2gsZq2&C#+N&2VJ17jL-tFZDg&6o*2|H02XSdvp(GE(7d(v>N==0 z>iBA%ks_+dV1;p;61@#<+u;c(rb^XZcMd!O7{M60)TqG3X<`r(7&3*-6lCETm%n)9 zR}Wo(u(9qwQ+Z;pu4G(BZP47$D#Bk_qS1H(lYCU0?xI&*dV?MOYNwZ`k-eD`NA zTsHNstuJ7zKB%HoaT7p+C~*Z9NgpDuPmV zCaSlW^2JhLS^`nvsSxxH6ceSH{IZh?ij?EI88BL!fsHk_^$v|38m>}FCAg|mQ6Y1iDtiFUG%P(DAo{ta3}OsO5u? zzUw^?aQBv{BHnW!c*_0*_>Wm=jGP>+y63Lst`OR&NicBfjq2JQww`8R@ zPlF{EkRqZGKhNYa|09~r;Z;3`>-WF^gOxFn&6>iolc}al6trV^6eLb$*FhfJs1c;L zn5aujm+&uViKteyVVmg^XMsT!G~0k&pd_s_bMB+GuhXGOcz%o*h$5CetbCp28UH62 zqYhEAzWBmEXUiHDTdrYMus9BwOq=4q7b&rX;s=l zJX4dRJ7WyRtgI>_t@qy)mgCBFg%!<8DHVEejzzaZb!>BzYOx(e^|cDrp%Mp$C}L=4 zsp5ZA9nMIhuv9Omi`l$vRJ4rTM1Utw>&2cj8vc`P8$?kVQsYz!i`85UDvWFvWURf4 zGzQ3N8550Xa$G437Eb=#OohtUM#UY~0t%JIiUG9Nfz~?j4TaqTZee(f z!d|I00|7qB&`6*OB(Ml9IyubADG-JAjvy+WqTk2gg)@l}tZ1>`FMhGN=ZlmY$B)vO z3wUqj_1%WBF%JVdOqz%LS6Qr*@eM>M&xjWBXn+d$k;{mDnWmL*NUQJp!yi!APF`O> zh{7=ZTespv(=(lM%%MK`OqZzbd$>Cj%?#Qe8B1{&&Obx!_uX3Hc%cw&-p6msM56b7 z>b_5XF-LQe8zU=YPOp}Wo__7^;azr#Ixyf9^Y&#WBu0vG2F*Z`R2{F|0cPZM( zL{%(%#RgGJWTXI<4Fe^y(+8xa)aVCqM^l~K4;^)wVU_?5-^BqDX?))kRsA0t9Cz11 zJ$(V1vx4ElJOEz=HgKg)IENM%I*Y>_v=%^YSR%GK_|Db03=}odgc!9XKK4IkqG*ys zZyKY34MoC>F;nfF958a;-libN&14ld;aI30brGID%cNuwRZYVWlqR-!A1gEv88y{%6AxP&9&RiUYon|iM3qvRI@aPy z=ZrN)@F$WiH#S?TXgna{;Q@SNhg2>VZGkAZQG9lp(vi;4ZM&pXq>9VP1P**_H*trI z4d^20j~&68&U6P?oMu2+72DXfI?R_=gIP0h$FN8$#6Z!>Bg#%`Q6h>TJ0yr1Wg)D; z7%767m?Iail3}(Xd|SADbP_h|7Kk_g^7H{vH8(#{$x3iXB1p(3VJONNEFk(BO(3)e zBZ*Vjq6V~=-u%*+0tbNbBy2f^*9W2^_4Q6?V{oU9y7zfcf7(-?^1SE0{hp{&y%+xhrNTpXUyum{XHfj|EG@=;w_Juco>Qh@vs%+{b4KA#`_-p7lzxl;)e)AjL zp*(MQFHzvhBMPFaQA89BnIH=5!4i$~IdOcM>bUYK*eqCTCEu{8$ms)9K*~VKoLmu6^mdwC@5m7^E!!KH)=!SsV!{pu!dUWV z)F6}OXitaBoQ&{!wkl@<$WXnufk|6y=M|qQAcPt3WTaZ+!&tnME2qaxNXFHRp-{0T z=7BX3vcL>$vO2ky(y6h}T)sR~22mQ?G$S5n(?Tj4jTd!rrAYBWk+WF6B5@o`bJrRN zrb5moDkqt#bOS^+KondIo0h_M-c%i;ob9P5J8p0Wp$e?j@XWxBn?nIxqm-iGKxm^T zkn$y#Poln55S650rXVVuO}RkH0x1##*V{Lf$osk&Ncq6QtLymwiCF`)g( z!XgGQVLaUY@;HcstcmesUD8xjY>$|@|CMN8wvCYYh11w$aQ$1?@56-N5H&(LG2Gr~OEuq?A!)*N+HS`p%;Q762s9K2SI57V#jOycA-hlznIj=nVRI zIv3#T>WHJGEbv9f>*U(N9IDL>Ed|?EB*zeV(e@Cr;=+j(06{~ea<3m17d5ouf%7sx z7QsF>x;R_AFYo|J;H!f|(} zNifo4qJWYg@dHvsRKYg&T)sKm(3|#%j&adC{Jy-cvQK8)RA~d-VQK^i5uy?^)ynvE zXJfImhCK)acu`Q8aCjK;K`>XTs)DPEN0ucDkn&ox$0G`5Ok|_P#Uz9UQC2S-J2hM@ z5{Zbv*wpPu0#Uc^bKY1XybxG$^eOj(anbuxnGK?rseT(7Fdi-{L`(P+OZP*Uu56zI zzF!F?BG-$zMsJPRv7073aP-J+5c)EmIdlIfp7NX*zx~DNsk>B3p#oy+7p{(hi;-4~ zCWsSF-zPNnniK#~(dZ2#Dyx_v3e~P-?O(t;IRaQ0U7`-(A#9YN;Pq|P%;-4$RhOt) z)Jv30x&B@(1lX?A!&b1YiIJ5y5jEivewuUYPjgivS3Q9Q(NhKS> z|2~-tB-8BICPc8ZpVC)A%v(tLHp))NWwjJ9H|=z~iFlF;p7WO7&{Zv8hOsKK4~P?x zVz-RavR%`%fJlwgOylGQj-DJ~tl+wUDlE4)41^9X!wHHTxJ(f)xgNYkDAv=5^cGS8 zj^oF_!MU}1hlerYuNJPAH4ZKC4xo^Pb=3a3@wo$ooK~46$AjVGDf2tl3AD+c$O2c4 z6yEhK)C*VS`#VgII}D;OKI4@yd^QqNuUk?e zy?xvPik!D8coY4~x2?lwwNjXoMkTJ(L-&0VUZ1X(OJ%BdZD0L`%M%gx>j{qE zb(^qc=fb-^eWTQACtqhuSCMU8>PAr)U`kEgkFT8&J9d zmk+mg>G@B3>KmT?r035&L=8eX3*YYF0|oKk=>Z8VAR-DjO2rs|kaM$~vC6pNTmIOc z_bNnm-2o9@lUR2hTEJ%i>1q{t6?5r8V%%Ut{MsQelAb+38tLl|Wo0d6*Z)&3Z6sYs zTGKGX_4N;qcIw6J-t~{{vA6*^8tvxFh>ApIu^!qQ%H|Q&gN?d^ zS~BYNg~iWiy1c@%@+fj%H6?GB^=4_M05coZf^dYB5m^tWgJgE&P6wGR_<@`ls83Yd zHkqhR5LHMvk@GOsRAB@K4lB)ODV%wZ;G|ZnRKYg` z|8IBzQy-Dh;!Ytogbb?{L=R!3Rm3Pvt4u3Legv~2czt=BWzrSmTdRj&UsV~k_Y~QO z^0+AF$;n#|FWV#VZ{V9&=J#Pc{ZSI5gqOt*kAzX<{uS8#fsK&M(8SUSXrd9eG)Yqt z9i}WCX=9^y^62ClkEnZJ_d>M%{LOP-cic)zl5WGkv4tY<&(0z4K7e03cxdedXxR}} zLdLlPAXQVo_{AbJbgG_budjXL7k|YCmWq77d#Bu4A_u6=1VZN`cs}YSq*$YPL>;2K zQ?p|>rt{}|Jw*{A(+j!siq1rd=y?-Fp-KayTYLLSXvhns=3X)h)59#`hRG2h?dA%` zXONak_%9t8NJm5j0Z&h55Jd6AiNm|`#X$LhF=N;c;|pJ+-z3srM-kYdxW>uBLxD=g zUljTICh8ThvEI1d<}28H_;S}1eH3L7jmYCdXM_3F}yzX$@6Oi7>_j+@*1Uc zkuMkK_LIg)vzUa3XGWLmLt77p$TiCATDeTM`NRoknF7HU{ry`ZrIu36a-l?JNWo+# zOi|2aT$kCqgCE<^=xXVJ$mp`tLOfd_WlHfBY?P!n3rV#(5=*IeD{VC!t)_}pqSe+5 z&90rcEi4c~R0%a}wmro`VVJD0+H6~>t)Wr}6DLcyFzXr_B9ytTPp{3u6YNxL2I7M_ zgFoBQ`x4H3Qm7`IDg_m>U~4;}Za!Q665i0HSg0m3PXt==mO^ED%K^+d5ln!{rV#Ol+o*w@)j{!pcgiDQpxD zCW^&GwYLEj^rVHCoOLY_zqZ{@ZXRY#6Z?BSi4u{$1#Yw&C!+cnX_U?_|4zh?%an5? z#P{xUxbi;9;0=;EF?L5_ad*H0+F55_JUN}qpbKW%hzRQZVe#>tA|sQ7oZZQdj9jgU zjJ35leelbeHODey43j(lpqGUt)#+8zY%^yL%jjt{bRDHKs0703)Q5&d2k?h(+?wd6 zqC<{Lf+!=LHFKNkl@{fj`D4|VPGr=6klsQmc)OsSIhmk^1NJzj10~d#z*~&GW zxt6Nxn|Tnm0-`n%^lwR)skcna23o3~Q{frvR&#c&-Nisnq${b;W)nKY8!l+ zDa7gw&B8iJGpdWj)!O13&nc#qmVp#6T4rn*2^0iJKvbBs!K&Zgn1dG}N<5T`k=DpQ z@fAcNe1+ymUDHM_K?6u3`9@0&>~W6fvT#E?1BcG?Ad5+sSR=qEgvIjSl8;R^)QxIc z8y~mEr-v&-m_jglgl5AzHtIPq`wfOEJm-=7$2Ej4LJvKJNFQCPW+DQjYHE|}f6E9- zMC;YH^M}^fwQRaKuH*k{>ZuZC(NftVS-vJ;V@bKnapaFMrl*Tn@xJ{7yNL3k8a;#{ z3iYEEM3I*)IYrxO6HXIE5t(h2^Gp=f1yTBnD=e+AY;%X}H$3&OJI^`}AIIzXEO>IR z0F0Sppl-n%&b~R6T9cyqRUMj5#YB)?ICfLznW(#P5xUF!;EZdw&g`~afw&+PD+r`qZdu8=QANs@t-=`F0n~adEvbDlJ4o0YC3#!vp zJ67#%Y^)PkoGu=Y)DWv7#5fb|2`*&?4+~9A%NVdxS#tRVQD;HaJZ%j}GVTIYi1(Ab zOnok6c-)~xBq}Mgv9WN79YU(cIm>dLmq{XOyrS3FFfQZ}_8rYH&*L;NqUXDadiHaE z1ELCPNx{R<0#aYN54(pFhT1&_Yu%uF%W!@8=-Q~3kx+1^^;fFT0I-W z?A3BI7mUghMqg7IRs^L>RH7e@!XNFc*Wsf&BRQb5qheX7r$;BEl0guaFhNw=GC`E8 z$66H0P*PGfYnhRB#nNLiRs{r`@`ciPb8JPOSiQWB9k%bIIPx}L0XD!eO(0=5Y15NR z*({EpS3wv|)-c00y|^(<77Hf>P~k*@dBYHuN;qrd@tznFRRmFHHm{@zsVoz9>^Rlq zU{Og#wJ>-dxdtp2<814x_&nh}rZH;5YYdMb!hDE3Z$AgNL{<~)`sTP*mJyNiLS1Ma zNJJfUiF)5F;q|@j+0T8;Bg;+HTV@=ht}{^y@T*zfV;JSwNC2rYMkt*eIJ73``jaW! zn%}?w7*SlU}s#5CR&PFd-ptwsQ$-4{_q2@dGCAQ`qsC-4SzGxL5ESm<-h}@ zEp7!`V*dCu!Oyspj*4U1?GUwBp0#r5V!-aY|Gt*yjlu_p>kbG zgTvXFjhlyHdGtR>abCgoQnoIuNE|_)T383@SCN0El9iKwJo+_Fj=aBp!@XV@FIoVd2(KL-9TUuP^p~tS_B|O zRGNrVosx-Ewn#)RPc$)?^wgCLPkqCM5nU={{s_6Zyz81yOcuTG;Z77}Qm0F5cd^(x zGzg>h(MqM!tPoM$$&BBnagaP4^~k-?c_GF<{^r>)e5BiGt)z*lp8_ahqwsSPyt#Bg z`ZHaQ-5N=T*FJcDW_{-5V!A(`vgYS#x5+UKM?7{MVF~Dw3218enP-k2JC5Ss%HY`} zMAVw^_I=W0s&jHiQyrqZ6KyP6Nuv70wt4TNu7jzzAZmh$GFQ;YS^)LS(-%JRx3B); zK@^63{15MXF`7=%NXi$z|NVEo4HHq=$%Db#p(Fg^0iduC{8+KLsB%TFWr4?k2nY^1 z^gNER3S~kvdc0t=q$0~`t`sjK#>S!) z(V|hUXQhnWB8QC>xY9GYpco^c%-QW+5+oRihO3||-BK;R-|5m86Kj+{df>8JX^%7zRWD=3)h>Y_JKu!a!cT4Ds+ypUOqPLohia%*P2Q+Z zZy?Mz+@UlUxq%x7>@!7KH$W8pzP=oYa%u+Ytbi!&G@Rnz&4Q@1E@q>~M0*1$L5u5_ zgwkJB$V!MjLn5F`ZgntfEizH|q1$i2{U}5pA=o;=L^-j(d!F~o=RD`x&w0j+??L|# zCJH<`HtLJLhzZ%NkDyTL6Bk;jal<5xb6RTp{7kYRL7nBp2!9+qhCp5W7c3_mHGAen zmm2Yvav&LjYTxVIwJH9Ci<;W?h~h3vTskXeQ_+C7GWo;(cmTj4Zi5mDEhb9wP=qAy+fTEp z;H>?3oq@~8ejN_J<9zx*69q5A_06JEl;h{Pm&;^ist~{v9X3E!tS6DEqikTKZfw-D zNX){k$;_NYF29)7!Ul@qG)mY?61Fsj>u6|b)M>`7%Mt1SL+R%bPB*SAwQOkUdZ?ZW zYZWb}R$!VohO%%r$)$pZq3I3@aRP)p@G20#AGKPB!7x$+2N=qCI>a0QnT z!X2{>FGi75W<^$I%|h6nA~>jL0{U>27uV6_HNcGY1&m@?HtIF9Qb0>V_yF6Ykllop zqCHb(UD7FGES{ZQKy14XB&*}_E-7)Q$H~mbdpXw*6!28mi70hMEp918#^UHnh?4$T zXkj7~h(cG%6PKQco%q;_f6qO~P&6kML6i^?g%X#|?N2=Vw|D*Rn-@mpnx=%#-d>YC z=e1}YG1KwoWe|lZ`xx@VJJM0JqW{ZSYxDNWv-`zBwmp52pw78P6S+Q!Ji1ky@6ly} zGO|)=+N`9w9-YhjSavZfA>~5HO5yTb9((MM-}&Q@AA9f*AAj`a7_ltGW6FidaJ}HJ zcfbGrZ+-uZUJtlH6qR!!5V}9l8}Z^ql(G+T8rE(yZlUWQZ_dZ)4BzuV^0D$s3*gxj zu}djqOb?tqw-$_MuoM6~aPl(r4y7qs40@^>QPiViX&@U^@Ybnn5{yM42bTjxVKJ2o ztJz#4;dGWrm+b2L=RSu}1z;i{?q+cQGfUuz#Yk;sinS1kDrTx16{rgD5t1|m`U->_ zVD*8G#c5zg|24$6YsefInJP#Q2ZJeFld`rFtyd}=8{?LimbEfFP##d=DYm(?y0i+I zE-ihCXd;+g6ZOCayMpkbYMG6eWwjeCmJ`HCE2u{svAfM#q_c3+nr+;{dd*bHnXA~S zd9t)B-U=u!1j7o8H52S(qM}s{BVO0!tc<@#lR?xZ(n?LPBpqAbUWJWP;#7h`K4O0` zNTE}T_81jY4r}l*)g1Q_h8xJsE$lAqGZq^rs?e>76O)Z4qv=dWgZbOfM4|8Pi3#jF zq)9%H+)f+!TkPh0{~ ze$51c`owJe3U^~E6mCBPqQKIw(sOalbk0?pTqw&#*nyf*FXb!De} z(~T7(3fIrP97JJn*%SWo;M-sP2saO9y#;fR-~QqkGG4gv41RdtEADzV`Xs*k)$hLR zndtdEvKdRzEN7HV*!!ppG+QZLp_>VEf#WkD9!1^>^1fXFcLtTRP~0%$%Jdq!a5J@y zx)eyT2bjR>MUujbV#pbJaTI~;!1OdZcuG+Tqh5ffyH(d~A?z;+Q>|>U5A`IpIw_>{ zb|aU$apS(9BXajG%*rQDZYIbB$!BS=IM^3bhOTFd)r}9}byt_eh_% z1gwS^2`YZ}0G38Q-e9kSQO(p7il*l_Dwy{7K5D^6F;P&vYjq*qBcwpoiqscZkfNf-6RwS#vV$=xy(0D;j+}bwgG|(e4?gzw zuYU}SrvtZPRd)%(vX96jq%i#J#Z1;)-u!0f?UDOm_o`RD>K!M*e10UI#zWdY2mvMr z!nZzj_5mR?wv(MRH|d$~)rTrj2vAHepbgi1V!_%*wH^RUPIIKh^!c@!#Q{Y!t0(%L+&YwOpq-*;c)zMuab z&>#Q^5m|rsdD;QeedOTb?8vccf~X>h3Wq{)LhC|9;i0;uhYb}ZeSmPn4FsgBxZ#!6 zD8%Xd1-OD?EWXmgC^}?HAE;C}ER|*$Vc0X87?pEL>?r!8QWR;OkgX*hx95@Hm(si6lF`GZKisO?#tOmY#M zrPQ<_s)vX&riT%3UtCAcv8sdH9L=?7EiCzjliStK~z~Mu@8QVoFslml%YkA-N^1g9ec6vnp z_WF(cn5fS@{J>Y=_rAL?^heXtoH2Ok!rc6!MO0a5)#drauu)t=P7AIvCwQ4CET(ww&63!0n65;6bQ3vs5J$-^T5L_3!MILpjEte){at@} zj0WTV;SY~}%^lW?nf)}h|F*-+OP5H(Y!Ox%SxJDsnMRA>eK#2{bW1#OV(G-vRp=e> zU?@oLjVHm8_chlR{b#0F=r#qSXku$5fz3DZ+M>MRWn%)83=T@#3OI0gG|(f zAga4;-omGtE+u0f> zj>1OK%YuoLM`sonI|HbtH|ha|ny&x(S3jk2-*tEuy)f7-_x^*rMz0nCWKV8*^yq%f z=s6ihtdDKf2_kBYi4p=)7cZcH+Uo4sO5xm*vkM+jGoCsfI!0A)Od(cDZB+U~OT4r2 zQnzbY=8`>%S!uiJs4f!~h-Y;Y&8YwNOCJPFKYr{Fk9~dT2xMn?7senX6hl+{shvCo zlHS64Im{LGJ{-7#@xqBZlEU|W`m0{?j(4ElFXXv+EH+b)>AC9+@cZ{7g8;xsMRxBd31QKT0^DiXeEFc9#&Yx7}vN4!DCL9 zD_Y(}@!LEGOH5qCyouGzE3GXMMSw6=EMc-3CQtl5bm5aP{*Z~P%P9~=9V3S7zpvwf zQ0%7?PXtv>hH>&WyutFgngLhPAsijr@T7z`#>Xk|dGNNo-hJ0y?*>RNP4M*!PCLFbUxP0OH{YfGUn=AvP zSTQcnsPp4?GC}cRa{EwR6T=V`bsqH+@cJkKn2A%sf}75Qs51~%AsrZ(X1JDq818d1 z03$^i_Fs{W0#UIzwsc;4A_fOfGz+w$x_a{bxxqvG_YK5jQB#FiO3!e+JvOpy9d(iF z89-DackV0^HOfS}FhSEeraN<{li*!~Wol1&x->y<-|}EQMntt?#27OW)ik3~5JjmF zBI-|%J^0uY9((M;zkkgU!vxWdJGCEV-FXxt383YX1>N&z4C_bV00?Ii4e=-D9&y-u z70?1+OcRsh>m9iKJDPS=2%^%hT4xl-XT39>b@NehETTaKqKmZ-HslN=AXQVae?21) zgtO^*Z@5!I7ATWMZargcOw+^#4PFo07#?22IHXT(UqnCs?Ng=9bs|bILs0RBv^Vd> z=RNZO*$wRHAg`|&CYXkPKlJ-LE<@$K$uL-+er#4XEL#sgSbTV=JXDPGilfu@ThQl(cE3hlAmG{IZ%Qmni^`i9sn4g~r9g6@rbb zC|XgwvVHg64}bO1uYUFJC-rYKQ7{{$3*(Cm3l;nsX^sdd`mx|<^{IDtRapwGo8J0ee2c;a(CB12cU3Vhu4?Hnq>sD=d6iiW}zp5RN(ou z=T4rr_F1`{g7RA`-Xjlf_VR9`{>9k&z&4qealGqlo2-q^(%TdZrS(m$RySMgu9dF6 z6}3IttjLU;xS>=RIS$7zqGp?$WeRL6s8g961BsG35j_<-hlhBc6681{3MT$bPDCXd z|0ZfoG||uV{Mx=SJoWp&ecNsP+ju{Hp5OC({_H-;j_}O3nbf8LXF!<02MtlSiBh19 zD&q1bAWEva3{g_3dt#@?CKCP4zDT~DUqzI|Wr38~sNL6o|7X0uAOGtQe*h+1(4?x4 z8JCwb!xggFrs{sii|*TgPT4xHqJA0Gu|mhiE5vMx-P-Z|=PO!BIN=Gz-n^Qn4R^DJ z_z^q2)??XHsc*RGZF2gf{t#7wnnXhgpcG)~;v$if(P=U@-g1OS;^DroQ8dwoc^ZuP zn!V9bQb9$MTs&pri#aEX1=@%rd6~FQGuikRi|xcN%Y&x zLX<^gyy9c3Vi=eJtFA>ol&mYY2UuOXQW;~!;C*A`SN^`deBvA+)n!{HnKXQqYi1LrP=X+iPC=k`; zs7#dCjIAkGHcSUe{FKndK-<84FReHl64R-q#QK~*uRGvuaJwP5Mif9n)H4dH7=4ro z;KrGn5(--Eahx*dWZvfw_KYP+nNXq- zM9~*ghU2T(_rRaO^E-)5{Jw6ZY^n@eoZ!XyRvFw+U(8b*5vh>W#=QL_ACQK+ko8%( zs?mks{j=jWw2sS5(0c9r*8fU*x$|ebU+m8GYpnpq6VHtv|EU> zEzr}Mp{M=2Sx2$OD?~jBQQ)LN!BwLlqCkpeRKSIGvSnaWuBuG+2~CSvu3Q=a`-!Vp zKTBj>4U;W!x*I4xOl0Et-w#4mp0p70AXz~omS%xysn{6x6tgY|+rqq;;si#8DBzjw zpBaFt8DETP8to7jYx5O$b@0hDzaw1j73Xg9_MMtq?1)jf)sgR5^I*4lRg=0}pM0Q@ z?xP%p2CtZ@Z~sh)8t_6Cy+^ZMl?mL|@`mZ82Q+C`?Sm*h!zFKWdMiZr=A^xp%h7Dc z`89iv&c2nv1focIJr(HqnWX+(v@NV;GJz*m^qBBO<0P6LJaS@Rfp3@@{$WRHYbkQ_qlkZO= z6DBl)h{jZRdsD&LLXWn@H0qDFMDvy|qqcSI-ua9lD^b7s$3O2TibG%2g_+uTm@Y36 zWpeis!@MBtLmNPg0HLDwu(D-4gSNz&NmO2)Ldb$GV8Ud*xo)+92w|P7SUD(hjSg3= zVvZXm%y{W=*ejbD_1SMS1v_AoXH+8cuviFYCa#n-XfnTZTtlA&&AkDK-$m=!j@`Sd za_XIzdfj%7Y*dMo)5hd3pq^gFS$r~_w1gqk$elYU?{E`+qeBPw1aQ)Wth^vSG4` zQtwYp6+}rDG+J+pH{bpd^d9s9GaH4r)wkI#o2d`iUceTH3(K{`thk^{Wh|C0M=+48 z1SoWprY~{7&#a?F4IKF3vb1$scqS1Y=`zXmtc27g;13^s;DP0BAoRU&@M@;o`gJf508}@_YEd1 zmk30i0WNL%On)dEEcDN`T2zTBQ9k+&v&_PTrM#hFSQ;i!jR;P?u~0N2USXQXuR@dn zMHV-cpCb%`Y-kwu`zsRegOO(W>4uzX(#a<>Yj$qfUWj{}e8}4dQCFD*lArES8#MrW zC1n{iTuXbam4u*KGHSWq*2#p7BhHMb+}EuqIR{+AK@A72*} z)uKd2N(+bP4rLol2%wNZu0-W>0VRn;E=GOI6Lv~)vTfAzn60~fRj5*H zg|t`Kxm__KYLR9!rnx#`vCCb8tObeEOCS-ph|=dGRCD-StpwJ}!eq5d!`;?Uf$ZD1 zgzR4BCs|>UMUlz0dwY7eNsHusn-Ahb0}!R_D0TW^YI{2S-LOSwMbvM}PqxMHYaMkp zHAQH9Gg0o$tj}!Uo{6-$L-I~W(i=oA%_JbIoaimM?)P8Ocdudp#X@I z-9S4kAvOvvkaCj*DJU{F$`(MG>M`jf06S(5BFcxn^p6g@*cqmpX8I?FsDJ$CBJ=rG z7j3Nq3Zfo`DYaBEwPnl3!(e5GBX?8&yg`S*K^9rFRP@&B%pN3R>nxEBVuZ|Fpe22E zwMC?m)3#f->3a36-=sMx477Z+BUdR9)bmRZR*H?Jv4!ryHz8T>l1;?7LJLf*F~58H zh>Sm4Uf#3+K>s8qJnTU1+rEF>3@t57+(Mjc-;_u_KL-?d+bE+y*0K37IDL)Eo6EdS zQtHqs4Kide>atsvZeP6V#-^V6aFw_!Ur$k|+3{u-uneWEq%}u#*w6U3#3HNAU zVQS3TVEIECLKEe6<>~E}fbV-`04~wXWMKX($$$`*ho}tRUQ5vs)}X!zZzcBXv-AAa$%E>FUtKT8+I@L;1}M5woAukLXkA(q-cY{!LL92Yh$23 zD?sfQ!Q8kIHK;OS3AIo{6s;0+BUznay)#2obLF#YqOe;^luXA;>te0u^--noluBl) zgnsAP-+prOcaqollfS*SdzMUlA`ylx1DC<;PE!R=#3|55hyp20l?)wM^Ne8@wAOKs ziFje`HInRNS$Ce@gW-ZLq3g4NRgJ!5x8$&;@r>8L+Cj%EV$;EZG$~G!;v?ltY45Rt z6rH$CLL-U6ltM=$#57NcyGi6>Ix{dM*)?0Y^1d3Q2$9Kc2`O|J8`pyCr~&x3Pd#Z9 zWjlOa6e#<1cZ-a3$+E>yAh}S8vI0O9uuQN|AJ~YjAXTzKvU&QXET0y6Au&FU^}!eE zr1t6WFCUtnJGAjTkDQvoPSt^esGS{3RKzPi%<59EoSJr^z93zo7b_%@ zFbo7?u||uHVPb@>QTAe6TLmj;0DrKJ60Jfx*`7&|1jyW^XdBafqrRZpD2$XY-1qL? zkjeyBqRkDJup>??Y=gUVwzIptwLQvC^I*BFyl#4W!*o71fBMq#;}0DeXj>AZep^ZB z%LTkXVtfmJLzH-Z5TzMxdnP-!rKL42**=-+iS@Gt!Co$_b}>-gL&j|B#R&2~@tRM( z=Dlx!s}%U%R~@~_(*6f4L3Fxb7!(8+Ssexx5`4TB53ulF3IM9y!?a| z*OwY)-fDC$4aOiU947fyS>jNy&ngO1E{M8I@B>zuCbdrpoG?->q@GUS|J2{tPp~A? z0Uk#mJvDpc_BN2`9uOOq%D5oPqtZ@hJUFUk30PoG{3MwblV$q-$)8BrxI)tgmRWhH zBSKphDuD_U+jx4*Rwx z8M6_MO53DVEK#V8b(_H!+F{7{2^Fc=u#kVtTRu@EOsmEmZ7| zl8~@*`Xp$s_Ni1_7&){#>hY1&8=`PEi35mqQVyxyEB_~OOwpLQZqRf2^vpjNJ=1cwvn5E z1(|HU|7eW<$iZn7#jkwwk0x84mJ@Mg$=$g*;<4h5B)2=mu5>t{Hj2LFMZ7-xTu{$Z z%Gn&*Hj0H5D2ey?mp*=#6QX(mb$ql8gf)g~fg zXIhBj{sbtrYdX=93#`!pEn-E3ymd7XBo9@_hSKfrk%4q&ln}zY0(-n$=Z}B*XN(Sj zC@O!KPC!&fy*}m%Swa-55p^F#JwQxJ9QLIdplU;{t4E|OxTI_-DYOY%VofY z^o_LFTlJ>>He0$4!+>s)_CkWF^uc6?nkN2112#spkT+*?*t<{?A5L`Q3 z+d`}@k_iR{=sHT*Yg`yAMW5^-f~fwn=^uXGD9Qi5hT=2)$L>+I-+Y#>qqAgLjb+Bx z%)b1^TYyXHQmQon?+aT#Xoym(Y-14x=#E@ zZ-4tU?lWl_ST2Hv0+%C5HUd-pP)V?oAv<2OuzUGs3KVh0We}p&z}2&xo+~Vy4oGag zwJ#?FJ4+>}-zs*IB1`x@osXHS^tj9kT#2sz+*5+fQ;ww&f(@LBTsiZUHN?XDcCJLq)>|sfbRD!_7U0P5hWoSZNco6J60a16$Y&m`B z!Ub_u*t(t@u1HGY(5WFA!6{Hd)c#4lzC^<711VdrMs+XHTx#P%;7Sz1qXw--Q*9!N zP*gW%gQ>C?MB7N-in?hl=v(mnhlk#}2kjN2%Kg)Yp1^mX^3YK+8FdjPYIdeOXS;_o z?d^U~Ix|*Ymsu}F#paKH^k?6{bkBif^9N5X%`ZcgMka`vLzL`C@mq=YRcm&Q`}clTSdja!N)j+7%hd1+P>HDN^KTK3s;aD z-ts#7UrItHsu4y0V5u~GXmBt~<6*H(N#>K3v-xa+9E@Zt7%Y^fftwYQ7ULm{&Nf0+ zM%ACTg50A(g_-J~t`gN80Fiecp6lv+3`eCTCDl9ksrKx-GG3S@l!sF)2JA&|f6dEZ z{=qL?sObw|_`(N2_`dhO&p?I4t9bA*p93U={O2qtek)MtbGDNXu1zb>zCd%Hvpn6K5o7rIlo7(5q52j-Qb^D5(3?LvPz`!O$)L-;r^hA{@km9_e4~|7y zNIfl5pT4l=Lf81%DABFKxlyTSKYZ%K+tu@fs1tkl@5&S)s@+#JQmwax1zI(}_>!a5 zS(W;OW}O9DxB;Nmmt$R*SsYGe+S)V8wpe03kuHyA;+1f8^uf0>I?BA+m-FKpA&PZW z*yGT_zM&A#NO{cH!2eQmqP)H!p^2Tb>nx)#9lz)PWAj%(_0T*vsz+>;hpLZkq*+H< z3Q=!ekBJf+b#50$_uC9n^F#RIQx)KyCgYXi+{WQ2->73<3}9L5Krs(|*{3 zDo*JVxo$nvqsD|N-kuCj!V_EJB<2j#Kp`m2T0q4#x89ja&@nJs2o1Ew@cN|W&g-yr zVq^xfSqD%-ndv2tRL}JEu?8WkX}B8V(-jk2PE*65ltxrN{bLNU{bXXF(Yd|nkW9>a z&wI#)ecM~!@v)D6jOG;YeJ>aEK`hn>w8W;1J1GxG0m(m~?x;yn0H}^_r0DEgT4n{NYcR4PXegC+$?Q-DKE%VD zGoxLkB1xiBqb1fz6d?P&BVjq5Zjvi?FDq_6HX`k+IGaGKmVYiri^^PSX9Y{Zboohq zM642fO&H0>@Jh5X9`^v!TDP`SX!gY8$w<&;xl-w*00mK8iGR7+a80_1n*RrBSfYB$ zu_%u#2La?i;6#}3(--(@jj!wM5~w;SD!Izsrc>Lcla&zl={-VJELpH^)G7gzk!`f} z38I`T;||6l3lCY|!SdyFb0QgyB`OeAF8dc<{?S>yK8P|lYCMyVeD|q%Q*)>#S~Nse z*bST=Xb*>5gQJyo9_ar2=gF=xL`~xL2~iefzpF$&Xoyl9MZMs* z(}t)vX^J8o-63%VTie>|!%i5;5KQL!h+}Z`XptbVsJjD07rq1RHg{7UrfXFvbh&wk!ZUh*oX z>l2XmLAb(jovLcfDdB1((y$;jDOE%AiYL`k4Av}?hL>G9g@|l%aTqtf_{EM`kL~~j zUGZR2s>#zmyG{@wKiGC~8K89L4B3xi;%X$PkFdER1wObOfY`b4AjHBo#qq z&oUU+6KW(eT{F|aa(V5_+7=~B1xuF+Jm^f^MjhbZ=+Y=7GpO;X9TL9h)6#I02Q}X$ z#^VPDEwVOJp`hmV;rLOc8@2EYDbzD5eRr#7oPY^kSw!O}9)BEwR(pK%`1BVZeCwt) zg$ib!@34|fbj=QJ+56mw%v`ch?KwypAIW_!+A{vXF;xePPv{G|I%+axiEA89mQ(Z( z3S z^61e+tVQHcioKIe9?Zh0PEa&;?X^g&ICO7T$~XvTP(uHO3$|y-DBnk`gApa(&XW>$ zRBhE!VQfeclMA1kgRCh6yJLt*p<}B`a^-sxsSrc=0qN?I{oC3YXF(g~j#Qe`zC}D@ z${>mn!HA3?^PZsy(2pX(nsbC2)ufd#gx!9B2@?iOCVsro7jMyaBcJ=+%2Su6JZgAB zSdusEM*U%zHb>$*%f*Z=#4fS?AQ8ah2*qoHC~8W2Aqo>^P8WZ1k~1hkoiSeD8Qbp@ z^~tel%oNWO?_;0IASG9Q$)PJH`rqT*jIx=K8_weD9Aa_1Pl@8IpWO>l1&C4`^}hvA zdQq74CD*Fuk`SSXN3a|!Gz7`tDhpAW6a`#;LX?CiM69Fe@%q$Cdvm~QDGE^xrkI#6 zOeESH0#wtEO|z6D*q1nX&-^n#d-d_>-ha>h)#dr+X^l)ILLTaQ!_9PGYk@5v-S15i z_})E2)b9ODOV`y%%^RkS+?;i+Aj+0`9i3?duNi&ao2KS}j6jA7mw}d=EVK@XPsc@3 zOS!oQRBi#Mk72AmDl+&8o{tl-qpcE^wYy`2QX(%m9ne8oQUZ{ffGndTu1F(D5%Q{( z2fUalujk}fKMzTt|2$VkN-yX~U%JRu1y>U4dvxQ`LrjQF$dm^GYneUOYDwa?Ym%_H zgU#8qZ#HPX{C!_AVAVqIfc41H!Kt~Uhvzmz*kK_|mRP#J#9G0Z(uQydC0oRyEz_`& zJw#Y2g>MRnR%ZTzKm_*?cfj9R9HwGwaWRKen9m0B z3Q4f( z+Nel~$ZD{*A%&tAJzL|&NG+)kp3DQZK&ft_7WEk;1z8&HQ=;lm;G{%7xPJZY)Wj@5 zmRbJ&6a=k%#)BvBdB_;4BiN|&&YoBqq6|_4b$Z-#)L)yApGKf$z6eq7bS0FH`&b}W zGQAH>XZ)G0ztC-n+G~iKOhDAyre;^s9cU1ug3*b}^mv7Wnp7ZWLK7P{6lm@D_fJ98 zJ@+gfw26v(8|p;0H~Tc!x1mndk^R^x5}JFroj!ftHd4owB;m>vsysK<11$_^5XNH@~By^8#f+# z^j$yr<{-P9Nw&Pq_)LOxY}nc@UuaggW5*8AV!`zqyg@-VhKOeA|*qcrVOB6_5)(WYT6B`!^6WhH1;q{>}D*K*9huF66cSU(>?iTdoG<=s0o zLX^6FoaR98nrz6-C+!bJ_6Ie#QWbx((%?^qhLxxkjV~f3-vQKiC2A6{&-(5PE?Y3y zH0*;Ye(iX9O{UA&6vz3hl-Fn0V54^KTAF|VxyK)V=$?Csog1Piw-!9a%uALjj5kDW zC(aE~=l1RT6z`g+uU{t#aKnac4`07-4An1>Ap_NIcFHgXPimbwqce(C)PThYs@7(2 zYnw9^E`rpAtfEFUth0%7Do;fL3Zh12*o-tKCa)?OFcZSL_KS2iCGKEZMQByT%EE<# zN*3cS6l+x~t?k&TmG6A@JjjTN(xXn*k1js}QMWTDY@I)U^5nO^^`jsC;0HhW=9k#R zSj;7~6Wl>13&W-Qlo~G3deaUQ&%kP7wm!JMkaPNJ_)BKHx`ZN1M8Jr%N|!$K2|n$( zcI~rL%rry0&Y7)%CE@Xb24{d7=~Q^C`?^_1|5|cuYm0pPTd_(Sjt3&6i!Kw|D^+rV zAX#k0;#|qxVkzpDYD60CD@!F4L)OXCMFRBV;Wbeoq$nXQ69eM?Vg(~mB;GbWA#nyZ z5-*v!5r4_T11)W?*(fI^h!pH=m6S4NfU?zBJ0OYEQN)KrXOqjm~W z1+Ra|tfQ1Dc6gJ)zzRQ}QpsDCxyGTQKT}>)>5R5Jx!1~-u}W8Ye4;#gb?N=jKYr<< z=iVa=shW*)6E#oD4sSyfM74;G+8{*jId^TBZ2OgGA}w z+3F0Xh$e~(Dl^R33>TKx5;KG+ASx2@%S_tV>{w<%+NrI*_*G~^HF$WT`266>8wM!7 zs^F;x)Hi8)Oovv&C1!%9Y0m^-I{B*ywv;UPZi!~lCu*;PwR5_hUK}mwXSXn{6xq!! zB(G`X77krN6-Na&wIfJs-B+X8pn2{2d=y1d)H!VQmCKTmuf@-PaC^MA0 z1}&Yoyh2a15$xGwk*e;zm9>ZmMqNxEWh&e7LJ26uUxcKjZ0&_S9wIf;Xt*}ljT!i| zu?R|yxOox7UOb}w#t~SFEb2M1Na?LHF;bgRsTh@+5}}|;?lVyRWi?hBK4;@spJ+bne^( zCytzksM9<5?V^9eSzcW~{qXUheesKzuAi1Is#Q@6coL#`*s7Cc4uTf#%>Y8w(0htq z;Ze*}(MXw+x#0lyrK3;c+21x!tDf9#bqJAVzi)MOLY4KJ9(PsL5`x~>P zg@JZf2P+ppUnj~I-rboWT&#Ui14@Yc7J?`&l(sxJ8ve>xXo39AZyx;-o*V)A!z@(B zGl|FOo~URYTxQ}ny#aQPXRPw*VxmIZrL!OS&_|x}nip4t7>2Ccf(ydr>iDz(bwn(a z>@^uN2RDV$l;I`!f>A^bIk{ zfy#yen@ZgB@)Io*68B3GPkxdfr?;U=)#3?}zAeHwsh7tiuG2Llykt4bDd9ly3McuX z!H{OWgYoSVZ)u*21lu`G{1hPRnXWcFaQkmP1i z5%nH^n6G(nJ&=L0T39Z}rzG=r>42fBNu>rvWREj!vEmUnfHn_L4fe_8am&x1(b~1n zNZ;aGnT#zrw?(#R5Vue4lI3SfiJc2X7zgZ#dStiPiT~krdx_OVSFl@P0ZJM-1Ss4+ zh8Fv^Dj&9xAnk4Nmr&RrPePb0knZgWC{U>64>bnzDg3}HPn^}`&JuZ1%|pb6uIaOBAw+j{@JAVs0#o} z)<`Uv>52GS$17^13K?(fCRs=6LWN(G|AYnvK85o6UI*|1}Hk&tA>OIXx7GCbHh zQ6AeqxxDl+Ih&WBHGj|2Rnq6vhNvdoMZ7+@5Y^CfxJDGUtDic3{a%Rrz}cHO@BQ_! zcf9HBi_X3BIWK$NN8f$?`04Avq{}!onL}j46Y{XJ!aTKdV4mvBC|1D)*9Y1*?cAN0 zq52SoB*=$8Y5Hkr-9F><+4q{flGkdsc;!_c^9=}50F{me!XB@i^)+`uc2tS-J}EXz ziMa!)FFp06i?+81PKGBKv2BzZDWQsIJ~BXwz9l;Ut@E-#yCFKygFs=|;&9P5OkO5_ z;qo%I7i=6Gos~nQgl{4K{=P35v>f}F5754fo*?>7a;}~!&?ILQ-%dCbk1PbJ2P#IR z4dGm|#Vc={{_Nl!gLel<1L*`rC0TfB=phh}>vT1Www-=oQ#2|gq1@CoA+~Z|q!>XH zN25glP+B=^l-E%!7{{V%yIV)p-xv=00~jrcnn@d?U<%G6uDk^IAG58LVxeR+f6RGbF#KyYTjg3zVP(;)gGqHjDDU^7K5nxyMPR0^K zRJcZzjf&^#tay z%G!kt0|Rm`zJXSEWpvH>n#|aSos(?we)wm{pLO5>xw4bxbfAFO2T=_W6>>DFjXJ7C zAv!HU6gKLGZ{9&E#_?OX-t@+gy!rXhdBF?refZM#>mYTYYNKF@VUh}zdVac?GB`yI zPWpjD=4)mbl2@r%L4yofDJ+vd5S`x;GhCdl$3!)xOm!;{TV772MDOx&TUvs^Nr@vc+%YHw#t6qa_z@AWGci z6}kz?&a@1`+INB$W{hbyf-K5<-}9l5yvA{?|5&rwSy5A+Bparx!eLo9c{~l#QkaQW zUiNSoMq%kN!G4ByS$>B__BmA_gz+p1DTKL(thgs!a(Z#&qb_;3(snQbj14HMU5az? zDyM(Nr?Jwohd!)TD!YVcN1_Z-vl|2`C2D%CQXnlS>ZRtB{|dR)$a8EQX5itd z+nq`|vZE8@_dPJaf$oT>kAL_QSrddNt|qEP4Pc`JtfPqe8Lw~6e<13^Kf47{&;P*L z9WQ+KtM5I1>H05EKYSgp&<Cf2V&aUdZm+KO`rP^fOBTD=g}8cj>+TaxU^X{(ti zVd}9Q&n4bFLpl(E;ju=>)3a5BOlCYBV*$q&O^e$Rx42jEW`wAKw~6$&%f?1=>O(Em zk54{%S%9i8u#^ZS7K*^ckBp6y*n}D>Ow^z{eTFE$ZWG1ttO;{)N>*T8?%rWxCLFZCIt6F~;cfMiB|i2dy+3rUK~bQKIC- zG{q)(AUC_TeF!9CF$Q-@O+%wBgTkQH>~a^z3Lj7Y92b3 zg)Nz$M989b;+6u7dGdZ`fDVoBa8Yw}bBD+{^qHb z-~5;jsL$JzTebL6hxsBj+%*5q7dMnKdH8b7;<;6@+s=HW@s~k~-YdALs2XHK(TbC0kZ&cN>l-Ezoed6DI)@jM z`h9{?F$*o=6AxNKR3J|2QbS8K0AllVGLN7HNJ-AT&;(0q>=N%fL1D`!3oUZbS|mf( zsL_&2khR>HEg~@pp^%KZA^*4+x33oM3r8(iKDKoxO0-Xq!b+*mC{i|53mjZ?91OtP zI{!F=D2+6H#uxE1D_3Kh1bq@=vrRA~}Fhn&7QBH_*LsWeog@bbK^l6B?wd4Il|}4qEk#Rh@tI z(W6u36)k3Sc}GJ#HBLr~RWr}32Cs+gZxTM@Y~acaBz`D-S4jddZdU}BbmvZOP6Qtg zY{Che3R}(IQckn1nd2fQA|+@NoY?thgI7(Be1;EGp%5*wBz2Foh}GfXO5Bx4sZqj> zCO6Iw zE532l77~zIPYsd2MMlX~xoe12*{naC$R~pX_wO@A6^c!QIOpBb244PO-d^p|(w9h4 zhv*6!qIwKb_u=$y(7Fg}*QfCXeK=IU7V|%nZHz}34pF=wB)sEy6Fy(Rrm}833#m&V z{h5X)u3nkUq=T76ji?5PufYdVcC7EL67`B(w?2GaT)vNDqn`cjH@)`WdtdPS(;8IY z&-@!ij%BNz`YVtbe4?E4!j4LiY&+20d`$W3rNdZ^Y^|EIg~zfowo6MKT>N;65{jOk`L;!z8|4G zh~ivjqKwmL+bFYxeDMc(eYr}e_~?z==WK^kF35y3Of=(B2g9l2LeXv3$p9s4DY6wN zX2vKfDmAt^S!RM0w3OrlQ*pPOj!6{H_2ev;OT0NXCi}!L8Os#0L@u>eh?Q2T)#Iy1 zP)S1|e9@>;amA{tq69d^f=T*z(1l&w97wT{a@C2Vii##p&QLM?TX+I0d7R-|SJ5Ji z&cB&|JBc3<#fog+ASEX13IWe8L)~MUaD*N2EvHV+c8yeY{xZ`jq=4aYs5Cg*dHBM_ z_wv)R$#Nl9$YP_Qfy-)n?5pbO44L`uT)cg`UT*!KXnB0A5ak+$sP6l4`Zg$1d#Bfx zV`WSJYaC9HVo#K^nP_nC86Wsa#^(!%TQdApD}{CU?VQ|y`okan8GF3E`R^C6529L$ z!A8Q(vQ1I*`pD}OqIMXf-f-#Ctv6tsZr!`%_{U#%@2yw777K-qdgn}Ui1#|T53!-` z^SGTR0jY|S@FXiKg=?lBn1F}6BuuxpBSy?G300Z0w)Q1gHkbk_5_FB0=9Mgyu)&2B z8Ow+GBLFHAL@qH=gy0v4{bHh;zI5?+E5be$1q|oe^*vv=9yV{f9aVSxK+3>mnc7)LrnpO6t*n+~h09u*4pXcN9=I>rl3_B75LM(R zb+CmPF9o=j0&!_IfmMp|BM{34JNz^V|4Ero}VMQ|a*C6^H857C6n z03N&A8e9?cRkBbPiJ>2D~U;-cri!aVIZ7m zAtmrguz^L7u}eu~+xRdQb>c6v5u%x^fnAF`PCc^A?SwmTFcOp;p^33fBomSSbswINY)KWLjQd+Nf4+6|Lo;rFqcbGUmmq3-=kn5} z4_~@O_m*RA5YKB$ELu6j{h7dg2B4a`vHkp(wV6D=88zcOC(`hY=lKNq?bKq)5VY;ql zDPuhNoRMKFZ3$5Um+@J+%bY?~%Td-eX5;8H7taq8j0iNMek-04P!Z8_|6i90RL)r?sWDK?#HbPWR)(w(0 zEC{Veih<-1CH$21sESXpYlUecngI?(086f5nq1pDQE?)wNh{z0(*LWfCFie01T$mY35BD;J6erttB`^P`oa!=3ca?;4FP4s}m- zk2vGG&bd?XI{ZjCy|{N4dTgTH9RHOm-yP2eB^xQ8yo(ixN~NP2Y}5nvfF5mWn0xCQ zoIa|Uwr|Jl8(RqHBFsy1d*acxQHKMfo{C3%UU=))8#`K@jEfo_q0V(|9kU0PuD}2B zhaS5Bn71uoPQ|cMS;>@*#~XM@rxLnJiNZ!{^jwHy33dGVuK|jQysy9ag)e;Jy)S&z z!w=*1ZF}c|W7RaFugivG*bGB64?VWUI#4=A+8xr+L<2+-POxDTQ**!l+FmZrENvq@ zRkUBQLKr9hl-9iDkuN;`9X|ih7WWL-wn^@4A7nrK_BiPh388c;rcz zFa`!YoUSz0lKLciZhL(kt4!2+(P|5&iR(Ame{E!Mx{t`bsl&3hiY^Z1z$keF)wPp5 zUK}Lch32~GJSQUyvw@`SdYh#s$`xfVzByWyZpGMfV}B5SUSnE_N?WXW_#|n3$r3eG z(N?*k6drr#ZT$t}hQUUy6d`Dp_%ltBupB&ZE=731tP#bG15Mo$k}GeAo6U&+-QVvyHcspY90WwX0`mgYAjbB7r!I=ZQAB3tY_b!w>7<8_S^ zpg4SCQ$9uociviT^4d_`6{E1_yX&PgSOrVfzStKkC+K3LHtK;yc-Yr4*S!Xym}|aw z=RUe3m90o1#D3D+(#qPkYdz$Wll#B*CixD#+no-dx7^u9i_~@F4@~a=<)?_AgTg>h zxg(~rK8W)B8{`K~?uktlHtHrsiGiZs9?l*!u3!J^H@$Gj^RGSp@ab)c5+u!M)h+yZ zp@;dmwwM*r3sFd~{Bk}?V8RoHC}W^(s(#5aug5CEki;;y>K`CfVXX{R%%DTtP)CQ> zOu2d_9YB!EF)7^LBvY~;g(&pZ8((?yiAR2XD0~u^uO^!(qm!SpcX+W&kOWhANBT~# zA_{ysAgZsgwvvND^aLtJjO zk`ZFm>r4ARp$Il3tJBWlOw#coEuY8H0tPcE0h6t78{f+7}Du|O3#{|YHgfs)^80gm>UMQ6C%X+%DjLxKF1P^-=XT|??j4L4JbJ~RG6rsM2->bc5FbWrBS+P&FeZz^x8Sm`V_Ia-lDf99|5} zT?8gUit|pgRv9dZ_{uKplU-yI%?eS}5)ac6Rf@qDR@^I_iS)Uo16@+@Z*79q2TBoF zG6GLX!Vgj^4MpiffXFHCpFc_&T0ZDD6v31rWeb>uGcD2$bJOFLyVojFHL<;}f1iz% zRCTb+m!6sFP@*h`i3w53lAod+kwV0kpT6Rx-CvN?K^R!pFt|TWh&)VIQqMg=Y)>>a z+BZ16aVj}mI$>C_@w?)(259Bxrv8*Ee6e z0~19fR2l5@W&#%CZlwntY^zgl0#eG9GnJOIKbj|`LahT75U0ez)WoZ8>EbjrNOT2%wM)1EtBf5T(g%-#M?_v1gvZ z+dFyrn>J9Q)seW9ETdM3Ccufq5M?7})=``_!Oge&h9gC)DBkts8wRB6wa%6OS=i#) z;SMi!k(dWeLe%KuBJcEUjV6*D+1%zvE1eu2B=T8|BT1WZV*w;5Hp{*eKV{N@ViAdx z7n73NN2PQt?PN)9jRf*erAaO=Zh5xlc0{FG!`$&6Pn4|N#yU@tFpBHR#TG<0S~D|g z;oXxYjzL=l|0f6WDLebY^+uS)08TyU|A zO}9fs1kmRWO?7rnkucF!$rcMEN9SmR)7{^{AFnUHNa2@lq>$~<*@XG(2lCZFvTc;g zn;rFM3YI^W7)uLLsfxRKZg$P~2iC1wPcKtuNsO+SKBxF~v4tc#JIT) z=d;!AACY9QS@LCfEy-;=fDfNm8|BYBuu&m@gKkd{nXqjX3#ro&zW}rJ!X2-C{_}V2 zcoW+3rdPiC1J{TdbZl)+k-ynU@=6t`22M?EaQomDd2^XOt0-MoskU`kUII}S3b4k> z^q4O1q+3KfHPbe5K*<`o3#yp|Z7F}8cjZDT)@Hs~V~^KL7NvS5U`U$?UxPoIDn(|BY$ zUq~!=4$TH|Dk$lvSJW(b==kVFZfdq`Shgh(y=x;jDi2XR^XWcW8XMiojUM{SK%|d5 zV-g&;X(OCg9EmGY`LS(1tfQ(#jgbN`4TaW}^Qq|vwE%L>dJaTaZstmmPO)z{83{q6 zEx4%J#<{79Lh5@;6gPe#6AUJjevM2-{cP_xa1S=Ov(p7pNQpYK;~FHLyGHgjSY7+H zlqkICoOJ2IJkh-htx!@>6`qM+8nhn47b#Z8%N3I~n#?D7YK?Yw({O?&6Vk^SrxmWI zwK)rEVi+xi;Zk7CaiC+O>}Vy<6wkG_nLR1J5G=IK8ZnAAODV~`eT+@cg)DglQ5ibC zcIxO4eskl-%_f`iqh2n?=T#E{;h=IsF^cvSwT|Sky*iH+<(v2S?&P3_w>^)Br!Swc|eB0 zI~BlBA2~FocksHgiLTK^SLehc!GD))iZ&fv68+mI%l+v-CyT$j+{irLX|t;M7`$x0 z=r6Y`br^C+53YX6@HD2Q9rp7|!vs&XLjHc+~m&ITLmCSYXHl(QAUGrAc zz>fwll<^8zN)~#cFxlUM&1!=xxIz#$=C{b`4rbcO^t)STYYMfQ-D3KT#4#0tu>5!z z4$lo2H$J*D_nj|2@q-!+s#=7gCOg(=N6#f;LYTTUcuq#25`}KB61j-O9a*RpiZ{ST zk-D2B`?c6K2T_QMNzJzFiKG#KGMj)ZL|PVbk^7L$jm?(ZTbjbys6;-~j>#}$(=^Ki(hU#G7{E8;Doff&lCL1W!qC|aR8Z1UTAv?k2w-cowBcz>J7YUn!cqC5 zWWqeFEDGBYb&|9_osUi2VY<^SO@uQn7;p2o#QQ|Ic*`*-@pil=>QBZ?j2iz4U!U){ z?ZaSr`9)3i{ajku4m&_!{d~Tk@8^PzT44l0&qhJitFTZ%Cz7rTeYiew=fihzet98C z2e>bC$qlIbWd8>#_fMNCuZL+7nTVKb=ZIIn_~76|ZMJ$z8X>K$U7fjdiYA%5+t?^! zO9CxhB08v1m^^nujMmaSYSo}owbDjjnXaDxaD=O_mJ*Hd5GAUfL6+b16x}=5n+JQ_ zU-;E$ze$ur>8N=^d{P6YiL%#Gwvp-(1(iJ;#btYa-(OD~Z7ZF55n{9+<49v>>t|na zl%R>OTXMA(SZySTWpMhsh6;p0i!}Z6$h0?9wkR%5^J-Z-pAQh5IHIm+XA{*SNRGoy**JN@GQHu;Tll+y>fD47RUYnZT~1Zve$0IU z8NooUUX-S1MYWt#Vk(WyC=^Q|t1WuPsmAxZP|`$Vqs+Wd6{(fxSwam71|toX)~AVj z`!7C>x2K5u$cLYP#Ak%8XTD6ciCe(~V3PA)UlgW>#5(D3!lS0iij9IIcV8zbSb0cQfmktP%Zt9V8>m z=#P}PA3h{D@ggw;QtGfWN01UkuwWV}+v}6N4U{IzPCM^~!nN1OpwqC`F6^?wdvx8@ zT{{VCJ)r*TXzKxhoM835`8*QF|FHKcIrW&2_3h1OhBxVGpHZJXv$lG}M|X}&UZv!RabSJY(shIk zY+pES)l;-R(_oFm7P0lwNi3FhzgOcWzz#=iOja+B zDzA@LFka@vQ4^{(G%`44jwzzH7S7Bi=f*+kFi(%MrQE^mH&$!GT+NDwV>yf#*@8A# zwtjJlE3#$MiHH}z3ACshU+2`qhg+{;@-~+)^hTakM$)p`CgD+l7p20#Z)fC`6t< z?Q{bK`pO$Ac7ZqAan)i4oKV0O2D6-B@|E2xIPT-Kvb)-a$*HMQ5hYY z_>%q}PRJ)G683_(ZW%6&6_$-nPeHe%&dP~PK(c{4LewCkt7q?#GI94_xmBHDUnGD> z%iHA=%RtkVc@Utsn2eR_a*vHlh6pvKbBk+2l#!0hE*f9>1fp!S)ce3DN^TO87<8_0 zN;}2%cp};#r9@W|mBvO&F#)-4`#{vPDq~f|Sjg#b)6P z0#>JIGQ9?^OfmpbF3FdUlfgoyCd{v=Se(4nA?oShfBDOgx?So%_BuodNI?6%bVKrf zjXw1P6ptVM;x~rme^*(2)wya2jqr3j*ezi~?h)@)tX`ctRb-5CY;NJ!6(L9AVcU zl^_53*Nz``cq)UI0tzu3P@a4{o+tERBGysZCl1vGDxTvYSW#I{J2sl@1?jfJt38ab zGO>7O&hH_x>y&XX;gBi`&@X#sOxzOtlU9FWn<6l=?UMj%#Mfy`+ty}@1DXzenkYor z7Md_o5rLGGtD}x>@}6L!?EX9FBxmCNuRed}{F^QZmW`Uk7Au>5}K7N+=q zO|uYAq}N&3%-vW!qlijNG68xVr{gwCT{Rx^lKl;&+er90k z;Gml&q9PLmUTU?5N4zfF4BZBbaZuCVsa&c$wnA6^`ww$ov)JM2sK$FnYh`P7Yf6X; zlvNC))^P>}t>?~M>}1XMMC;pIXO_G^5@f>cjyP03v6Ou9N1{kX4Q*gO{)WP?M5Z4; z`0Wcwfh9!QUfr_BEV57WgDuC<^~Xf6M{0BiXxRTcwr&QLqAENN_KR981;zKxlTubnwCmse3fS@ zc>TnyuSi>F?pUe`Grzyj@M=1WZP7M`4V6S6wmuw8TC_>6x7t&4t7jHjN5#{_(}Txt z6gq07IBlY|*i1Q{*%s@xSK%!sLAGNw+()fI?xOPgGOVED*=9B#Va*xQTL4l{JGj5E z4ey{^zAFwodHKTm%BUDD*+(p!yoEhv0F0Y5cNQ+8SORHll0lo0@PQ(s)=fIA*>YAZl5Tw+0l1%Etp{U z0jg-n2~XkzI)_4JYE%AD-LU3VM_ob_MKL{Iy^@N(acWP`)}dTnn<&&-Mt%1>t`mL=EBxXZz3r>X zmln)gb!>L_)acCCYRsD~TIO7!nz~$Mi#3%`u3o%q#wPq356$wljv{sZLyeNEG7{?) zDeP=B^k{Fnz_%ieKxqI_SYOZA7B5O<;`#LO@=l{9jcTGJPKTaa22fhPtVlGiZqu+$ z{~@|B)KjTey}bCIBz@?kc|}x+{h>xt&%$H|&Fti;M9+!5ef{>+U%&T>XCBE$)Z1V2 zy0<*dg6b1Q{66pqqUeMqME!~5cNnQJerAO21~M+-*emGt`6GQ^aRZan;=fLd#V7K& zG?gD88$ER;M}VkSl~iB!M4%?sHMwH0mKRKj3e=1G)Al-x*dTfLYI^D_?t=0M$;7x2 zagP-Ixafs2-X8hvdV|ZBR6s_$WN8tw3WW>1Z5%?nzS5)|u67#V`c|{qF;cjK-3=*S zI`}wH)ElxLm9{eR7t}iH@0qD@ep7(@0qZE#qe@^hg(pEP|2+HDwpF?s8;MYa>&wYU zi0bF^Lf>FqdZSCXlZm7RxAPMh784HD%bcoDVsPT=$vdj@)H+TckD4rvlp-cwB5ebf zQaF66EJuT$Vn>N0*e65mNX&&)!$_!LrHVK{jLp5Ux|$EQ6P}dii%JF-^9Dj2aaV$2X{sNWtXi~jQf~;PB(N*x=0&7>dPSgeYO^M14+x z`u-1oY!d}e#3qnpstr#pqzbWb=f5puhlQZEE|-LXxnW)nw6`6}6_5EVK~6#tD7m1G$O zQA)>&Iw>fDG*SDswfpWRwVo#qeQNU34cuDhqE)M-W4!+8FqV&$M{Cv=fwe1F#^wE@ zwz&G-V*Wn+)^2B|TL4ywty+&^&p>$g5}hdrn_zxfrIDMIMCzs@N5*FXC3ABCvX zU;CsODWr+&8}K5c51OdHA$K3|kwF0WlH)hfkFV-mni?A)n?2P^1bsr(j7^j_Nym)T z3P12*S=LdhV(*h(+zz>jDzK^BQ&mYfbIRx~%7v0-K&jGs1V@|-C~goWIPp}e+sR(Rlall^R0hx5<5BzXR%Qkt6hLi*P)>a0DvBRjuOi%B8B{PB;! z^@Csk__q*c{fOBWsAr>o#Dz?0fRd(7Kwfm?>WxKjm~AL)tK2ue6b$fbGY3&R3>0X@ zrJ-(;o|L&c8L#Rbk;)ti>2=%1b{)OL&K`|-*Bc@j$^sKMif24sPBr|&$8D6Hd=2uD zf(aq2uS--fE8_5DmnP1x`V>)kD)iu^B>qjWmdRqTUYVR7TU}-Q(aKq@@fobi3$UCU zAHy__%LKm^VXW%b;@Uf;K+4tj?e~n7!ik$LJAF@oB-60yB(<@*xwm(AXFW_ZypJVx zD6{u)b9p{67bjIC7l5cWh@zpua>=UD*s>jzl#+Ue?;4D+B8<3Td~Ml#AI>QlD=dhrO6O(WwCHAjI^8z=!fR5)s_K&|#vEx_ig%lkTG-Ptg87)#&^_v-$w$6hsleEt^(8SF7??F5X67 zRs%DP9b-IyYB|g6WiJ1YcaYc@XeS^FooJ&pQk)|4zC#wo_C*S!7b zuX_8NfBxv{XYPF9_FEY#K;Luk@NfR~C%ul6onB|KPuJsUqKNekc!VgAUdd7J;~T~i z%xj_;>E|E6u8DerY-6;twnf&J5Y<}gp=QV0ZKSlu$0s3+3}6%c;Ih;>W;YC(r%#0;~5Mx6pamwHyA(sHnRq|u~vXZ=$$QNg_E>8%9LEL zw!IyNxZB2xo9LV0!R7nx4}bgPAOH22hrGVFNh%J@tX;t}h8N$vmSyJ@mOZ!uCoDMHNf(gcBLNiY9E60t$6m(m>J6zoLlJ7Y9f| z6kjO8#snUwci=ctCkM@iDem&FzJKoCPku@(^Y7hfuIvY|$i`>&9jh{5B}gmTncD=M z%DF1*<26YFZ=L5AUc54zG#8(PsEOwjOZzraFm+tLyv70d!N$W)aN69Me*?z)fbH(| z&i2D5nc7m`oQoUNen%)$E7MeV&6iFaL7A+Tk-6Fxt5nJo!b_2OZqa0FNV>L$8yT}v zabc(=JIJ?ADsLtfWa>{S;>BGM<2m4?=e%VG;}P)?JI*le=0}UHpDqbfr*41!!|#9V z+g|_XH^2GkZ+^|wZ+;|66Stqa_UPWtdl#Q|4}a}XfBK{jOh6P}L;zQ%OsLSrum_?b z)j2J{`A(ysp}|^_l#KB!IDPRt%cw&{O+J~Z)mkoyw-fLem5s9h*j{hxOS2_-T`_Zu z6SO<^XIog@qB}ww{u(>-vOVy8+E1m)i1>C~I=C)Zm!~O?B@PW4&t!EK%P=C1@n??H zZiiDQy0R6%-rQ5MchC|+RDXZl^f&FAcsn-H8(E-&5-`^WMiHp;S@I&7nm#z{5r zk~Ac+m`~nXsQISVi&o==Bn`l^8%+RIBA-mMMXA~yLX>7IY40})9%0@kqiL3V|-EC~_J*!(d ze*1x1ttNfFm^3{zc70V+Q(JF3PiFf0(W&y{8CA}a>=30);Ss9bw!kU6{_x=r1H3lo zL&VAtPCKJiUTtRM{nCcSEX@1L4B6;+gdEjXygoCUZm0c*kN0`$0_x8!W2nX;s?6Ik zRkBWy>SGdK+85toervka%%%gr2s`27ptBHn1-%f3R~T6j_-kfxZmMq(qO>rTj5vfS zJ)YzC``0FK)2{miuYb)4o_^*7OniQ3a`M{stDku8;{M?2gFkhQ6w9d7bhHg;!cN{F z_;L_MBTlz8I|~X?-R9*(ODRksHY%7%#78fEU2K#F;`lmBe^6Yjc>!NVUdii{pc?CZpSRlDo(%@g8LI6J){RRo-An9h&6EsV|`|nM)99 zj|6d$ol|yksz0BW#o{6*#wT zl~E5Gm2V!5&c(4Eu*Mi9R_b5AE)~@4iwtcx(5qa^n1(ieodp zBhr{%{ap^MR9DbyBwh9t~10?C`D8}E!EO#na1khXtu<9r)s%m z(ns5q;DDOAn_IAI7DN^Gr}S}D$S?YWRe2$02|x0#d=@5LB5FEA0Y9aw?a#>vgB0L5|ffu!Qx{{v&E!tt|eutw9I0nibt>A%|#UVQM^4pD9L`Z_W}iBsPY zK-nVk5;W5FWULYs_oB0l&rK&US|Or+Nnb39;731bsK7whKz_3+C@E=oZ(PL7p(C+Z zHc`cd&u1^Ag6iTUh~f<=8Fu$|)x*ffY2fj&M4uKP-r}O*evw-s}`$q!z1~p0~yy)Fc67OY`yQo+WXfM={!@7BO^|KrO1zo zs{+9bK|DcPI*=|Qy;@kE2K%!+*#bWngE_>ZLNrWWJg+HuBBde9zGfv;iTUD@?*Al~ zdC48!8NYO?PRwui&Qni4C7T93y!+ZyPu-bR`@SG>{S!Ce@eV4mqX%CTiHRcY=pAb8 zu9FqDGsNOq&uQsnedwEJ+gVmpk*FimmuVG8A$9!L#S2$wugjNHl$@-|8?^~vt(FhO zFDs&slQgM0>qad!Q3->-Cpm`Ej~1<=Qfqu{yk*Yit7?B6v2j=xvXCicwM|mGlRkV~_N~7lbSVe~{HfizXMp z{p`bEsY1iOvku~XLX^5e(qW#IjmoQ46g<&l3_J?uc+f1d=(S(P9irMs0*HJ$BdOK# z^(4~glL@NLrp(laB*hYEszX$2G?i6HFEXKTEklS(bcnJYzhrP~e<_h<9o3Od5<2el zp+0@^WFMDLkh*&@7V95roNX0V5>G5fa3Wv!O_Nt&o*F7hcrS19_IKq?=U@H3b}-}z zCuO6a58U0Kwu!Qt>W&u}aPB^Q;UPS2?;2RA17{?fX*_t)OoP+Bj8h1EhC!Vlo3HH} zO8A|@iSm{rs*oP=j2P`yLwm&FOA;v!wy^w>KH{5!xO>POvi6#3*;pWm9B~%1VV^5C zI#!Maq|TzST%s_gY8exWTtr-RFBZfT3{jTb9KSTf*b&SWs~lAj!h{y6lG|%P^whO$ zcfeqrSERLG_zeY8=pgJ01R!d?;?G#kNYX2zzCkLcc!7rd#6OWYk8sG_S7{W-u1}sC zUATGihDsmoczq{wHG2aOu4b9xc*`d0#Ff{$jt@dqAmh))ir{+%KY}^0t#Z=kkJU$& z##CvhE^w=|n`i=7#^l~^)1Mnh!Re5cE~5VOn{rq+GfG4ASUl*K^_BukCk}ZR3!fb1&Q3NI>#S%BJW6C0R8)X#{ux%6yat5Qw z@X7KMC;li=oKM)-RUm086ZKAIq;ADrv?V(WQKLdsJT5u1W~{G33fxe_vTE!}S(l5< zL4VVmzL#Zb6U~>CSJxI3nZ>*3I!M_}$y*>sidD=(Y4ZUzJ=orzXO0i4@zMFchYuUO z^b7^2bjIZz7PH}w#O2rQ9}4>;!HKo&7jC?7EfJ47OVT%oh+oADI0usnIvxj%s1&{! z8|zl4bdcWL+X(Xmp_!Y{ohV;!H2pqTg#p3Ik)i1Bawc3@-e8AUa)D$7G~w-FsYG#d z=nc)$$@f2dmyI~)F2DarwQ7BK{M0o})oWk-UIbP^B}pW_B4rb!Lcfi5@;S|s>0p(L zkya`gTN0uuUYsUK;R9Chu++-C8L`)FjE`QLJT)ss%|g@(Hp&KO^u|`wsBW1?`iPC1 zeEf0JemcHVt|oG(D`&QZsAS)A3v{H0CuvEfk#`D}-zY@MiAG82saS#*GDXrM#Rxh^ z2&FL+B@;?pRadLEzb z$@(%FrlMXebz~DYF6StJWFJU9upxECMggm?r-S zpg`&_K(SgmOMiWNLmP_+@+7>N`K4$klN|JyYpi&4RWf+wHFv%hBoRDcK67JrF_Dkm zJ@?Wvq7XZ=p3EjGWLT(*439N@^pD;lbe>Ticnh>>iwyTkudp-?1+CpQd!s|~Ij1jS zUSC*y-x_5jJF0)qMk(fB8j6gBj58B~px0vjZ{ zEa_WvCpIec{Z?~>ba^Aj1Y00n3=V$g$caAV??3Hrnq$_i-#hQ+8Z=AR&vi2@>VU+<}EgAiEj_4Y%NJdP-PBUR@{{-n}=c- zOH>3%U=XwrJ3y7DHd;u*rEQcQ?CUAdDL~~rP!*8m5ml^_V3k#`49=K3!!!k9OIk=o zGd_r-SC)49M9M-%Lk)gI90-7p$o@=LU05fO;#oc0P#aP0# ziBsJUsfQjuAMeuSOWeErBLf3cI4jGjIz40=&pqH5 zV&=uG5EYB>i`%E`#Jd*CEoLXP_uwHo5h+0Yx3^%I$*`;>S_-2?sX@u%ACqoX z^W}`jk(r2}zVZGVjcF+gdF|yEXtjz6OU3dG>9s#gf2%D;2eBBmk3o1vioHtQth?jnB`$o+&+yKkJ=GTb^OA*o(-n5zRN^?@=Omeh!@}<#^#cb%%nR; zC-l;nEXxm3nR$<#sih zfKrlSK+4;bIDy*_O_frKaau$t7{8DX^`+B6&v0Ct%B}@m@n&|{pH$VzZoDfa$uf!w zo)ORK-OZg1KX1nYGfhh1uG+^-)y+A)>|Dl`&1U>oqiMSE1xJE`oPTa^VQyqv%G5gT ziv}F6@l%SZm%WVJ%eDC6-sLNq-&g z<13?PEt1doyV(08-Ew#&TO6}|@rpla*6S(g;Y5>iaiCeORu?WFkbabFrb=g} zIBp%klR_+xSD}(zc$4&qyb;UFv4%|hJz~V{sKwpx5$TM}cOt3R_KWG4$+nfGw-?VUGn-#)J?R;?U7^6bcgIvn>**?fVrE znBSBy_xc9qB=Sd8|9T~u%6|0m?)bmo2MgCsZvxO?ZL(^)6CBkY-Yz~mSD9R zU5b~D!I8KWst)=#3hm`e+mUV-rM+aW8o|zc(&dX+*J9+A-I`LVOd{MpFTE??08ZZn zs7A)`XJm*c=pq!cw^5KlIlkRId<=RpP8(P!)tnP6CM_{S&Y{TgK(u15LX=4zXGUfn zsC2CeaW!|Gb=3Z}r?j)#$YAS3gx8&pa78)B%T^}Go9l?bo!Tg*mmABpa|;ur_Y({= zB5_|JNY+2I2bISQ&8=~j zYby{{oQ{xMRmL4Rc>k+wTx`v12|T!d96Zxt=_i;jwy`EA%6N2fS!p31!!S*jT9ll- zCECVlFTdX`r|tN<&S~lhqPlGLU^9*nD7*uUZ+yF9wfpBDup}tI=cfTAB zz(}%lL)4;4@_AZDtU@VLq3P)M3lBCiP&>OW>Td}O8O;YToL!gRfpK_Bhu!3AyRc4~ zHh{^FQ#h>hup)!}8~)`+t7VqOM$P#%BrXO*@u6*6i+9~opk!M%T{4`r%~}6{(v)R@GoNIBGFx1EAq!dwv!Z5!;aP{HVWf>Ya(~! z?#n<5j6eyT-l?GyX~sGWEr#~}s8+{kx~v3PLwpImVk<*gs5T!tTsD#z(!30XDMbtl1 zBd0#XqB^4$pHx_*r?WL9%i`V^VXe5`MJ7c!)-!D15?s)kOL`?)T!-Kk9SghZ{ z4x=N<2ixJjv)^?`5&8ZBX z!Kv1aOH&EY$OL&w8DD?gPf&DNhd3$qY|V;|+Q&=G-4dW|X`r}lDcp#P-cw`|8f2ZN z0vI@ha=(0DL8e<@q_Tu|0BVvh6E}ZyeU>C7Hl#!+VseGVyj%HNEe2742PO_Q&c(e* zXfVk1d{%0|`o%_B{7ie149H?#EmjM2 zRi?v~5pSC@KhA(#6;YCAs#V32NsJQ?f?gVk(`>czW#m?X9a=1n~lJdMMTj z)5K!Q@W6PVbGIa>390#)A)#pmyX7uqi92>Ho(2#Kt{ZWr29Z0Yd>g(^P5`<`6 zhbYJ8(aBH0bnZuIH)2E2_5u`gJI)gVC%NmtL<~cs?$7;&*kE<`+BLh)bX1O^qw71#m{1MA?ibEqzH6iz;`} zgDK(_s5Hgdp^DSN2~UUAOX(Auo@Zwlafd18_JwilQq6L$z94zc`{mh7`!DgT(L`nZ z5JWU8ra)2`JfZnkLlM>G74r{byqd3@8sZ?m+?2&F|gczW=@Z4E?5;m*FMlCn!}43MnmZq6*u*3rjEfN+o;# zek=B#2@|58cj)r=%0t2F!PyeCbc_Rc#J}^x3!Cc&y^Bj#jYCB)hI}RF;&(FeRXLaw z7@4is+}Yl4N-kCdtqY%Y$94B-~ z*(l0qri3V?Nv!YA$!Y2eCXPvL6ei8L5%$I6AvB*VJ2m|Z%V7U_~XUrs1K6RCrBi(67BgJ6S3{9Ha8V!mM zIT_nf3M6QJzIAbNb#*b>4pJyjuNzmT@$hW35F%@jbyz`y>J3%h%ycjkP$=&uZz8?C z*UT`%#23Nc!{1|QfT#Zrj!1=6Fe4qMDv#_N=YS?^0I%=%b1%KL&o7B}AD+`PSsA3%3#r<(Vx^XOETH6RoGH`?V)oIpT!qtvDc3i-GxU&d-9lVOFRmCG?}FsNEHae9^% zQ6)S+rJm1cZ||nl+zMK8>6MH9C|LPvqW2eXEKPR{TJbT%CDng#Bolf}v`ubF{Jg7T z>XR2eQh*u+}i?nT`V5u8^a|DB8okGayDrC!< zVbli65>kIuugKd@#--a~I3pq_QjZRd2~o_jSs{hN%(P?lzcl^PLZq-Mv4|HQWF`C= zia5hf7E{X^aDpd#yhez?cl$26>~A27?ZFX`R)9%$J;;{gp`cWyX131Y^~DlxhS%ZG zH6L#8v<-fk8M+c1r3N%*oANtN8$=_pUOO9^67F7{e?AzYV3+3fUcA)d(@a?PRRT$| zQ2}Ei$b^l{XyFclqX&B?5^J46SB6puAMq1M16W;ZFUp@ zP7;J&JGDZAr4+@_g;T8)fYO%9Mr(X!t2$>?g(&g*VngNP?4-i^g%9r>6f zvwTQx@D?Q$nAL|kecS~x3|1;F&6?V=bgP+VICHkSvs~F|G=u9>YGby^ATA@w$_rV3 zAuH%~JSJXDtlvA&^(XXmBoDn$j5tTs>FEA-LMvyr?Gt*`Iw z>|&l|tBb0rXq>nTWmZPJVg~y>Z%Cg$umaeqyf2WvHRV2iS`+2&5G8ZiyF@*KCpk`7 zR&|fV(x73q-U(NCYfsJIzI*rPr!Sr<+Qov$?NpIV7aW$Qn4{TxvW+Tgj(SX?t!lv7 z@VnAGIAyK)khL;9D?{C?RdN-zjjGR#%^U%TL;hU zj{G;=wN89}oh+xP2a-H`iK37~7K_m9&yQX?9C#1k8T zEziks9L}SE5?$(>tDT`f7#kJDJY`8VGUj*Nu8@&wO6-E9*^TvdIEZ^U-@wz`-Pvoh z)iocD2z9PpoGq2c4wJB=%tbyOu?#~I#Uv-UM-e6AO9w>#HKm(#qv{Cv|X;O$v zhBy3yw6anDp*loeV8c$$uhSsSsNZza zeE)7EE325I$^k3#yXj0KBHqr0$#NW#=SfuAcBW%Y)E$e|ee36gE>AXj_KWCWdGR~d z7w&TC`3IPs48p(oC(h$W)qd3KLfj!-LDczic6@WL=ZLmTFRoHx_Xgy)Og26 zJ#)-Z={rPS&-u2bgtyf?^-qZ;q;l2pvyWZw5S1;?jxAh#?#ztZkHY-ap{YJQBTxRJ zW`wA4xNVuab}`inx6AF2vg6sj)El3%YGqB#RH0RQ%VV18<1r= z{;&VA4!rI_ZSFm5<-CtgCtx5YJ#3IP+d$%Hq(cWR3|-56JEe4LZ?DaIEhOoEVLX(u8gbQO};VjDjUwfTT}uc8CJ3PT=XC zFMrvcrzRysmP`dz!~P6B*$82m^aq@1<^75%(nMNUx_@}GB&(0JTusK8{e}=Vy5s62 zWukhEfxWXrRH_a~!qeiCo#F5f$_8a_vUyaCkkd?=Y51t*1>RUNZg5YVpr4 z8x1+a8xp7(?@9%+^&fNRbo^icVI8;!1Jb5>E1xh6;N%Js>I0`HYS5QOm4y*3U(T#= zZ)ejqGAH|-Ryu{a!5(k9&hD#eQM6jE=9~r6oC30r$|NQ}{i%CPZks3u2?$ZoLX?j6 zovaQ=$aep1r|%>ib?qs^X_Di3F)q=)$37~)|I$RFRx=G6x12x`r@oEL$>VIfo=9i? zhSeIyM!EW^H>|OadX7|zvHL}a#703B!N0ggLwwzDt$}%x zu)7OSZ#}cTy}gc?N4U>#?lRsXO587En$_|a32!D%aci+bKP?{HY8{oB`|_9naL((o ziJF{$(DZrQ)Mk&ys%ia&c9F()Wi${)IV58)g_WwAH_xylnBLzs7i6{F{0E1 zC)TG;VOfTda06bHMpLcUj*)5<4YQ{SdRZzIg#UkK|2rj%rZ6#udnTMX1BL@ zps7K))(WVpT=UJ%o!#BW_D*Jg9-e&ZHoH$`dNC``NS00V602%z6qQVaA>!!xdBmKy`^4+p>aXh^n_nXCZ2se2wzd!mVWXg$Egbyb1(prhcN0s>>}4O?5#^ z*(iw0$LlI%qJxuq${|Xn%y!xkqFNfKQ9%l#b|6Yn5(!8)P|{b>@qhh?Mazf)Hfq(( zCvxj-Q^^8~BHnn&mkdSwGkbgD?w!rDzm5agZ)T`NP10sI$Vh3Q&m@-yl%(RPHj|%r zd+6^KPWs5}oBO;X%6)_=yuMznPhA|Sn>_Jkv}_}FB2X_s_ogehZLyb3TGx(PEQm@b zRl%Y1`tF=Wl@6fm#w{})qLv}*RI4y}etg^{)qDHb-;2-3<1$kVDE_XEs?RE#xIq_h zMadXMxw0uc5wKHK1y*Q0h0kD^rL>AJrsROAMk}$?kf%Lizij;%+o=B;5!^G&4Ee?D z3pDnK?-AVF4f~`5+P}dNk4$!Rd!1aP{>VX``t~;E@Pk8rOH=3W(l)vrD`TSoDi^Db z<-Oz$8a~cYCTb`f=aWBtC1#sSG12+5q>kC3u z(mZ(`rSGzc;=)uh#nERiheO%cC=FZE1DA{AdAIT6UmM}L0A&XsPF_cW65>Wtuep^s z@+xJ5z=X0<@*oFi$3|t?^lP`%8EXD}K3<~{-J`(raTQM{%5&)UfBjqZH}=jpwymp- z{XQnVCXSCOsS_tpuL?^Fk4kq<6WJ*lRVXv>TlCBhCao)Ihq zYQREvYvS=DG#WIZEovGPrjF67qb~s}R+f%YUQ|R;B=~?(VMF47o@4tYcHDM@ZVd6i z*Y{pKUB+mBd7kr}=S58*^nLhYczuD9aFxZ%&0ZHx<3d?fEm0Y*YC58O9s~h(U6Xqx z@8(U6sAIRIKq(kOxBXO#5tZ{JdckY!D?( z6dhe996sE+jp_~*h-xbx1SZ||$c_Vh$H%5;eEz~@cN-5eHmVy_Brr9=QYPdkQ6LB?H4g6CB8!1`ee z7Ga~Z8k+SLW|e#~B=9L0v}&0dD^8WTl0wn{1)|l(37#j{ZJee(;(E+kg# zpy1rD`B=F=xuX&b8+H9O9(xCp=_0JrV>XzG zuvnkZgWuK&a0F~b)N{|hMAlCbTyj; zQrmVw0;r9bQ#(NtKXQGA6gGH4lp`1giKrhc?FwU7E%DT_Q_+G}bEuea7>=$bDiW+l zac|Z85n6P^@jvJF-Dd#_8QI6LQ_hXiXL%8fC>DEC%r-eaI-1o=Q&VBqEXV6H*HF6{ zk!jLC3P?ey$H1DZJD+;zu_F(UVc1Uv;BkhO84EAPV&wZY>d1LZC+=r6j8Wr(u^`IEmffZgGjXTx{YE z`Cn@{AnF#AUWZI3sb(>3q!P-Wf(OPA?~e@nyb8KXWD6Dee2St=aQ6x*23EY*9zF{n z2f(tUAQ91XBzhlyVqy&ObGB2NpZ0H0<_go;)(SX5)F3139nT&6DXpUfQIs>W*6G91 zVW33Y2_|8pgppeNz=?Wamz|}3odB6YX20*=jqy*;NQ0=mczw|_Le}#uB^hhVtjlFn z%CK0$)XH+jMQsp0wjhdBIZYfTz|b}52ak`PJY_;j%^VoZ;oIlal?$V8JEbGxqzi~b zSHFOUF3v?k6s(Yh%yY4TqU-;3^!&cYCO}js9(S8a=H|^zAJC&@MhPHJ@frOA_KDk^ zwQT71Ws;gB7-ZvaWGTB8E+jEqRMS-?o4aeXnyMjM4w`U4K#H!+`DA6-!I7b%fFrPH zPrx_)5jk1L4rp>Zp`O z<9Hb^U(KUdlZA83=gcw^NMcTNLRLpJay=AeG4BveNWtNc6!LfgRKnwXBw#2#RC6ldIj1o;8Cp-{QjueQB3Zh`1_)XXFjKqXnvf)ptsrK?4~q>_a)*H!aul3OMdzo}Ia2BLcH z8zn7Ds@n#l4l}P$N?>Jx4XI!ONt(JdfMQ0H0m6-9h7GTe5!EBrFeF8_@CF%s5W27r zIgwk7b(DX&ov7T72@v(vF<7aeiVfa7#risGr9>p6dFNz7$B3wP5JkmXf`;?NOL+Gm z_Mn7!Fo1bNck=l9GL_Z&Sna~f6dI{IYv^-mjE%0Y&dO$3sA?TYrCv;9rw%n`iey$C zWWB8xbP?P$lp7exlNwZkspexJZSbn7XIH)OIht)zMM{%idv%N zi-(dwiew8*MM*DZ;wMTYiR!bNYQ@cM6hP>d>_sbl-lkbmRkPP-PRwFWtQakJFCc=5 zCi46G`PQn zxif$K^(+7Q`#(;Y(mE>D)nZtxOx5byslt-4ymT&E)b#XdH5L2O`?85*qB@$WU(}P) z%F%2zvCDlYug`1m^-Yh%Mhz;e7pdipC)wU>wFIn8)C_|jxP_v}=2ln6(A%r_0;cBY zh_HKYcAL-n#Lu34u8pV(gd`q;vfRCd7xjC|>dFP}^tqL#_zkbO7L(9bN?%zm0w}WtvjopiQD-yBBx?cz zu0~593#z}-k1>(Nq-cv07)<3H+GMssBc+Ha%wb993z<+hGP64XqQ(>i4HLRbX-uR> zfqWQyUbTc7nSV-{(BVfEnO|kRYw;r@6I>6z<=0X710-Rs8%6(i2Gk#a{l_zB$m>h! z_*0VXKN*W^t_%vF<(4b@tsPkleE6-LX^?c zvo$!wY}Bx%E8s~}Yz894Mxi}BPNqh@kGwvJ@Up13o*vZ#S@|Eu&F*qqY?6EYXRuKp zX%S`X<3s@|VWap3w>F+yEu2L(y&ug}c&8~ab_rnrPvarj(K(nm2d zW3;F*m5WbLWzxkZ)C7(eUkr{WmX^|)sU>ZGv{?7)Q&Z*cL_uiy9GRKe4I3pXk)S4d zEZo@Ow=Kk25;E{B;e%U`W&}~zhU^By&hK%K$m8QrwGovgqM#O0L=wMudVPdZn~Ca3 zKo^e>edg)DwUvTvi{Ts3;t@m*It$Z2zoVU~W)~%N{Hm|4r1jsf&Zn=w_~MIK&z?AO z@zT=D(&ftlD$RPzyL3%sohZ#{9VcP@CWeDz?u@b5Rm|F)y_?iY)MLQ4^Z0!z!pI}_ zLGkVO`NB_2!KcgEznd9!ATmButhjVN8Ro@P;btgNrK7;{v zP!wW7al9ZtSm(cDl~p>$e8 zH9bU&-OZYvjz95zB1(9Dj3^G2AW9T<;OL@G8`UyWYxMR%y>Ebs>L}U(7OV{EQVMPL@Lw4YA z0E;TgWTP&NhThq_Zj+=ys!UGaK$NER@E);jn&_aX$Kx9u38rQS$FRY>JBabCrbMxk zQGtuFQEDQgr}HVD1>#%FsG?+40s*hlW>&KpslXO;p(xe#;-EkFzf{F>pZ=#Cxq)Jj zAWC6GQH&f1Ma?-y>^-{^LTI)O;Rz(+Mt{WI-9~LvrzbuP8)b&MF}Be0TGnkrHJ?11 z1qdNT7&G)Fq+V-}uZ0u+Q*IeN`Nzi_L~U=_C|XCoU1Z6M>~qeP&;}7d0hAz0@#J>`t+ME_>0wImgFE5hU2P zP03EX-@#HQ0watlx6`b+B+5R5VQPuB?Ter_Y9<`i${a{K%0-)RvWj7?S?s*SBzk4N zP(&l|$ud-=AmD$;HqU>v;PEj7g$FC%WnusXqOdrZxyZt})jCv#@P=u!@v73NNq5&+ zpVivCNtu2aL^;f}TP%h>R`mL9ETixsn8FK}-k6I|GO)PZ379B^(2dO3qh*!Fi%NMv zh?csqz{S)QCF~z5=4Em!$t|Uh}u1_?1}=SHY)`m?djEX zYHek;GPn8C^|_Oe3V|ztb?y48Z8?S7kJiY?WkmTI?;P1Xo+w`j}@7#84lS{mC_ zHpv`-{Qe351lg!}v=arbuQwDA_hO^guv&=jN{6JPCb$EmHh;0|pCVmGBF!l&!^RQiSEwRN4!m&<1_FA)*S(fv7yY z)6_ zbb#%2DYNbcduZ9z z(-U@Ku80X!6RZYIyEM2YH)c4{IRU6(qksT1Wf@Y4Omq?@s(4%4c)M4qy;rmF`fk6Q zXc0hljD8mnJ5g{rJUz49rZO9~=1WmlSXea$_lU1b_)+f_b!6LrcohXD7=0KEG zU__0`1mC7TTwdc)syqI%L6h@~J!vKCA_aLQih^BHBu5g_>|aKiEX{x9(3 z{xei_K$r@bKQuG(&;~?_4lZ;OP5i(Kp4yla7_HsqMFY&8?;7C6fpmPaqZ*fg&fo9g zL@BnTlLLY^9GLW5I=4C%JG-)S_0)^6UOx$-KopSTdXydb2p6FiSl6#%l~tJ7giGwqFnNbgj&OO$>|KJ%*sjz6Nah@DHDYc_~5nyBC4F< zGr5*1d_-80$YfOw_n`k$qV5Qo_1_J~izSqC4N!)xWQteMYxBioZEBZ!Em1`^sn+#i z^}}cNiZWG{(nUs;uX;D4`WF`Z-G$+gfv7-X&z3C=B7kGiWrPl8EE9|{M-9jsH*0%vqtxJd6mr-P+niqlBLj&&y z9Q`OM_%YVy*#l?x}%e*4>hKFRSpi9-N| z8$Go{1>trX&LC_S!WS&}5?(`?kwq4YY!&W#+0tLg`i5bnc8>&S-BOtOgDi`-u_cA_ znk06T7m`a;Syc&#__XW>QP#<*$UcIAR0}F<*(`pT{sZv{BF5DCRF}qX{(})2ezot|q4LMihYRbx#j6qWq~n zm>p!bKn7iN>l$j|6~%!@=3b|Pi0awmtbrr8p3;is{@LO0x!Il!;PVH#CP0+`VMf%% zc0RI>hd^u>c@X85Jk>BCEqwRiu_&{!@tVk=-BMWU8` z=%P2jJg>q$eEZai-(Ee_1d50vag_L#UU+Wfir-s-!KhLV%(Iw_^%dJTn0{cI`$K z6bBvd!r0(}Ac(TrduXJ+#p}kzXtOG*nwHR19s8IvOA+u`T*?;q^)0r#)Z4?nK%-lc zWj1-IE={>umWgQ?YG7<@E@@xjytA!N8<^=$?-%K%nWa!jIVtFgAQRwcB5CIyY_K&PE6uL66bz*}4^D>YdnyR8>_`6bT6f zx|9CT$fPa3aQQqEn>EEUv-MEf;gNFnV~;%rqWA`{07{S~7F2?# zjersy3A8}eyBSgZ#x2@ zJP;`a6g%5^5>Emxh}kOv)z@!co4b7KlA8zp0E{iZV5u&zrqx2gkpfY*kmAY3z*(jWhnP}9eO>&;_u0!34vbMdwZ$#mvAtN-@I1C&e_Ccp8 zpuJvJ@$m1<+WPJU6w8x<3E7CKIEZq`BsYgkLhwO|yLyc~J>6v;SbV^F?~f?iEGNp52zY2CENh6HSymhJRmRlKbalfcRA zqwoY0`zX7C_M75UKN7$(L=^7Ay-gp90kL`aV z0;0SjicGK{&*bPTOXK_HZ%m#5zF&;FD7I}VmCd&F| zg!qj1A-fRIvgRq&Rw0ov+W#6ELGI|i(qsj(eBPRo1@{n>IKvE7r;P$f%;__g6bD(U z#(tDgWi%O{5@3-^=C13gDz+%4f--zy|89R!k^Oe;^4b(tft<(>bOjzB+Oi$-J)=kV zVCyOC!t$vQHg5MaAJFYaFfbT8h-P)UZBfO^#z(Oq_~#ztJG_FZCR8}+vY`Y| zT^CZsRWp6|?GL@L8IyPfC&pci#8;AP23pILpiwD!)WtLgZhOyrOvKom;Agn`~xI30KhiB`BBI0?OTBRhJ zIZ;A&EiroUL@_5Z8QeW__`q%_63+upt9?_i*Bg)}pX|oU$no${z=i<&_AQMY+}K6ZxB6$F^LS>Yf+z*Xd)X0q@Mf8JJDCRgDB#OSfU%WVE}N$X3d?G zc!?_z^)x{PTn@eKJJ5NQO9>lA_vVEY#fmw+r80|-g)`{AcjD5wf4Opkd3=vjj)dT; zJ5rB!c}GZ{Jo(D4tG7;EMz(q_kfD5~LobGM<8%>B&E&)mCSUIbD0d$&=} zWTIA^ovk%B%b&$t@e%6W4cxCZwo=VIiQ+rFv(?%9`J!4;D@&DmA8b^cis=e06?88| zWs1d0G~$~$aNt7|DbM!aE!($m?eQ45SdB1A{z1txG&F>;Ib>()d^O`Hwa981+^|o6 zf3S?9m+0-dBe$b(!1si|NffNqQ!pK{QE>S{lq+|rNt94C54|I*F8n^x!KEe9rcZqG z_Mg5FG%>yRv8Qg|{=g%*k3WJB+F9au>b;+yi3~BKY(!Kpgt}ZkyR!P*Q`fJ)dc6@9 zZ>fP3UAq${Y!q%BsH?BudiB)F8$e1;rxWp5(d4yGEw3gP61rZ9_!{(ic8#9jXQKKSUw-NN z=iLoGPmj2C9+%k{fAjL9#UO|hBjWLDKS^c{#s^|oZi((-q_WK0Yb74>f!?I{SYKj3 zy_7g#K02yarqa5!5mC6@D^bB(Fzbu>opE#a9y=*|>9a~uKGqqn|&>(vvBbIe91D@Ejw#a;d2<+L}g zd9{KMDHAD0N)}vlCf^8KB-6F2<>dr``Yq;$mo%GKLSxa;K&uscG@3F_3a5|MfJr>R zsZ-O4sONbMIvzLi@(5fZT!m=4f{K{uK@`!`KIq*_H*q%CP_d(|K*`~5eM2*D-IQh7 z<#vOp-RKmnj{+OXShkc777E3*TFRI^h?=Swv6`Y&5Y@Gs!x?Zye8I>Nh=PsU3WKs` z>t-kRrR=aw&K|#K&rkO->jWEx>^-BdDsBdp>~Ul%#f&u~nZaLnV6Z&vgn^=S!aweb z^zEEJw13a0t%#m8qV_()h!SpJ3n^iv#Evf=oxwg~qt<@{uaAcwV1PdI9P|<7`H78P zT1wFiS1O7JQ4zljOGs?$UO0X6!s-R&<-Ph!Bh9Gg^ND2?yWs395kkkofV#ziI(cK^ z#^rc*sbsx)X@P+1uhm>qBD*^P8#N+jQUMtoyx9Cj{YOEoEH5W(s{o2wsF+QT`FzQ> zX?^906GVmj_zu*1lA?{rH#dW>->~@dZ>R|atIflrAD1{85_20>4hMdYKvb{Q4m)yB zLXE4gAI=dNx9&t4E&a_@b339E8!8iHp>rv2V)akB#Zg{}1n5px*S$$nzrGC_ zRZt)}9vs;dnZY;#KO*N_FqhD2hY+^$>~Y#3f6`(^hWZxPH!Gl;ffN2SoQ^#6_n>@V zG+YRKR3%U+qHvIg@{`Dp?TaAN0W&2}KPHG0>nM6|!--fDTT>meJ`z0&z5Q{vj$(m{ z_kQ)AoT!6@QnMxsN9){o_|S-R27?deB34lFu&&~V_}b;uw{ETp@!=+bS`+QVt2x%bWpGGXn>eL>NGw zJ-v!Qb;+C5bjfCtd}@e#Br)My9`UmNnyqye7i-Ke)Fl}G22o|T|K@McJkO#B#gc~K z{&Afl6<4v_!#W!axnXDA&%gAymliD`svo8i2SvH*gy>0}^jf%no&DsS%=)t|L>C*O zZwbIit!K`he)h6;jtmqlgxc8p8bK7#(`L5apJ}#>Pg* zoV)iUc{8xNm&LlbI<45pwHt>#o`7cvxwBYYZQo*(6f>MX2TGunT#@lKz=$d*-6PVh z+2<=J5SeJk`ut9<7{xR*Y*U5vg_=4u1EM+?QQZ?L2&{&M>abC5dMAh)AVc(tM?UZi zM%;6s+(#IFg8O|Cz2!t<3a^co@VYWn%PYy#zlFzlWAlv@e{96Sg&0Uo-9qR>gc6;& zaG*}%ADLU+dgGGIt!FOZSorPoit4SMc4;POI_nt3Fcd{{1iVr)B^h=0E!dE3KsX-6z27{+bChF@Oo40;O+L`{PUmxeAx|0s#w&_=GfBt zBG8GCn%&`Z=cXhof+aC59v!h|YOD_8#LNgK=oc?-_d1P$(!{j6Q_RfiL2FY6v`0R|NPP<*e>j z&6>H;S1gc?YAAr#=$|=$AR9tb^kg{?qS!i0kVF^3leoWAV70+I3dg#jgdnOhkMIK@ z{1xr}@J2Z&CWb`t9pCun|isdF!B}#nUA+wFW9%f^FS99l`H<>y6%paPbODaxrGL{Rw9byMAx-6HJ>`WByH5ar6DoFM4c&L}lOKHlm%j9?PrY~F10u_>#S(ve;LrrxOpJIE6p}#U#?^11xGazmt0K;l zU}{6p4+wER$`dUXFTZ;0>Z{ipAI{x4eeoiILLx-mm56z@_=3%xogQ{zJfxH;hBL`< zv0j`tTM{f}4xkd?PEVI~-DHbNzEpEYFK$?@4&^~qAF0zk@l)8PH=)yzaS@RG^X2DD zQ(3eTnkvN;OT{UzdU{G3RWF96`Pi=V)7kUIB_&S3``I7<8}hyGs^6XY0Jl#_nINJX2t7XZ#8W>z^pwD2oP=+s&<6Vqj{5{sk;2DY^n4cU>2&WRG~ zeE&t=#f*lChIyLJvlW&E<#6Mqt zVbO}{!Cj7~E?>QRn%uf)KYB>QGKw+ur`tz?(Kqq<*FO#X>GqZUpR%{Vxf_4x;)~a< zb0`1End;v-oshkwx<6=rvASiQ#9JY2mtRhUOvAp&FlPhnAiH+s(UXfeUxmwe6Tf%oPA;AVV3)3+ zUbt~#`J79x>9Pv%+iN4Df~kn&w#iH}&0Sl@JSqSc26S4YUa3pE?1I-f-2{qkRDMr6 z%7CI*gD2SLri6_mS>N!8pV9uCXRse7yTeJXR7xaEv0^=|7OSyRJtOI}v67@0i%NE~ z;Gn3tWP1MP7dBZ8EG_}@ANP%qhK#z#S2SwS;Wi)5UHQ|M+ee?h{Rlii_V}kOG2HUc z!lh?Rp-ex;`py6<=KIlF3hJ~g_qIe7PyE@6R~H+_&D24zyN3cj7T@Fj;iA(HSGDL+C8aOQSI^Ob5i~(!iL&iBiuBVfsOIQkih%0a zod8j{z$GBM#w^t3xic-I zPG4NOOhBPM2q?j#-Q~-s{3C3@e!$2YD#`fTGMqweMipajDS>%-OLdd(bt$?p-^Y0( zrlKhjCH8x9@(d(!B-Di(>wOPbSQ$~z{093`4ij(6)kx-M!9D~GBp!yNxVi&aIPeb9 z^DVq!{T>z5@Esf!C2-KUqu=#co|WQ=(Z}Kt1uE!Y6;JaTs3udioFb&|r&>he3TCC;?QbnqPb9Gw2vGad^7;^wEIdW8boAyWeL|KV6@nPb1(c1g4mc z+RKO1=jpGt0H*L0{5Za5%&Beu2NR;@| z<+&U9rie-));D*FxqS0z9ED)7Ne;NsU?q|bf~W(#cPj|X$}X={U0uF#39<8v?usRl zVWA~;iET$IAgb929cS6+B%-(&OSlS&Sl^o=V)TW-y}*d#nRjuz03r5-m=^9hAUERF zbZ12MzLqQ`BZ%S&6OEl?+C@UYMEZV=Du@~yxrrz%hyq1mipBgIz8@gFeu zPIFseqc*buI_eHRtRM=u*^G2pSE7tKcw?MpBrN$RBa(TtFpZ=G3`#;=H$TWXqb4{} zuu)Dl6Km*6B5J%#781_(9!dPx;l{J0_ z*OYmD0#9Guap2GsgSqK(W6Xr)=S!TZlUoeF|%0s;gcddr+5( z$UTb5E(G}!SzU6+Vm4DuB^$+=VnmHOCkF&k{K^kurryN;U8D6k&oH7IO(Wy9yDJf1 zL;&N0@o&DQ5QB=R%U`mwk-Y40GjY0@L zHLQ$SW&d_&q_%De=mBaT95 zs%G+dt5G5eXVdH3vHuV&inn>Z9;-{cK}6BdKVG&T)vu$ z+=C1pv5>0A(6N({(u$KA36wdqvnJ#Tn8-%GCZZG#%cCi(On*9)NTOf~Cx4G85+T+k zN|a!++zH-R?0%+Z*>Mg+9~*iKGek)WtwScO?p6A)+1_A3Jgc zJVD2ge0Xdy;L;Z`>7Fg5nl=gs3Ja>eAZmmWwP4p&1BfDl6xftz%p2C~2Dn0ZBi4n5 zFR?CRbECbt1c>rZ9Q(+z$KMVe^WC_4>I@Nu??)zTQ~%UTeIcG`0rl9-bTF7w0+Aqy z%BIt`7=T*UGAuF?Ur4jY9@&J=BVovR3`FrEI1QqrLy_{pTAErm3M@7CrZn`jQ+BO! z@oz8iygr8+lNBmzJySiM5AV7-A5jw3NU&T>m-S*P7RK29tOR4_AfjH&&$yzwn?#MO z)qLV?9sQ!x*-RbVL+KLwf;PCSn4t9f|Gc?Jk&pD~T>l+|5&iUf{ellW+^|uD6RAOm zWRp?1>ya2w0Ll??2m26?06Uy0b2u8>yKf|@1)~&o%EJfDk03#o;(JuV3lUNsM4^WF zr;U%g2Kw63YN`Pb9UHlQ4_$fpgO7|K;X3}68&BiJC)kYzP#tVp2y}8#O)o01@?-hK?K=$U9V9%wtAN zKCVwRBNH?G_a8%>2@vJ6C+Z*y0vRWpBBB;?G{C~v5^u-{uwEf&kVgeC-=Kd^Mut7t zQ)4B<>3MvCh}yg`dak+knW209S z4y~B3R%dJHLsL0gPrY6n1w9R-@<-E%(WjG{T5=X`+`_6x779pJ+KK9?en`zBH%-KF zahJk(R*5c9`#oa=kKKuKz(x(rNa3I*0%_#bJ#(Si&1qzY$J}stc$db5t5eq3T zwvd?BEY4Yzn$D&*NpaaEmNKzJG@Fg)d#KgeHbK?SR?P1~T#2eTYsgJM>fB#?sY#UC zlnqMQhpMLYdNmy#GpDPtBqlwrSF1;>r9v&NnA}aG46l!uXm(BI(%iCF=yFtcG-q#Z83p%s*(x4e7O!VhQUVh=P%N7_-wy6q#@uBccMy za?+=C;99RGrakH2P62@T+Y z+HBMt>-td#JmccaFW5OzOpeA6B`!!b$BtC%gBTye{(9C?F&3HN_33n_mj9z%6*RJJ z6*QSUiQ=-009LYeT)&M5mC*B6jOBn%z>c;d7r@^3TMu(+-&x( zVZqBs8a(~{xg)zJa{1B@qQMlj~M75P1HV*!{mZo(@haxz! z5mu;yM@!j#APNQwL_vhqhj)Xh*@GZz9a9hNKeT&jCaY|=&aa+}F9HE!q#71#t%xZ4 zke=34HMh7p^cA9sh#E7T#CN-N^YZ1n-piu^N>A8qn6E{DvlccW91TT1zElLg#n889 zetEfc2|%5Qdo?zoKN#8M3aY_eHmtj3r^~EF@4bbNgRY$p*$BSO2D+f2|6)_WicjOUy8HI z*2yeLsa7(;R5{_uR7SOuhHrv@%ZrCivtiR3qRd*I3|M!fAQ-9f$e=PdC_4r@RE((L z9^G3o7|GK~l+g4s;q?h`uX~d*k<}-N z+Q3lp(H!sIw{PZQ5Je{Ht6wFk7*Pv_gX?(uJcv4Q=)*(P1*aENI6Rg)3fMtyHmalO zsXcH(cPy7M!u#g{ie0`sY(GgrUAobGX=*8BgoSdN8BqNOzE#f#LH0yuA^{LJqOC3$ zFJU2-yd>)htyd~!d|Ty0A(PD|-Co%vn{^-P$?@344tRYYCECiHZCg!=HP!u|aMnFn zfC3X%WS{@#p7qkpi#;e^x_7zK(mhMb^jN!X*)}t1UqOAy*;u`H?%cU~WVM`+#kBeQ z(Utd=3t0^7D9tC-`TC2&dg0u>s?ArF%6zPJEsJX8WzgwF&VAUy1MaHA;MB7 zr1Ww<2EVTq!>sItXR9j{c3Lu-Y!;1?(C*qJ$5r3990Zt%qL4K;fd8BMn>O(eI%9p- zH!O4x>-+L=*gnq-FFo^8OV8k>gWtr*jpK#Q7TOcKccfwplYV!_%y7018w*4k+2phZ zR+e}|%Boo1XvMHOIhC9$EnWGxQpFm$SgVzuuKVJ*&TEO{Y<)^CrPI}DMLm^I)bB(T z7wolkOVH>hX;VqqC@^!cVwvYRhClw}9}`nQ{_;16?Q@6$UUpedzgS6QAIf7i87+o3qCCL@ z`nDitA~PQcP}P_mPba*aw;B?PF^Rr@AZpr=d|$U&jcnV&hK@1|g`pk!o*dBOM6C@_ z>|AH1-i%=~%mQP77ok4<{>Nn5-rhy7-o+lg*wMU^=pEG4+iRf~5U;@)S}i1uRA*xM zw&%6FTb_r}dG;T#DCPpZzVQ5%icHG+sZ32`D~8J`hDV>e&FJNf6}-==DjZCtD8DdKka|$}@vlK9PZPuz*B_CZTU5 z?I0UPFyRH+o+NZyMry~;&2%=ITDgvT39YBqu6%T;w?L}^Kuf-!vTA`4icFHy*hzf4oy8|`~FUAnIqXq~l zE@7J1RxjEPSqJ zMxqCr$`%#OJgih^XOq=R@$_V<tHd#_rY>eApPz9*A4HQ6B!|BU+MkkPl#Lm7JJ=QleIDti?m4fGY zQGfH~GByJRZnG;$?c{&O@J^!4;e-558wGHLc04X36HSmr zq_3SPeu!iwkkmCcK{jgZ#D|UxpAY&Li1HdT`{3+>CptM%p9WEx;MUDODt=!i7*X8m zgIcY5Rf7AuKG`I^5It^Pt`a1e1lM;$=L z$Iv z)bHBu6ra8qrkXPZC@%5FBV}(H$fSgFC3dtTg%u89LhqjO)Y62S;f>6gYb2r=C5NJHSt8$JeotB zT#2-)7r)@yf`a-TfGTvLav7X%7^!Kdy$mSWD8(M_qg54X;=jo7YGZ2WPJ_@J8T7N- z7hn1denOc~cE@^iJ5C(J?Rq1K>duulLwOM>i4;3$Qn6CMo02B?onn1te4M&}uqg)} z!-F7-rALG#0pf`Z_9;a634f(r+ZsdxrU1ifL!xq>Hi}*%7|}t~I;|~;YJ=*XPk!g% z*3WzsM3KXX7ul%6fVV%qk2sZby}s}M_*cLB z@B%igu2-gXk28i&)(AE6LHjt^jT2>e6jJCi5%f7$F6eQWmWW%J%d|x_4%y@J_+3Vu z&87Ns3@9A%{&EAu9uS2{1)yRFg!v70!1c!YAZ_?|Bk6uRf0TT%_{?vZiF#|u&W8*z zqGBd@Ek@hJGF3<7tWUMZMwO_9af*r@Co5BxW`Sd=J5kJ$V^(U=soDm)gxALkcgrCq zAmandP#+s+JPkyNC;U}5guh`BwQm9@3Ib6~-G~w(@t5%R#BI&Y`0iexAnNh+16z-L z`kNq1SgGS5dKg5Nq7O8YA~VHpls8c`TJ(A;6xD1CYiv~ehEx~CTJ^lJQQ!Q+uYUDi z=*Qpv+J|odsL`p|g07o&MEQh;B5^OnAQf23M9`<7)6n;*rqSRqORs$mQO*E}a;XiX z_JXP0bbi3;h;CyvHPoX2QEx)?%YHkB`mBbxo-)XiD(c94<=es#h!S&dRM3MV zya-avCRH^Fm^f73i83~A4~X)L=y@X-3G@8(yAj@NiLIXqCvxP8CR~}gjbe?E#<`rR zg>NTHNHEn=#z7~CifMhYPnfE;>!>~N8hHGv4-rmlh?)qv`b%X76JAX8xZ}W#-R7%= zhJ4jhxTG#DtO-oqgW87fKL4Tb{p2U#W%|hSatA$vWgXmbGtqR3Y54F>Ij`3u<|4MY{yhKUl42y*U36Yg~0 zy#D*&|KShc`~LU8|Azz5_ao@)Ua08?qf3$nB0`KPm5sV#L}@lPEy-D{1s@|W!PFwk zWAOzQUkWyghV(+YzMev!Y*UV1!4}I>fw-#xs2ET?AG`xQ_tkj4MTxRAqU!Vdd}S$J zudKIGQx(0UM|1^5C8~80H7WxqF*WqAL@6MO^F&uhlo|e>ECVL?(fIH*?LTpvT11Jp z)W9$cp93ab$VQ30K0%ZK35U3Mh{)m+>!{AK1f6dmdUuqF5<*@dBdWhxZUiKVCurx6 z$cXUQ7(&A3XEwDs*9G<-x!F=7m%B3T76n{T`dk z?6O!kBFb*pc$W#EYSXit)m!i|cd*B3ZEm&zk3ew0kk@CorF=dj3Jzb6*{E&Uj$$S% z2bgj=n0AW42eMPbMj83hg`WF?l^wI73~xPwD7UGatk+A0*iy*dW~20^l&NK^Npm7y z)Ut_$HhPalQGHZE5JeheNXd>SVdEn?@YF{lhXcnNF)Q`JFj(@B-_=HOg6OeJr@rRF zBq|QqkhETJ_aA&<-^0hh`c2x3;`_VbJaTv(nFm-$5mIz84NNPk`3ow>w3h0q$CMV< z8Y#d9{pJj6GB{nGMv4x4qRY##uBfz!jCKi^e6@>pPrDD@W-8nLWxCGD9 zlRy;U5eq2}7UT#7h$jF=+PO}70ty0Aei9L7>q1lusP-8GZ3#%iM0M|nL@pm}RN&o= zsBf+@Q9t~|@dLI&zq8mN3c?NQixe-MldL`7bO`lPNzLV1;Po6r)E9}d#q!dHi?TBAZDH;ki?pwEHeZL4L_5J4Dh%tD_5IegWS$v|em3f!VbckZ3;O zwvfDr(^vdPp`%3R^3~Gl$G%WqMBI2r*kF>k{rPp0iWh)gIJ{mKJUR_ZIdXg z-Q$!1luz+7qV^s-MA5#Tkv*Ypdzm;)f+z?;;oz~pyW6L>@tJu3_hm#C#~wixJKqXG zaj%bRB7umB%bd=Ks=r#kP`kL zF3bOz(>iq~)6uvq4}n6+Bmym%5vLoI`agNtL;uu-r6vO(0f z#pm5=#k#P7DUlwxD);sX6D5eU*b)U3BT5MZD1)`fQ}7_s(_rO9ai(0eh@3;yjHhYv z#E2Rj>La3Zl$JzZpCAfIHHm7Yg^uR4_)t6&U;n;P63>a^-}b-TLRr@nMMcK&{BULJ zoWonG;4+2#J$rqOsentShTs)4Q_DXSfcHDM>$6~8#QtendM*n;uk;h`5%1xn+HC0hp z_AVHj20r8dP>%h-45ql1Y7|bjh~j@U>#dOhhMtAXhs%HPC%>PFvfJ0JtNxpTYKxwO zCkewCiwbHEu`lIr?C=UzHMPRKTC69k$Iyi+!Us_Zx7X|tc}PsMTtK)y#QRtY5mEq& zL_9$|cY>%164@xvU5MgX-Dxg|$dwf~N(A_D5k$S0oH{Ccf8>jgd~-bL8~aeuiNTxI zft{d#id^`)h}qn>))3h8@z83hT4ge zV^vgd)QeTM7%QT9S2773)nKTiQcKzW08fi?*E}*gH`e84m_+iq~9@?)*IK zyw#VV&d;xox(psP{r9>Y$}9|&B6*!2zuCz^+72^?gHg4G*YbcU9E1^00*k$C#sum7 z<13t~)s^`sq8@zD*I8jfIO&>_5a+G$?d_KXG$nV=Jh$3v7QHs`uyu6l?!qI~5 z--`DcS@7I$G`(BB8mZpf~u^hu&@N60#SQuHwrfp z#hQ7r1c~XHROCSL0JzFAhA3f{Nf0GK>Htcd;-h}?_`0{F5IncP1$kmbVI6f;QWIFa z>S;BWsF~pPtrvEp1W;3Ahqu?TkvLGpi0e5ePn(VMhbhNAL>LK)$OLHz!)a#v@Nm=X z8>hU9p@-Utda{L>NRiz*`v}kc1$Fp*ohFKidXNrI)c)~;8$==ZS1q%`)?8uN%4)&W zZ?k!em55W*Bv-)ia(TVZkpOUFVgr7xJ=?c}sfLNNa?vw+Zas`IiV2e2$Gtyhx*mOj zxq~k(%%Sh|<{qofV`S?n+t#gCBc^P`bX8SjETV*dEHOn%`1}f%QL4;JyO|hK5R8=p zms$9H!5{-_cWMV5KAh0>&gmy9WrC{Y`vy>Yh(?|V(Cc}62S{q{YcQllJfek`xZrcT z3NH}1Hgop+kV5A9TY#vw|9MtH6t5tp6LQDHMP$T zO0QE1p+#eq|(ohiPK+R4{Z zpZzReAnNdVAus_O6|qHFTJLmjesxJUF7$hyk#afWWLs>*0X8ytOa@H7gw&?q1#gej zW!c0`R&NhJ!IgnTWf-s_4FHHKP8CJkNt^I`exctb^=#=icx9XHc3FD1ZnfK-h92a= zdSpcl)?lu@Uay)M2{2?7d~f0vm(BEKwZkf^302Ya!QCt{k-{M`t+HiUfEheoQ6{o0e2t{e!3y{k&VVf-}Db4;AvsERAItFN#IbE_u zqY;^C^u?A%oz8eQaeCwYm#Z)4lD*NWZ~Xp#Pw6u(_;(tKe$VMSr)AE2xqSHkp5OEP zJ&*jZ;K4>0H=;hDAWFW(a)1g8cX~dF4|!=!Maa%kpZidvSlGo{v1_sl2}Bi%sNOn9 z@*t0rMd$b=L&+exZkK7zIg~_U;g0n%TnfK@jya{Aq}B;;3)D z6rrfk^lz+23zgMJkMf?NA9buNrPX5G9|%JjNQHwAKtpF&d%I^{3)*UTV-Cx3w$o=F zEZjOBB544w*h=;mCgIhPaBpXz96N5m_oTbE!v*it+O(h(L}81n7VKy2q~D0Hpki1i zTHO^dh|)tXXoVMYc6B0&~hLa?%I}eW%NXZMRl49EA8zBH? zx0f7;>>A2ZA1-|%hhm3ANuli>hRjlU{9A)cDc6i&O19h+J)-(e)22+;pc7gZaKPIk;kBkVE!tO z4#y4}+1tD=$einVVVPx@!{K+f+ORpi(~XPALjxt3nNuTX0z|36ng2?PC!KD>w#z@4 zG)Fhe(GZKaZ(~(3!K+R5QV}{%7!^?BwhjOVxF`ywo`AxlF*CDo93^jc_u2mupYr2> zUfdl;t7!a}OAZwq|Kg+b>3>iqi0*T)1Br4Ak0P%65}k1XC8dT7+{7yr5<+`-YA2`^ za&aS?iZ4>CVntfi*!U$$6yO0-59PZ(;avkK8TmEk_zr*yhq$muz5EhS;)>AkO)oEv z7sgVHOJjOVI$OK{Bp(iYJxZwINQ3(2oC@>Uu^@<|d{SuJ^Whd&( zfk;P^ywF{`5q~1zi`&0Ql$(h9@3$!VuPH;^<{hKqiU(1odR9UvBzh^>(^Js`jaFs`!O>(R>RWlZB`eKA)bc}FdoCoO_R}O! zsCjjX229M8Ad0dQLm-N6>ZQ+44vw8(%tU-n>+X|nI~I@jn59J{w_GvIXm-9<+uS@` zhO*`sOoC%08{M< z4xQNc-L83D7%F)+&F9i|R0TaAhHzg);Kt&wf&pRX}0zg&+5gFe#50!Ap$9m}ZFB0{; zuN(=Y4k%}o`KSFgE{%7N=C4B3*LLt)NCQGdRDWC$wU_-1m)N63#K$B_@gCQ?a9mw9 zuv;u5j?7X49wkj`a`NWYOP3fTV&`f_61C?|vTF8VkCH?kHn%HUcwhJCmjqFa6o?ux ztYiuq4}f|U3u672h?X~UmBiq8a)z!MR(d{b+H8JX3q@M(*nqq=AIr|Atpu>LCruBT z4)%Zdn)&jnT5V2oIXe1Tpr@Y^V#1If^m-8>;y^;e<7v~0C@%@cmK&oQMcrPnr=#L?P^9m_4o7uD2Fd; zV&4=~(UCBV6=*hS!yMH-Hb)1odg^y2OR*a4$_l$XJClk7_&`VqVn+BF`k>5Dd_r-6 zD4Q*4+O?pj(X_5+&ZXz!gtc-tozxs~ISjO%JNW&kq}RQwWhAVf)^?lTwMP^IWzXv& z#R5>#B4;KNAW3v{Of3u+I!ebynJilrPL{~H(u)hwp+rT`JW39qgb?mw(J_}6O6msE7K6v9XJ?nDdMhG%9sy6d4Pc|` z(^rH7<2NrbQLIDD`T&qXiqHLFU$aL^qTc!z%tSRj>P^Q31I4j;E_C~D7BQG7P(4vt zS)86;csLfJC9^{%6Fd=6J&tx;((CsI+Z`p{@52`pR;d_^6-pb%hKU{1{LW5F_Mx=a zOqapO_FdCioySxyn4+?!&Jd<*i$xV4)Z$IreaOhem=xUvg*D7&WV6+^-Q9b`wY-LM zSSJ8Vu3I1qqET8f$R-7%9FBHZ9u8$ zWPMQ+Km?k+zEGsxU;Eh+BTDMuMAT#?Ac?{$JSrhQsuA|l{L_e@HGO6>5{hEs;Hl}w z=^4Z&L%9_(juM)L$frJgnz*`gVPSgIJ2;@H94kk=+-A(*p%N-Ky`NdEYt`oT9?y|bo$Zh7uHl& z*Uj{NteTy(EWT$i58Ed=bdfa+h%7w&j}wpwoV!A!twC2uCAcv3;M!-m!?s$ zr=U3?ov&_U=^S#Z+U`AU{;)QmY-zJBuN}dq>F7W{BH1t2>qd6OpGSSgC?dXCE>vKT zGN|7WO}yk%$17XNkq?Tv@A(9Uu&6pyREX3fBw3Losb<7p$RLUm((bSQ@c%?fqQv%5 z^{8(zHG!K-L;)F~#D^dXK=tN=>xhh!l(juxna&iZsGVbIdL=T+9z`0PyuwUfym;oy zwKE`UiN{fL5m~+-8uRhlyarOUkeDE%8kq?MeU(Vu2)%Q=h%t>zsh)^MS99Zw)5~{O zE>Lxk;z20`w9^BQM*TJ<=^Snk%98Yi9>?6T3u7V8H;Ujdj{vMt0#{bZ?y@;)U2^|1 zhqvk_pt{ zZtIpAR4l;L38H+yE(cABAuM#v;WH&)j#W!)DbF5daH@}?nmTUuN0B_29#v=%C2fj_ zQZjib;i(UzGqbZ~PZuvvUL4O{xG?+h;d4tM9qdt%xbJV{IK-pS z56@2^>iJyXOQEsCiF^0rVQ-t)Dwh#P^%erg(uE64sM;w-S{Nq))f!y)dTekeO-)fx zOC}?FD0E%XQ1OQeD+Q&rxmY<`EE($?mZ|uZ(V&tHwqt|^pq#t+t6Hg8Fmg6TeW1we z^SF`kpmtn8Xl@%F)kjAa#FZsY<{@Rw}c zC}Rv2Qc8&Wpq%h1u0KDXnurz_8y+>aFEs%T@5fd8^=v@gez%1p?{ zF1JlC-u^ES%E+iA6!D47#72i*VRORC4e=3uRqSQMOz|2>g<|*OSho={O5mxxIJ2}s z{zQFncP=llAlAbvG83Vh8%w0w*-R#|v<#1`hkG~=QBx68vq#C)gsho(!=<;Nsc;ZL zk%qbliubmoVZ>jmKUT&%0oX=vaFMFua;2mn?HnwJ!?J={v)}Ep))S$D$pM_9a3HRW z%(Wg@eJ)HfMKo0bR{2;gi?GbJ<}43*>g;Sk_TcXQHCLqFV%qkxDg*|=(OSLE0v$0sLVw#${93o*30LV-MPiD20How%5_D-ELpAqxyda{E$ifnT zDJ@@`YgS%r?yoDKlr|@cn&h!mpVg^JqR6K}6!&l-KTbeV6?Y;Y4XHGK8p8N#VPSAc zI23zS4n#FH29JVheImx{m09vAcB$q}-{GaQ{LDNZ)Xah74NMeJnp(hxR=YTLFN(4~ z4Si60Xr#QlcIw2b54?ml*r@{6MA^X<>`t(!-O77WaOd)G};=B^q_2DIp&zmH7=x(g!EbIH`TcBp5pol-oMDe&v zRLVx;A3#E4WOXDravWK`ksQ{LOU0?qxp!)MX{kaP>p>P1WspbhW&6UItD1o*?88{= z1`#FKK>EkxKIniVS-GU_)i)0jQQYaUdhcw~HK1zojffH|A>nuX_G4u6R5V%KfGEj1I$!CoI+8*-rCE ztzElM?ta2!rdwL;l}a5pyWgt>B~TD5X1OHSr`hEgw({b{;j^T)a(p%HFJT8k~(y5w>j#g zlXc)E?;DUlzuEor$jeyK97FSW-ivvIw28e@iWQ5+5sXYuomfNux@@<3g4_|m)6o_y z&)Zspt`-2m2&5um^mn8(6Y+RBPElXV@AkF1Z5p?HAm&Rcy5bAAbi$#Klh{FR6BaH1 zgwG)w6(PUobSW;lo`-=FNTCZW7{ul$RO6>4H`cAVY8YX!fs%_sLE=P5L!u3!*`s6wd~@o2KTt1Xg7?3A@uR~t z3LpxcFf^d%aH80w`1SV^6@f=NTxvaW4ybr}vDN4YzO%B`=~=VZW5J}+Tj?d93I)Sh z>}7uvKtT(FsL9A)uJ7XH4=!EWdiZeb(s=6h%=B`+ALevPBJ?Y~n%@bcaOI0&2{%3j zO3fJxgncVlE?izH^se5%okT_=oD0w{f;r3;6-Q8-n9Xm-c5K3*T(mrMd2_eya=5ur z(oYnGN%1&{QpYBclgadXlBUfQh=9%1#8@0|=Jip_tph+Q_n)kJgP$-p&54G3fmBdO z&y0(IyVKuTC(4UgLkI#DUn1lQT4;}Qqp@)U{U82gZUB`;@lmu|D%q7%HCj@MsM)1y z(lW<>Qzd6{5Fy`!oZ}V4DY*o?I3!W~swMVEd^lb#P&~og({uEQYH8W|dU7w0%PjZ~ zCCaC2;`6`5qiA+l_>#wTcz8mJ4$;}0I#tuRwkEdxYi*{c7?p0(JvvRB?h;RznI}dH z9<{VDdw%1U8=txMy)WKexdcsITG{G;?O6fY%;RX`mmd!5$F<0kKb&VDZt<_@lmd{4(sW1bG(De93 zCO$FYiDTlR)1@f32yLFAD(hf( ztk;6*&rfE>RB0ryMm@vamF3mpQ4_8G7(@AO$D9BPqo>tatenhR7Ggd%L_mS493w@V zGMv%kBFBFXrlck z23|U&w5h5+r2lP?8emaRtIKqH6p@vH_^zJHy0-d=sA@0~FHpi9`MsG+qxxJ1eRZNH zC+pesn-|{uj(40te;oo?H?RJR>-!#(1XXftL&=o%C|NU6C#imuG|6gNK=rz}K3o{; za9Kgs=Z!~4hQW@Gb_DtjrC_MkdC>FYKmOqlpFc_Fqn`Qg zYtI6SL3Q@oFE7sorth4o1eQ)uEu2}neEOHmXMX?2*)!8qXMXungN*9rb2c{L>D-T0 zy$ET1AmUQo!lQ8R^>nNjy%UptAZkM&839mJG@&~sa2jHZ5}7^{h-v^e36DB|{`@=M z@!t2IKmVcgAG&_-2+_o^g7tp)jg6VM+Xd}BvaxhC1!c2Mvk>> ziaLPb?K8cBrQA{_mn&^pmbI?Yieg^x&I7N*Q_F9zZC2;gN;(g&YMTT>H8vO05DkJY z-RE!z^@tL!#HP zK&sC-itIV$?DF1!vaR{8q>qY}ipkanQK}w?QhZ_tcP?A5t=-5#!f4){Pe!BFJb+@85=4P1097eOJPo2`YU0lGfghl1 zB1*PO9XKKNqKL9FQAcSURj-b?^_!m}>O+OI+U7g++ow-|`wD*W?_9h5xu>uFk}T`l zvtPe<`stac*IxPcZ@>8TwO7vk{+BbfiTqzD3ivQj;3wj;F;R4~1|lHJvof(|t6?W= zqcV+xquxfnEDnj3@F<|f2hK4NC3NoGxsO2SAi@fl>(@UHu&&j)l5M?mC0S`u`^>6& zVv3)+N9yJ7W5?8)h2;wu#!vSa7IV2&CV`)N9RnHxR8LQ}>h0N?Z)^9Y?Okq{OY^2e z8|iE|2BL6Kad~uJcWH_?l2=E{ws455g;Rk(^gU7gt*zaB^rW`qLP?`CYF8D*g)R+2 zRA)RB&yZ&M%2XtBrF^V*7Faz3S7*!lWDu*4nd_=YT~{#pa{3(`>&PLhMU=;ml#=N* zW_U5N3`vh-RSJEPVr2nH3GuL1fF+SS$fG1q^m@U|$VwYLdJD=DQSP2E|MZqWrejVC zVO-|-XU@z#U78A1W(Ut)zV`Gon7a1bZ||Ib=9_u;(zW+Ld-l1f&we@k{#=_KOSt@X zkJ=kHA;5PtQJm-#6H>Kec!ClOwQ>PHunXut-&>^bd5QnRZ_0ou2uP7t-Pj`vci0p$ zB?Ybk7EJ(Oytx9da0t8Fw_b~U6i?0Wgja*8q3P5V|IkgI&dto==dfaAORArFLe9L) zTQjlbgI9Ap{F)AvF+*x3k+;(8X=D`UvsLT>ehP*)yjhK{&Ks*~2WICq_%w0}l+%F4 zRi8Y`J2cDZ2_k+AB{T;-s)LD|08gh+11Q$gQiu*li@3_x&hFm5d;f0CkDw3py{gsL zj-bzJZ73#cB+4-mmC&d)Dijatp^WgTJ)n?6Uz|WS^1_~`=x6}NP<@!7lDR%9W~kYt zULaCT)YsfcW}$QOJ>i(|r(bTFC@4ro;8b;=-IqCY8o@iQv3KSSEeeL)nE^GBI<2Xv z11i24h*JSH!Ng2aK0Vv%ZYC;lF>n#Lh~{W`6fO`vDl~EZBcHpuT1*&~LhqYoN@58A z6)!i2QS4DEA__2xuJ{|*KXe`b#7Hq*A0bJi@Ff`5bnGM0z)i@>s3S=fyBob16E4vqUbPY-{W3 zIr)u^{JMo+-dGu2)v9H>W8o<3D%2LkIntFpM2%0O-Er^{F~q0vN`7!AECj* ztug0B;NUCtRs}iYoj^$yYbViLe0VTXoGBj&s}o8}-CGh6 znzHEohyUmm=3=c`QAXU8Yw86%TOXj}u1Z&R>mXLEP>UfL71;e()EMM)8)>bbOK zeg5;``u1qrY(u**G=;21Ki=d~vMyHI6<=QDARiOFUpXopMl}XfWKlg# z6k{WBBKbs#gsR5M4MnSE+g`lse2Nj-eCu<>nL-nBp zt~7df!!$?dMw96cyIMQZZRW9GN0oNs1xA~->{_`xTwRNO9X;%26PS(CILi4PP(&0V zBq-V=s-8e6qDG2i-+b5St`@7^yxtDiWJ-?`x-)eL0#O(1nF(>d4oI5COpypF9$E>V zqeK3o>pV9s!a$j`*pHHY#)+tJ2tcuxm#2qTBU^sddy_$RoIGo|I@IBHGnZI&0SYyN zgr079d4l0wY3{)<9`8I}he-ty1?oxDvMd;uPxGaRw>MAj1buA}ygTJ5Ps+jA+Psz2 zY+O6hl3Yi^u61vj%;3C<9>wrLDn&N6B*Y|%H#2ye4z#*N`GjTm+X^~>LRl=V$}@gg^}WOP^d+!sR&&%^#Vm6Mcq;E zBNX&;q7Ok|ov2N7EmkX4b91%mZZ?hU8jQ(QSJ#SGZPTn-)wwydR@%&(*dI?$vr;{XKjNt|VCWXAlNnr!4y=f{GEe7Hl zAVdOEB!Sk6}(K(Fje zp*I!J9%v;0#Mcq+Hj3}Cmx@EI5QEi*+o67KJQdz6jcCn7Z+4zr&bFmFyZTOwF zWI4H(wvwBr&!;!@=CH9gtZi7?a{O%BSg)OBq8#FTDm{w%5kw_A;<)iMBL$+O;na%sGii=^mHvQ_k+9jGbn$@-79X z;z3$;1!`~4KYDV1-ZFC3z8LQFj78v9;EM8fBJu-K)1FqZ4?ua9kZR~j5LK$iMvBR5 z5@c12;0WDVScwU+Ww;0lai1V+(H{m;BGo4|=;9E$37MW~IY9r8YCbu|TPNy>t=w|! zr@!eDMA_}td~LIu-i!^Sgl2Va4vRFF((~(Wwc#p^$lOdPW0tvQBI~;rHRk~oGPCPe z4Lga}iL%)a_NalCL@S6AI>V%e%TZUPdu8zhQP2cQp7QckhnwwCN=!y;fb_T%(kQ)za#X4SPE~dE-J)TQ+-tS4kSE(lBzWyU*|Eg_R=c zvSPDgRs5}9jfsLg0Ui)FQY|X;StX09T^$aUQ47&xcMcgpDw&ue9%&d=S)7O$7Pz-V zietY09>qG$OJtwaiv)^@q9UZPv>Y+{r$Lk)R&f*WNYm_SZn^(qr#~$34hN?0T^lzzIm%b%;HxJQC8P(NZ*v#%Rn$rHp8?7$u^pWMZ0u z0#OTY@m}ob&I?% zu897TQZJz=etsUO6y6l}p6BxO`BD2pLi!Xv%T&<#XI^XP@IPwY02qwY|e zZ(;DIX*snE;V}TBfD?d{mL%dlLWR}vD8`9J1U0OR!D7sqy!V_Jxj|$J-+^4R_<@ZPrSu}9oi$%iSQ(DwcN+nZTKL0P#6m3AG@N&uRs39t#5tnTj_6SAKl+AZ;aZ_Pn6Q5K_nzd!ObU6s;!S*fC5o|zr+dh5Km(s528)cgXr@m6u4AeDP|Sb1l84?4?&-vDn^SS zDwGl>6AhDEnAuvK5(b5#hanM9a)qxrq-`cwP$xnUi0cObwf0=`l@-p^<|+qfWi^HeppWt^9oX zTeoig2wPL1-Tf}>$)oLBI&Bh9Cm%fU`R%2-;Ak?aWNWcPB$Nn*eQl$(S;r17@hk

f|o`GS#%%}1koRiT(K7cD}^QN_+g5l_&}^uiKP z@Pa1cQ56Z4O!pn`QLKLtP+T5Id+@gOV32=wB0pOXGJPVUpymIT=IWB~o>P9#N12J{ z{i8roKoS+GkE5_i91116WxU6CdSKz!{ZeHTKuu0YB4CLV=jbQenwSMp5Ces{u7OIE zO??cnzp3|p?A<_Wk4cuuu2XNwb<$@ir#~uEkBI!O%M+frh`P$v>bYjtOprYN- zm5vTgb0OQo)&x1kGGWf3S=sGf}u9kA^XO z{}r+*m=q2Ke=K2B2N1>n)5u83ui&UV6HeIF$37;$Or?Q)3HeWb=-hdf;a>mDCqH`! z>&S@Y`CxA@6d0T6=sy-I4UA!(PV8z?>?>eBr`6TfkyWs?ib}0=X;@PebLKrTbljcZ66+fEw|nQTb<0gv z6)QL-Rbdzvdlbqsf<9FhL@5O$6vGs+t`bo3SQJ1NibZ@ab9xCxu@L<&j87Dn#W+e5 z1)v}RRVQi?SC0Dr)3Vt>RLfB#>d(}jX=rmr7=@EqTWAZh1cUX~*b*TcO=w7$=xt&n zHHxN1No#9qs|E#IOIyUMZAfWFyMPOde07O+p=bqh#a+=KinxB_0`3Zm3ohs%1^wfB z&rI%gaY58-&z+fjZyHznd}rpJcV;AZ-e4%uGDk}JrEzW)zfrYKuBzWSku6N&o&!-~ z9hX3zCQ$~ca#Z3jgi5YU2*pkj9^3>b zUP|cjQG6HZP^nAs)l07@SJ3sB-*NeyPd!e_zae1H+u2BFLHdHw@sYy|X{3P9&d%0% zTz1{+d6>=P8B&e+eDm5jJ;@hdd*sP?Rlo10$6!(5>9milhOsg*wi5_)MK@o)(0U{2lcAF>y#qBSv_S8VC;r5R% zY-sq6u5g2rwj;KGNrou;(x4^^f;o7o$ju6qs!$^tcyoM z^eAvd;ek+~Vb%EP59mV5lLRQkj&d+M6@_PwUpXv~cdWlZ{q#3Q$UetZFY`um&}KPB zDmQnWY#43Z*!h1JtIx0N+!qS9w|h$01>nfdr(BUwiH1mz#s&2|zv8u-fUW z3B+O&n2Y7-^P!qX3lmC#>X5e*DB>ZC{?3~~z z?Ih}N$gifNMA<>R+NbeSK1Giz8jnJe2k4yR4?Jgj#jG%FWkkYTQztl8N8ORJyFik* zDCJKK>78*#-x+1Wsn7~XAc)Z5K?<7kD?y@gzZOKX;!!?uD!<)*`dQtlW3w165We+} z^{13sp%Gnl(ecNRj4xo@Kq+H+?0_CiCTl%dK6Txx^`{m)JCfM%wP)&^*B*YX@iYjX zzJ`Wp`n^?tOMd(F=#<$(YzXG}WB!R4iFnr{QqkI};T{m>%~4*{?;}uUqQDGeeI1yH znh)Y}z_L#5&_vCL0hILm)|o2{qVmyLVS##zR;6>13IY@g>f@3sOZ^8#`Gu%Gl_=|x zVH7*6{{~TEN)uHhL@AmUr^AYlwD(!D2hZu%LUkzB8nu5OYOQxc}Nr{cyZrD<0y|Tjl%u6iNfvg5oN|v zgPB_8QDOG_fR!Q2Oi9Vs;)l=W091Jh#jTI-ylN%t7Df516&=47=0u)u3w~t_npz#-Q9AACPmrRR`uZ`Gks^awDk7&_VxCjL8^=hR!d7?OK*2~_ZbkN zI-^f^H3L+XbOM#mSzlipT+mBv$H%fOQ3MnMS#+NA*Cp~;w0_Gs!v{Bn9>aR5mxEP3 z@4j||H`I#LIuMSqkq(jcR9A*7xB8Mi^IrBSPv=xSJW7~i#9Uv%i3UZFI-oHfCsDDh zPo1)Sc+94YnA$yF5tR|52DT8jw!A!QOiGAi487oZ6kvK>_5605C|sQ2_3R;{Jf256 zjQU-o{vnS-rg^5)%JLaNjkF3;SjFLV`$&_t2NuGN@JVINJb}lJ^)8^=9y=<9eebd zZ7tpS>&4PJc(d7gMMPDx(5GcP|a_O$7}?Kr$Piu&p|N#`r89*#(&geM|((ZE_^d34lRlpsZ*AQDBBLMw9Zrf5=F!Mm68&ix)e8?|MB z_XfXz=VnRz3w&eyd-6LEB+AO_IjO;9rDZ99(z$)jm(?G3++l_%sQ%RBCdrdRDltf~ z7B|*6_T#K)CM)p7i2#=Hk|rg+z>otZpkxHU>h6OSa12xs7#J4Vp-D%rgO% zU?l+z2soj%0Vt@g3*TUeQm?`iu<)$h>dmvy3BXzxv$E25Ae@M<4b`?==qgPXBJIoh zY-h>Mv!QVI?q#oiGj#yYw>|*7kRgG6$P)-PGDMDzaTQe6n-nc`=58FG2zeOaqkxpa zWM+7!s_CeKbUI(py~yI>{Ha9>p}yma16llx9tE0YLB~Z|td3f^f=Fqcq;+_LJE?+Z z*NMWf=bk%*R}G^mq@OoeoF?*76~682@%^DHf;&Ab%S)6~}c z3bhxv-ZMcNf$HjNYisK|^w6UYg^oozy6w!C?$d!U5k?Wql653^jIZe2^K=6Losl8z zo0dlM(#A$)J#p2X6m^EkGy*sb`bMcHR4dw3h%-E4~q&QeRqlS;M!9}`OPq@K@rt6)4xgi{y)?F_7759ybTxjO;w3VmX%2P zg{VbkQMenT6i$*NAxq!ElSWDb^%ivJjr;4|)pRNRhQXsilmbdMW`Jtu#ilb_@(vT;Sc+^Qn+aDrO?G93!B!(p*?93EX9u>++6gDLG%=-9e;SMVsA;QhbJ1N|ORei=qN2@^;kw{{-H z;iv)ylBcq^oiQ*~xh;)k-i{;pTzizKi6IK@QJaWTk@HiJ!vAp+OZNVhjRY$zaMz&rtRCo+(f%w*pjn5)xb5 z+K#3{30BZShaPm$q0$WmR-o#7-2=UKrF{@rqCFi7BIbZiKdnTja2)=O$OS^)`Cy%% zvh~i}xp=0jImi`)APN$qmhO5By*@@KPz+RHs+ta+DyIC#ql`(xqoip}U=qBML=h?| zo38IDIy$a6Yh|$s%$yLlu83NQgpnt!2T~@l&oBj=&}g}KS)Pzg@a`$eY?RBR{c1RV znsXwXK1KlI9YsE_;44$oHEn!pqL_QW723nEyWrH~d?p=CVAm^8&=Q{XFp7~0Ig|-J z6)}K1en4+;sd{~UBu>=IS{;8Osi=GWP3d!yD3cUHnbg-lT9l4Ypy>lyMt#DOsgM)r z19uR6f4H@Efw8uukHvMgAaw|cI_Mw)3vP9ETN}I(9tFTb6b^(!X^)3^oHf?Rr$a;d zlOdAxCVa`}TAUOhz%*S~OeceZ#vl;DNr`|-5jFC<00oMqK=_yu8O$wWfgwm@F@ z{am}P(A!V%trfhoHp)4m7#0*l2cCNF1s7C!gV|O+A4Q}<)L|;ZclaoB%;`)-Nj*r14@E--q@r&1 zn^qGYyqS6DB2Yz&2$U9>>gy#+r%U9I0EzHnnI^elMkvydCb=23&?^+C7yu+wUB`Bj zC^nReRG`Xd=bwM{tr7fo4<-T?!xgC*Mvnn(36YHrWbI4>y|JcdBo_to2T{T+i+F>+ z#zYggaLL5n93y$G*yKuGRFkENLSa=Nb@0q^5Q!MuJ<98N6nOS|eU3+EExV&0L`@A( zmB&%G?4`LuqSh5rW06r%G>S{Djv`j{C_|L6Bz2cPiqlYUKfPxH6XHyMSrG5>sBn1W zS3m#!uw_kt`_uFRY3l$ByY{tCpEDhVJK=cq!w_7kn44_EswqpY(0IHxjPHc&eLlLH zP&Zt;EizHWA!`R7b2xPBd5z5p9xOnfP&gk&o(c#^Bsh554Aq?v-HGy$P(_zoi&E(G zt-zwLcQ%^P6p6%cFtXtb5z;25xIz&rwl+(Q>)I9-NjEc5>Yc%gF6!v6qrp!ZtRn%E zK;>B0K_n`H=tL%HTNp@X<6$e2FJ%(Q)~l?ps|h4!^-@JPjD46hHrCPmZb+S!O1fo; zFD`W=tL1)_QaK4B@FhOF3io%KZ_N_$kX zBa=;Mxt0SwQKNG!Y6zu*eVVAJe#fIOa_y!(a(%LQh=M73WEk}TCzm|xw3}Zltg#<{ z7z>{>ZY_NG>Ew5xK0bZrcjM=L_rv&4pN@a`_?zF2jvjasJ|6w<)9IhS8=wB}JKVBZ zIV?ApfOVsK7xfyR3=I_Vo_%bPAz9TeL|wUq7r{R#qA6f&PuMtNlAAUwrgi% znK?VNbn;sQRFtaLDyL9XO-%%tGT{U#j79N|Zl5m%qR11rOJdxdnq@QGDFHy8GNC31X3 zIF#)^oE$a%-RIx^@WXfa;TWmu@lSvH{PXFbzW7#-znT8-p&zEd`{DD?zxZh~tfPKA ziE`om&tvM3KL)36oO@o*^6HEUEpG>`Yc`$R0n1r^Xs=+ zlnR?O$sFQchtrumbP2~)eNrV#PI#`>XbD8(QFt<4K>ezxfFWAb4x-v{9Sg4T=|MMR zKFTZcwnV_22xJm+K4>Np@JH)vTrS^C31;31ziLeY9&8C_+jh*Vh{xR3fF+-aL3Z}_ z``*$(VO66MiSo?M>-C1Y02BLAQIwh)6G`|2J#ihBNY?`>L)38?P?gd`R5>s)CW*4y z!DS(eB2rR7lU&r}TzN>Wc9|%4`<{M(&v+E%!P+Pi)c~*h^3nIcy8q>h$#1{-^xNr4 z-=roAXRqD-tq}Fl4_|!y#plzY3Pk<%5Z-UrL4zlewz3L3`KQ4#Y4Sgb~EB9I26677&23EJGAOki@gHIo>UEh8#1gsLqi zz0Ew>lSGZp!KRW)+s?wHqP3+A53fnDt&u0H9NE<83AjTuC6C96Oyp1l^e88WE|Cck zMUV1XI&MCz8_3SY@goM$IgS#dS{KzY${`AJcsfTlyYEq^8}&b&j`|a#F0Ar{s0)Rx zhG7I9Mn|pI(a$f6`4)Z{o&0oqdHT~U$3LB3nEv5YoOC$(!@?EcEsT$aFZ$tAIMn3i z4?j#V{E%f#-4JEusdtXtIQ)WK8bs+KlqlHV5z`BxT3L-nz5Y6JQo8NF+wQs^*Il>X zMU+r^156Z`TWIN38k}pASMr2MN(@P8qCg4ILY00W8jAO8zlJA$&7cLXi)N)~ej#K~ zbRm$A$oXc0siVZB#3|rW%{c14CpI`>fhQ=6q{KRJZC!0s!XavGER%stWwLcLOp4_* zhScs;t50% zCaEYQ#3Dp+CC!r-xjF+yn~{d650!IH+Pat~iyIMwaNjXSg^M0_rcm_tncBNd&L6Q- zlGq=;3J*dQOzNmbhbT|n=PmgV1E{GMmL$hl(5kBqlBkTGk>Bdkd?BB)Ekq{v-+0wn zK7)_f+&g%pOK~@|;8do{V?q;XK$8@cJArd^PD*DXUwo!>cv#|lvrE z78e!j!4YCT@t!!c`+9nq;g?S1=_H>oi#I7IdTx{m$MVYz^&NgeA`^1PQSA4H(If~K zKPiu(1SpX7(0wnGB_n`zDGy?k3gH2b165hHr!8-=DLyLGVib^5Q{7}m8eV-mG$AGh zln57|TQpECy5VPt0Uj&Tb5%!-XrdYuUOP~-V%gXVP@>T316xr)kL+mA*zln|Kc9*DK@=3AOl%_8P9@r#yv=c+^!lv0lW{() zRm|80E1bRRs>zLUaVTniaUH`bjT4>-lr%J{$8~Zac%mM6?XvuD|M>Ra8Ao|IjB0=` zgL5 zVVpx&Jp6)mMtRgC0Rm90;jj?Jiyj4@KoctUVwt87G*q|2oRF7_0$ZZ4LBWN0-SK0E z`sAW1kuhKeF$zeix&ei*lwbmJno3+si253ziA!-xiZCg!>P3|Yfr?ZCsjfrr%;gw8 z4<_clNjr@sbR3}@EhAO!4^>t1e}H%t7I4@gDih1My7xcyBH|IzT0plc^BiPt^{DEe znYegVfJBv{%9(5=uxbUG<5(0WM0MbB!{U^K6qfJCmJ4AJC0e{{V`E)FT3;kYDt^x7 zKDnr^A#{}8_9%}K_2C{Os=>oF*>ax`Oo>Mg$AD0i_>y(gX~`7r3P|CEoBpf!*{dfg zU5pFu#TV~ey=8Xl>hn^vOY=^m{J~a;d+oK3CGw6(Q3@~f4tru?kJ@ZaY>mJaS5lY- z@NAi|%18ZriHh@~NE*b}30!&>X%mAoK?#;?K@p?_=P)a@N`#I~X#p_dtxdQ(=+2y; zkFs&BOdQ7`=IRa}8UjrK%U@MfRaNW3e=}^EM5R(7DwSDi6`($2fKQ7o?ewVXV3(5Q=R*8K;P=V)y|34nX7NXZab^lXKosHP7>HgR2dyu&|oef35PX2Qux5T9zt#A z31L0>5k-q)!SZ*WTIlriu>1)b;AHDkHf;4;V)cC;BH z`jonB)9OVLb)C4fLZSlJd^?aC7>HN9*M@Kw{!k$5|?$}lqxP4 zYgv*P=Cc0Psgo|7m|5+)sd0EU z{mw1P(q$KKCyHuaTwGM0yXAqwS0hNxF+4G1z6g}qa`dEty7?{v>Mkdw2Zl%&9{6qq zU+M!^$W;~fX_zQIUgD#Z*(aq8Q;RY!d_s{al~3zL%Sn~SN7RK&H5w&~-@q5ozmdZk z{K;WqGZs4?57yOyrtBbiQi=wwFo?43w6!`6kBZIOW21`?5h%S;?N*mE&o!twOayB^ zTZrGX*tsgD-bz|~S!Qy520O}c5P*PWl4Zq15#11FASyg$T>=uNR+*N)tVYZ8EtVVquP1dk4zIqDWViq z+M|Y=G*P9ioj_kzRAS!a?}8kt)hxk`v4Q%2+o>99(On9F=FMS~J(wn=c(XFrL~(3MybCm~0t@yRF) z4LgM@>PMDz#yML96FxO+F;Fp80`pF7!cQAShmsfGlzK^2LS)TbF%Z+94%d022iLAl zk|=l-h-$Q?-XY2Ad!n|PCImr`=*7;?{H)SH!qh}1T)Ms4n6?YwhfrCbqs6xhD zs~!3LY<)VciJDY2;Zir8kv)!Mvu-WBmeD$?I!?NLkZU&;@w=Y*@QFP$j?%MHv?#Ty zw1*zW{0D+1vV3L%Jj-d$Ym>S`vUUpZCJV_ZnNG9=s+Bv>*%(M43uJEnHWVwu)VdCnJXwctAR%^MSvwNSDo z&=(kpyF*n`HIBM*X=!O_X(>|Mloq05^LeBo*@f9WdVN#eLSjD_DepJ7w2dfw6cT0W zQKB70={c!H`%u~t1)iu(HrrXuEaNH6l!-}gQh-P?r6ok6K)i1mUx7k|ES_@hrnu?3 z-?K-?Q63Z|_3<<|I27dy^iTY$W`6%i^ZkJ>kqKZrlj#YbluFs@<@Gz^QJbcx^fFzn zDKuj!N=@n-pst5KoqjoF3`zqf4R<$!m=SA4xQG#pnTV3KSb`^i?RND!ErG&K%Q%$A z3S4!`i~I;^aj5m?5<7kIH0E}Ffta`23s%;0SAi!I6^X2cB|#_{TOPwsDL7IZ^HDcV zRpU!YLwfN=EaTW;v(2c?VFFQi^NcOWbCD;hlnM8Vf*>lLmCNer6ryNR$@F}OZR4?k zt$e`~ig6zlxo!ndsOxwjRSGK+`hajPE!VEfgY||_?3Ks_h>~H{-KYSHNa0gCz^3wV zsJ3dWX}gMtgkX(-E;}5>fSofM4K|g z8!_5RjiPb;NJ{6#ny;x*63po==zQ7}q0%b9s1Wq1m>%Cci~v1ZGzbvFZvp_RoO z6;LFK9+h0?>4JF>m9qN*&i>Etd-2|T6;lpQ6mg1jyICa4+O^D--9E)@Jjx3Axt0Ta zBnnZ`46wopyoHPeDDti7_6^9`X#ggL`?yph1)9b+QmB;SN{z74>@rbY9kqvu!Z6BM z6h#gkIp;(fxvJ#)9r>$vbc6kp5L&E1w|;qSEH^4dX{H1yF4=JUe6JHIB|WoCrg%O8 z22n(ck|!X+69dSEfkwtiMk=}|)uin?5Vb%WDkFd)7vy*p-r9)GSz<&eD&Kq)Rzezl z>gZd!aZ9Oj9;X8YVj1_r-pXk0P;PNaDFULhLX?%62T;rQ{Bi+AmE6(&u&8?>!;}Wf zcoZJpO~nj6ijh8)9ia)_u!1)-kj{!lr8_$rmH<$(XFCgap@1D_V+i$y2jG%*L>AVR>|J zbmfZWk+MNi;0R1f?onCWMo^TPi8>&lTh7J6jSm0;Pkn$&q+Nw_fHJv9*Yak-!Sj|x zJyaudq<^T1G7_Y;Jvm5mY=yNQ+zKgSH`+LEqa6zgtGuC_P$V~f<5J{C0yPvB^GK7Z z{Ai|-pUtOALe$cI_bQ?9C)2&vN}D_i&u*k#R(gPvFtxJHqH?NybfD=TD3{)B@BiHVUDHBh>?eg!DP0u~tsZWy5J)7nF zhm{}4iR&X*VT(8rwJ->z61aHU2CWGf!x4~4gcX@Zy4-{ z0&0Q`aeXEo)~w6W(j@VFGRX^VPUJH{N$tiaeeyu6P|xD?p(M(RVaKpIzzVqifk53_ zB)5nSGH$#PTVxEmYs5T!O{qeDG>>35E~GI;_9IpHUPojKG=U^Ys6s0@ch6LuM4?cI zDF>=}RUifz#FBVPl%1M|?D%|V-o^u5N{GsWC^9v-KDUmW+{fk=S8{Vrjj{=H+k@%QBp_3IlWBjZ=Bj4kBC1A|Dz5uOOt;_Hj|E#7>y z5T(7z44^(>G1E?$f+q+Kj7sI-fh)m_Q9PzQkSo&#R5CNR6p`tI+6Yv)@*#OqeL?+U zuW~1pF5^u?P78MD!<*Vw9Wc?YaBn&E<`oc?#xN?A4utJ!O{CrHu2~rbQBVZ==k9}% ziHxN(ww#5Lx0eeD_2uVoe(SRrHB54`>&IaFW}@)mK4~URqKwQ0uO`ZOuvZfmySg|9 zqKXAya(Ffdp3ucCgb_T?N*@mbI_qgJO8l1YdjONbFA)YZdb?n&@wZ-b16az6?lD5$*nhJW53ZLzroCfLeXY;Idyvb*IjKhiQV&=*(E` zezI&`d(e;`NxS4`B--DjtjzQ5j!T6=p{2Stg=ZupK2x8e%pqJZ%F})Q=izZVpBI zhn_hFpoA!hujhVo32I$S6g(=DXQEu|iQ*G0;A;r@6jAL&RCI)9m5qnSMxg_v?j(rH zWVrhTl-Q;QA)XmYga<}yRWk*#N8M?n5GqE!p~-Z&5LJanAD8alQZKm`Nd2hqd}nI) z4h5b-6ivv&OsTv*m29LXbx^YK23v$N4<82;Dm+LJ zF~MqtG4&*I2i!1fWI}J?P##028+p(^iHSo-^ns~D)K9JXfe-ivo`4k^f=pCnJn0Sl zoUXXD$?gi;dwT4BAPOFJw5h4JsR#WitoQ?>pwQU1=1{np)L{vh+@9kI1(5_XQLm_e zEbpi@ZQ!XQ+-Io|#Du8F+N1eA4e1u5#dv`|YNVg%AI)Sq#>X}V5m>y0D5S9B+p;c$ zr2mgcwY2=~k5&^@F6hHkIgX~^>&Hr&Hj4i$E$>F>jZEMNZt;iyHU3l({{^n#tsJAG z&m^kw;-dTt>$=6I5a3kz9N!a`%$U*ftir2db=xVs`I2Vh&{t} z42`vqWW0HMt7`OpWY3|?rv)kLO@XPksp!>UsO( zV|ia}F*;V{dXB@RJ3~Qg_7PDT$jbo=fC8o(m(r3z_D|v=L-Zk|03@F;0S#UPu>j7$t)eeDRq9+~T!?jR3{I^m?3?W2w*h zk)UGeIQ`Y=Sn-WuWd!=xjzSSw`}Tbh-h>vQq#)tPw)CYzlrIdT(#d$kD{5T+T9 zh)U1Q^mx7XO)dobY_TMWn(oJ(El@nzdg+`nbZXzO3x_W=QNk36(xr!3MPYHQ&FZR* zo3E48vDrpI<&w_gYs$Y9s@q{2+?u^#UmtsN&8OkdjHqD##iXsD!IK z+>fe5EeBoow-%k17VAsV_r7OkyLeI4c?pd&D-G{{0v1(idXcW%2PnS&Mc%ZQsB@HA z4wpips})-AaZmLb;qnuwh$oEa0xI&R)4V2>*b}s7?v=7RvC2hHxHDo2Je#t}0E&TA z?nN7kiQ~5-P634QBLo$9tXK?*N;lUWX{u-@%-8Q@{*<$AS(zcC;`mC>#AB`XZ7z4c zCrw0AVq;H_H*WPH3kdzF{%LHXeylD~OVgZ7=={_(Pn<;E#Azl@0JKRil!!a+0fAzV)Lh8eX_fJv<%$aN+|Z!OxV()SV?QF2)-+qRS8S zuLH{+E8W3>FXqKW$U#_7i!0!6Efcje>AXgwL~k z&YU~<_~D5Q{G?p#94{wjta6R?CTzX^1V7<|8@gVj%?yZ(G>0suORVM8Wa_op95h{D zC#G%zDoPduC{8fP-YG=kHE(9Tu;JI}6%$pfy%0n}_);xbzoME4EoWw>2Zcf?ogTr} z8rUIRBnCmty(^+5DNoI;tXhAn(uswS6fL-L-v>w8KU61)SW+!OgDHB!zo~jw@|P&K z&VPzKNf7Yag|#;j)gx(|v?%)mM5S$6voDkM4`l+?E|a6N)oM>OQ8Q#yo*AFtWp^jN zBmFTy=CW}o>#%aq@)M^RpF`&#pBkDlh|)G?gwd-T3L|TXN)t`mqadm`Y;53OR4(bx zJL}roL(QY{=`rF-h=M<%_>;P^E9l&zd%G$taeIegSL3X8A&LniN_gT^)g2WPWm-d2 z6{Nn+Qx7&DSh&|yOKlxehi$)+!i3lx~D~6&sJke1uw9qO)X026- zOHk=9w3etbAK<{437ki*#-<&LB@_7RX9CJ?qpMoG4bx**5Cxo`K__Z?xs~REq=Cz2 zMEZ24E~InICC>;XK}3{RWg4r_AzzawVdO!m@SG8+BeRm)i*o;nDZwyPIgp|ABP0e$ zruRmH2`8`wqISJz2b+^{C80l!)gk=umgDKPtr&`VgZ^=M@)dR4E!OHDdwO=NyE~ok zwtEnpu*duj_MpFKCP>RZX50-x<>)D4=YuFgrwP6&!%vISl4zY9AqvY{>&g1k6>*6) zSMa)OeT3Ak+g%KLoG6G2eTzC#2WaKO1EYSy37R5-_2V-$eKB;Y;t2Vp9Vm@I3Q=eg zQP=+CQ;oyx<}xYJ181@g%sRNF%Ijv=sw8R( zveadO%bomJ#*%(`odzfK)O-ndWHpv7We$@^k7(5m8zcM;DK( z%QI2fNZOllF>Vs3S_^s9Y|`Ct3p(4!2IEGP@9^}2X(5W!k_oF5vxHUJ0|Rx(h^qLw zVyYrKF(8dTz>X=Bs_v+;(v4|NP|iw2zCU(=3Xz$V?@i$O7UEAFm2Yg{`0~#hh*WJQ z#x)h8)!ZMmbZQe}IVwC#(`7u`3bkZWKX1XD1rkUUJ&mc+4S$lVe%r zkL1o<@XO5XcC8Fm*RCeaYpZiAOS_shqLJh&(sHr||bGdq!)9D-&6>O+O z+C%^=rUhnZX2}Gy*+?Tro8Iu*--quqq2cL3gax zS0?DkvMz@jgrYf{fBcg#e`Af~K$!gw?WROmqz2E0m^rZ!2_Y|q0dUwhEGmsg-lU zPkr_Wzl247;gh5EEeHe3|-@Ng{nHx8*3|+@c1NX;(RLw$dg-4y3T}Hf$$0;`h zsQLyb3P|acBNmJaIFYEEk8#uw?!`%!w)2;KkMxW*52Uq2x|%DFNJzE1+_68gFv_dU zN(7?hkQ@szWpE`IiL9%YZMa8;4ScXxZ^_}ENwHM_IjJFMQ^p;m-N7) zh^TZoE}N~Mo@$f?`uu$}tK;})V;t7nDv>@Vnm<=Nl-4Q4{FdumU0Vx!VGdCmH%dZO zgA0K^n&Z+vI&<9H9-4mez|I4s5X}!Z?#6%YEDD}Z(Hz*=c=D-d&V2`Q3aA@htF%8i zPCP;56rZI)AXe;|7>kw+g0_YAOG#ofBVTd);LaQYO)kII~*Nzz32jU z&WC)DedY7*K3}IVVYVbJAZk5R4*nbO`Q#VY>x(}H0Dpa&i2B3tu9;K6`~B~(UAva* zq~cnTOJ%iq!jZc6hu{D1cYpYUh3-@E9a<*p`{+f1BN5-@PyU8H$~^qS&70SUlaA!| z-1RfpuV85#EWTD#lf>=K;lZ2NFJE;$Ld)G;89qN`vkkv6eEssxzUwzn3}1NxCWTHG zh%y;Kfv7W6YSn;`S!2&(Ycw#N>Uea419p>l| z?dlL=Bv?TTsewD?QOZ0#n6^bfnb58J*-!rV=Rg1P8xEt7a7VAM)i}tCe)KB_2@dyJc>U`2!5deu48fypWUHDeD|^(@ zYJ;fF4Xv+eXlR`}qlyZZH*tmptyx145|IE&@7;@r;9d#7duwidA*v0Z(f+i0WGfP&3^@4*_5|1-yR$YqcX>E6>S0xh_gx+N=%U}N5Y54=d`TO7he(f57 z!7ac6QMgq+;Wf;Qn8FEX^trzOm%sdlNy6~6l8hFcta&U3FfeFy4-QV`+=Ih|mcc7n zC+f;|AE^JUBQ!aejCxIiAVoa>IBtcx5Pw&tjpN87<3&hDxGVIQ+{V)c}*K zZe2ZD&fo)0@F)=n%^@ky{owods?Z9gjf*_x6;WKD!PH@osOOFdX=K;5S}IEcWBq+NU$GrdjbWox5pX^p>o0w zpr&Ri(H^nB#_cw{!x=zG!t2Km&bk}xq2=#@sDG_fK+4}-tg1+hHE0U3MG;Y!)<*Uy z=)mggz~~6X4mC|CwTjnMCl66u8vpZ3Jtr#Yg(Z$}m>_TrooXvhdKRH+E$e)cT<}Dqm!oi|x-ZLH2Apo2bd4~Qhy+f_#_)%GhEo|GsX;T;jda2 zzVgM-{0jZ3x+-f$4ADxnivbB0%ium)Jm*Fredzr83BS$ZwxL4}=X6jY0`FtzZ%)u7 zMKIhBoOrkjMCtjVPM$ckx=hhuS?+u@CL{KMC?jT0NEwsv>D39PWP=-jd-tM2rBI-g znvYVoP~tlz_PigB&szvEJ; zF7<6KnusV}wp$UH08$QfeVdPn%1y0Kte)J7E)<9&QSkgxUX$bUzCGBODl`Dp{|kcE zQ${L_(h~>_f~wh}$0>x)R&~dSY9XQ!>Jy^S;zN+{dv!b>wFan~a94PtE48qg>WVH{ zviZb9ei5-cbI6h^=6#8LmrX#@qWfOIH7^x8`+H3j`Qvkt`M>K z;1hjAxxP#+6OV2USvOACB8Om=YHM%^ zQT~ac*;Nol^DHZidVC5zO|4#*@d*i|?i1}{toZ*DZUyQ&3J5A3QxHNIFsqjk48NUU z;A9>v@?_OB)^_Ivw}4$>LC!doSvFJ zb4rMUHE}|@@B~a~iXs`z)nyl=H;ULa*fZEtxO1fhOsFhZm@=@EhMzHwvN14B!3q`= z2w^4`!fb8aqYM^9C#x8Wsqt0c%N$92K-8n-8FvzWr+!TRG&G*;_Qz&Cil`M3MXLV#_XNw0~fu*7(7`HPDGYdM?%;bcU&>C8bn=`G=o42t6enku>l zbL>C{Qi2E_Z^fCp(lc8E75aPl&wV3YkU^CJD`^8N?(mtM4XlX8O5sa+dUarMI+IMM zF@Zz~Vdq?*KjxXifa-UE6ZND}81L~1lU}TKQyg_VeKwlRZ~2LTs}FVVI93}dM!l*Z zwLWxiL?*%}t1UJQC6gn`8UKSjc_9Ea`KA$;m;z8!-?_j;={PY|jMYBuBx+W_t&9~1 zEl!DK@u8Ch)@@IV0IT^=Tn#9Js4vMHQV2?XN%~ey6j(|{u^6YNCWQf~RLAFz%=g+r z4_+U6sF1QyQ!RxfJby4=#As6ISZraTGZnKCVbH%p)LRM(TnQhZ<6kH`%ammkh29d{ zWVDke0V(=XEmfZcQNMCkR6@3pM|GBZ6Hn&C(XW@n3+)|=(t)Ky^vLe6E+XpeTOx_l zRLMKp)jm0vcqp}tAqMoHe-)DYtsk#+uebJba(kCWmc$1hEuJJl+ zESHyOrNu~ZVJTaRMB3vpnT7UZ zWG*qc6kaH07fX?-CJK3dSSgfEiaFIpf%`~l?#cLk@7c+&#kr-$rO{G$?#Z!ewrInk z*}?XOx$&iKmTaLAO&tp_%(rI`F7!@*C7bw4Z`Y?MVT9QVk3y>tNqQLixP1BK)HCOv zKo9CP>1|WMB)1!jts#hiUN7}IiNCA0)XQ6T7Aie)>)2B zKxy(QyE~ZiV)dxeey7j1JzQOnX~q6U=jj}9x-{c0CN{SgqBiMAF;3c|6j<294K5~X z);&I&j6XdXhw2VWCBDwSbIdkN+cC%_y9kEm<6a3-6k0x(|;%s zMS%%0gpeNtg}-JH<){fCtjXphOWDaIUr(HU`pKpFuV78iBS#XSFD;awK9cIlV)4Ku z;ko&)XlJ3cbT-qKpHIzC7A8k2POXUgryg}IvVb^Zp*NacC?yud;jUs7;rL0*LKoHm zjg+u_T5qmO{2alF^+e$>&V>u@ky12L>I#J?v%X?@pRe<~s^qOI?N1WbZe7c_kbWWv(EKrvC?2fC$aGeU!0>EF%#|?B0sX44JEy ziP~Xk3v2M2MDc7Xm;AqeN$YBUtH}o-{7;HR9!|$)v>B zU{iV|N(CfXyAU=PFO>Hf`IQ|OHJd=W0-;^Fcx)MT@|J9Iw-;2si3#sj`3Y03JuU^ zS}hbN#cAi`lz%j|JarlQ$JhbV9^vTix(rRG&w$|nGO`D#NPvn1?S$2B(8OwCIBruO zY4j0Dc=#F3f?3rfL#7m&fXyWE4J`G}Jz1DPn|<=>`L46QbCb~{^Ib>GPnVwV$R5d} z@6xfbFj**l?nu7$WHDP=WOOl`jr1n67(*^% zTHd+I@Z1uHlOxeWF#@8FkS1#!OjKQqlpI!O;PzT*ksBl!I(RS)BTW{LK-%zVD?T(& ztHRGk=M60_E%61yIZM|?vw5+hP7}5Fb$j-{RZXZ&vku|RUt_M(lP@?0!?_P7TxljMMnW?m-XI7a3rFN|5G$g1dA?( zN2FZBdgZXaN|Xh>csz9Z{KWM1bUz#lh2-P2ef~^+lRr1xCmxkXqO8jq^kxFFP|@e~ zHB{StO_$Eyf~cp2CSLn6zHJnLcXWCr8g%LT#47qwf|WC&h{{b3hDLYNPJ%0!plchy3>8o@dA*tYj`9FpV)yC9a9;EaW5Eyk#N3km$`no$Yb2_fnh{U|dN1^OnJdgtb&kpfnmp6`tw#LCkLdtn`=x%_0Q zw}jSaNum{#fRu>hX5S}JbGV);v(#8QKoY=0=)F8hhOlBkVuy=ebYk&EgjJ;Ibr$`@ z1w|Cus%H-c*3`t3Z$BkG8DQv~SD7W{5SU(4+gcqtv z=TkV*ZcEiSf+!%>H^6-;91w^aLRcb~yHq`O*{DVXO;o)}{aD`BiAU9GoQk+&?GdWj ztDxH<3IIIwk>~$2J#`d~J&ZunK$I0=i4;*Hd{b3Pxl|LWI6BVk0sN7LqUHRR=K3ko zKli9YNoi>br}ikW2M?AG9>iq{uW+c3mgEwZ`luENlQdILYQ0Bwa^{0kwgsT5Ge=}~ z&39C#VbDuN;L7`MyY>*}z63Ap87o5PLh>2pt;hgx(^tbjPTF$7ICzKTc zDGTZR#K3{W1E6YfkfP_wOg)IoNtWC)VhhzmRII<~j5(1)5=%A-Q5q)YO@b4IpIRL2 zheN@pMn)Q4I`^E9%6^pDTpyrNA1FS|8Rz0sqX!=En>}%2b*8C$_A&vbmoL_7Uub+A zMnzVI-AL*(l14z;-dhl5x)o8LXP^HVVuUB5k73_`)#_YS@aJT~aXnPdy3{@*+;M$dkoT30n+m#;Oep1Tb2#uKVbB zUh_J{z0pS^;cU=CFQg+SNk`hMxS|8k#4B~vAZ4A5?IA8V6sGp6z&!zaXxGV|(*qNj znQw@D(W&j+n~oW1=Ld@4&4#d5Bc%5ky zqW02##jI`n;9Hbn0Es|$zrROFQQI1#*hb35c8mZ7qA&$J$(*#9lS!&Lx0!K+mHzOA zD{Z(!7Wy!WCku{K7k@#C=O#+#YbgsZw{e?NkKLx@bwW-#&7 z?CLr3sHUdsCcD4e8w+Mey^e4d=Cs`G>pp(s36Ml6i8E=QX#OLp+B`DaKg}8$_2@~N z<*fTs0iL&|-k;&b^Q26FbU@mC82~l4O1WUIGlx%e=?o4y6(b~4`Cs}>V!M*edmaSF z9h0(Am2~0EY9XSym7`icX01-_`W2P#;VcK1EKI4n~g#yB2T)K)fpf6>NZtzPy{nrEtdr zEI0unG|8|*UP98~v8}R1JOee@HwB=EFVTqd zrAIHnSAe2~O1RM;i2vIvq$)Q;j`J&llOn3?MPy9T$ZV-B9D}G?a}pV*ot<3X4cia_ zGI}Pml$X#QeZbjyNqE$ce`Y0z67y5yv8kVY`Co2^zFhGdkMt34zEo>^QKamJ|4ey@ z5cM9O_*~DJ$sW~N3Qy*rL@07$GIeBkXl%gTS?N(giFhLQf~bG)QC1KoGU5>85PA%V zks=R)qzQ)yFazP6d>_8O%oLf;eV|0zcPi8^zk&z6Af}`VR?!0Fs{%`UJ|I?8MLa63 z^l%pojYS9q(VxK;2i*zZ64@u7bh7TlE9oG2XYA>2H$^65$yT=?Md%cm=x%LlXs}{Y zl5saY3Jsjiv}~a(j#MNRQ#BUy`Gp2}2&UzOv_}z91+l39>5+bqOM4XEiOP`)UsXer z0~7wt*iO(SK82wudUv#miJHBzSFNm%eXor0@?=v6PH-kol#+}ALumD-*2zaIxMX_0 zvPVfW&hcmOyZDjW7!}2)I&E%bZu6WdoEN0}K^#Ru(&@E7pdOZq!^`BEcU*k#D(VY= zTrm|A!D{`|H-7e#^`%$TN?&KAT>p{k8l*S`i*t}qnJS2?nVg&tBWk#`&{3H0!br5a zW`jr3hMYbWPoDjkL`gq~!r3q$DeDueut9Vpa}lD15RnYp?f_GyO(2T=iGt8Lia(9p2? z-%*2T%_G06t*g4Ftabm1z>{wFaVioHQZFSwA^XXaf>~J*O84O~W@#!?Fz;WfD6u}^ zDMalmTMt3Q*+H5q{tD~X7pOBN5Qui*j^Kc}@mCJ);io80PE3j9su01iGeYbr0taFp zc=7tz5l7f$*Rgeet46GtXZ6p3Ulo@4fQPW>F-}03CowBnbQ5J#<5WlMd7}YIEdm76r`(n zbx+FM;E@7e{~(AGo>ZGJx2)EpUjnyaP6Z(|SoWu;PUrkievH(sYqAk~6Vg zvD1N0bb83gRGr4F&;!#{3uFALv@XjIgpai-=Y{Z|p747zsA%mm}U#z0#T3V9n% zPS^4b5!I)Nnpp->gMN1?ZVOw@+bjI+JHt#T`w@iMAcxI zjqXThc$5HT^}v}x)AP?id+MokPrdQ4e|^oWS(lmP%4OyZ4>(d~=6_dZ=6Lz1-(R!T zxcA=p>y7swMMfZa!d|(226St7OuYSbNfDFvrBbA&k;e*BG%6(>KUK}4k&;p)lz@xanfh3Gc!L(Wkl)yZ zP8cJ#qud640~4YAOe00UgEOub5qScsEJ>W@Kfr8B$>IAklTa`nATb>_({u;raPoz zUS8&hh(ZERiivWVQwbvKbKm`u%L8jVzH;u=M=xG{{@HWS9LKZObMEV*WR5Hh**K^DtKO{U! zS^SRuGpH);22#O5Iv8>ycH7o7!-=weH0!&)(bZ}TCYdN(7gpH z8fiyLdzDkk`rzeOpAP#;%TVRCpch3R1%M{ozjE;De9`vR-i5CDep^ifGoF0<+*8kf z07N|`r;{ijlg_g?!LM z7Uhh)(Z+KTQ*CWb6V7ehL6ogE7@H;eQEG^|IecoCEy^!#KI%q2O3CMJQ!pjIz^b&s zkQ{vBo)*tNFHz8aOq97aS9 zp6Zl%`P0CrldG7_7Kx!t=`G2|)44KH?|8<<8RsDCE|JMZG@10`))fD&ZP3~bRo-t@ zEmZMLr>ZqX@mG8o4-Hj-V8o&&s11?F;JvVg11Cik26;i3jPn{uX|odZ(%OX2*$LMQ zZwOWJ1lE)-;v|$abgHz9KB2HUZUHvgk4QWYZY2?VhDzdm@-sUQUFe$_@5xNN?eGgX zh-%zy^Ut7|97I8v&~{|W7Q z@`i_m`LE-TN_axfa?#C8P$lNYuW?b8j$nh+Y;j{GIcdF$8hwYr4;)OeQbotukvw&| zZz6Maa5~vzM}cn09rQF*1=AqvTpvOceMi#)wAfs+c-p<_b=r!BLM&iyXbO1iA1feV zUHVb$JgUAdJl6I0+G&K>6%NrDavaUXc+44KsKl&%!DTn4Odt^PAR2wsNICEJ&titK zbakr`wLJ7V0rfFnT8PR%dHoZK_lY=uuEb;kBspV)$fGQCUD;#34;@)Vn&{$u0Vb6A zZkJU8$R<7v3b@sWQd%lFqKq}2tVTMEjnuJ(AK=gA;}Qah$eB3$>__i5qBu11D^m+6 z_bHRYb>q^e>iPDAi9*zU`#CXh|9%?B0bSBg6T87i#9#*r8VeF7HHdX*3(NC~cxJToxTQ4+um!nn1Ea3I4a)@BIgQTtBMF!7GpNID3DD`*ZK zdVF{wcl6Omlh($RGZ{(-V@`XpTTR@LzEsd+vml$_8%XxY5f3f)V*s`o@g;k{N`pa(UU?D!s=d&6RZ+f-awBEo{xj5(dnIsvA7LsS*14h z%szUW3O*@c2Ln=7k}zj6r+93|jLl-P^*16@v^;VoXGN5| zCd`vIjD)-9ahYGjdHx99q2T->+;c7(v37wkI0) zt#VPdA%VV@lZTYSj8=lfZgZmNg6~^T;jl#05x;;=%wYROUuWn&YXlh z5l31dgp3&{RHq4&NIKVfFi_ZVLt>&hg6_cCNX9D$>SU}(5wMY{`AB|#ZXvQ1j^wlR z+0tW?QaFNwzV@z#d_1}o=_(Z?^NBng)g<~|MAS1EpP`(lyNM_S`@R68$fPLf|34vW zKXQn`)5G^Z@W2E2-uv*q(55Z;rb_ZbS(_flM=&Y|hA<(qm5JmQBmp38W*iwn3r|@I z6QzDdM-GW7p-H5BSq3INI)y{X!e3R)?4l(D)H_x=U6y`EoJy}$b@{}^uxDVvUsto; z?hVD#fmnmxjhT=js*v(n8>|kO%?FQKbeJO`3P?@I-J?X*w?I@e*ovMNLB+OI9*`1` zs&0&CsXEH#DKbbxR0yXy(TP@M$lKsj9yLHj?OcUJLg$W?R#q^>2i8f!tT{4s3wAlA zI37@uD%yS$MaRJs(m)i;0jOlWgw!9XtCRHe%4KL3QKTg-ANaWxs$sjrOW{KJb8~bz ze{g$v;h~UsVSedb=E(?v0#cI>A?oP!r#vl)%-vN)Rncfv3z?MbzyFUd(Q~fG08sa` zNhy9d;Uu+%5WNI!4}&Nc&;m3X50(x}C^2`Sk6$x}Ykq@Vg;NC$pekJIK6NW2&RpyZ zqYT86(Uh{->uXA6praLS*?hr_Vg<_6$6lZfLAAdqYXP-?u!ohA4l)ZgRCb zyy;|U#95Ol@{~!Kc@{ZF{fty`1R;y6268E4NK3eKv=^Bu*Qf$X5tWJKgkv!jHio18 z(+EuL98hgOWVXX3Wm!qRypRG(ix=+F-6=U^S3uDnJPSl=*;LIDJgTi$rjV>6rgWp9 zVtpWrXLD?~bY&+e6CpGP+D|}j0#SGgnmDqDjU*r$(lI~XsS<{8 zOXjiZUIi7-gc3ufgNFhU?l}rxW|NUK&=OI~5?^oJ0DWlP4#F zp6T&SSHiiyG2~qi#_TihDG=4Y0?nim0dzPmzO>iw!Z;stAijlwgg3~|KPZIeAIfw` z`h7tc2!dT{uIM?{yJ)3ul)YGP@Oi2Ar#n@?dKr$InjP7RBCS3@aH8qUS;h)@q|>U9 zmnl+Y$--Td^2a>s2s+cm5kNdtnV}8U3|;oR7b`q8F;Nk&Pc5~V=8-ZwInuQ>S?ZW9 z9YJSmer{=LZmEPa*~uk*wq!&m%2W#&lqCBP+jPHs`mF-$5|Iv|1|H zn>W^S)F1M6p!#P#hjwjw0F6Etpiz#5QbLmQEQwr*bxCB8T7a*<_toHxMHC5RxZ~_T zNQQUm?G}97_Z>pF48KoI@$`Ejhr@`_8gz)M3K4EPM~Y2KbHv(VsCW{0U4pFg4wE-hV zU%=HMLrBaMhzj>c>flkP01*}PQoN600$K{GRDCd$BchT!M|bYbQ9d6;^Or;5NiT?^ zgxj}sb8oLAOR(aLlyPXZsIr5Gc&oB6rU-^0p<58OR5FA+%+#=CNM2!=d-Zaz#wJ8P zb@6yr%iR^3FmbXhh*IIc7FR0#Qe~;=ka_lV?}_6QHOptXtT`xQvqu(s^l_xeL;9)ENuJu$e7RRTjh-I>sMcV=~Ub#^5Ufv2?HgKP?) zI}oq0Zt!^nO|2MR!V;2;7?u%}g8J!Tvl`9NjtIJ!SB8;*=J3qu#3}UInOxE5S;T5~eg&L=@HV()eTTIyG?B z_C~dMs2|nIGOLSRMHXK3)>6YC$Rl3REI~}v@r%z`O?MMfJP5@lhhkFb1V$o~d{lX8 zZFuh7@H3HAg$p7w!A(BpN#F=rVNcu{B8r6__AMBtoHDemXIVc+#$AH2jRvo`n9mI!clPA@-{M`vDeR%Sd5ujuVd$ zcmm%V?>kP@4h@bEOpmXwp27T=>24;fr^khC3U3fZ)wepsShlU&7uiXwe&k1KgzD2`HiK(O=?XPlL7l+g5XQ+PHKOEsd<>N zx#yl&Z$dYT+(|IP$NV$=v9Jb5qTZCy#SgUO3Y@STm5Cq%n5Zm3#zf*18zsJ^;uV@G zu1h4EPzHrQ7nqW)b4a@rfu)e5Wu#tp;?aqtfoV+C*GH>wCUZkrF+qsxCZ>8kc7MR_ z4FtW2Jz$ytw$|3on7+u3H9LAduAn6x$rdG$E>QKe7^~4m%rP-KVxj1{Js2T=I4D6> zWisMZc-&qa<3^us}j-tE$}8|az!K|K~=XU z5cS0De$HpR@S4MZ`_Pp-`RKs1eR^no z`q2rRQ8v9YD@4t(z?3KLamE{i7U~|^5@7<%ne?-PfhsiVoW4kCQK%9P5K|Dc$Wd@; zGjXtwdSmE5EiS^Ibcg~(HCjOwX<#P-rHPUdpAqF#{HSasCJMsD%pc*4tk^1|J8S?7 zZzwP1Hi*DiAdpw>`y~AVj+(kq&Qq+;6frKy6FfUeQqq5~>k`}H!b|Z2}sKsD~d=wuKYxO%Q(upHX_) z`0&-QzK1$t_^bjVz=0MYITRpcvm(!8yV5cDO|%0;JR8HaTd-pzN^oHo87QfG#~o9} zBA*i6;7-hx7M_GCY`8rH?YOXp=r!UTpK!wx*i|eD@@F*Y!s0gi~&*Aiixxojl z=SP~YKM0&3QXN}NDIf;|fKtk*|?kpQK&my6&PSUC8E_jGfcL|KonJOw?mcB^jPxnIzFG*4YTdUp|JR2`y?CP@AA2j2uZ?i)9UkuRhCNpZzK6r-yp+1Wo#MN@7n zni{@8My};R<2ZT0+w9ojQEW#{6&n&?DTjh~#);3MMtVbA$hRa2h+jjb0w9t&O_n8? z=*%R!11Tar=!8Haj&21Mt^*cFl3V#%zJ(KsS?MHs{(yMm6Lx_K44q#i25Q&-!%fvl z^zpPd?tJv|)m(01d^nd|o$7--iMZ+4v)scu5u0lgk%m@l(v1&zaj8B!+wC3?0;evt z4&xZ6Dt_x*-=dK!#%f|ZXfknbEJHe!iA%PFe&^11t!*H1M;vGyOiW8 z(OHQ&!XcUNbc0u{iriZ9DE?5;!kze$*pdQDeqU>c==_I2eE-W{c0cssPON%%{=&Ws z7f$whT9NaBc`lm{pTB_B0Q>Dd{^8tkHyV6eWJF9dIaIZ#Ivod2|4K5NdHmwJyQ&`r$ygKu=Y029)VX}6 z(}CsTFASg04PU=<{pQUp&(ZSm@S)@jSFc{bdg8h3mv0We>;%?^zw+Gm6Be`oh1?5Q zZVX?&{>1g?UKpk@PQJE+C?t)uFu+6-u0%qVwD?Hih75^`lhB}u;Q|sBX%8|WWmuGA zY7=%Ey5dIR4v?{nE8+o<#OwI)>_Tygki(n-C$S*-gP3FWx{M?16 zABdtHqb7SI;E;l*N?*9NL)h$bQ0H=#~lg0=WE@9(BUhY~s zE#X9iU%F8QlphB#qNaipXLOv8Lwk}Wi=Fs^@Ipyd%!46_;(fffsN|l*sBRM|oL&ME z$V0N4?y4*#{0oEgWQix-J`IohY-jF;n>ViyyWPXrPu$4exN`OCl`A)Lm=N^ljjK2N zuH1a#^3~z%&s{n9!gD9C44KWtFI;`D?}dSzFI>HH4j%O)L~YXjAGH2pIR-yS_7kM& z1lYE0dEn*uuwh}>+!={W;OE7~M6qiTQT!wnh)ab~Jd)X5h9`2hV>%jpLQCN)^*$_0yv^^E}Il_*%#_i!yaWP_cwvkz_kkD%D zUV)*pOpV)pSaB*}L?=oMK!Ga}$U+m)TkmF?M8iZBR(!$+l2o8iRaYM>US2>nE;WAI>C) zZwz10UBB|&&C7!~2jNjyZ(hD}^#**3JnH(Dn^%U<54qj`7p}siZeG1{?)p_}^;Ht} zFswc>^vK(;uH#zu%Zo%(V}jba7O-xSfDVX zf)(W%j-=&BEEyOPe!8`%F6ZyRzqx()F%Om-3>}+nFZ6!x$!wy%`N0p1cAkfIqi1z^ zdc+$j!bjZ6KEjE6Nr3<-5m~EAKx(rym2fQfwigyH+f9}*tr6~Xcav8EDN%QtOwHx0 z0x;&VNfXs5E`_r(-vr!jImti`W0N=^fI6jzp=bv~U`DYdSJIlXU4;C^qW}?eqs-R?oGKjetHGq%i?=Z1zci8toPAEK_)@X+w^ zcn+V8V-06?vaqgSE;H^Q9?DU_%Jw4tC>RqAL`UfqRIi4NRv#Ul^amkMPI@(6RD+P= z;tCGovXUnqhhT!xVWX??1pDH#Tq$c5P}C>VYSfuTI;)7CYCrr47cIl0nw#5?g)Hsf zQ2XxP?IWm1O=a7go3}pr;8q+cMh8y^P>#Me77Q(5;Q%)`;>4uvXvTT!T3z)Dsk%0w zudS^n(iJVX)G9-&;nx~;>zlonIVYygo8FlN)hF>^dtckcG0Xv zCB&gP;|Le=Cu3z$Y3^}S9~KEHN6fj;1g^l4%!h7hFSe@N(o3YlN_j|kQ9nvLiZme- z&eCDTifoX~Ehb~TnH++8?%c%0Ag_Kyqu%(alcyeY#wI2P)P&V;x7+5%bt6&aEk@p} zYL4NNkir30aDXc&4KxUG019H*AR6hV4*`nmLm6}lRwDXbntpUA2bt{cm)B)>ccUkBuL4| zKE+I>K~&5=lN58(Ls2?47Rj+R00ovrACyC7o%0Fe6BQpaR**m?MkTu4Ud2n2=b4Mg z@2bcI`BIfjjqw^QTeHj%7BMg;?PFdniA7pIYGJWU#P=b*V#%6Pk&Q&%%U^a8-$-kW zUVV!6%E$)rN^>9ZsirF+WxqMSltt??o1ikA-c18vI=`M1P2- zJPK-r2&n+(TlYC_zr=Jc9P*zV!mQSENL2?A5~we~s$9pF-%TdhvaMGHJ)p=`d8jrc5Wjpl`X zq2HVF!{L}JimofH1Sq=@ML;o8!8GR}DWJ4R5lrG#KuI9N3HS&}B0RD{4{V8VHCAdB zoVSvD-BF^D*>}!!HzCC(Q9L0MI}|kLBYU#++mH(!PKCQ*RK!+q%p6&CVBYig;(U8A z^Mn&03{Ng9&}A zU!}29O+X#=2EO87#$01E4=e}yqywh1^`sJ#Xi^6xtw4nnF^>KHhtYQugL>qVty^)^ zE}qpshZ_b8NWrE?4~)e#$Q??9lXTGS_Xit$TI&P;_%tP^yIY&sr5aEs-?rTsuBmTu z2JKd>3qKvOw>cuk-rjs6;@IBkj39I#_qhopimnq_X)U{9Q{BmQz-tfYv_(BZJb@@U zlrTlxnmTyJk#wIFRj@4)&yYkcskJ*K^IU=zRd-S@56XD&y2ymg+@dO-@~N86#kqyg zkA^1~C+8yl;b>PP+G{DqdY6h=NnptvoiCK4`HpDepQ5<}^b=jn>3RAml>5+^`hi!z@|E|z=^kU;ia=!HD^FZ#2`GAM z%r|V*8_BJtXQd|u$oy+QOY;^dX)d627Nk%G*<%C zKB5X6p0ri%F%}shxR@(?4WjO(OqdVpu8W>a9j|(zSl?11{Ppov@8?U|uDPY+{76T8 z{>hQKC=oU9U7YtWIX*oXj}{%J?Y&)-;e%t5#9T5v`Ig4XP)ElGqA+s{^?!sJ&Tt@9 za2WJxipYNyAGo27q~Zq>0mNw4J&Y9^Y9eVtzCrh+_(mQSQF7MPjHw!^Lx9Q%JWz@r z+Y*lhBTgYj8$z4zQGMvb%Z^O~A#U#pP$G6HDB8R=daT$Vjl!tB{aB0I8gMiswLD4d z0AS(I2}E)RbCh8;5^Sw z?s++4=D2dp&-iH(*~Tuk4v8pg0ZRA}Bg6=*vu7DVsknGWh3*EUQj1f)UMdO=Z1&>@ zI7xKkVQ9w|V6`7wV`LZZXMh+eiB8A`L=jWl5Cc5cA8$VvZQr_enuwZCHU{HBX_|A$ zk(@VicyO>kG>$~P>aef2$CI|#J8dz4_Y|_lllG<_A7l$4RE{Pf$>HlNM0>LlOIw>G zftXMv7G#rJkw_p0y2!5rX!wOZZi$`aEOmxwq-3`|AVo-hP$V}-bZ-yk9g%RBK)Ngr zFGLYiLKL*G>JAD-A$)GVo2ufKN70CsAca<6YVvH?Qb+#Dj;<&3g|4qphI%7~Nngj4 z5p(hEd?>Y4EQM1`@kD71KRMSCNgYe1mLk1oUkOhgCG+}L-!9BXDc(c2b1&m0Bnem~ z;t7Hez5L}bzvtD&1v?K!r#10$iv7J)rK%HG6nw`4=|3lbUIE3bq)MhXR|`#vRT&{Z zC29k52|w{fx7g{r|H1(nlSq0~av>2>W6}0w-uSUnvA7Lgsspg416#+ok~#H*CLwBI z9Cn2y*zI<#Ws(Sb8mk+Ewj}82oAqE>(IkejVll7R=SPACyo%(oETRcmh$Ob72?(=_ zOD-VitdsiOh)nq79;8f&Me(dhdMpYX&Hzd}QcRN;H}Y_yAOv=mA}cLFqm+Z+lSkcQ zqO4WOmA#t=q(m((pTNwrGW{i099np7RErYssPM7|Ls4Cre`9h!nw=Lt)WMeyz8sui zS}5UT_9)65F88C1RB`G~K@yk{qPEBf_~af6`Q4)>vmvQ!KphL0-prd6QaH$`bQlmw z2ved;uY$_U_CkP)YkYAgtc+OtezGW#q{pG;H2~Yc|NMmmOwb0k?IBCnj8r~F z6ydaiDDo!ka$=;kI761kqZlR89VW`dxw3a5QQVQDY>&ELR1#t;HW4lD$ZXZ%M%KIG zx+oGLD;GE8#&}7O1@b6O)F#qvw(yspPdG%c;+H)1#Cm|PIH>)H7&`ZZ*l+|qVTuKe z2q=*t#b=7cb4i9G3cIe*6+-pmQfk!#F4^V!c>)JcL_Fcx!B?JdMg*eHAKrP4_)#K{ zdKori3P5d(9*l=d$BI7uOn-daR)i^b0xM)v0IPxN(ZdsDQG*9Y0{9>M6)>Lu{=s-0 zb1j=*VRE`LN;Tv5yFK+yGqZhtM3oy}6-x%}@TwpN*PV`3B%6;$3*prEMn|HnP>7=m z2zSbigQ}t2j0*I9=LsWl4yLrYVt0cKw^K z2Z=x;yk3qC4L};1!hA-`q3E{=5>9>PN?&p|JywN_QC!axY|=!u+NUa@!bMNLOh`$j zg5wd2p#3Dx6Z9c8`Ys$k@W>-DDeNM3Pw5i~_#I1x4wi~u0xG$C>$c+9*w(G1NKP6U z-PxR*I50guF+Dgmz17}iwPU%3dV7((S0h`;A}$2~TJ5t_-91fBJ)F^pV+#8ea=bFJ zpxrZr_=C;nblT#@k!Unpv|tUz$YNKaKL+s9-ADn$Iv|QDl7#srEP;bWL_shnZBa5u z3l5DGUTKtY!4%Yj*_|f}>yJMFvAb$ON)bgJDM_J-L=qxjqAV{z`FwnX ziKJ@D?=(?_0yYq!q6n0EC(#FksF%Nz$D9BZ#7N;#RLO54FNvU%oIIn~bKfRL=z$7x zzMyo9K#+!tF;YD%LP!&(mYCWCqNp4ffj>rwtqL36^6>x>wbcMgt}MO?P-ya%cJCf> zAKSLAXn}F{Pd7L3%#G|G@i*^8*585g!4Yp$J%*x?{@TGtPLXm!hL1{@5~N6YeWzP}CJab@{G%Mb`kswxk^;dOERXBRTCp|`8)^$LrUUVuV%Mns<`wWG8Vic ze(0`3J4hVbgG=oqQFrQI;KUIMki}3DQ3rPJ-YASmZEZgm4;|b+W&u!Rwqtuw{;WUO;Y4|TOKS^6(?KZ=+E4+<-qs_0eRpF+cpsUjD; z2j`bla9mY!5MCTBM{AH-lWYqJT`QGvPC%9Om0)o4yArlA1Q@`E{QTNQ1Vn-p(?bTe z1JMUn`M&EApehH_x3FV<2t=L7Dl!|8;t}562SW%-G{?YFbMV-<=0}pv=x}95@bNHw zEx5Irh#DFk4RKLCs{tkL9J&BhXc%toZtY3-DTi8t2rG6esnHlt!mHx3K$<#Mwpc7_ z@kR1;y%ujKJv%hiH_W*bqEmVT*|i3BTBXNwS)mb_c)RqZL;{s8)`8^_*q+3pn6Eoa zlnGTVPd$IsbJr17#Y;%ZTHpWO2?xca7$%)6i&mRVAb}_93`uel9mD`Il4u_erUR&m zTfwQ&HKJg=K@>3x7(fiHitLHg)kQjHfo>Jk!%=vgaF3185CRay4vp(#rz^x66UwT% z3CN*75QSO|H2fY}N7PoZbFAonX!mX}8I})`^xe}jH2g+lXby%3(XaCEMuehyB7+%? zm?)7Y7I%cO><-BtFzGb4Ji<7=l-gkHf6eo|ymwf-$qt=J)1ih$seX zN+rmi!L~Lmq2m&?L%6NzIPFy%8x$sw6~uI4LK)Yc9pS}y5!vUSyACKdeG5pU4f{)y z0I7*0R?3Ndpn!W$a3-*TM=~mf6mVbxAV35baK}WEC`%nDP^fas%VWbv(j7sC2nY1a zcM?&`?p}@003dNhVzTr=@2*`B^E5JBm>!W))d9dDp63!j0ixc2fsjHleCKY1sdn&0 z{Oq2b^BvoEEZ$G2;_j`xw+43Ob#ep=>PdWT8{5|W;Dh&P21ZAN22l;0Yth2SLdOe> z3x(bh!fNNX!+kT#qMlKu9EKRES)6k@p~~Nlj+H;=PmY7A)uC>VOHe0@+k2Hb(P01u zsk5H@$mk`hmYV1xriuN)!iqKpKB8S%N|8cktvC&!6)zNhLdGE zLWcuLF;&v9!mZKrBcZn>?Wq(jlSrY>jnA%tsC15yDtDoXq;h0J8hzNfii2U|ji+M~f^af=Q({Q64x1pS z$Efaftj~J%`Ma>5148^<78UvL69sgr8-)wuBz8nZiRgxl-vNxw+5+*%a3#QT4-O7A z+{+R#Q-B(kxZ;3Yu%SmqgH_~H((;oec4;EYOnyAJ3zj&-2LRvy@Wa@pX?HI(1kR}b zP}THG4@=yNi8_oL-RT4OKO#h_qK<D?Ie4N!Jca@)2?$g40c zm6^uMgD%j-E>&A!lP!*nVZ%KNw#lTGkkm#00~dm=gIS@h$Q9JkL3EI zNKrUxG(oM3rlTU|GXCs4wE5gB%&&j#t1u@w`s8;Fp$nz>aGE`Ns?akR6)DxmRT@0E z>)5ATh)8UB;@BIGZFuA3Buq3uN}I23kPqv7wr?M7J+^8i?$ft%$V zUA#%Q3?O>A>J1N{+Bf<;;85iF_P*1JL0;IsLJRC!itxF~F=8*buN`d0I5=bI=SkSeV8`dqZ{V{S&r z|AMICQb?C<(F!-M2|BK)#9b-k6_3;9~a>r z$K37R*iVgNXAJ5AfI58Gg5*9e)*66Tc&wa90TUP6X-HYauV>G(M|)bHe*DL1d?tzA(zV^}jwvNsWQ3*$s?>?Q;(xJqOLWZnOd*_sS z@ZOrhM;-x*HXkM8W(LK_^BS43p44YQSAZRVqz2}})Fa=kSvuD&X z%qk|un)+j_Rvl|yvwiKc*1=wr1o0!REHo6|&3z>arDE1*nZ^4U*}K zQirLHI}eQ;Qt%^Q<;9~O29|64b&j?sQfA$gGzj>knTYVryvybg=zPX!G!+$FK&J#~?K5^%#?$y3!Mie|~ zO8JW{aStg!$O9!L*?aCXTC4Bq3%zKGXz5aU^J-<0TtICm8kP2U1X13L0#Qy%R2R2E zl;6NZpi!12F9N}nQ6-yM8CA?e3}W8LGtayQn^K^B(~nr5O^hdoeh>Yp!R;W0FOfG< z|LCf`7xsu2EB?_R} zmaPDZDssEt)E1p=SyV&rp60+-aiN%&c{>2{4erRwP|@wS+)t|BD1R8D)M7ZfKtTs= zjV50j7)U>`s>SSQR;LT;L9YZeyfDsp#{SRchoFC)vEh?*4( zSDY)s2*x~ByyD>z>H?L12Vqg3sEd?n3?PgttP1tO68$GBJJznfXM6qrwQJXOe`M8~ zwQGC%DnyMnH{V~nf^qQsTYAPkP|A~(8yU5dH1#yQKTVEvnGYfFO6F9)N`g`y3q!NV z=u~(19CDo~AX1VDN>Hkd8$$+#%&cK@~7V#Hi9Pt|hy6 z2~{#J9;z&gL1Rv2+!=%R=e4_}Jt=B|Dp@{VZh7*Lx_J$ z$H7!3PbbRCtRLkW5~5U~;gAS&mW31&btq;RinQs6NT{WA#j$i7rL!^%{~3watAZ*g zxY2`;HDC36l7k*J95 zAoaU1)js?qP>OX7)EQ3Bb6|ujaB-(b6R!@-l6O346Ob#Gtb0hrwo>}S6SYl%LKL1T z>qK$#){QXbMgO>7w0yZV_6(<8H2N?C#siH=!PX$nBS4?>lsCo%82vsbQ2~l*PR^d%+*KY3FzJC4K z;G^r;-$N>_Bux36P$o4ZT4ly$Ft*;99oQcr%JacR+NKN zB}~!sgD3+EqPzqsF553aXX=_P4+2r#E+`7*DN^v{O=`X~WeJjHzIUPEh>GYXv!s6Y z*RNK^*c@QC0e)&qVs+pm*a%sat^Ey>^_;HTIMBd1>SAoM%B8&3b>B>@k;QuV!Xt+# zYN^HeIK8OZljA_%7z~D#Iu#2b!IYj9+Ns(m62Ee3dp0;sV8a9H&B`VLhp;+4p)QY* z+K@d3q#RccDnFGMrjR%mY#lxfNdc-u6hhR_-tLb5gJkBd*=&tJN^W9WL?kwD-@JbP znqH9c0I4f&-nsFJ7!-{0k@CbuUo2{vopOfL-8=g*C}HZnU^R}wi5fQ!K+AR~RxHM$ z)T6jEL#M=~;7OKc3DO6@*@lGkyaPdxzu{4A(x?~ZeIKS{MFy?f6NfRyNipBCKBCIs z`$54)&!ra?q5Q_LWN!}kkGe6Nj`eiZ^c)~|>Alwm2CmIc@?m%H&YA1I*i?-piXGXE9?d;c4pfe#j6k1`gKFEP1S<(7x`5eXZ?6?N&sOOKb^W!KNVGMP;sR+rK_ zhX*z?0_$l)o~hw*8#ha6_?0|u zL=k6`a2&yNkB*f&0Rsv&@o2Ic^F-bSB546`!>dF~O)rKh+u6;<2w{wyjec2peQw+C zwSFWj^qnxD;7}M6UW7tI9}gyi6O02N9c$aalO9yQQHe|SrJLHC8+z)o8P=2_vq-oC zD2Uoji*Dx_#$-To$C!?2b-nULykhU6-b1>q%dl#?w=QvTYYVo~49c2+S#}@AqRQEk0GvcqL(}IZ)Tb;VE3u&*K|CNImI(4;bSkpz zz0hPI=-uMz&a37>GEwyF-xn%Tgu1`^^RJiG^x;Ia>9GyT8v{brEJihZoryV=vo~(u zm_2oC@A~tzv%}X0uBGW$9hto~b1i-G(CjU+V#_HQoNbE{qA;Q!ux0pc0TyRYlt@8R zuX>S6-iu)c!GyjMn|rae{D29AQlgY5p=-%fw|BN++dKyyElb^ElzINwA`Zq5%1mnar<+E-Om)1NMhu?25yO&tq% z4;;FlOeP2Vk8B=G53p2EEZHEt!`BhCh*ibvH*Oqk80bv$5F^%ClZ?d%l6=lZ{ik6C89 z+iRx_DL(-x7mMI9{3xiZLph?}(O&z8w+-$D17JeK!%}+F+It8@*gl{kS>M>SFLtoC zs;9XJw*nTjD|UjAXb_RSj)bK#jb}ydmQRiT@yg*gY}|7h>F#a zl}kB8j|!U+nzSpXtu)4>mh%mR%4EaFDA%caAoRre41u4DPc$;2+fgY|L5?Ryhq@Gg zJtW3=-@^HtM?TtKyXWzq%yy8PnE|9>gjX3<+*m@40bFJdw)O1qsH<;Tw61AP@B=CC zFhosceI|~a1S+m!?@^5{RTYDDq{N!?m_nz7sqsvL$T^a!Ru~mZWDY?TC;^o0Wr$M+ z-*K!230%RFkhd{=(lu<*eR2<;HP5RwMN|G6{|D{Vt~pJA%3m{xsDe5oGgkG zRKsiOHOZxdFdfVCM1c{fDi?ms+sV*E4~i3PC|pZzHKe&CznY_`5_i*iQ;sO)8i1i& zCF8`nlH8Ft5)pxXzS9LOLY0j7-T{^QR*K}bkIXY1`GOXu%A$Qam$I6D!(f9iN8LQHg+y$kR+g15P%&e2&sM|5 zGs6iVpk+@&SNPPtOi3&8IH{aRl`2tUOE#M$_drwMdRWd_UIyFa<7X3s0$(6nK2Y_BC%Nc+yBfgExMsY!VSoDj}5G{lwy z<*j27#W4d{!K$e8aB8{%qAH2?tyrNzp`VUG6f|+_Tn)dfx$*)%ibs&;)q7M>FfXKc zz4RMg3fX=0N|eoUkY#0y3RKbP!L3zu{f3)=kOi9;*()y|s_eE%KIKBG-eJWzdo!)?pTipyg{6i9Idm^eh|vhk_X^2HYHbB(^K;b&&TK2Rzu z5{L*sC2KqdpllA9XANY6UhkTEN+NQE&G*VJGKFaL_dh7m0V&b4H?nKdo`>%cZ%yGd zs^KA2!;58(C>>Z*lj5R4Jn5qiI3fMFFBEZEI}ps41DJCwuK=Y)$6p1Cm=Z7vglL<< zK7 zR@Ix_w`li6RV|xXK)IQC1Vou=5C({begBCf2T`C2gX&{f@m4xX<@X;P2Bq7jJe@l= zK9yn*(o$M|3`;3d#iP@wbdPEZC#_g2EP6(r%9N|z$LU@Ls`LwvFS9G8AIb(`L>=1s&Be)dYVXI+f<^gcyX+! zcZP5Tm&k7BQ|IVNbxyG|WNlf(5yfqM`kahL!I4VWFA_mRP@pQnHHR}Fu`r+VkOk+O z=YG^`IY)o}*@7iXp?YCO%bbe-Wd))P9iZ@QO=vsLUQ^?gmfI4Ve4HWrx75|}DkU#u z*vbW0Zr5FxSD`%l*dEL%V)&2;$aknXjWK<;4+!x=lVFvnT*3rEZ9ew!8=t7`=<82c zmX|Ig&{i35-oFbP%zWqHL*6rBcHimDxpg3RgD8UZzxN%YHBNfL} zA4m=L_3v#?6i<;3(a}3SGedk&q2dfkNvkj0o{C2!6%d60N@M3NCLv)yb*Zo(EQey^ z3xP@&(B-o36>-ct=H+N&#}Y3WT35D;=2Mb{R22X9=L$D`ZbU)Ce@)iv^VR|if{`~W z_~KK8jYIK~!gsDP8@cqgV93|K=60%J%2}0&JN^Vxx(~gCBer#k97UWIsLQ>zHy9BB zsY@Z&nYB)a5rtD7-h6D&zK8b}C#SQ+9hH^%0y8Koqnq{%F(3sY4Y8K0-90@AOEy)N z7*S{#DLg6&5|pg%#}lW=Ns*F1)ZPx}Xhchk8~cVB;)N$VM-($NP^CE8VDCtGCKYFp z7n+o+sgCLC&%9HE=6>NKKnl7oIv#wLS1@p14bh0KVW_gEh$#Vp?6PZZk5q5nHU z6b!vcm{E}YBqo&08$w|fOy7&*22Eh)o@}hjRE5lEsw^#<1wMC}D>7 zp8|wri6kM82a|rHQi^;QwD@=)OC~C%6<1kN-`1Z!$I7s$ zU`nwvRtze-QX^+CU(QU#Q&Uq3G^#-Hxm(p-kqS^581D~}KJ_Rqk;`8UM7jHY`VGzn zBuZAAD9l;Bs)*BSlfH6Co+5V~cPHu**(X4Vz^MFcvMz&FC5=3@F4FOg6F%m(xRk`X z=|^c>4&Tv|y0*bNHV6l?{v*O zo_I~6*GyiskB6ZQgp?=B%2V}iL;V1S1Sl4<^zu-VQSs{^eGRN zrIP10_vQrk;Kn>EESyW7-c?ZeK@P;C`4ru#NR)+|&lVM?BDWD0`FC_zqWns-(DWkh zPEpY}W;{|cg&YYTqSc_Eu_UI$&C3r_>9U&oWkplPk2xU&oRmV9fuuxH)1fG!GNAA= z7;~s`9pGCBsJPj?Qb_20&F&p7I~Es563O0aqSuGgY)!+Ibn@yLX|31*RQsFPJ-GW7 zRZp$kegD>jJs=|;EX78^@pCn(_|{+;grdgg*B$Md_V(%&78T#n*3myrNKc89Rrls1 zC0-<*DUJD!X9*8F3u7w0p9U4|NpX_9`4oT{PZX3v;#2C*fhQ|n#dw@=kK!Lzbo6@{ z;srP9(C1A2XL?SGqDb@wi6U*>lcIKl!qQ+Ss$O$*`ut1}3t6BCmb#dQBUsVw#ImMrn9|~ z%?{(qx@0}M$`GT?KEL0)rz*gOtm3zR7n(FO;SeeTMCtmgpgPDQt|u!=IH07-;G^U0}D*asoQ&okvd*PF)F z^Cs1+cTwIPE2j0=&#BfUmz z{yA{K$wS2zq>l?iR78e&N2wMdQvBb+v(H|+@@zPeuZM&4gW+>MogVdMjwvL=O@0hlu=4Bh z2}WF+YfjCaDCC>p7y3k^K#CFO4eAjNk6Y+t>CGgSc_vD<+6JTw(xf8KUH#4XYdAQ$ zRQ`D#hg9s*4qpA3OJDrqk1tHr0XIX#B+yvjDIX}$lBq#U*}fD$A~Au6`ZMsBjZqQ%&(PQ&0pTK6n*zt7X5nw#3k-J%lqZTw3g zgLqmXqP_xA1v(=2+|@tGg0X%P%!fp>u%)UdMwJg`(LQwB@|WNL$PDQ~OuWF@AOe#>t=_DNS?Dy!9QeSaH z$`$8<^@9&@ZP`>*$%txcSt6b$;)fY_mxK}Y>udQB|VUG>wJ*B2nt@UX~6kdccv6v-P;ZlD8rx~CU z*#@At#2z#SWAZ8EL5>x!JgO`)SPBIU`H%A+^m##uvLW6AO+Uw@gcKMePXU`YFt;oYy+*naqm$I)EQw)N{d3k zl+WH1u6$0c>h&%&F9$|QFA6Bl@g7GORj5MZR%TYtnL-P2zKNo(R~xBih&Nh*L`4Yo zUAg+~_hBWrcQ&c;R2ex;*2S8n4qmbPn9Mw6Vz0L;h>8hOWp^ivLM{qzr1@0Y0E{VD z3sDOHf$naD@Do7EebW(Tg@z@pFrsj=m7t3ZD&Y#Ht)Q!9YUQ~_8>I7{f{z}o6^N{~_sRvs*?rW!h0 z8)-Q%W6$bWw9@Kp&`Iu4WP4J>6HguwfBW0BH6^kd(m<@0wIq_VYD7b_uCA3Q zsj`g3z-)Iz37@S`$D9uO3XA&9er=}5`mzEhJ! zyhxN)G)CNF$&^rJ9GR$4$a6r+S8^(DOxACxlcA_oQ)5%f{Tnc;rfDTgK;lxI&ZrSV z&x~K1g$sF>&|I245Q+p)1Y6P~$bTgO<$fMwfQHn35*5~xoPemJqQcrdRHBr$`Tq8& zKmD<$D%O94W%rs7)~)~e?Cixfiy<8uIC6bQNB z6@e(}KP{C5!PXL((!^H{q01GNhmj6NaRQ2O_Iaw1wJDtUxHts^Npg{nkGmQbpTgKB9}q_(=Ls&PYWYkej=W3fG9Ne&S= zB?+e9FXj8+&ND;><pp4uz?%Tvt%DOmLqD>KO!o$ z_n11%sh(vEx5%_~V=7oyzLt6)@~D`tsq8}vWK_8nKrVGL!3n55QMviQ6xssxNwf#( zPKgXCY50*Z;TwE%K3X4t#dqGY=ZhuxmqH0dNwcnEad~@xTOtZ2D~gIM%gaH=@e;(V z#heZyk5^D4)yZbM{T<1;kXZ&$@#>~nbuyXm$n^V#Sb{uNM$tQGOi~ZC0zFh<;KSeE zc)JJzzPxq)*7XaMxYQ(T$Fg!P?`~XAmKalu{vlD2WK3})VZ)$e(FXy*_O5}b z5Yo$+Z`$RE@@&Bi^xXD6g-PjR$yu0H0g-u>7xmDsvgkQhZGNqEvP_qBzZfcqF8LAC>S51)=~a z_k)%0JIDtsxaKXke1SnFGph@F=j-;I6W)T1_4z48qs;Nw4127GB zq|@V*viZgojY)X{MUuHP;-PU`rOs$G5b#dgZN)Lf5#3V$A2vY8cL@+YYWP zdqre1<4&N0C}Kj$;uR3HLQICtac<7U47`e}V*VF;kdeKbSJW&^w$}GC=u1PdUuY7I zq=(2oqA{r}v8*VImeMa<*0`*F+HbPqu=1n3oO-9CcV)>(C!CC#T*D7Ykn-bzyE8Ho zs`;N8k-U=Id`Hh!3`mU@UiAE1SFS`?Llnch#K=o1bi7IT5RGX`06kWP9+aSZRV>Ln zn1VGOu(~Tz&QTDCgluUQp$oY1EAuVdXtLZFk}2+?)0B%!fS>D*@u`y!@-g>GcgF!L z>bw!gbh14+VRFu_UoHdc)kYIH6;!dZx~2Kiqf(?WDXBnIq`YC6w%PvX($Yv-ad9B3 z1Zs#?@Je}_m|z;<)Cw8u^+c7%67@|@%hs*CpL{*(G)+%uCxb{HA8O)HKqMmXwxV=J zqIz9ZV`KNUj6Qj3O~DFAg_)lJSiCj(m^R``MrQ5Bd}dewD3z{O5u}i)rV|g%Qy01$E}75ouHtp ze|VI<3j0y%sS=(jf=wyI&_qR7=A*4g`_FlkdXU@wkc7c>_{>Mk*w<;VeW-2U^&SJOkz^m{`3?!C&HmnMPda! zwKtBR(r%Oo$_$CpWVuIkw+t|-LZnZQJH=ZGPxx^uA6rNEU^S#^Nh+vwNwo9d>O+pG zNTi^cS{?n(m1u2TT73_lsAnt}mqNR%cI*bP7^*t)z8`gDRYgT|IE%(ttxc6iN<+Ag zG2ima^2PYms0yTh`&)&|jYd^Q8!PIQ4e9O?T6t;y#3^J@Wf4VxDk13=NP1ELRb1WF zjt0UscYrd20!G9oxWc0*BIV^A4~aG_+2OZ>8Zzt!M!hk)1;e zizp5BMI#Z-LVCJo_tRgjdi>$tCpLZiiLY-udE#KpiM7etiFa*y{OJ>WKDZ-xe1Ff= zdv-kj;8(Y9Kl!c=PoMmRBdYAq;W;5HPd0xY9%NV0dxa!D(Nd*~3XF(+>rN(X09h9! zNIcmmPRlh4Z=ku{+2t_#z)EtB!kRFKk4?~WIPnD;cUmb}A)a*f_YuGO8cDP|9L1$f z-IGc+H46>dk+qvsWsx%S#LcLxxGyFHY4q&b33%ds?6JpQhEa)>sM<)XJ~=YpJtDh4 z@h3DPFss6zx;ry`4Pk5QQ-lmtI8=M4EcNw5 zJn`+VKiv0;4O{l?d&5&z$G-ee1>Jk^QpeObE#XQHh_5)Jkl79QJgA__(gi6&N<)FtHFN2)8r@TllVEEs-v#?M-o!|RHnWk9B`?PYgpB*v?5_hRZ);Z5zl5XPn^x5 ziOZK@3bfw(*0;h+Wo2WktS!wZYFRt80+j?N#P4(wLxzp*s56-u8HOkq zj=-bdliN>?64&xuZ%EF0_(V>Z)OXRa^6(fWrjUXZs4|7*3TyRoS=^61w}m3=e7vZj zCUZoh#3g8?S*vfymIt?-cxvmncRc>>mL2;((Yoc+`yPHuT78diczjRC;|HH;dwR>; zw!U%4@%m#=J-y+VEyw>EQ6cBZZm@udyjbIW+k_*S;^J;b1ydRd2P=Tm;awo)At%Ep zv;h^WZP*pNjV^Ur84}my zmXc#zK3#L-*uJ-I+H`#1rV~$XdfTSmdp_9Ga^e#w@7j+tqVfevDri9xKK~G{Kc}V3 z)vg4oo zVj*y)>N2yk8zhNrdep_~(Nw0xh+@&#-b^Z*Dyt|)HC)kXeDtN4FaOs1QJ25_7&y@Y zeCeoWpRX%TF;Qb#Qxn!xT^nZ(luMySnowa?sZlRqL5_NLdwWBAe2U%QPd^D#D%%g}`voXj(Y3F)dny%QR=c9I`2Iv?1w>7}^|zN__ELbN9|che zx~6_AM7?4~!sYcPyvkKN*+T_cPKgTsN5i8A21Z6kM+u*^!i4ygnv++KBERRS&E(*G z-TPnf-@2Q4k(_yX!Vs1D_3sO87B3`4H9o-zZ%%$^8-U`W3b<5y3(^mnEB~9j5QVk) zMO)yC{*K{XTwjtwN+xBWLAiLWDgQI~J`OiIU+FsbQt z+2P*)%xI>zv8l3L(uPK--ul>gos_6dySUU_!AE*pCho3syB53Kic*M*R@V)5caL;W z;ZYDp;M@=HiWS+Fx52LVnz;FQVXbm*#uS8D@Xmq_UR`opGM{J8-OZ5loJw9S5K-~d z-zzMlqS}pGE$d9MsL>y|?8ZsquJ7v^6rSyK=J4K)C={>x)cmv%3tJ#IFj1UtF)8m`bXPLghHgf$6#gG@_Q8|!wLBU zs#G4e+*t1;Z~x@E$l=Q-@tRuxqD6fj(L~C{9 zvg+uaKqc}Gssf;*k*3z<2x^}i&7RTOhVKoDe3l;zQogSgq!hV#@AF962U?gHbC>vPfz8p8;lIEO( z0#73ALg^qacY#L>{ET&!EK-p(FrVA!<}a!gPkt?C#!I?Wp;HE8W;`#}czoB&2Mj1v zz)AIS!3=kjlIy6%CD0@9|KyYBE{(RICHSp8xe!HvI+H1$T2?+qsNB=U&6q-uO}sTx z{9t8eeX9fqs}ljK+ohT4>=0BD&D5nCx9T1liBHA*PZ8|%p$W_6d+#0gggiN{dZbtx zO>Wf|-waefAjsN&PKP~Nh}ULH-lg2SV_y3CLJ(y`yz!y}iA_X^nt$urD_9iskITxw z^&iUvm9J=*O&;{~05!Hp6VKscmx))lSK2l=J5k88UXkHs;st-rxU&5XHB~}SeNT<5 z_QY%t#BKaWKNqwp7{7HU1w=IYl%)U`cc-Jfjvm$C)Q8VJd3usoUSr+(Ic!S1Q|GWL zRzPq6=@dl0^s&c)=?CAvC#AdYN~yjrNw-!51P<>azjsZyh%$FcTW-3AmBhD1_3`t6D7eHn9?U_OR(d` zlPjH-6)lJ+3W%sU0SU?J69Iszj4MwmJ^s-tV7{QD2P~o7CF4n3jDO+Slt&~;C~*0C zxQz9&oU~CFM0*daocOj8g?N;TnG%0UO^-q$Q?R;tr^yg`?Y?(>T!{K8$2%Nd`r%O| z!Sk-SeCCr+p1(9YTHS6gbq>K3B1SQSLrJCtP+hqEgIs6ovCC(_d)bI;ZY9vSEE@t9(n&~K6(1Wh0&=@`-u0b>4~38LXj{veRkqyLez!x7ry(mpFxuxH2Eej zzco?8e2=!I_)?_!1%MKJszBmTbsbr9D=u9+f2q5>Gc`5Jf6|kmQiwcI)aEq#v`-b< ze8^`Y83w_h3@CLe^B->JOOy4;6Yr_j(T!d5@xW(R8YI@Pt4rU?hN0=fOWx z5^At2Cu6#9Rc3(;lOnb!K6NjhCzvv;ddEB7@c}N?N8j;*kAC!{5XHYYh8?@RVLb+1fz(b0%EZ}O3Y~mDlMIw zig%8u$7Pns`SV!R$Vi4pA4@^AJhRNz5SW5PSyY0PjixP;&&SLiP)OZHp$ac-?~M>V zH=pA4Y?(;I3QTE^Y*;jDq54tG;vJ0?1X3tMH|jT911Y=TuA+Y|+r|U?x?4ZWrW4u% z%Np0#nS_!tA!wLO;Zs5uf-RLc0fC3ZW95KaE_i*2Zwozo20;VF>o=#`SCzU50icVDfXlhh}`lM_k z09CmGC$2mRRC$d)pJ7DdC{m=9q#&NbNe@IJrL!y>14h2RILD+GgecuPbfQ3rirCbs z;6khaBMFVsyLuGoizp>g&qPJ$yCaxUk|63sQqJ)xscAf6Ir&1nJWpQyY6);Uj|%Jd zaT;C}p{8>iyO^1%C@t|w0hIKrxLJ!2f}je00hE*{=n|%A_I*lBDl?i&#jD##*kfj> z9HOj8MX75x6Qb)TA|cu5kG=G*d^J^3!RFHy&6z|Z!YZ=PnV7MGps51lQniiAESek< zpfn~iGSW#zzB7Byg6E&n#l@Jan=d6RZ_vq2iT4VdbSqv6S~y{g11U)%Kw)xUK%_T{ zUHQMowJ<~>i27cE5EW6P{s>WqR6s;7ihnhYNxD*Z=|{YR2ayNM!0#iW8I-Jp@lQ>R9l+A;A~Vt^8HD61&db&kZ7 zoUo;GlKRN7?M!#{XGQ0fCvEU4P!;j<$VIe=Pzy zodvIk3_Yn-@l-r68|J2_m`_+*0b2Y4!sK-Z(I{ z88h4k6;wI7{uBUFh-4d3 z7h;!>`KtzGSd~^vgNeey<3-(prZz>0LYdm-1xdST-iaJZA9=?|KJtYx;8giXDGk5N6Ex>QVnbzOC_M>Es!2|kK?g4tTybTGhuGX^NC?X^lLKx#(mJDKnr-3x zoiicghpEcWEHGJ>M9wt3Y8RLxXN{?xF}Rclp+LCK`!S{i9$+|&;*ZeLY2xgjc`56 zCC;J{u?csGLA{9rd7=)#<}I%WsWVR!p12$rq^hgSh<2+xotlItj?0(NU{dzVOK=jr zvYgySco_wfUzz%+ij%Y$A*!K06K4gO3zsHwDD+u~ak**yRgUI%kBpg1Y?&>G#UqWPDlAzdgcfB`9>x1_#^CyE(|Rk0FQ4AZNMBF4e1 zSWK>Dl7}R3crx*lOOCp$S4tz1JBjk!skzuWh4D0J2BJM0RNkrlO^FIJtTc<(D0F`+ zY{l!S@(M)p-kxQwIlDU&y;`xL1&Y$$zMvS3rS%bJp;qvKAd z$qT11pLVUlAVAXQATX(fqwo`v-1-xht>Yu(Bi)_wluAvUy+kicjp?)Rc@HQVPuwkM z0-}(1qwu8s6g*YftH$?;Y-@xdBc+Su04H@RT&_JbUow>Bj;vm^5UPzc#2YPulnEt@ zmL55-_6$*^oZGs~ROG7Cnr56=)qobF;8AnVOKLc)cwV=t=GiM1+8MipD8GI(lAhA? zrLvZu#VUeT85g=BCBwg`P`!1Y+^7Lh?D>&S_ zh_Yvgrl~=c2g-<&>-6MldE!+^qOuN$0;o}TkIJ0AAZZ(ryau7eSS$k zDMI|gMd_%SZYSwBd1RD1&yr0LEknWZLYN|C`MLbsZBDt|a`^~@TCz)l(!jZZgi%3}R)s3CB5?wf0x8CS zo;)?_ZHm#U_6AlsQa;ZA;0HfAf8JY>f<-Y>Szb3y-H=jWI`8aBE|`)Rx4<9+KXVHQPqCPiT2t=*6)mkFlYa5>F;3XXF)nPzrqLQY%!jmIPONg?uE9**W zIGiu5j3$ALYQV}o3P~Xk0V)6F$9K7zj%rUzZOSg%e_~QyD+MX}M=WWxmxzxGQtW8m zF3TKg)bIT1ADllGT76QP?yfAZpAHtqE2q;~l;{$XiOF(ROoke_Nhfd|Pp4DS+7wctx&caf`rLcuQh}8% z)uLt<_KR|w`S3He`GOoi!Hdjr%#VPH!q5sbqTtCJmNFz(Wj}RTZ7x~}MItgFRRBb- zM$(O<8pWc1^GDe~>icyUpMU<^Kws;?jcYf~vBk~#8#k}tcwTnrNME15{yg;?*V&=t z`PuWc*L07LTi25KmJuaK9#OmQmD#j3^8^l|!O#E>DP(pn(iJE?OnM1jE@NDy6vm-h z6z9^er7nS1$x$@Tp;T5kg|?rRI;!jJ3Zf3kshQ}s`lNWr(GPs!3&Io}$swm&6#pvO zed*=*2~_l^h@)RJrUa{ahJ3$nyeiAklE9)|Np*TOQQSYB4ZSPg>t!^Jz!Pd{k4KHC ziL(SH&f!oN;`~=H2hZiVsTt9#9R+=Ty??%*N(u|n2u2`4=Lrg~Spb#hk z>P5%`fe-klm=!EtFm|~`DL@LY)TAEB3;+3HVg-q|q_Zq)0W0$;vM;p7$HgNwAqb;p ziAb6pD_tsU^*Mcnj?^wC3elN*-RodVZAu~(Q|eTbNzvX3RB7A_W#LJPiWevFC&l5JU-5vY4y{&dYvt^||L{AKtqD8|n1yWZ#B? z*%{e{?FL&$$-Yr|)J?8y_*8#CEM1?)#BN@@d2{AgZ?fjDMC}3#R=NEAhd%###Yx$) zxwgw)$H;c)FoUwDAe4oT*aRwZs*m$qZ8y60{lul*vo6()JU+%^UPeW3w&7f&G~CB2 zl7Cf<^h%2l5v2&CC-qU8)A8~gQLkrQNXDiv0M&%?01;q?S2fV9GJ)36ROR9}$*s^4 zDGDWxPsWi3_u_H)b6uM3!g+wA$K+Ug_q&y-cVbIM)P1i=yFefiS;N$E%N`J%hG`e@_vZy%sO{&BS^ZS`@IyJwku z9J~;#!I;Fgq?M>s>G2+mfvd&ra-j-fx>tw_i>7;13rul0xpp8m0V+f#cJaW;qh|^o zMOc%i%;HzxqBt}(u~Lb8Ge~KF>g_XU&Yc&iGTNaERAt&b8wS{>kog%MsYE$MDM{1W z=~L81&;(4-WHeT!#Go!;zQ8aP4y8c}XmUi+gQAhA$RNuscWHc{sr$TFsls@Yk3oQo zBBd8Exa3t}O-rrW+qpE+yYdeg*B8yZjHpqT>??qN6#o@}bM;$*C2@1Oq9ha^BO1P_ zilUB@CZgk25_jM+7Lz@s>T1N0*aoM{Mt9{^j33>NDD4L^^_*7KhdvJwNIk|A1w%+1 zgJ9y84nx!w37=VHY2#{1;%lMJ2T>wQNisr9L!iRtDPdOloN%T{ErBSbi_E02K#nN+Jt$O+LZNcW*G6k1XJA^I#fBPO396k$7?g~?cGhWnwn%9hFD3qqeD|^ zwV@|8#l5#7^(PIQpMj^(atKqeQ>tj?Ib&k&2utI$LK$)>g_W13orY}rPUl7r7GLnV zS>EdB>m6Bk^VK_jN_6o}MGGPR9gTjjFm`2=oefK)MYR2{kcuQ+*?^O+(pMsZ@~RT5 ztTT3U#~dBhV)u^SRC+jew3OVPC@;D&wEn;)QsnP*D)CYlWg#u-1wfAXsnEp&PV~*lHDp6%`d$+!(EtRf#c96Yxfy zy2a=pN}QKyTun?sovEUZ&{$n0YBYX+zwh}yr*8|xdol8Tp65L0dEU1jCjIz5=XZYR zoR9gaE-(??yP2*OOd&!M$)6T$pMbmpVZ|)nn8!qyM}n!aow$pqITU&eQdE+Gnf%G? z{PgrO;pctmc-3sEn*WD7efIEW?@^X&e&v5K4ck5C0)ZTB+K== z=3~QssM(8VR+wFBx2}s3wfVXok^1VT2A3QiV?Y@3!V5c028WFT!;#1Fs03&84GYnf ziAqYZfeI;lD7K6<7Pu^k3YHW&uV6}n^N34`D0|#Yvv1QPi}gLzJ<4T40?yR>vp|I} zB^#_TYs1c~UVGJRIYEpE+ZmLtaG2_WK+A9<9zkO4(OWIO{D4RJybr|%TR=sdE-5$s z3YkgCpCrMg(WL$KiNGUEyqI)bvUC5Ecn+&FT_pDRhL_J8QH0O`7l^8^wz*MtYV&b; z7SeDFjXul?4KHu{2sqU^QGLzp+lR0HT;ICo(1ci>x#`-L#(`^BHuKQ~5ETQpih`S< zN7h6Tf*YTRrGhUU%C_PVCvb#(Ctn*1Hovh)b)&X&+IKX4DxAxH!IKr2kenzAwH^6g z;AGbtt!gpFJK0Pq);xkH#2^%>_n;^UOR$NW@AjFT$}EZWqhiT&9$f+|<_(6eU{u~g zM1j?uoiiB=knCFGM<~sjM=#j7v}%@AJ@&srly{@5EY9aMF(9fIqJ~F1nua?1hkEW9 zUVq!*x`D2~z7~iYDv$Pc{IIL(@xyE&(AeMAG}!j;&ka3$pa-)mJW9$$z5JjD`P74w zWI^CH&yfPA#FSS}_K8x+-J2qQr$7TI6+~pv?F@>tVM)}$5U5ZN_F-7Q$^`G+rod4$ zkYGwYVN;&o$04lTsnqIoErzP+zL4{o&w?nV)rsz*{pV2q;FC7v(73{bD)f@L{lZvs znoi(Ox8F*oTMWy}xby@pVqTgipY8qN5|*# zLSx7b$!{_%L4`-HS+mKPdS;Y&(W4*z+~;oGh*LfD)wKOy#Q>~tKZ8F0@!J`vl3R_9 z0ga=DV2H~|N-TZSV4|(3rOm~XD9W;5&Vd};XDyZ>r`Q*2J_OCDKxrXnM0_qrn$Qaz zttH`9$)>i8r)*z46J!edy}(RrNn&h`{i^-Xd)~Tr5H(9;KF8%x)Pm|d7HwhksIS_z z_~cRT!(Gi?qa7XV@9G)o>+0$n+C9|Y)v?})>RI34^TU?G_Kx*~L)SjOYvn+x|Jyw+ z1O3f-RLzBmV#@u?jirMeNk)ytCQ?dFDgu702r@p2x z=ezN3PDSIviDPRJ1w=&xI=7rJK}~;fz{!3Di$KbW!lgEHZhYp(7jEP)o+cWNG{i`i zV}%?n3~LNgAXRz$+0POuFS7TDLzoPrSBoS>nQ9wN3@e*cEe7gX^TAZ?Pl!C@94X=* zF2m`EOZYfVbAl(mQfn|?M&#YNN->NjFW5etM6rj|qqqsk2H6DZD?S$Z*;i%meJ;c=F#Ti(LQhW?Y<~cwE6^G?ard3r=3RPHgo&5}5-tsft@-UQA&rwn!L03S(mu0F1Lg&`NL zMd8^;I29m;Qq7ky+9X9dA%F_|nWI?w_N-t@j0vkH9HziOt!pgpgzS@@HCubNw3H;t%ZN(*kQ26kHHxyOu3Rix$bH7GqNw)eFs{DC~w;aaooUY%QjsB}n}4 zHjXm1D(0=0xsI0hU$0;TB;&tC*8{1-e|` z?^>qjpP0(auozd-)MK))LrLK;0y=LPrtmr9C!HogSh_4BW&X57Kyik6NJP=%!bZ$)$KE5)?3iqhKirxMH=vkf)IofhfF*ihe3HWFj{MJ~>~ngJ;R2 zeor;3km3>^F%P0x;WLzh%E(|>oPpF0VNhHF7bGoNB4dLu;|ZcxA749*9#wt$@6Vw< z4Y4SCQPKjQzx7Y+tM@+AsGROm1_OECjP348T%oB{#d2cs#Ddo|Bi)^eycMcvVQWT3whK|26EFp3M?v^GI{2?MF8{Ujuegn9X5e_uz2Ev zIDrBtK5i?QGGKVafkYIfAbp$D>k)$Ia;J*?BiYnu4h=-fqYfc=DAh$3AF~0~qDKco zbet&JGjY*#9V^;`{KXppI9P7}frWCGrU^FG@j}iJB|vS|X-a6pQRR=B7OP}b%H`XD zf)PN;qQaWCZl&c~n3JQzS)n<`)E15qUy^bIaL$~a2+Ml;@pWs5)>h4isTNbv(hg=jfP%N-s z6)1@+DFY>lxF{F9QQ=XGIZSHvS%6PFo(ieN#b%K*Q#s;^vKtW{(R>jGYSb{UeU1kLlzQ}|lz)LtlDkZ>j1y!2(!8KK)(|@uM3|V}ff5VO) zG~|q^N}xcB1Csp6L~W)rdK;#)X4rbDEMS?LW%OZ z+#RUJiBPAC(``)^xI#`K5=n&45g7S6FX0Ibl%znq)|T)VAOEx9DMptf^`nv{InzrE zPnuI{U2w!v_?7jlUN8rXTDx{u`cWdP;eeK!Sa3NaC8DgsXMw&nJ++RFP zGO8#<)rZym(`c0P%|#Ved*YR?GqGtt4Lnn3$*Wd4RQgmOGmXj!+xY5N85!R210CMr zXfUPmEQxn|@(_GdM9^~|Dv-hu6IhkwQQ4!A=*Wt>DQJsa>muDJ@#YmS5A_*ObLPBs z-MXc-LR0|t6btro52ET&m6V_3{@<7HzDw- zeNRItD^@o5PzB^TRBH6esq9PoqMMW)YE40uC@Cfx=FA9tL_w5>ebZJPROM}eV-UFn z)S-jm0#!09n;3-xr1Y>09ooT)nXKF*6p|NVAsH?dJW&`Z&vM$p0-vGw>X%_VymENp z%?aVF`nEk8gX&NDxAQ<r(g)&>Ov4@%{@?x5*aajb{(?Z z@~vw0g)MQdUTuGe`}VCqbO_$oEW2jD4M-UT7jFImkAMsAa^DHp;`0{@7TJ??0wZBo zP8c?p26;C+nka`e6q~Tto=_@Ue8`B}lszh3DrO;bh^o~_)(tic%6HETq19X@%K(1e;kSq)VUJYHJ=Veg_j=eyjPMa}rPQ%HJs@#n0m@1_y8 z19|L01t*S?C~&HHg}^5w6%hxdqRc)3gdBV)6D6kd-GdYbXLQ3jH85OkDP{8=jii?c zQ3u5ok_#0R4OKwYuGNQDAK$YFydcVki03bIrlgZIxuUs-RmDJ6?otV{SJ6z&U83B8 z%koB{!|9T#rJpdWd_;;)RBGuZgA!6k)Ur*ElPS2^0!yno;Ru+x+mrahz%F1_5+3Cr zE8h30)yKTeH?*#5_C#o+fyQ5z^{F06)tndmq&oDUAZji{yQfaQmd?|(7F@1N7kkd{ zi(5``3ZgbAqL34%5vFW0WIn)D5Tybs2q8MH`98Afm< z2`A27hYs$N4&{l45Vabj_Uzk-g&9#cQPGw{yXKljm9LSG-w9_0;59oGHg?vE!L~ zWoBRkGKc~x6EsO`^et1UFR>uoW#b;s)rCY9rx!}I4+%vfUyRU!@oWoUM)cVRM?fu43&R{LaDP* zM?roB1vt7ayo^iHI}=DI#|xrN?pNLkizqus3S%Uurew$pD}XYhgo1excU%dKFei!- zj>VJuSTL3B%qZMqM1hou+Bt_hV^K?qof}kDv!!b5NPV{9DThzo{V!_lFa%t9ptxb| zpZk?34#O0~yD&Ak%Hs{m<%m^$%f;=V*1cc7_bP}IsUk{pQV8!6x=TrVjM0X`fSmKG z(-UG-}qZc(ev zpd2X=O^}AW=E;SaakXel)GxT2I=_P>dsM{l+@TyOz<9-bZD(qO1c|D}DumQ?slrgO z%N0#T5hbG%OG=m!QQI?8NVEV@hUrjvm0hV<6<}>qzLGKn4XhVzIlg)=M4{Ou3ZL40 z`ar|s11JAwo!*NPU5F?av-l@_WM z8wD{p5Z5!K>I|lm6r>Pp6;uIKh&-fy38&6ch?+&Qddt|!(?^c5L|cemx28NDNxEs8 zj_A-wS1+t)l-Su!67L)0U}O>D9G|P{CqBlq>48ejYBga zM+b*^cy9G6bg0OomP0q$JIRU4V(Gw`7PaFLtiVwcZp2|kaUS1CNpOPb1n)gIVMALs z$sRdSl4tg1lX9AzD6VW(0!k{r3sb)A%PU_0%$Ge&SP7@>Q6THjl3qh16*&|}{h z;M_f;b202N4SO{8xD%!Y2WpyK-lrNHPG>dGRSxvuik!+ zC1p3%FRWkD+S~fh6{)EQQVV;xv@U#3xu#tIfeoNla-!^ahDS+0{3D{g9hWR6VB#); zf5;)iWgg0(z zearaubJuV9%C@&mUjLTY@yWLF>sPQBTle^Rs=f6$-Zk=F%EBG@vQqvp;Tvgu)3aYJPRd zXWvI)(LVG>A5cLRQUKkzHVme??0_aA1ykHSse-K#-KEr#qKust6H<7UQ6Te?qTzRz zTfoGjR^MVjC58V-68{uwY#H8vCFy*}} zr-?5_%Z~>;sJm53b6&o0oz0Bm9D=CX6k8omPE5Xn&6Sc^N^)SNhbiQZqoXaXg}kz< zwsCZAXQKhe#plyiy6N?k6XRohFQl>8PfU*Abl>m)`uqFtOr{py9EbpR<#8YJV zDJ51=!4MKsTwc(Z;tP%wkqL(gVUa+k0EPXfbEf8B5ut!34l15WyGT%RiY6{8RW0m5 z9-yX(6b(G{CU56K6n72n^567T#b7E$&zC9A=gYQl-Cmi1gbbFYT!rj);Yr!1asx0U zH3y5b6eQLZo^_)3-u&l3{&~@nQlXaTuk7m>X)6u)FJHC0^zFg5gUi43&Bl@8+q#CE zS_XPbXc|$sPyXqTe}4PjZ$B_oXD9#kr^#Da{qFa_yZ`sVWYFCIyZa2Ruitk+RZec- zv)k|QzwdXyzn@o}r6W(}Up0R3sjmton`8JR)17y+CEH(4t>`{K!TwRb_3U$VZrizW z@VfroHueS`x80;Be|7GjGwdlf{{Hjhz2n=;HLd4QoI5jl;@sqs-tlwyDAt#WS^!a) zlmQj-bLx>40WU(z?a9jIJt2?&`HGl1ldoVYQYEx64&U_!YNZsCkZ9lOW$|Q0M}8kv zfs<23Y|jNo94>B4)x{E0o95$CzBg$WNMRhDYNHuc6W>am7ROHs% zQ77ue(bF?^Gek|?y6V3BLFKQ&;$*=Wx?gvmsZ!X*Hz;T!9+~{}pZ+|KJEa5%m+#JY zr$r{}-!j?TyJXvAUfjB++lV@M{>%;R3tH}`a(-fR;{3! zwYVWUO#(`D=jBA=N)>w%MAlx%^R#nQ^Uy34)o@~bV)EmyrO^7_gTw0whkL%> zUOU<`v}$Oev1jnR$CeL|eDRKz{dWxvwv?t3r6$_=VP9{aOFE1w$L?V_w42&~_xrz^ z?lYu*&uKJS)o+*=HJIa(C#tojn?BC3Jn_ojy$!~Zx@Ogg{0`qg>KPl#wX2ptqn4mv zZ++|A&UCL>)xGVFZ+r_oMfrxjY{J`GzpC4|zFGdpH-3OO^}W5l<=$?h6BhfcBx)B(hY|K5lmKsLc@P2_ntkkTIoxQ>1P1 zK$uSsmAume=pqWyr-G*ANMO+hbfVx1t)aCie0+QRfXOe2qTOdkR2Vi zG9{#LS?UQ$h7+sE%{Ebc$4Xm2`j_7@+WTdgdiba3+6@QVXCA89SM8%uZ;INi@_R7I6THDigx z0IRK8_ zA!flnctXHr(LR*o5=NAUcO~fJF);;ISQIjkGN6_jMP^Ud{-TCY@qlZo!s{g26_|jC zI#E1GVn!+KS;mbFNUZNigcvt zZJ|zetOOKc!qrMTUps2usLsx+*;I8MyNBM+U!TjPeVhaeN){xjUEan?uz~?4p4BzWMIGM9U+2`#MQDj7nQ6lLRRWMG;G2L@is&CAe;6IEALWXjr_VpCguF>dR3Ut2=5h`M`D zB~Wn_HMz!Fk!)-7)*dUq(4=!{irKqH7dDloY4Hw~lt9{*>}bzEs;lW#9hXz-wf#T} z_0iaifJEU@^HBnd{*>&58!v*Tj8p{qDu63qi18emET zQJj((@q7v46ka6>r_RJrW{SE$iKtt)zjTWMwa)V;MoB)OU7{cWq9W8MNGxhjSiGH= z)Lb=wK@+f13!to8Mi5mO8xrOf`mJn$DEKIWRJ#ZD_=QxUMk7zihGz{4)Q;e{RIV|i z=6?F8+nzaAM`AlXIj=#K{ajnQ#@4p1U7mhXQ*BL4W2uXcqHNzNFZ?z%E=Bu*-j?wg4SeLMEwv@`6Gqx62R{UoII7@7i}?5 z!7xzu~<$R;uHSLBSiwzg1z(#Z-A(|z&Ud^ zhluJLouSTYkDXK3RbE*#qF!>pTWnG5) zJWh^~FiKDvN^V)_ajic212vJ8<*9e}% zQ`<<_?yrMSQ%_@yf7IT-y99O-n+T7Z29)PyKvc&u`->j!7?6L+L*j2G z@>XBfTYvhkjbnA5+)zPO+i1tg9q(#f**846d*#4D-&^{I`iGw1Jla+2(ytF;QT?A& zCBI4@HMjUTLKGIo1zCFz`r=~F6o1<;A8FD~)yb=_i!4~R__ATyrvfcv=%GCCkOTWl zS>~~$B6p|C?wbRtgMLwps6gtFXo?i1J@!}UkZIl_NcpxPP7s9)q+CE`5>g>dN=-m3 zMbL#M;3DeoU(5_rcd_o}{7pb5EfZ47qug>UR+b2lT3Q^zQbDwK|{=mwW%_HkaM}~Tuhwl2u`k{{I+eQa! z2iA`a5BD^WwjJvSwZVZe4!?VFn98-~ng=9muX~j5h1>P@;jaFs!KT}~nueP?Zfojq zTHkRSEOo6PX&i3q85(RF95JGrGf~xF`swR7j=k2BWh*_Zqp#yGHnF*5W#7s{HUxds zaMxhpZFlvpuiY(tRB%GnAYAcVbx@f}l+8E?B~Oyw!)f=ebaRmM$-%@j%bhNt%w%um zSIYZSGA(#bS8}CXsuqZ8njvD*B}F8xfG8^*DPaUvInqZhk|vM`CYC~!g6lhcwF!s< zD9&s`^AlBzklf2nOa|p$DksV>Ce;%opUG5=3&Txh+r|ueJqsz%KSBo7nq}@#TA|O* z&FVsh6v`{&=7AQav^GNNPMs8?2~I|LSErP7m9yXKtEwjVyo}Kdd|>&HzxKs}Hw}z7 z4s;9;bq%)-4R!So+|@SJbVpCk;QBB0fBU6vJ)O;MD+j*$(ys4x-q6%DcuV6g^=48J zK-2*dWk?OQG_LRJ>FDTc9Byf9>gw4&*tL9UxV>xT&_G+`=)g!zN0(Y>K~#11r+@mT z0|)jt5bm4Sk7{ghX{l{oUTP#X*tERVW|7I3#i7|Oq6;hfVAhj zJ)EHB!9QON(_4S|iPJ>W51A9$OG<^*AxbNqXVc1>@j^VwsZ2miP#uJWC~&$iLg%t4 z3{;X!MVk+)RKnk`w8Mah4=wRs?LCR!lpe&CQzfi;!{tOFA!U>5FD_iEGOae;OY(Uf zZ}3%H7=-c;lxA?K6D7%`7_Scdp;DoJB1(95LJ@b043#R|`CLG8cFsCc)ks9uG#&fq z7a;2SL;Zbyw;lUt6LCl!qidjVbmjWtmcjL3qbzGJ)Z>VN5*`kFs7(1=I< z9YlGDsjIQ6qh43M(%971*wxmyvfn9ysG3C7f?xmo z#L2O0tqGyUT%0Jvf;Gq@go>0zu(E08;Nal3gDWXal++Q=I;@tW=iWV2KT1*QgGLh; zCCRDyI}c~#(pDU7edCYLgvBbfcC6P z)IvLj6KB9gH3ELIDSX<=Py@T1nu(#d-=PeX`&8Dt>`@j!_Y1PTpC#$e7n476n|+T8 zqAYl~d^r&ZQdqfa+LqVWw$!$_w6UEaRR*UBSGTmaweZ^VTie=JSp>XRW4%t)g?_t; zs_Ah~hKN24adyz0#4D&NuW^*}nAJQq;Y8K?{HVF`^QE6YcH`-W1$7D|F5nhKY1W}t zCfKGS$;P6(2#N|jgPMO-49eS5M& z!OA)@mEr2tS2>e9ohSrJ6tf=dOGK4Ca9#^hKw{%UKGMXgqFmCm9X74c0OYFC+Xp7< zW{4W;=y7#)c%|R#x=ZhVce=gP@9WEDCyEg$ntgYl9V-^xTabuq^JxFV76x~10IRhi zidG+BX3^}Us1zIWRuXkcaXvw0Hf3$Uph`)B{)$x%DEC&ffCTDE^{&~ z(&Ctb6N-(kiv;v#P?bXHN}BL=-Dvhj4=Nyvj#MR4DCQkP6glYFl#=^I)HUiTSryhi zB}sAh3YcV9j+p$-;1D#$_Ed5!WH)uCz)jN;4JPEPAc^0F*iH!KC?wBW=;o@~TKG-aO6h&pv-4~u z$;qG)F%&W-;6&5AIlnIpNPIfs>l-Z*= zjkTZ1|^rJxPDR@+Cd8+DXK5$1A@f4+WnpyGH7bU7< zPGNbP{I{ZV+$6R7tl9VLy{B(J>|?w^)VJE(M>|)xbqtU6t^elkj>h3*?}I^1lZ)7f z6mh-I(Kc=sf~fC8l>as-YCAEtycJu;^h3>(_pNi+FmX^$1wY0BAqyjFUNru=S@IuL zWv{}bfQO%$8kBhQ6P+k|R1#)~#FR(+wiatN=b7*hRAqCIKS5cQ8iNOosG{Y!%m!MO zFq;rjCn|{t6SzG(8iW2Kg6#S{kg~b(#K~hDQtT-t((FS>@-g1frZup{v7Hc~)>vLr z5$EHK7{fG+a-1?yax1VASn0>0r($&XvKiq$aP-#D(WAF>aGF$mK=A`?HGcEiz5J#N zuUdPSFI-Hw-kyF72cqyVQ`~ystP{l`Z{64nPdo*n2>1n2g!+fO?jU^r?cv6|2D+|& z3uY$;QF(;7t3yBuvdBUbQFg-Wc174SOVmQPDCQasM?IYB=9vrzeKaOztw6ibb((z$ zRPqu?Z`m!QQ^LD+mlr{R6?u*blRHbQ$sBkG~O8H1Y zMTt>4Bix0Qh~b15V}e+PGq%ZXi-)ka$hbi6La7_&h3@hx|IAu_1yWC4mfVS(x=(PG zyHK&RM7UHT{ukNo44C4|K?)N%xl!R#=2mOh$)lp-H~S;Jq{=oNJ^8Qd?A@=u$TH2< zV`oqPbGn;sc0@;N?`v3Ttidfst-ezG@H0lc`kET=`u1@9T?73c&j%=JJ;TrMpuz3PK#;UD7!Y|ZJ@%Rcn`~8lNz>wICNEtr zs{Ho_QcrS|ik!ZKY|g>yCME4tnV1q)nW#g^N2Orie9D+ITxg|w<1b7nc!3j7JBJ3t z45E}JX_@OKl>}M^3^at{nMY$J@L%328aSF zQgI=wrqngqQ`^traMNH{Ps<>^DlIKGg{a^3Nh|w1h9YYgX@s|AM0rGBL}^)Al#J-kQQE+?O0Bd?8W3aPqFZe!!ngDC_uz*#?VycDaAswicoMM94e+B7EnP5 zP$j1JWeKTuhLk7vNj^W`e$uz=PMPQ)U2ua6TBrqEo)GI}yA;726-jBe@kF+Twew=L z8zs;trXWfRlUgRCIJ5#-b|K;@3a@^x;<>wVsq@9wmG{D55wd zkBD+)^g`;a%*tI~TEWUK{CYoaw;PS*UZ+eT!V-3HW1bX20{+zHACyWS@;;DWDtAIs z%91Akn&Wv$(D`!(MitVa6qn)Uu|B9SW=kCeC8B*)c4dK1=4u@%q2yDsyzCBhsaUjG zNMS_+29gY>6tVDSCn(^-?hy=B1CY=8;UuaYp1!Wm6g-6@wyv0jt?1%yK1=4)4jjtn z6H$Q@T#@7&E)|_6Ni9BIj+cKTqJ)&^&t{76QyIJ2CE zc%sZ|(5>C~u^hCs}96;|V+~j&7_WktNXzngyds9bYW}ePF%@L#@1KHerUJPvL*`P-qHHflhVPZ5G z_)<8+HzX~fVx5VY7oXB&(+cOYO;6&4)krLR3t|_y1TOiAMu=5C=00a4mvnjwD?37QpnFK7Er+y z@jfUq$)ilUCzWJXPWLYl_$dp6v9z=-Qe;DzjnMw{5i46843xNh%`sz3KBWLdb}49r zET$1+Q+mxM+e=va@1>TPlC|wY5i}_<5&ft`9IJyIU}0QIk9rnZA%!Snytj}!9N$hJ zm6Ilhhi|F+U)F+4chq$I2bI0dI#P8fY?@S^6I}NrR_{B-B~kmwbgvyO1b7u5B{k5_ zOH4%JRuKt8JR;uFVAHa%?ozR_8tFcU4wtrTqsdxog?rIfY<#-u^(e&d#Wmx&I z3Ya7x<2CuBeM**yv0Wg_Qa(lMOhwC2E)@tU{m8=*BqL!nvG=vfdDGYv-xC`NDt-a8 zaV@Tnc%Q7*S_~=+pKp#O%bh9PNp3Ym03yXm;8kUNFF)x`rpb+} z(}04g3{+^i>i;&4SCia_MY$hdb?3t#nMM8Y)k8V_e&<6UdDYyiOq7Co z#zjnp(q8dAstd*46NM;0vd-jAe5FS&q;136nbnzGk@HZXEv z5RE`E4WF{h^PEIf%-^Lj38_O~$~h# zT}4M~?%tyt57+5g5*me~HwZtt)N0G%lVFC3_|giH3KjLV@f!Rbo9aOOh$Zbu@m zwv_sC9QKN`klt4uK8%&5ybF6lIi=Mnmi$I1MnFLnq@n0K<*jphm!$+EdMlfj!4gVA zcGV=KRlAF-PqoZ!Dw~u!pr6{9jW3F)G%MZ{d1X#w%6dxnR~a2CPA?Sw%QL2mEI&L7 zfmD{r0Rt^DA&HD4E@+4-aG`D06wF91K4S)`JWv5ioHohS3UBsv)}!X}it znWE`PaaJH_R7FcvM425al7P9yDzCg%=AJQ=x<=`e(klU{iM_#*O5Gh5 zd}1yr*>CaF_oxD!w0nSG2*}il%GxQSQg9-e@-`m-V2w68Q^$~TVpwE{;x$#lTuh6b|n=&c%Re-Ue1MNJ+3ZIqcCt+H2wNPFMi9M`C zO6(I-C^BP}79j~KQDwv^9ip;RC1c~I1I6bd#-Wmi`l_zz5*;bVc-e^RHJ02bB>rW^ zZ)s@oy*aLv0;#P}Vy0oV`IH$UYy^}PX%r|u8)cZ9@A^(fL8L7$@#^gm#mb93U75Gz(&nD(Z zR6;8-YiFt=*<4DkK2nRJlqky6rMN1EHz^KiHR_bclU*(k^Myqz!cL*h11R+wFxjQKQOTro1l`A=U@CDG zH%=i%0aT3sW~4G!u$HzCShr40ffE(pHxE=@(F2G9D8_in4m`{#Z#B==4Ido)cc}qJ zL3VTalWyuli71WjIuKG264FO`+_!SE^LeUN{)kugAB!v}M^Kz9(C08o%I*t~a-tNQ zh$w_&d_|{9mw0j=ia{xQJvoG)1uVMFgbLt_9#u@9FYL&2DAuSOReS(vZccoHYBstyteNnRaf-Dq9gTb z?1Y|_REa%>FI&DxUXK|MD1{<f+9yrw<*h?Q_93RwQuhs zfXahXmEj3s$~CbwjVX_rb?CMJZRT0Mvn(PUnLSUp$706gFtfCePVW1wE3H z{0;If+O%6#+QK?{l!AQtlPOtL1}cx*I!VVlT#2xd^3*xj@-sK^Kwtur3aXGj9UE=C z;!&5%wAC1IRb9j3TVFMXN1c9uxvh2EwlZrf`Lx5@*4EfZ$84#_Agafqe7cl2?ExRA zD6T3yPPUEPDkCw7+PQ;?P`021AqwMY>WWD7$cBiqSc;1>HRCl<38qvEs*tnfcYLWx zl#m>#pep)MPE?k0WM{q?CS@lMrUW{GvUO%t&a7oiJ%oIuWf>}$m{KWasv;dp!joQv zF%f{^x<(^UlqS{Hf#Q@$eK;C?S=08niIj-AJ54tQ{R&Z+oVE{9U(&FNiPfVOUQ~!Zyl)o}L zxn$cXCco1Aw*9LB>MQ%-bN>K^2C`llkeZKYSpDFnzi>ThdQLVXKGf&Z-|={Wv6wwIz?2cogxYuP|eL>fBcnJ-`_E( z@zZpqw5)91`zQZA`Ek&hm^lCb-f}B!be|gsuQLT4 z{CnM5Y=!3e$~+H*q%bFHUYDluv`EvRsHUm%FPcxdoE<_Rq8y4%Yt-zE?V?P1!IqgD z2SAj7nx1R~B!-e$3aYFQJA@^gbCb{EQk!p}=IK|6`a6kIQmkboo$jrO*6Swc5*hVL6&cu<4H@HTpiX@CjFlx-?Nfk2jV`B6?m^v%I^eW<%>UT3OhL<(+Rl)4QUz^*#Idf1uSO z6g8__%dNIXl0B3+?BD;qRstBMnuWw9%JpdB!unoYMQMshIWtC--{eZF`h;Fjn&oXU z#mWC2KU_HwNKpto!^7sK_(O;{2|Et+D8MtQ$f?k%mFMVQM@bPu33Z^rDFL-d(%9|{ z1yy{O`%xmw|F40CrXvptFtqVTNcB9%8@yFArB@tc$^=TwSVznSOj0a?1XDrOb|WfW zD)*P{$`Hw?;wfZCrPSFp*o&{_)x@}m*q^E930GQuf7gr-#&~VsplR&nXKM(Cd)VB< z;w8|ir&`q7Egb_GFq=37WDrf(t%Wqsb>@s<5cwileWm=J8jEx}@+WALFgoba;p= zx0@^*!c!w+yAWKcG%_$SFwCW5hK6&kqtsduWn)jsVY1snhNgU)R5ZnMK#pjF7s`YH zk2KRmOcChIiAYppl0C=(6v|Nz53F0N=`!2+17RV?mNICIiBZvo^1<3bs(_}l9~E(m zkbuJE+@$TtLMi<Xd20-bXwoOa zi{JPC*SEiO)KJ6Y`R~2gUVER@8q#0>YklimYaOxE_z_1ONV`vsz6USh9{X|3;!r`9 zg65Lk$=7X>+@RW&{mMi>x>QBZ8nV7qC+6*LDIQfbi<;PGpuZjC-N8c>zPcDh)jUz+ zU~uAet70bsHs_w2tmWPuopz(sdgYvsKOkSLxqYJ7?Okg$TYUfpMDnHCSv{va*#iKw^Nx6g&vhTzo)S0bLZ^N&>acpdCK-7Aq zj+9T4-xi{3Q?1rhOM9Qt?R2{{3k%)uaqqQH=xnsj3oDOWoawfQ8;2h^bJH_33p0xk z%r7jS)ZX&Ur|sBMpfyx~$;YGA>hmq6d{h^~ly_^WsiD^gR#jKGt1KexIF+?0Le5HT z9;KUH%Aj&%Qy}ohbkU zAyw@{v2=@0#NxVPP$*__M4q|UyhQ0z!U=ddvK{Bj{#1g+B{QOa^&ApVxm1hVedlzi zN5=4|-L@HMT?-=NPcY>~O)qwy+IrG_W2y7hbFIxATQ_%ZI`O^5Pv?7xYAj5)j%?l3 zof$i=ws1o0sP2i2CpFIb?Dd=6q9|JRgI}Z9=3Zx7uZS&zsp3f+%^E69rDDU3M*# z04Z?}L&m#Kjz?NmnpNp$6`~*`)%*4Q0ODd~N{v1gzln5K#n5d|lV~E5BPSeknIb** zZi+wUsh=oxWfCQ%M3pVcEQAag8C5bRg2p+iRzv}kL@*xLHJUh6v+6~~iV}EK=1cfq zpXpIz=y%EHX;Q+f;V-m3N5ROMvWKe8*BGW31yJv7Gtm0x@%p-aYV|!cbL0tkPR>6! zIlpmoYW{@b$*IW`YR}9QnTQSN+czyXj_kHh?6!|@br!o@7TfLC`{-ST08jgtQd_r##6(Z(4v9iQ6n0?i$SUT?X%Iz- zPo1gKj!T|6a~W8Dw_*mOoVb*|6iJ@rC#xzQDK1q0S)|_?OgLxJ<65RUfvSQN*p%p6 ztDe||{}K=_Kyg-WXrnzH}o zif!KII!IID*Qj@_H~h)lhE9~#k%;1GZyYi0w%>rL^>(DRnB|v0yik*dDp9SMt>%Y$ zU$+@hL);k7E#eJ>!iJvM^8qapwJ#o}nHv#{FgXL(i;{6U8D(=0gF}zGXdf~R^&M!E zk@?3FR0pU8uF78Wh&*MGr7h`c^&y}_+LVKmyO_#Ol+bdz*6>szMSP>Q`@GS|4#6C# z3OT4nHx5)R3kz48HSa`aC?a4&wtSdX9IR~er3BP$Njayv$G^E~3K8V9o0en&oj|DE zs^la8EEbpmpEX+tR4&zR4SAz)K-4;=jugSZ7eD&?5p-|A^t@g@;=kdMCxWQQ5kT$e zF#$=N6$&p(g&KA(Vef)dSWw)x1xKNYLqz2=W7;S{_LVKekg;`T?5D^Gv-f-i)E!<( zxz~*u6cws#oGLbz3ZmTZN~>?Y@FZ5?sc!@~_H3gb!?;v{FL)vZA*#gGt|&N48BaF6 zJNsnsIMm%TsJKjXR)`xe0TsheDPZEX4B1x_CohAiEnC_fCx&pS-3COhS9GL&2dVoW zJLNBQ{`u!qaLX57*YhzwUp$6~bMG^vwwd+bKdIn`lGTbzjav-8 zFf|T57!+(dRKDk@8I<#Opd*E{k%t5pr#Dw=@@Yu7;>nTH*shZKo^*!p=3=2iJDey@ z%EhSCq>>^B?A5Y<3q%<~C24j}2g+_#r#3R?L~Yox%|L%E%{tT`08hX9+H0SrRA0Yd z<0!Q^pC@>Z_}f)VpJqp;gp&jWz7=6vgwO4&FFe7a%vmb@ppbL;3QO4ltYRCbBbCx5 zc{j#cmn~m;14IN+%7YL{)N&D*T>e}YiElelBFaX2k&uEYW$&d&N%+#Kj*(^+Rxv)! z)sP6In2JF`kSmyaG%O0JJjTZfLoz3^bccctK0y~Y6oyEmq7FimT7Je?Wm4Jj+tTT7 zzH?}3#D;eVM6Hvk4Yt=|*@^qY|3UYm3wOYvEHYuUb^QpWlBhTUMo?K$PL@+zfQ0EH zpeJbs&B9uL5MBK*y%AAb{F2k&Wkv?AJ_zs=6u3pp&j}GyeLM0>)Ou!ftVx?d_FsU^ zqTHT>s1)9G;9h$iKu$$r$`DJFvPp#@5HUq8e z@BeyM?E?V>2fcf1a1Z5k{@_~01|O#4QK1s-D~qZqeNP*Kh6!2HotV;#7=@~kDSHsa zo>5^{JaJYr!W8u?5>M;^m}F4_6eXc^29+%FzzNE+sT}e}IeVAGRlduQBM+dPN0kkQ zJ-hD@L__Zg8ig+4f~0Xz+~aho${Y#1f+!SN5jK}WsnG{fIf(3*mP02}8myQC93E3?QOfa?L=;mEN0|P$-)$I3224{X?|` zdRYJ+Hk2f1;R%XVAtt^4I4Pi#Z$iLi2K^lbRhdpicD1da#YfMT@)U~J9isI$gVObi~ZR+trlj^nebs{ zF$vfocGRL05pNIaVU4sD6Y@r1CijUdP3R4l5-Z)qo}kGaeIlxaLBI)~IFQ>Es%&bn zorpq6dn~Ji7=_CN4~5A4{PQ} zp>`oE`%;a?p|P?3I$K})@Ri!mgMQTd_vo-@AAYl2k0yHL&m5Hbfme9+*F34FZ;ecB zP^?b~Sy9zWV2%e)rz<~H6nv-b6ak7;LCv7yO?Il%*sj>IXA-ZhXe~k7?S@+Dik#1j z*Jx(EOMoR(6x^blWfyXu)asKNilZxI0YUIVyDHt#2A>W*LOTSPao|d)8-&V~z?fhv zc|wU(tRS08mc$b(k-l)HFe%l<6eUh&5>7HEYW)&-jSmR(eXz83>(&oHoZo)?Z3bHB z9vwvcD2L`}{wK}PZ&YN$gAo*dRw~Ixxm;h$OsZOfg)ccr@*$Lcrj-4_xUVW^Mah;3 zj$#YAoN!3Zi{AB`pG=bim*9nZpLh`;BX|NQ4ezEwA^n?#sC!P-?gt)VAK^sa-UFmW z3faWS3og0jg3|-0>Q>?r}03( zTBya@ppa2jI90KAjZ2lx*rd%3YMftWFbS!cx-lDGWxkX|J?;gf;#DKZTq?8B{V;xP zf^11m(kHr$EC1=(?8dM_+2pebgvtJu#@TnnWGnhX5igS{YWi9Aq0E|Y1u8Qo{q{1( z3r!j6v-TcGEY*Sxr!=Yl%wJi3jGQTRrp`*IHfic^}lIjHAZ_QvWT1^BZ&hAR7MBk32w<0 zXN6XwD!W+*nlZ>vN8-7bX)YZnA!Rh#fh;|?tS{?>x_rxkvY*1RAWT$6JVI+R+cYSX zHsH9yPM2DI;3R?^E0T}|RbnNeEI1A~IX-0%Qec-vsXN8%24{P&v3Yvzo!XMK^xoE` z0a5Fh_GbI_mtVda8a?Z$pPEBwu^KaCmm99L=t1##WhN`D~P&Mk#Q3>N)Nf^DzIL$CQ@O^VWKGZV($wnH zj%?!s)2i-!V1-dh9yg$s7t3GDmk=c&Ash-gxIjukg;V(rRe_3l$#X;|EHEK+@`MNo zD&`X+RKCvvHb1JY(`-gHE-#A}(;<>mMDg$HP}%b4W>l7Ycs3+H4R?h>dA6KvW>BehTS2z8*>EYK_R=!wXU1?5F)$cy|>~B|AzP)Sp zr*GMC>bjNHFTVTnr0FC|(eXsenG#4Ta!13ff+$XSlIUL{{SNPgc}QJ0r9?W2a+k8Y zT9Q_KEer^HU=ePc4b30a5>4U;Xm)FRu?ZSHAmhrFot0cC+#=yWQBP8`rVh z4b|0)uUY=_i*K9TX}23*`~Fe)`2JC=-~ROG%JTBX-~RM%J%}PQ0ZtsQ80*z4dkIxM z*dL;~R0?YNYmHe^?o$?_;0a><3uT9!AW{y+#RoL0dVC5|iYP68fnrAi7f(RKb~lR@J9mC$Qz)Yn09Dp*Hjuawg~Ak|WGeQwYe8ujjv`j)gDFyZ4JugT zD9L;Zm_HOcC-G4wACf6U$a_>t70@D>T)(? z`{~&qzgum7vHIiiP!a_WL6j==m(rLxIiirnl!6aJLE%7TJt&tFYT<^)lYTyeeS9NC zRU^J8cPWeUDU5EymkcLe6qNo(KqXRDpwD6A@0rrZgu&6n=Rhu^LNH}=ym%yVp1W^U zqB})@N;J`_GH2q-Bnb^d(RIS99=-M2jG8MfarfO^9E$Osqr;nk=}bJYl_6Ecw?Hac z3b4*-yEbp08QX1sDTo?GCjQ0L!`DBX9=d%5` z<_rHL-WyOzR;35YvX3}jg(%o6OHDW{7OAF2YmWmZkH|9t%R*zy1Q$~=Bfd(Pu%1w| zM7xhOOiC@g+*wNZ2>;z+Nvh(>x>24ekt4d^2BrB2F%WO*5|VfdX@yHcWx|$H`&Ufy zZ^UdUYyD}lOJqPn6jGAZITcev$zjo%W4>uxYSe|qkS;!Hb2U)=jP~a4)X3N?OIru6 zzJITUsUdc>uGL1_A!?{zAFYiZcU_$=p?v=+o~hP{Y{zTv_0jriha7Tg^DG`~eEZACHSEWyzKa@kKFXgM$^D118FxCm)%8o<-sRhBi`+ zL2)AbPW)1lVsQ!SZ1vY6?DdOoo>r;>E6ArZydGq&r)x*VfcN0E-?2-OQi)A}Sdgi6jtU(ilyI0i@_`NbOD!gYe2`BjzAladGj)qh7fb|{C-TXbj2dKy<%9)YB~0j}Q65Ry#Yzn<3nUCGm|{Ik?qUj2O1uE7 zm=~qYJ_RL`Dp=CLppWjxLM=e099di{7MH=G44&W$s8l-)uGG2WF2|CzbP|j7<(kY} z%8aP4-|0quF!J1zfQp9SAPeaqYTJ$T&-|HAIN?t}dQP|0aa=RcR77Qt1eYWXk|;Z& z=Ku<`D%i4D-h|3!Ct?juA*HorjZS{h;L6}R&pyIy&%BYeUoW><^;|MCka|->Du$j! z4)-F+(pRNSLGoSFVvrY@gpjJ9$!9*b6HKK`K@&)+)rZ7WMHDE_o*g(rJklr>|7s^& z-8T_%ffFE6P;qC9oIOXXxDwTB)fNF|I%DqYoW|iWQFOh+t-(UFOKDN>QD0gb5cN-U zk%oqcNj|qdLnZ2AJ$gUfqne)9s>U_CgGP9PA*9WqWK#V|$)nP)4zP=}il0>|USYey z@1K-vc(-c%St^3#6t3h*k+hUV3n?VCGLobS>~RG*9;#4Ky>O+*Act0$P`l5lq9f%@ zNydw?>J{&7TT#HOK9oc8gPDRPe=@1n$I&mwqQJ`c3Iz_gCj}&;f<=``MKaXC;<-|n t<`~>93VVuziBZq(*IL?|2@?uU{09GRpiwnJRnh - - - - - - - - - -``` - -You may notice that: - -- The first tag of the tree is ``. It should contain __1 or more__ tags ``. - -- The tag `` should have the attribute `[ID]`. - -- The tag `` should contain the attribute `[main_tree_to_execute]`. - -- The attribute `[main_tree_to_execute]` is mandatory if the file contains multiple ``, - optional otherwise. - -- Each TreeNode is represented by a single tag. In particular: - - - The name of the tag is the __ID__ used to register the TreeNode in the factory. - - The attribute `[name]` refers to the name of the instance and is __optional__. - - Ports are configured using attributes. In the previous example, the action - `SaySomething` requires the input port `message`. - -- In terms of number of children: - - - `ControlNodes` contain __1 to N children__. - - `DecoratorNodes` and Subtrees contain __only 1 child__. - - `ActionNodes` and `ConditionNodes` have __no child__. - -## Ports Remapping and pointers to Blackboards entries - -As explained in the [second tutorial](tutorial_02_basic_ports.md) -input/output ports can be remapped using the name of an entry in the -Blackboard, in other words, the __key__ of a __key/value__ pair of the BB. - -An BB key is represented using this syntax: `{key_name}`. - -In the following example: - -- the first child of the Sequence prints "Hello", -- the second child reads and writes the value contained in the entry of - the blackboard called "my_message"; - -``` XML - - - - - - - - -``` - - -## Compact vs Explicit representation - -The following two syntaxes are both valid: - -``` XML - - -``` - -We will call the former syntax "__compact__" and the latter "__explicit__". -The first example represented with the explicit syntax would become: - -``` XML - - - - - - - - - - -``` - -Even if the compact syntax is more convenient and easier to write, it provides -too little information about the model of the TreeNode. Tools like __Groot__ require either -the _explicit_ syntax or additional information. -This information can be added using the tag ``. - -To make the compact version of our tree compatible with Groot, the XML -must be modified as follows: - - -``` XML - - - - - - - - - - - - - - - - - - - - -``` - -!!! Note "XML Schema available for explicit version" - You can download the [XML Schema](https://www.w3schools.com/xml/schema_intro.asp) here: - [behaviortree_schema.xsd](https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/behaviortree_schema.xsd). - -## Subtrees - -As we saw in [this tutorial](tutorial_06_subtree_ports.md), it is possible to include -a Subtree inside another tree to avoid "copy and pasting" the same tree in -multiple location and to reduce complexity. - -Let's say that we want to incapsulate few action into the behaviorTree "__GraspObject__" -(being optional, attributes [name] are omitted for simplicity). - -``` XML hl_lines="6" - - - - - - - - - - - - - - - - - -``` - -We may notice as the entire tree "GraspObject" is executed after "SaySomething". - -## Include external files - -__Since version 2.4__. - -You can include external files in a way that is similar to __#include __ in C++. -We can do this easily using the tag: - -``` XML - -``` - -using the previous example, we may split the two behavior trees into two files: - - -``` XML hl_lines="5" - - - - - - - - - - - - - -``` - -``` XML - - - - - - - - - - - -``` - -!!! Note "Note for ROS users" - If you want to find a file inside a [ROS package](http://wiki.ros.org/Packages), - you can use this syntax: - - `` - - - - - - - - - - - diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 393a9c75d..eade3ca77 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -26,10 +26,8 @@ CompileExample("t05_crossdoor") CompileExample("t06_subtree_port_remapping") CompileExample("t07_load_multiple_xml") CompileExample("t08_additional_node_args") +CompileExample("t09_scripting") -if (BT_COROUTINES) - CompileExample("t09_async_actions_coroutines") -endif() CompileExample("ex01_wrap_legacy") CompileExample("ex02_runtime_ports") diff --git a/examples/broken_sequence.cpp b/examples/broken_sequence.cpp index 8684e1558..50642db0c 100644 --- a/examples/broken_sequence.cpp +++ b/examples/broken_sequence.cpp @@ -31,7 +31,6 @@ class ActionTestNode : public ActionNode virtual void halt() override { stop_loop_ = true; - setStatus(NodeStatus::IDLE); } private: diff --git a/examples/ex02_runtime_ports.cpp b/examples/ex02_runtime_ports.cpp index 87c4183db..69c3be233 100644 --- a/examples/ex02_runtime_ports.cpp +++ b/examples/ex02_runtime_ports.cpp @@ -17,7 +17,7 @@ static const char* xml_text = R"( class ThinkRuntimePort : public BT::SyncActionNode { public: - ThinkRuntimePort(const std::string& name, const BT::NodeConfiguration& config) : + ThinkRuntimePort(const std::string& name, const BT::NodeConfig& config) : BT::SyncActionNode(name, config) {} @@ -31,7 +31,7 @@ class ThinkRuntimePort : public BT::SyncActionNode class SayRuntimePort : public BT::SyncActionNode { public: - SayRuntimePort(const std::string& name, const BT::NodeConfiguration& config) : + SayRuntimePort(const std::string& name, const BT::NodeConfig& config) : BT::SyncActionNode(name, config) {} diff --git a/examples/ex04_waypoints.cpp b/examples/ex04_waypoints.cpp index 6d768ef83..9b8cba3cd 100644 --- a/examples/ex04_waypoints.cpp +++ b/examples/ex04_waypoints.cpp @@ -24,7 +24,7 @@ struct Pose2D class GenerateWaypoints : public SyncActionNode { public: - GenerateWaypoints(const std::string& name, const NodeConfiguration& config) : + GenerateWaypoints(const std::string& name, const NodeConfig& config) : SyncActionNode(name, config) {} @@ -45,11 +45,11 @@ class GenerateWaypoints : public SyncActionNode } }; //-------------------------------------------------------------- -class UseWaypointQueue : public AsyncActionNode +class UseWaypointQueue : public ThreadedAction { public: - UseWaypointQueue(const std::string& name, const NodeConfiguration& config) : - AsyncActionNode(name, config) + UseWaypointQueue(const std::string& name, const NodeConfig& config) : + ThreadedAction(name, config) {} NodeStatus tick() override @@ -95,11 +95,11 @@ class UseWaypointQueue : public AsyncActionNode /** * @brief Simple Action that uses the output of PopFromQueue or ConsumeQueue */ -class UseWaypoint : public AsyncActionNode +class UseWaypoint : public ThreadedAction { public: - UseWaypoint(const std::string& name, const NodeConfiguration& config) : - AsyncActionNode(name, config) + UseWaypoint(const std::string& name, const NodeConfig& config) : + ThreadedAction(name, config) {} NodeStatus tick() override diff --git a/examples/t02_basic_ports.cpp b/examples/t02_basic_ports.cpp index df0d14b9d..944360e53 100644 --- a/examples/t02_basic_ports.cpp +++ b/examples/t02_basic_ports.cpp @@ -46,7 +46,7 @@ static const char* xml_text = R"( class ThinkWhatToSay : public BT::SyncActionNode { public: - ThinkWhatToSay(const std::string& name, const BT::NodeConfiguration& config) : + ThinkWhatToSay(const std::string& name, const BT::NodeConfig& config) : BT::SyncActionNode(name, config) {} diff --git a/examples/t03_generic_ports.cpp b/examples/t03_generic_ports.cpp index 848b1d80e..a196534f0 100644 --- a/examples/t03_generic_ports.cpp +++ b/examples/t03_generic_ports.cpp @@ -40,7 +40,7 @@ inline Position2D convertFromString(StringView str) class CalculateGoal : public SyncActionNode { public: - CalculateGoal(const std::string& name, const NodeConfiguration& config) : + CalculateGoal(const std::string& name, const NodeConfig& config) : SyncActionNode(name, config) {} @@ -59,7 +59,7 @@ class CalculateGoal : public SyncActionNode class PrintTarget : public SyncActionNode { public: - PrintTarget(const std::string& name, const NodeConfiguration& config) : + PrintTarget(const std::string& name, const NodeConfig& config) : SyncActionNode(name, config) {} diff --git a/examples/t04_reactive_sequence.cpp b/examples/t04_reactive_sequence.cpp index 05b819b3b..676b054fe 100644 --- a/examples/t04_reactive_sequence.cpp +++ b/examples/t04_reactive_sequence.cpp @@ -9,8 +9,7 @@ using namespace BT; * * - The difference between Sequence and ReactiveSequence * - * - How to create an asynchronous ActionNode (an action that is execute in - * its own thread). + * - How to create an asynchronous ActionNode. */ // clang-format off @@ -51,17 +50,10 @@ static const char* xml_text_reactive = R"( // clang-format on -void Assert(bool condition) -{ - if (!condition) - throw RuntimeError("this is not what I expected"); -} +using namespace DummyNodes; int main() { - using namespace DummyNodes; - using std::chrono::milliseconds; - BehaviorTreeFactory factory; factory.registerSimpleCondition("BatteryOK", std::bind(CheckBattery)); factory.registerNodeType("MoveBase"); @@ -76,60 +68,33 @@ int main() for (auto& xml_text : {xml_text_sequence, xml_text_reactive}) { - std::cout << "\n------------ BUILDING A NEW TREE ------------" << std::endl; + std::cout << "\n------------ BUILDING A NEW TREE ------------\n\n"; auto tree = factory.createTreeFromText(xml_text); - NodeStatus status; - - std::cout << "\n--- 1st executeTick() ---" << std::endl; - status = tree.tickRoot(); - Assert(status == NodeStatus::RUNNING); - - tree.sleep(milliseconds(150)); - std::cout << "\n--- 2nd executeTick() ---" << std::endl; - status = tree.tickRoot(); - Assert(status == NodeStatus::RUNNING); - - tree.sleep(milliseconds(150)); - std::cout << "\n--- 3rd executeTick() ---" << std::endl; + NodeStatus status = NodeStatus::IDLE; +#if 0 + // Tick the root until we receive either SUCCESS or RUNNING + // same as: tree.tickRoot(Tree::WHILE_RUNNING) + std::cout << "--- ticking\n"; status = tree.tickRoot(); - Assert(status == NodeStatus::SUCCESS); - - std::cout << std::endl; + std::cout << "--- status: " << toStr(status) << "\n\n"; +#else + // If we need to run code between one tick() and the next, + // we can implement our own while loop + while (status != NodeStatus::SUCCESS) + { + std::cout << "--- ticking\n"; + status = tree.tickRoot(Tree::ONCE); + std::cout << "--- status: " << toStr(status) << "\n\n"; + + // if still running, add some wait time + if (status == NodeStatus::RUNNING) + { + tree.sleep(std::chrono::milliseconds(100)); + } + } +#endif } return 0; } - -/* - Expected output: - ------------- BUILDING A NEW TREE ------------ - ---- 1st executeTick() --- -[ Battery: OK ] -Robot says: "mission started..." -[ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.00 - ---- 2nd executeTick() --- -[ MoveBase: FINISHED ] - ---- 3rd executeTick() --- -Robot says: "mission completed!" - ------------- BUILDING A NEW TREE ------------ - ---- 1st executeTick() --- -[ Battery: OK ] -Robot says: "mission started..." -[ MoveBase: STARTED ]. goal: x=1 y=2.0 theta=3.00 - ---- 2nd executeTick() --- -[ Battery: OK ] -[ MoveBase: FINISHED ] - ---- 3rd executeTick() --- -[ Battery: OK ] -Robot says: "mission completed!" - -*/ diff --git a/examples/t05_crossdoor.cpp b/examples/t05_crossdoor.cpp index dbf7a5f01..0b77c835e 100644 --- a/examples/t05_crossdoor.cpp +++ b/examples/t05_crossdoor.cpp @@ -1,110 +1,59 @@ #include "crossdoor_nodes.h" - -#include "behaviortree_cpp_v3/loggers/bt_cout_logger.h" -#include "behaviortree_cpp_v3/loggers/bt_minitrace_logger.h" -#include "behaviortree_cpp_v3/loggers/bt_file_logger.h" #include "behaviortree_cpp_v3/bt_factory.h" -#ifdef ZMQ_FOUND -#include "behaviortree_cpp_v3/loggers/bt_zmq_publisher.h" -#endif - /** This is a more complex example that uses Fallback, * Decorators and Subtrees * * For the sake of simplicity, we aren't focusing on ports remapping to the time being. - * - * Furthermore, we introduce Loggers, which are a mechanism to - * trace the state transitions in the tree for debugging purposes. */ // clang-format off static const char* xml_text = R"( - - - - - - - - - - - - - + - - - - - + + + + - - + - + + + + + + + + + + + )"; // clang-format on -using namespace BT; - -int main(int argc, char** argv) +int main() { BT::BehaviorTreeFactory factory; - // Register our custom nodes into the factory. - // Any default nodes provided by the BT library (such as Fallback) are registered by - // default in the BehaviorTreeFactory. - CrossDoor::RegisterNodes(factory); + CrossDoor cross_door; + cross_door.registerNodes(factory); - // Important: when the object tree goes out of scope, all the TreeNodes are destroyed + // Load from text or file... auto tree = factory.createTreeFromText(xml_text); - // This logger prints state changes on console - StdCoutLogger logger_cout(tree); - - // This logger saves state changes on file - FileLogger logger_file(tree, "bt_trace.fbl"); - - // This logger stores the execution time of each node - MinitraceLogger logger_minitrace(tree, "bt_trace.json"); - -#ifdef ZMQ_FOUND - // This logger publish status changes using ZeroMQ. Used by Groot - PublisherZMQ publisher_zmq(tree); -#endif - - printTreeRecursively(tree.rootNode()); - - const bool LOOP = (argc == 2 && strcmp(argv[1], "loop") == 0); + // helper function to print the tree + BT::printTreeRecursively(tree.rootNode()); - using std::chrono::milliseconds; - do - { - NodeStatus status = NodeStatus::RUNNING; - // Keep on ticking until you get either a SUCCESS or FAILURE state - while (status == NodeStatus::RUNNING) - { - status = tree.tickRoot(); - // IMPORTANT: you must always add some sleep if you call tickRoot() - // in a loop, to avoid using 100% of your CPU (busy loop). - // The method Tree::sleep() is recommended, because it can be - // interrupted by an internal event inside the tree. - tree.sleep(milliseconds(10)); - } - if (LOOP) - { - std::this_thread::sleep_for(milliseconds(1000)); - } - } while (LOOP); + // Tick multiple times, until either FAILURE of SUCCESS is returned + tree.tickRoot(BT::Tree::WHILE_RUNNING); return 0; } diff --git a/examples/t06_subtree_port_remapping.cpp b/examples/t06_subtree_port_remapping.cpp index 760473ec6..c20753572 100644 --- a/examples/t06_subtree_port_remapping.cpp +++ b/examples/t06_subtree_port_remapping.cpp @@ -24,23 +24,21 @@ static const char* xml_text = R"( - - - - + +