From a4e4fa88d2a0127cfc9c482d88e839f64cab60dc Mon Sep 17 00:00:00 2001 From: Jesus <198890+Jesus05@users.noreply.github.com> Date: Tue, 29 Oct 2019 09:11:19 +0300 Subject: [PATCH 001/163] (3dparty coroutine) ifdef MSV_VER to WIN32 On Windows not only MSVC compilator. --- 3rdparty/coroutine/coroutine.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/3rdparty/coroutine/coroutine.h b/3rdparty/coroutine/coroutine.h index 88ef0d0a8..3b3929e64 100644 --- a/3rdparty/coroutine/coroutine.h +++ b/3rdparty/coroutine/coroutine.h @@ -38,7 +38,7 @@ using ::std::string; using ::std::wstring; -#ifdef _MSC_VER +#ifdef _WIN32 #include #else #if defined(__APPLE__) && defined(__MACH__) @@ -60,7 +60,7 @@ enum class ResumeResult YIELD = 0 }; -#ifdef _MSC_VER +#ifdef _WIN32 struct Routine { From b6312a021c218bc42a467059cf97660ca7bcd943 Mon Sep 17 00:00:00 2001 From: 3wnbr1 Date: Mon, 2 Dec 2019 12:07:06 +0100 Subject: [PATCH 002/163] Add macOS support --- CMakeLists.txt | 8 +++++--- include/behaviortree_cpp_v3/bt_factory.h | 2 +- src/basic_types.cpp | 6 +++--- 3 files changed, 9 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index afc81f566..8a425da4a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -38,7 +38,7 @@ 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) + list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${ZMQ_LIBRARIES}) else() message(WARNING "ZeroMQ NOT found. Skipping the build of [PublisherZMQ] and [bt_recorder].") endif() @@ -174,6 +174,10 @@ if (WIN32) add_library(${BEHAVIOR_TREE_LIBRARY} STATIC ${BT_SOURCE} ) endif() +if( ZMQ_FOUND ) + list(APPEND BUILD_TOOL_INCLUDE_DIRS ${ZMQ_INCLUDE_DIRS}) +endif() + target_link_libraries(${BEHAVIOR_TREE_LIBRARY} PUBLIC ${BEHAVIOR_TREE_EXTERNAL_LIBRARIES}) @@ -233,5 +237,3 @@ if( BUILD_EXAMPLES ) add_subdirectory(sample_nodes) add_subdirectory(examples) endif() - - diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index dd92ccd15..d7dd3113b 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -52,7 +52,7 @@ See examples for more information about configuring CMake correctly #else -#ifdef __linux__ +#if defined(__linux__) || defined __APPLE__ #define BT_REGISTER_NODES(factory) \ extern "C" void __attribute__((visibility("default"))) \ diff --git a/src/basic_types.cpp b/src/basic_types.cpp index 8fe7d03b0..9324a852b 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -124,10 +124,10 @@ double convertFromString(StringView str) // see issue #120 // http://quick-bench.com/DWaXRWnxtxvwIMvZy2DxVPEKJnE - const auto old_locale = std::setlocale(LC_NUMERIC,nullptr); - std::setlocale(LC_NUMERIC,"C"); + const auto old_locale = setlocale(LC_NUMERIC,nullptr); + setlocale(LC_NUMERIC,"C"); double val = std::stod(str.data()); - std::setlocale(LC_NUMERIC,old_locale); + setlocale(LC_NUMERIC,old_locale); return val; } From d23561102840573f856c23cb88c6b7990a93315f Mon Sep 17 00:00:00 2001 From: Mateusz Sadowski Date: Tue, 3 Dec 2019 12:07:48 +0100 Subject: [PATCH 003/163] Fix some typos in readme --- README.md | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/README.md b/README.md index ea37b3450..0219f8bd2 100644 --- a/README.md +++ b/README.md @@ -23,11 +23,9 @@ There are few features that make __BehaviorTree.CPP__ unique, when compared to o - You can build __reactive__ behaviors that execute multiple Actions concurrently. -- Even if it is written in __C++__, 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 it written in C++, Trees are _not_ hard-coded. +- 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 link staticaly you custom TreeNodes or convert them into __plugins__ +- You can staticaly 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 @@ -57,20 +55,20 @@ 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 the a given TreeNode. +not need to read nor modify the source code of a given TreeNode. Version __3.x__ of this library introduces some dramatic changes in the API, but it was necessary to reach this goal. If you used version 2.X in the past, you can -[find here the Migration Guide](https://behaviortree.github.io/BehaviorTree.CPP/MigrationGuide). +[find the Migration Guide here](https://behaviortree.github.io/BehaviorTree.CPP/MigrationGuide). # GUI Editor Editing a BehaviorTree is as simple as editing a XML file in your favourite text editor. -If you are looking for a more fancy graphical user interface (and I know your do) check +If you are looking for a more fancy graphical user interface (and I know you do) check [Groot](https://github.com/BehaviorTree/Groot) out. ![Groot screenshot](groot-screenshot.png) From 59eaab8be155f9843ba09e42750b4f73b3169cd3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 11 Dec 2019 17:07:49 +0900 Subject: [PATCH 004/163] Add #53 content --- include/behaviortree_cpp_v3/bt_factory.h | 7 +++ src/bt_factory.cpp | 65 ++++++++++++++++++++++++ 2 files changed, 72 insertions(+) diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index dd92ccd15..8fc84d5f8 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -173,6 +173,13 @@ class BehaviorTreeFactory */ void registerFromPlugin(const std::string &file_path); + /** + * @brief registerFromROSPlugins finds all shared libraries that export ROS plugins for behaviortree_cpp, and calls registerFromPlugin for each library. + * @throws If not compiled with ROS support or if the library cannot load for any reason + * + */ + void registerFromROSPlugins(); + /** * @brief instantiateTreeNode creates an instance of a previously registered TreeNode. * diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 7170c2769..a51c74673 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -14,6 +14,11 @@ #include "behaviortree_cpp_v3/utils/shared_library.h" #include "behaviortree_cpp_v3/xml_parsing.h" +#ifdef USING_ROS +#include "filesystem/path.h" +#include +#endif + namespace BT { BehaviorTreeFactory::BehaviorTreeFactory() @@ -131,6 +136,66 @@ void BehaviorTreeFactory::registerFromPlugin(const std::string& file_path) } } +#ifdef USING_ROS + + #ifdef _WIN32 +const char os_pathsep(';'); // NOLINT +#else +const char os_pathsep(':'); // NOLINT +#endif + +// This function is a copy from the one in class_loader_imp.hpp in ROS pluginlib +// package, licensed under BSD. +// https://github.com/ros/pluginlib +std::vector getCatkinLibraryPaths() +{ + std::vector lib_paths; + const char* env = std::getenv("CMAKE_PREFIX_PATH"); + if (env) + { + const std::string env_catkin_prefix_paths(env); + std::vector catkin_prefix_paths = + 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 lib("lib"); + lib_paths.push_back((path / lib).str()); + } + } + return lib_paths; +} + +void BehaviorTreeFactory::registerFromROSPlugins() +{ + std::vector plugins; + ros::package::getPlugins("behaviortree_cpp", "bt_lib_plugin", plugins, true); + std::vector catkin_lib_paths = getCatkinLibraryPaths(); + + for (const auto& plugin : plugins) + { + auto filename = filesystem::path(plugin + BT::SharedLibrary::suffix()); + for (const auto& lib_path : catkin_lib_paths) + { + const auto full_path = filesystem::path(lib_path) / filename; + if (full_path.exists()) + { + std::cout << "Registering ROS plugins from " << full_path.str() << std::endl; + registerFromPlugin(full_path.str()); + break; + } + } + } +} +#else + + void BehaviorTreeFactory::registerFromROSPlugins() + { + throw RuntimeError("Using attribute [ros_pkg] in , but this library was compiled " + "without ROS support. Recompile the BehaviorTree.CPP using catkin"); + } +#endif + std::unique_ptr BehaviorTreeFactory::instantiateTreeNode( const std::string& name, const std::string& ID, From cb0ebe1f202442435f9e983034707a644ba7f3f3 Mon Sep 17 00:00:00 2001 From: Steffen Groot Date: Fri, 13 Dec 2019 10:55:08 +0100 Subject: [PATCH 005/163] Fixed compiling for c++17 --- include/behaviortree_cpp_v3/basic_types.h | 4 ++-- include/behaviortree_cpp_v3/exceptions.h | 2 +- include/behaviortree_cpp_v3/tree_node.h | 4 ++-- src/basic_types.cpp | 8 ++++---- src/xml_parsing.cpp | 2 +- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/include/behaviortree_cpp_v3/basic_types.h b/include/behaviortree_cpp_v3/basic_types.h index fb5d58f9b..639487f0e 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 = {name.to_string(), PortInfo(direction) }; + out = {nonstd::to_string(name), PortInfo(direction) }; } else{ - out = {name.to_string(), PortInfo(direction, typeid(T), + out = {nonstd::to_string(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 99a2f7997..0ea886c66 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_(message.to_string()) + BehaviorTreeException(nonstd::string_view message): message_(nonstd::to_string(message)) {} template diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index bfeceb395..179244d91 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -208,7 +208,7 @@ inline Result TreeNode::getInput(const std::string& key, T& destination) const "but BB is invalid"); } - const Any* val = config_.blackboard->getAny(remapped_key.to_string()); + const Any* val = config_.blackboard->getAny(nonstd::to_string(remapped_key)); if (val && val->empty() == false) { if (std::is_same::value == false && val->type() == typeid(std::string)) @@ -258,7 +258,7 @@ inline Result TreeNode::setOutput(const std::string& key, const T& value) { remapped_key = stripBlackboardPointer(remapped_key); } - const auto& key_str = remapped_key.to_string(); + const auto& key_str = nonstd::to_string(remapped_key); config_.blackboard->set(key_str, value); diff --git a/src/basic_types.cpp b/src/basic_types.cpp index 8fe7d03b0..2ebee5dc1 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -103,7 +103,7 @@ std::string convertFromString(StringView str) template <> const char* convertFromString(StringView str) { - return str.to_string().c_str(); + return nonstd::to_string(str).c_str(); } template <> @@ -197,7 +197,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: ") + str.to_string() ); + throw RuntimeError(std::string("Cannot convert this to NodeStatus: ") + nonstd::to_string(str) ); } template <> @@ -288,12 +288,12 @@ Any PortInfo::parseString(const std::string &str) const void PortInfo::setDescription(StringView description) { - description_ = description.to_string(); + description_ = nonstd::to_string(description); } void PortInfo::setDefaultValue(StringView default_value_as_string) { - default_value_ = default_value_as_string.to_string(); + default_value_ = nonstd::to_string(default_value_as_string); } const std::string &PortInfo::description() const diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 9e268b95b..dd3f0f920 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -520,7 +520,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, auto remapped_res = TreeNode::getRemappedKey(port_name, remapping_value); if( remapped_res ) { - const auto& port_key = remapped_res.value().to_string(); + const auto& port_key = nonstd::to_string(remapped_res.value()); auto prev_info = blackboard->portInfo( port_key ); if( !prev_info ) From c61d913b83eb87e4cb2416521721d09ea1bbd55a Mon Sep 17 00:00:00 2001 From: Christopher Torres <7156279+RavenX8@users.noreply.github.com> Date: Tue, 7 Jan 2020 14:30:36 -0500 Subject: [PATCH 006/163] 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 --- src/basic_types.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/basic_types.cpp b/src/basic_types.cpp index 2ebee5dc1..b1116e16a 100644 --- a/src/basic_types.cpp +++ b/src/basic_types.cpp @@ -1,6 +1,7 @@ #include "behaviortree_cpp_v3/basic_types.h" #include #include +#include namespace BT { From dd5a3a38650c327519845233775ad08629b73b4e Mon Sep 17 00:00:00 2001 From: renan028 Date: Thu, 6 Feb 2020 21:59:49 -0300 Subject: [PATCH 007/163] fix RetryNode loop that should be an infinity loop if max_attempts_ == -1 As documentation said: "Use -1 to create an infinite loop." --- 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 c8422ad11..d777c716e 100644 --- a/src/decorators/retry_node.cpp +++ b/src/decorators/retry_node.cpp @@ -52,7 +52,7 @@ NodeStatus RetryNode::tick() setStatus(NodeStatus::RUNNING); - while (try_index_ < max_attempts_) + while (try_index_ < max_attempts_ || max_attempts_ == -1) { NodeStatus child_state = child_node_->executeTick(); From 7ebdc80dee873678bd6c97c968bc1154cbbea0ae Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 8 Feb 2020 18:43:56 +0100 Subject: [PATCH 008/163] make easier to create ports at run-time --- examples/CMakeLists.txt | 4 + examples/t11_runtime_ports.cpp | 84 ++++++++++++ include/behaviortree_cpp_v3/bt_factory.h | 163 +++++++++++++---------- 3 files changed, 184 insertions(+), 67 deletions(-) create mode 100644 examples/t11_runtime_ports.cpp diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index ca9e8b967..827fe815a 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -42,3 +42,7 @@ 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 ) diff --git a/examples/t11_runtime_ports.cpp b/examples/t11_runtime_ports.cpp new file mode 100644 index 000000000..2456d91b9 --- /dev/null +++ b/examples/t11_runtime_ports.cpp @@ -0,0 +1,84 @@ +#include "behaviortree_cpp_v3/bt_factory.h" + +#include "dummy_nodes.h" +#include "movebase_node.h" + +using namespace BT; + +// clang-format off +static const char* xml_text = R"( + + + + + + + + + )"; +// clang-format on + +class ThinkRuntimePort: public BT::SyncActionNode +{ + public: + ThinkRuntimePort(const std::string& name, + const BT::NodeConfiguration& config) + : BT::SyncActionNode(name, config) + { + } + + BT::NodeStatus tick() override { + setOutput("text", "The answer is 42" ); + return NodeStatus::SUCCESS; + } +}; + +class SayRuntimePort : public BT::SyncActionNode +{ + public: + SayRuntimePort(const std::string& name, const BT::NodeConfiguration& config) + : BT::SyncActionNode(name, config) + { + } + + // You must override the virtual function tick() + BT::NodeStatus tick() override + { + auto msg = getInput("message"); + if (!msg){ + throw BT::RuntimeError( "missing required input [message]: ", msg.error() ); + } + std::cout << "Robot says: " << msg.value() << std::endl; + return BT::NodeStatus::SUCCESS; + } +}; + + +int main() +{ + using namespace DummyNodes; + + BehaviorTreeFactory factory; + + //-------- register ports that might defined at runtime -------- + { + // more verbose way + PortsList ports = {BT::OutputPort("text")}; + factory.registerBuilder(CreateManifest("ThinkRuntimePort", ports), + CreateBuilder()); + } + + { + // less verbose way + PortsList ports = {BT::InputPort("message")}; + factory.registerNodeType("SayRuntimePort", ports); + } + + auto tree = factory.createTreeFromText(xml_text); + + tree.root_node->executeTick(); + + return 0; +} + + diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index dd92ccd15..dc14b9888 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -32,6 +32,58 @@ namespace BT typedef std::function(const std::string&, const NodeConfiguration&)> NodeBuilder; +template +using has_default_constructor = typename std::is_constructible; + +template +using has_params_constructor = typename std::is_constructible; + + +template inline + NodeBuilder CreateBuilder(typename std::enable_if::value && + has_params_constructor::value >::type* = nullptr) +{ + return [](const std::string& name, const NodeConfiguration& config) + { + // Special case. Use default constructor if parameters are empty + if( config.input_ports.empty() && + config.output_ports.empty() && + has_default_constructor::value) + { + return std::make_unique(name); + } + return std::make_unique(name, config); + }; +} + +template inline + NodeBuilder CreateBuilder(typename std::enable_if::value && + has_params_constructor::value >::type* = nullptr) +{ + return [](const std::string& name, const NodeConfiguration& params) + { + return std::unique_ptr(new T(name, params)); + }; +} + +template inline + NodeBuilder CreateBuilder(typename std::enable_if::value && + !has_params_constructor::value >::type* = nullptr) +{ + return [](const std::string& name, const NodeConfiguration&) + { + return std::unique_ptr(new T(name)); + }; +} + + +template inline +TreeNodeManifest CreateManifest(const std::string& ID, PortsList portlist = getProvidedPorts()) +{ + return { getType(), ID, portlist }; +} + + constexpr const char* PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin"; #ifndef BT_PLUGIN_EXPORT @@ -128,7 +180,7 @@ class BehaviorTreeFactory template void registerBuilder(const std::string& ID, const NodeBuilder& builder ) { - auto manifest = BehaviorTreeFactory::buildManifest(ID); + auto manifest = CreateManifest(ID); registerBuilder(manifest, builder); } @@ -196,11 +248,11 @@ class BehaviorTreeFactory std::is_base_of::value || std::is_base_of::value || std::is_base_of::value, - "[registerBuilder]: accepts only classed derived from either ActionNodeBase, " + "[registerNode]: accepts only classed derived from either ActionNodeBase, " "DecoratorNode, ControlNode or ConditionNode"); static_assert(!std::is_abstract::value, - "[registerBuilder]: Some methods are pure virtual. " + "[registerNode]: Some methods are pure virtual. " "Did you override the methods tick() and halt()?"); constexpr bool default_constructable = std::is_constructible::value; @@ -210,20 +262,56 @@ class BehaviorTreeFactory has_static_method_providedPorts::value; static_assert(default_constructable || param_constructable, - "[registerBuilder]: the registered class must have at least one of these two " + "[registerNode]: the registered class must have at least one of these two " "constructors: " " (const std::string&, const NodeConfiguration&) or (const std::string&)."); static_assert(!(param_constructable && !has_static_ports_list), - "[registerBuilder]: you MUST implement the static method: " + "[registerNode]: you MUST implement the static method: " " PortsList providedPorts();\n"); static_assert(!(has_static_ports_list && !param_constructable), - "[registerBuilder]: since you have a static method requiredNodeParameters(), " + "[registerNode]: since you have a static method providedPorts(), " "you MUST add a constructor sign signature (const std::string&, const " "NodeParameters&)\n"); - registerNodeTypeImpl(ID); + registerBuilder( CreateManifest(ID), CreateBuilder()); + } + + template + void registerNodeType(const std::string& ID, PortsList ports) + { + static_assert(std::is_base_of::value || + std::is_base_of::value || + std::is_base_of::value || + std::is_base_of::value, + "[registerNode]: accepts only classed derived from either ActionNodeBase, " + "DecoratorNode, ControlNode or ConditionNode"); + + static_assert(!std::is_abstract::value, + "[registerNode]: Some methods are pure virtual. " + "Did you override the methods tick() and halt()?"); + + constexpr bool default_constructable = std::is_constructible::value; + constexpr bool param_constructable = + std::is_constructible::value; + constexpr bool has_static_ports_list = + has_static_method_providedPorts::value; + + 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&)."); + + static_assert(!has_static_ports_list, + "[registerNode]: ports are passed to this node explicitly. The static method" + "providedPorts() should be removed to avoid ambiguities\n"); + + static_assert(param_constructable, + "[registerNode]: since this node has ports, " + "you MUST add a constructor sign signature (const std::string&, const " + "NodeParameters&)\n"); + + registerBuilder( CreateManifest(ID, ports), CreateBuilder()); } /// All the builders. Made available mostly for debug purposes. @@ -241,74 +329,15 @@ class BehaviorTreeFactory Tree createTreeFromFile(const std::string& file_path, Blackboard::Ptr blackboard = Blackboard::create()); - template static - TreeNodeManifest buildManifest(const std::string& ID) - { - return { getType(), ID, getProvidedPorts() }; - } - private: std::unordered_map builders_; std::unordered_map manifests_; std::set builtin_IDs_; - // template specialization = SFINAE + black magic - - // clang-format off - template - using has_default_constructor = typename std::is_constructible; - - template - using has_params_constructor = typename std::is_constructible; - - template - void registerNodeTypeImpl(const std::string& ID) - { - NodeBuilder builder = getBuilder(); - registerBuilder( buildManifest(ID), builder); - } - - template static - NodeBuilder getBuilder(typename std::enable_if::value && - has_params_constructor::value >::type* = nullptr) - { - return [](const std::string& name, const NodeConfiguration& config) - { - //TODO FIXME - - // Special case. Use default constructor if parameters are empty - if( config.input_ports.empty() && - config.output_ports.empty() && - has_default_constructor::value) - { - return std::make_unique(name); - } - return std::make_unique(name, config); - }; - } - - template static - NodeBuilder getBuilder(typename std::enable_if::value && - has_params_constructor::value >::type* = nullptr) - { - return [](const std::string& name, const NodeConfiguration& params) - { - return std::unique_ptr(new T(name, params)); - }; - } - - template static - NodeBuilder getBuilder(typename std::enable_if::value && - !has_params_constructor::value >::type* = nullptr) - { - return [](const std::string& name, const NodeConfiguration&) - { - return std::unique_ptr(new T(name)); - }; - } // clang-format on }; + } // end namespace #endif // BT_FACTORY_H From 9e902e7539142962022bd7f52cdaaef6c1bdf4d2 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sat, 8 Feb 2020 18:49:59 +0100 Subject: [PATCH 009/163] Update t11_runtime_ports.cpp --- examples/t11_runtime_ports.cpp | 27 +++++++-------------------- 1 file changed, 7 insertions(+), 20 deletions(-) diff --git a/examples/t11_runtime_ports.cpp b/examples/t11_runtime_ports.cpp index 2456d91b9..5ec74a348 100644 --- a/examples/t11_runtime_ports.cpp +++ b/examples/t11_runtime_ports.cpp @@ -1,8 +1,4 @@ #include "behaviortree_cpp_v3/bt_factory.h" - -#include "dummy_nodes.h" -#include "movebase_node.h" - using namespace BT; // clang-format off @@ -56,28 +52,19 @@ class SayRuntimePort : public BT::SyncActionNode int main() { - using namespace DummyNodes; - BehaviorTreeFactory factory; - //-------- register ports that might defined at runtime -------- - { - // more verbose way - PortsList ports = {BT::OutputPort("text")}; - factory.registerBuilder(CreateManifest("ThinkRuntimePort", ports), + //-------- register ports that might be defined at runtime -------- + // more verbose way + PortsList think_ports = {BT::OutputPort("text")}; + factory.registerBuilder(CreateManifest("ThinkRuntimePort", think_ports), CreateBuilder()); - } - - { - // less verbose way - PortsList ports = {BT::InputPort("message")}; - factory.registerNodeType("SayRuntimePort", ports); - } + // less verbose way + PortsList say_ports = {BT::InputPort("message")}; + factory.registerNodeType("SayRuntimePort", say_ports); auto tree = factory.createTreeFromText(xml_text); - tree.root_node->executeTick(); - return 0; } From b76a75b6d4621f9359fd19d5420005249a7504c1 Mon Sep 17 00:00:00 2001 From: Sean Yen Date: Tue, 3 Mar 2020 13:08:36 -0800 Subject: [PATCH 010/163] Install library to portable locations --- CMakeLists.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8a425da4a..f8e501666 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -211,8 +211,9 @@ set(PROJECT_CONFIG ${PROJECT_NAMESPACE}Config) INSTALL(TARGETS ${BEHAVIOR_TREE_LIBRARY} EXPORT ${PROJECT_CONFIG} - ARCHIVE DESTINATION ${BEHAVIOR_TREE_BIN_DESTINATION} + ARCHIVE DESTINATION ${BEHAVIOR_TREE_LIB_DESTINATION} LIBRARY DESTINATION ${BEHAVIOR_TREE_LIB_DESTINATION} + RUNTIME DESTINATION ${BEHAVIOR_TREE_BIN_DESTINATION} ) INSTALL( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ From 70c77157bde283815fe66db142b30ee5baf1317f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 6 Mar 2020 17:41:28 +0100 Subject: [PATCH 011/163] Added SubTtreeWrapper --- .../decorators/subtree_node.h | 32 ++++- src/bt_factory.cpp | 3 +- src/decorators/subtree_node.cpp | 20 ++- src/xml_parsing.cpp | 23 ++-- tests/gtest_factory.cpp | 2 +- tests/gtest_subtree.cpp | 129 +++++++++++++++++- 6 files changed, 192 insertions(+), 17 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/subtree_node.h b/include/behaviortree_cpp_v3/decorators/subtree_node.h index 88ce9e7ca..5193f28be 100644 --- a/include/behaviortree_cpp_v3/decorators/subtree_node.h +++ b/include/behaviortree_cpp_v3/decorators/subtree_node.h @@ -6,12 +6,18 @@ namespace BT { -class DecoratorSubtreeNode : public DecoratorNode +/** + * @brief The SubtreeNode is a way to wrap an entire Subtree, + * creating a separated BlackBoard. + * If you want to have data flow through ports, you need to explicitly + * remap the ports. + */ +class SubtreeNode : public DecoratorNode { public: - DecoratorSubtreeNode(const std::string& name); + SubtreeNode(const std::string& name); - virtual ~DecoratorSubtreeNode() override = default; + virtual ~SubtreeNode() override = default; private: virtual BT::NodeStatus tick() override; @@ -22,6 +28,26 @@ class DecoratorSubtreeNode : public DecoratorNode } }; +/** + * @brief The TransparentSubtreeNode is a way to wrap an entire Subtree. + * It does NOT have a separated BlackBoard and does not need ports remapping. + */ +class SubtreeWrapperNode : public DecoratorNode +{ +public: + SubtreeWrapperNode(const std::string& name); + + virtual ~SubtreeWrapperNode() override = default; + +private: + virtual BT::NodeStatus tick() override; + + virtual NodeType type() const override final + { + return NodeType::SUBTREE; + } +}; + } diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index a51c74673..8e176016c 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -42,7 +42,8 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType("AlwaysFailure"); registerNodeType("SetBlackboard"); - registerNodeType("SubTree"); + registerNodeType("SubTree"); + registerNodeType("SubTreeWrapper"); registerNodeType>("BlackboardCheckInt"); registerNodeType>("BlackboardCheckDouble"); diff --git a/src/decorators/subtree_node.cpp b/src/decorators/subtree_node.cpp index f42505109..4b49d0979 100644 --- a/src/decorators/subtree_node.cpp +++ b/src/decorators/subtree_node.cpp @@ -1,13 +1,29 @@ #include "behaviortree_cpp_v3/decorators/subtree_node.h" -BT::DecoratorSubtreeNode::DecoratorSubtreeNode(const std::string &name) : +BT::SubtreeNode::SubtreeNode(const std::string &name) : DecoratorNode(name, {} ) { setRegistrationID("SubTree"); } -BT::NodeStatus BT::DecoratorSubtreeNode::tick() +BT::NodeStatus BT::SubtreeNode::tick() +{ + NodeStatus prev_status = status(); + if (prev_status == NodeStatus::IDLE) + { + setStatus(NodeStatus::RUNNING); + } + return child_node_->executeTick(); +} + +BT::SubtreeWrapperNode::SubtreeWrapperNode(const std::string &name) : + DecoratorNode(name, {} ) +{ + setRegistrationID("TransparentSubtree"); +} + +BT::NodeStatus BT::SubtreeWrapperNode::tick() { NodeStatus prev_status = status(); if (prev_status == NodeStatus::IDLE) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index dd3f0f920..2d3be9761 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -466,7 +466,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, instance_name = ID; } - if (element_name == "SubTree") + if (element_name == "SubTree" || element_name == "SubTreeWrapper" ) { instance_name = element->Attribute("ID"); } @@ -579,7 +579,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, child_node = factory.instantiateTreeNode(instance_name, ID, config); } else if( tree_roots.count(ID) != 0) { - child_node = std::make_unique( instance_name ); + child_node = std::make_unique( instance_name ); } else{ throw RuntimeError( ID, " is not a registered node, nor a Subtree"); @@ -614,15 +614,20 @@ void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID, if( node->type() == NodeType::SUBTREE ) { - auto new_bb = Blackboard::create(blackboard); - - for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) + if( dynamic_cast(node.get()) ) { - new_bb->addSubtreeRemapping( attr->Name(), attr->Value() ); - } + auto new_bb = Blackboard::create(blackboard); - output_tree.blackboard_stack.emplace_back(new_bb); - recursivelyCreateTree( node->name(), output_tree, new_bb, node ); + for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next()) + { + 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 { diff --git a/tests/gtest_factory.cpp b/tests/gtest_factory.cpp index f23da2309..67164d01c 100644 --- a/tests/gtest_factory.cpp +++ b/tests/gtest_factory.cpp @@ -131,7 +131,7 @@ TEST(BehaviorTreeFactory, Subtree) ASSERT_EQ(root_selector->child(0)->name(), "CrossDoorSubtree"); ASSERT_EQ(root_selector->child(1)->name(), "PassThroughWindow"); - auto subtree = dynamic_cast(root_selector->child(0)); + auto subtree = dynamic_cast(root_selector->child(0)); ASSERT_TRUE(subtree != nullptr); auto sequence = dynamic_cast(subtree->child()); diff --git a/tests/gtest_subtree.cpp b/tests/gtest_subtree.cpp index a24d5b6d7..57b830106 100644 --- a/tests/gtest_subtree.cpp +++ b/tests/gtest_subtree.cpp @@ -1,4 +1,4 @@ -#include +#include #include "behaviortree_cpp_v3/bt_factory.h" #include "../sample_nodes/dummy_nodes.h" @@ -41,3 +41,130 @@ static const char* xml_text = R"( ASSERT_EQ(ret, NodeStatus::SUCCESS ); ASSERT_EQ(tree.blackboard_stack.size(), 3 ); } + +class CopyPorts : public BT::SyncActionNode +{ +public: + CopyPorts(const std::string& name, const BT::NodeConfiguration& config) + : BT::SyncActionNode(name, config) + { + } + + BT::NodeStatus tick() override + { + auto msg = getInput("in"); + if (!msg) + { + throw BT::RuntimeError( "missing required input [message]: ", msg.error() ); + } + setOutput("out", msg.value()); + return BT::NodeStatus::SUCCESS; + } + + static BT::PortsList providedPorts() + { + return{ BT::InputPort("in"), + BT::OutputPort("out")}; + } +}; + + +TEST(SubTree, GoodRemapping) +{ + static const char* xml_text = R"( + + + + + + + + + + + + + + + )"; + + BehaviorTreeFactory factory; + factory.registerNodeType("SaySomething"); + factory.registerNodeType("CopyPorts"); + + Tree tree = factory.createTreeFromText(xml_text); + auto ret = tree.root_node->executeTick(); + ASSERT_EQ(ret, NodeStatus::SUCCESS ); +} + +TEST(SubTree, BadRemapping) +{ + BehaviorTreeFactory factory; + factory.registerNodeType("SaySomething"); + factory.registerNodeType("CopyPorts"); + + static const char* xml_text_bad_in = R"( + + + + + + + + + + + + + + )"; + + Tree tree_bad_in = factory.createTreeFromText(xml_text_bad_in); + EXPECT_ANY_THROW( tree_bad_in.root_node->executeTick() ); + + static const char* xml_text_bad_out = R"( + + + + + + + + + + + + + + )"; + + Tree tree_bad_out = factory.createTreeFromText(xml_text_bad_out); + EXPECT_ANY_THROW( tree_bad_out.root_node->executeTick() ); +} + +TEST(SubTree, SubtreeWrapper) +{ + BehaviorTreeFactory factory; + factory.registerNodeType("SaySomething"); + factory.registerNodeType("CopyPorts"); + + static const char* xml_text = R"( + + + + + + + + + + + + + + )"; + + Tree tree = factory.createTreeFromText(xml_text); + auto ret = tree.root_node->executeTick(); + ASSERT_EQ(ret, NodeStatus::SUCCESS ); +} From fcfa9205e6e1f6b473a00d4b04ef23a7d9ceaff9 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 6 Mar 2020 18:20:32 +0100 Subject: [PATCH 012/163] bug fix --- include/behaviortree_cpp_v3/behavior_tree.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index fec758182..96fc0b796 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -72,14 +72,15 @@ void buildSerializedStatusSnapshot(const TreeNode* root_node, SerializedTreeStatus& serialized_buffer); /// Simple way to extract the type of a TreeNode at COMPILE TIME. -/// Useful to avoid the cost of without dynamic_cast or the virtual method TreeNode::type(). +/// Useful to avoid the cost of dynamic_cast or the virtual method TreeNode::type(). template inline NodeType getType() { // clang-format off if( std::is_base_of::value ) return NodeType::ACTION; if( std::is_base_of::value ) return NodeType::CONDITION; - if( std::is_base_of::value ) return NodeType::SUBTREE; + if( std::is_base_of::value ) return NodeType::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; From f6ed17ec7322401a2a9bcc833abe6ec25ad26b7e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 6 Mar 2020 19:06:57 +0100 Subject: [PATCH 013/163] experimental integration of Switch ControlNode --- CMakeLists.txt | 1 + include/behaviortree_cpp_v3/behavior_tree.h | 1 + .../controls/switch_node.h | 110 ++++++++++++++++++ src/bt_factory.cpp | 6 + src/controls/switch_node.cpp | 15 +++ 5 files changed, 133 insertions(+) create mode 100644 include/behaviortree_cpp_v3/controls/switch_node.h create mode 100644 src/controls/switch_node.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index f8e501666..53e4d3030 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -152,6 +152,7 @@ list(APPEND BT_SOURCE src/controls/reactive_fallback.cpp src/controls/sequence_node.cpp src/controls/sequence_star_node.cpp + src/controls/switch_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 96fc0b796..3ea38a3e1 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -20,6 +20,7 @@ #include "behaviortree_cpp_v3/controls/fallback_node.h" #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/action_node.h" #include "behaviortree_cpp_v3/condition_node.h" diff --git a/include/behaviortree_cpp_v3/controls/switch_node.h b/include/behaviortree_cpp_v3/controls/switch_node.h new file mode 100644 index 000000000..929719b04 --- /dev/null +++ b/include/behaviortree_cpp_v3/controls/switch_node.h @@ -0,0 +1,110 @@ +/* Copyright (C) 2019-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 SWITCH_NODE_H +#define SWITCH_NODE_H + +#include "behaviortree_cpp_v3/control_node.h" + +namespace BT +{ +/** + * @brief The SwitchNode + * + */ +template +class SwitchNode : public ControlNode +{ + public: + SwitchNode(const std::string& name, const BT::NodeConfiguration& config) + : ControlNode::ControlNode(name, config ), + running_child_(-1) + { + setRegistrationID("Switch"); + } + + virtual ~SwitchNode() override = default; + + void halt() override + { + running_child_ = -1; + ControlNode::halt(); + } + + static PortsList providedPorts() + { + PortsList ports; + ports.insert( BT::InputPort("variable") ); + for(unsigned i=0; i < NUM_CASES; i++) + { + char case_str[20]; + sprintf(case_str, "case_%d", i+1); + ports.insert( BT::InputPort(case_str) ); + } + return ports; + } + + private: + int running_child_; + virtual BT::NodeStatus tick() override; +}; + +template inline +NodeStatus SwitchNode::tick() +{ + if( childrenCount() != NUM_CASES+1) + { + throw LogicError("Wrong number of children in SwitchNode; " + "must be (num_cases + default)"); + } + + std::string variable; + std::string value; + int child_index = 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) + { + char case_str[20]; + sprintf(case_str, "case_%d", index+1); + + if (getInput(case_str, value) && variable == value) + { + child_index = index; + break; + } + } + } + + // if another one was running earlier, halt it + if( running_child_ != -1 && running_child_ != child_index) + { + halt(); + } + + NodeStatus ret = children_nodes_[child_index]->executeTick(); + if( ret == NodeStatus::RUNNING ) + { + running_child_ = child_index; + } + else{ + running_child_ = -1; + } + + return ret; +} + +} + +#endif // SWITCH_NODE_H diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 8e176016c..1aba1a4e0 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -49,6 +49,12 @@ BehaviorTreeFactory::BehaviorTreeFactory() registerNodeType>("BlackboardCheckDouble"); registerNodeType>("BlackboardCheckString"); + registerNodeType>("Switch2"); + registerNodeType>("Switch3"); + registerNodeType>("Switch4"); + registerNodeType>("Switch5"); + registerNodeType>("Switch6"); + for( const auto& it: builders_) { builtin_IDs_.insert( it.first ); diff --git a/src/controls/switch_node.cpp b/src/controls/switch_node.cpp new file mode 100644 index 000000000..2ee43624f --- /dev/null +++ b/src/controls/switch_node.cpp @@ -0,0 +1,15 @@ +/* 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/switch_node.h" +#include "behaviortree_cpp_v3/action_node.h" From 33026db304f1771444cf19141b57f966922d450a Mon Sep 17 00:00:00 2001 From: Vadim Linevich Date: Fri, 6 Mar 2020 10:55:55 -0800 Subject: [PATCH 014/163] 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 --- CMakeLists.txt | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 53e4d3030..b5f02fa60 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -24,6 +24,7 @@ list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}") option(BUILD_EXAMPLES "Build tutorials and examples" 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) ############################################################# # Find packages @@ -85,7 +86,7 @@ elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${catkin_LIBRARIES}) set(BUILD_TOOL_INCLUDE_DIRS ${catkin_INCLUDE_DIRS}) -else() +elseif(BUILD_UNIT_TESTS) find_package(GTest) if(NOT GTEST_FOUND) @@ -166,7 +167,11 @@ list(APPEND BT_SOURCE if (UNIX) list(APPEND BT_SOURCE src/shared_library_UNIX.cpp ) - add_library(${BEHAVIOR_TREE_LIBRARY} SHARED ${BT_SOURCE} ) + 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) @@ -203,7 +208,9 @@ endif() ###################################################### # Test -add_subdirectory(tests) +if (BUILD_UNIT_TESTS) + add_subdirectory(tests) +endif() ###################################################### # INSTALL From e6bc62e13eea42471a4b36d99d26b4e8e8db225a Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Fri, 6 Mar 2020 20:57:04 +0100 Subject: [PATCH 015/163] Fix bug #149 --- src/loggers/bt_minitrace_logger.cpp | 27 +++++++++++++++++++++++---- 1 file changed, 23 insertions(+), 4 deletions(-) diff --git a/src/loggers/bt_minitrace_logger.cpp b/src/loggers/bt_minitrace_logger.cpp index 0dde4f8b5..65d518d81 100644 --- a/src/loggers/bt_minitrace_logger.cpp +++ b/src/loggers/bt_minitrace_logger.cpp @@ -27,6 +27,25 @@ MinitraceLogger::~MinitraceLogger() ref_count = false; } +const char* toConstStr(NodeType type) +{ + switch (type) + { + case NodeType::ACTION: + return "Action"; + case NodeType::CONDITION: + return "Condition"; + case NodeType::DECORATOR: + return "Decorator"; + case NodeType::CONTROL: + return "Control"; + case NodeType::SUBTREE: + return "SubTree"; + default: + return "Undefined"; + } +} + void MinitraceLogger::callback(Duration /*timestamp*/, const TreeNode& node, NodeStatus prev_status, NodeStatus status) @@ -35,20 +54,20 @@ void MinitraceLogger::callback(Duration /*timestamp*/, const bool statusCompleted = (status == NodeStatus::SUCCESS || status == NodeStatus::FAILURE); - const std::string& category = toStr(node.type()); + const char* category = toConstStr(node.type()); const char* name = node.name().c_str(); if (prev_status == NodeStatus::IDLE && statusCompleted) { - MTR_INSTANT(category.c_str(), name); + MTR_INSTANT(category, name); } else if (status == NodeStatus::RUNNING) { - MTR_BEGIN(category.c_str(), name); + MTR_BEGIN(category, name); } else if (prev_status == NodeStatus::RUNNING && statusCompleted) { - MTR_END(category.c_str(), name); + MTR_END(category, name); } } From 59633024c17b77d2c943be189076d7431c5385f4 Mon Sep 17 00:00:00 2001 From: Peter Polidoro Date: Fri, 13 Mar 2020 11:20:16 -0400 Subject: [PATCH 016/163] 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. --- docs/images/SequenceNode.png | Bin 6604 -> 6916 bytes docs/images/SequenceStar.png | Bin 8066 -> 4640 bytes 2 files changed, 0 insertions(+), 0 deletions(-) diff --git a/docs/images/SequenceNode.png b/docs/images/SequenceNode.png index add5d017c3e27004cba5e77ea0602dc5584da4ac..657a5ccacf115e62f950f7da68bbc19a068869e8 100644 GIT binary patch literal 6916 zcma)hbyQSQ*Ea}KN+TeQw3L)6EuaXDbR*p*Al)@0AOZp+(lIn5CDM{2HT2LWLrQlH z62p7&eV)I*wchp3TAaDFFZb-d&)NI8fBW1BbyX-a5gid078bF>3t3GpEbI$#9Zhfp zjK9T9KZ7qqmlyi(SXj3xum7;IQqyUH5Z^;VMGk)%hnSR*`*_DH4GW7dS3&lfw$Jo- zMxeUZOH3!}dosnEXfpe0oBJ>IGkV&17FKSS z&6G-P>TY>(@5nrmD4wsPWbxUl#q_N^+eUFOn6p>Y$O@C;@$FTu8i;zU^N~#S=4%R1eDso|CVUgXHWyJ+HBJuzKht_AeWw3BnwW%yxZ-u=z zYKalRIy!o`=5ROvbajbwnc?XXnE2n2Lked7e}>jPw_OI`OHVG|*4+ zh*Y6=JIIvZ*<<~x_wQxdc%v`Y)!J9+rjB+Rz>oIMPh#%f3%^L=xD4k{zMa!K=gY~( zS$4gU$0LvE?n|*+l6N~lA&u$jV`Cv#P+-1ur&;ax8#5VfGGU@H*m+^Wa3b|!nlk$j zGi;%hwN|Xx&V{{+$O#kwx}xl0ZmLncyvxg~qKJW1xs=X_H4)z&L={;>3kpX%<)=|< z4L{a?cvjV&E)@I_KWnF~s!2RSkDPe@aLtX)@o~HSfeOA6M<~k}nzjaiqL8m?pe;+v zkheOhmE>Th<;2(IV!mu?%b~-~$j5K2s0PP8W0sPG=RTHM>xg1abNZd5pg@`g4@_)E z&#eiHMZR4NnWvEB>ewbB6D%qUYSH_1@>%Gv$?+LRK67*1!(*7Ir>$qY4W3UEj#Eh^V9xs**?2_p%7HbMtT5ig>k~)jp6CFg zcp0BmK2c1Obs0Z$S2dt9JYiN2n@rYh`K?=6GdxKAprYP) z8ND>)3>~kniQ#eo-1+nE&Ag&lM?I~PH<-u-+HSTvDoabGF-WU!d-+{SU7k4@7%7W5 z2h}0WvLYgmy2&?O)C=S3ZhQPa2v3u`7^;jjG*X@@%{4Y2UC(2LDUXamJCDQ^mt1b7 zrmktJAcjw_XC?MGx25MK3bEY(+<}Bt++Tv_^{i+wc`6M~&-p9_K4^ zXj1R1`cNbhiUSXcFW~kJm;6l}JyoYcoeZ8lUu&`y$dLD7xXzc{)>e);YdBa~|Mx(E z+h}l?AR~r^6jrH@B}zzsYa^73$cP7InhfK@6E-1HQ9I!@@NsZ(kiNP&wC+uOJze#x zBk~T#iE}v?lh0n85LVsV_V#NhC*iby`P_=?YMoppXF|`}*;%P!ZS(QCA$P*YbhU$h zwYao23_NIGO-GJH7KkNtJFS0wc-Z1GUBAs?!h@HIJo-6f_LY^D)dr;<7F^uie!ER* zAhf79fSpvr?@&=S?zP>juC68~Cgw|0DxaXCqO!8Jjgn=Nr2rn2aq1Q)Y$GKy2JR~* zu6g_@DdCBhr=&b|p&GRktcV;eaTSHg$;nw%)P4P`$U|*dIu0!S@k2bSBWGkid8fsQ z59)(0%lL+?bH%N?rbbZGFCM{09px#0ZzT6+k+vn8vG~+ctmSO1ywAq{_3P5bt0wKj z5q(or)X5lGd;*#q9 z8G?`AMVad82zlXGPW4@2d3boN9s4zzknYj|N0K=^#VZ_RGYb#Sv;*EfvK=TfZm6lM z@;Lm{&*1%S%F%Wpy{NeO5nc3N(6zl;KNs51Hp>sR1MoVhd3ktd8@&0uUJT67n<*(N zsi+V)ngT#(dU`5afmuvieDvYF*WYyEf5KJ~jCe(S*6CJ6bhTIDjep8%Ra#ZI^0=gK zg;#G<`m}&BU`g7SsE98=y)9L03~xOLflWq^i;T$N?y#MIwS7?E5sbdYbjDPYOu*q~ ze+T~4)FDYNYyR@adnp1*_UVW_Zx<_th+C(R3IFMou^mp=Ti}%H^(pz!Y)n+_sE9jR zz%tZ-|4FNrO1$E&PQW`e{e}Rium2`X))Px}gk%IR7OYzPcV*iCqjT@~i}`jL zAn2Z6aWC%iY4P;*3?&0IUcSdu<)K2+XWIcM=G8L9$A*Tmc4=}LxmqK_7SBDaL%&pS z#?Q@}*z6T%XJgOt%Sz9_p}f_>NSf`meSly+#4)R!y7v8f9V-q8btEHC+b^JV>2iE@ zG+CMbTEkGC)dJAX@!kc*(kw(oL}X%Y?B{vd+N}z%HlRd}#2f_1D~oHVwFuMoI5DFp zK@0ZVXShHcOw(ET`suLelZFieWw_T9&U-(&cIKv1s9u8<2qz@t?oHfl-Q2RDt9w_y zAmBN;b8j#(lT?FcWO`-f%L1?vdTlpp<))a$zsQU>LWW-poXvpei7X@M(Mv{36!K-`4Ek&6Zp#L zjgOx`wefMVv9WP*#PXunJ-*XDe)8mrVo17b;cutfDaXDEpt4B2C+J>fmS)lL@US+w zPJ7I)n-8FZDSb<=oN$PzhsV*$$vfQ`O)V|onpOpdjX1@8=F$9a1Y&_?NxNfe-Gj)! zWAjj`g=($be@MimC7y2Uz0+F!M~6BO?QzvxsH6^UlPa!9+BBnBS# zi}ba{u|i999iY%~nQZkUZN+@eQr*D}iI@4BVJo4G%bbmb%pEkM%-b=_S!<*uBsDcP z!XhGR$_3!N;dj{?Y`n}^!h6RkUz3Z|(1<zvK+EwUHvWvhl0r{GDRf8*MwoL=}Zyq`(O*!gvCx~Y_ zAwJ#L*Voq?z9}Dro4{&LvKvY*!!SqKp?6dNNQGT1Ft7<}=jh;|RXir1!IyKU%a_z^ zQBhS@1u_5>w|GRA0jPI7JqZuOD6yCA1l@5TzFiA1Tr;hA%m4oU`;Q+6Y!r8>sTZ?3 z-T|)?6BFOP!^=f}nb@2tGfqoN645b#7E{0mC1ZWxY$gX+zgpkf;p62Uv#)lm4_F<@ zNa8cjX;sSV>FsrQchA>cPvkXBO-*G#ERM_N>Wh=fCfI6iO|{Z1F_nXztr!0N`6SFc{#*c2G?p{gAwyitK7uBb2w zAv09Ua6T9Ze{pe<1R_et6S%LN)g>4*c6Eyb$q0d59Kx^CGcz&Wtg(H`4=q=E67WLI zS!7`>GLpRH;{u@Esg^p3HetXWlUtuw0Gm^)!-rj~!rTs9^&o)ylko{QAh z*5)y)6VNN{*T{k*p=vNHdJ(69{SKNdbjuYn2}#iTc5PQI06XJ@X$GF+RR zmzOu}Gp>@Zu;V0CJR$}nM)5gQ)QznQ;#%9Pl*DIkZLOh5!=oo)zZ|WDE7LvW+>()+ zN=HwB-uGxQT^fdgUtO%Gi@7f@Ex}=!zYY^+`}{7B-kHz637Da=48~P<8b(I5OR>_; z=D+YjPCH3@ZhV%{1=*Y?>3=fUq21sCo3v1XJ+v@TO;Gl6VbIrX9-n zrDrZKE)EXdPNL>~S2L1K{1ikbFGoj56BDUnmTrsfg!M*qlarGZ6BCn@oJqZEaH;+Z zlOf5=?Ck8eHkl07iK(fGPHET2LP7|u?->%_ctaVoF}P{0G1NX+n80d-z}-1X#r5r( zTG+)BBdP_4%3U*U4oK18Szo_C>m=mD$Ll93}Lzsh#k*Ha!^;&u52 zM>dNH5dzXDRlL-UPt9!!+zyPxhY%uppaGA?pzap%Y`66zw=DZ>r4p(ByvukwqW@at*si|R`W)0T&>dt0KV~Z zQ)&B^v*XRFzsH!9qd@8xTp3`so<9#c$C5LX3=H}CF*(_1xtl!v*Mf&QG2X9(mEOxH ze&3~N5l~Dqr(M!``DnWK%pfnXll`TxZLjmob94*lY!e`Af11eo2SfxVhfRO#7|1#l z3Ncu9 zcAU`I4S9KNUdrR;8)Py)Jw2ZlR{+}B4rX5NH0=5{G&hZfN#c9oa^guzNonxfUL3d! zjp>9}mz9;JJhJtJyq?cIS*=)vB!$*SIGF|>j}5{whwbg{P{u%yv9CHicLP>4yln$0HEnhq5`KWpJ6Q41! zpa7&!zol^Cz#k7&%g1!?Zf+D56aa6*MWbYM`+h}vxf&1k%(ho{L=XsouR6sbUC0?3 zr9lhxyTP0E_U*k0ME3J=u$C4U7V^f3x$#()E~=;?P+N~TCjxt*^75T1kiVIknf~aV zOTd>*n*426vK!+B7jw696oYtXf0pvuGwV+k zYB}xT7d_B0F!(yMUgzE!m%DFUT3oEeLw)#A_*8p#=Kjxz*{{LL03+;TAB}>cW@Z{J zyJC0^YXmmw>FB74!u*LQ+r-)iT&b?|a6jfEd?lZ9Y8o0gxGr^?5#C*d;38uqBKC!y z=I0E8j&d2JGuSz+e9fq%tmhhi9T6ZrEh9U)c_kgGymEO2K@veY0UQk4HZKOYCU<~2w9kBA@(VfHjO3?f_yy>i45a_;|B9_=& zTHie2L#ggzy7_G+oDG?zn7_qKA0DtZU9H5OfH_ENDJdzjA`ZkJ!0GMo7D!S4tXVnL z=(E50ruaF5E9|JKu#n^7L)R^*Yiro=-v=~tCm`Tt$`-)GarH9PS!B>_}WS4{# zm&i)*$8;*5p4DpS=;H}fXGce6B_+TfGeB_$$rr#taqr%?YtzU&zzC0eqhG&%eJE%! zoXIVK`J@wHV^Ry|xIFYDhKYtGHTlZ$q z*%G@3NE{1IyjRn_(M`VRGqUR;{<1_bSY0`geHNfRpu=E~8jq*Tj2liSEn|^S3vsQi zt?!9@ydTtn}hqb(eR z392{RITY%Kh|vLhYtoeZ`Sa++#Og~mu*PEVyzTAnXO|EpyMWPuOR;xyvQe6+{jxyN zFu0IG*hB7@6+hxHmmVU}_?)Z1ug?Q5Eh%i)WCAuv2>jwZ1a0yzacf8=lQ~JmT;TD>)#F?o;$a76vgE%8F0N!-CbzZ&V3J(At z0EP+9VT!bW_#NB-$$+(`x&Q8ev$UYCj zW_p@aFO*+U@Mp>vE|k{)w)CmC_UMS3bdxhm>W{G*b7=3%*Dqg^AKAvpWSg1HZ8{TX zf65)Qz7V_dbgk06Q`6YERGkwr*f&Wv_~ao!vp~zlt)q^i5V|K|w)Q)>A;grz&mVVyc+k*e)R00@bpA&mCS>8$96V2I&L?4I4-U z8q)v`Hi`w?M4YG&O+aCdjd_!Lui1OhrC){KlWf#`2%$6-i@;kMWeEQQY6+N_CC+i` z`%2}Y)UVxDPN%uXde~J^wE-`6l#-$%yR>X~+@3q`Q-Y%-sCn&7EQ6$hiHVe`X!7;h zVOm;7#=VMo2p&Fuzm2=4W$sV2Zw95HPYDYP^Y!)BnnB9Pgu+>|*rWF&o6kSq82R`? zK367tXx+oFN$SCa2V2hZ#(YT~7Umn^j1h!@N%_R)abIQmTXCJ`7pG!3n5<-B+BgnQ zPEK}q-}J5vp?HRBF0v0UZCa%L4m!H!b-oIRIaM1F!M%85)yQ&Te;$I`-L63zF%!y>jxqX1$vWm8#i#3$3exA(2z#L`8UPcPUg zB4j~7&qe{JOi*O>-+Blxl6rwk7ZoPx|GtR{#X%DM_pQvoS2O?ja5{K}z4YKUx#d)! RF*u;cQjk-XEt4^O`#&dxoAv+z literal 6604 zcmZ{J2{_c<+y7*%Bq9$JLUxIfETJsf2H8cjHui0-5e7+-kUeEc_ANw~7)w0}*_vUp z#bh^S31b`Ed&cv7-s^q;%glA1?|05Q_kHgDe9oB|Lw&8Y^c?gM2;{6bT-_J~Ik6Ak z<4;k6c0%4Z6+CF1RrORMkg9|;`}b+VZ(e)2u^t2xEChi(dIEuvLD!>22;_kz1oF!c z0#SGcfv|gLHX7Xk19S*oEp^Bd<@>g|CvyGNu;p%faT8ks_mizb}_yz-fd)Nr0h zw5f-E=-Jxgu3vZuqOq}&Y8_JWGw<>Ex+xhGkmQ^#m>s5roD?vxNX*mHw&(wMY;JCL zOlC4Lfk&8*T2zd`wstnn9DXBgwLJ2qwx_s7^%Ixc_L)np8mAie2z&h(bWonG8jL(b z?!(E|QtMs(?QVi5Cfnk*$cunj%sjb8Y3*zzMKaz{8#lKu;$SyH;lcBF7Haxgd~(P{ ztWkB)wV+Kr#*3Ef$^EYG6afywoO2cp##Ur1_dJp6V3`YC0$7m?Ji>~B$y-|(ud@t^ ztKr#AM@li8-HRflwYm;>j;)aoQx8|pajmvL8FcW#cb;K)9v$K(Ba@Vr6awq~^2{t` zdo`Z3J7jgDp2diG=3RVl*Y3vlWFzXe>79v#y-sDJ@ZFvt59r^~<4#ieX}rqdi)Ku! zkf;t2FDbd?JTRH1KbZgV6)Ss6F5mh$wI{i7BkV-|WwF)YtQl|E(px@_i9G+&kb){% z_x0WU^*=b7{On?0Z$BS+WG2#OZY!8wo_i~qwECk#PQ%WVis!GiH0^xY`^yxsLU0BV zL|0=YpY7GNoLz?p-Oe+=Cre8C(qRPj;XwH0VEv~tntU(W6#LHk7O{V6*mJ9rxNho5 zSo76;r3@(XFE7vTF08iv#gP0}XL>WaL{v&q_pxfVW6wmr(!OL+;`pR~z>2`kj6=Xn z)c#eAX7ZaB+V4WV2Zqn~f1aF;WLi1nOKV0;2_hBpEe6J9&vCd0ttd>m%q%J0R!9!{ zBV>D4yV~`&%*ji6VH|DbnBTtLLBFg_e@1obp0-9NlXmF0YY&4M`ozvJ4E;~#T?h&~>t5P-O+cm^a6Wj;uv<0=0; z6?oU61+%-b%k_GXDQs1QVmc5xhQ&oi&J&FfST#H+n|7D$2`xf@BAY0wILkI%VZE_; zz!=@;ASKF5pVIA6dr$20<*>~%TXE~gnwA!u0%I9z>5ovyOy>+gKR>d598vX6x=%8$&uQb~jU>1Lai57J z+tNTwE83>A_2C+y+*OWvGD->Er#V<-QyHj`rKYA9lg&fX-{GP}j3*Llb~%kMGUvmG z!G(<&n}m%E*=@@K?$R0g*BF?X6tnd6u<*eeyqm_>8DRG6u1M{7ZBu{t4sd;9Zm5?k zyl;(5nrvVM277z^(9lq}SlUq-@L87tm9|G|S+Wa?O?K?Tb*{f}%2(aJ0%hRaqXkwZ z@(afFm9AOLt7D91Igbg>3F8F=ZvoZ3s%9NB_+7jqr8OOzG6ZdPZt zfBn4k<4qy+^7F?_>?&lHl`D5y#CT@>dWFaSIu<&@>h6w!S=1Nj*Woo{^vA3;?3h#T zjsjLD*osv2<>Mts@uRuIRZ?HiuiNJn z*W{}?j@QJURHo;?I!M1>I(nf4_?{LL({)bhA>Y-p&kSmH!ULBLmyZ4k7 z!DY~c(nD;F>|9xo2`Kn+oey+=MttR4O&MvDQ;KB(;z#pT+roJq(r@V^&b04X`OIDT z54Q^~ITF1Bb#LPaE^QneJ5dRKQlRRoE9zzDvj7dCHIaHPg+}{I+(5D#5Y+OH?4Bc( z4oGXe$Q$!?ZMUlfc;v*YZv#asTAJj$Q00O=L9IM%qY7)x{KoD(GcmBVGLtIHnVErT ztAv1pAuQ3KgMrSWH8Bin+eKk=O(P8G@_y7ySN9BMvNNNFK$T?J%dR58yU&OBoC*-5 zhh(Y_c)%EfE-dTFcTkp#Jq?x%_hD*9#s4EJY_U%WblED+hSrG9!6{_Uht*U-dYC1> zz&|EcCQzRO9ob^6reID07f=PZ*-H^`LF6fgbx9Iny{$s&7+te^e;kx&%*k-X{r!D9 zU;_IR$qxjoWF@dr>syr?v7}o)VI@s4Vajhi)f%+hNtH_ut)@2Ii+}|6>9LEPXZ)=D z7McmC1$a_Vou|Pf$7XG}#B7PSO%Ht>90Z^Y!Ob@5J@|9UYP&|)9HhZjLZcFx_C`BBUZh^caiVR$|jJ2S6Hhu z7bClGt6`xVYm7RsB5Bm4zkx$rnVS7$nQ*;?s5;uGYRm!|>S#RX#+=U+uc@V}iBigL zn{x5=#Q)wD6ckj*>PJ*v=XxW)=Z|*_cj9^Z;mQLA z%F@#9N~Crjf#J&V!H>OM+}tb6%e8l}Tu##|8XWbgt0#n6nu$N+5O+8xP%Z$RfB7ra z-Yd7M>{K)0n(`i*S$ps6>h2CUso0S##n{}TQ&Nvf8#?5aloU|<9i&{PGgeks&ag|o z#qM&HR#sM)l*AMgU%Yr>C{mMnI zJv^=$5)JhA10FoUN-qasa*}VmcDU7+;@v8T(Me)HLvW-FixM@=>f`(SZFIM~GGyH6 zNliYQZ$;b)EukPd3knJhly+xdUvoYr6)BhBt1WG6+6QYKPRGIo#@c7rhVXa*XY(s6 zRuaPZ^NIsSo-3es{*2YS_k8`z9W={ahF6f0>1Ynw-|>n3Y-na?W@)+iRjkrmoWHR) z2|kO};%N@r5UMYAk-i5KZ1dNh*YMV+rp(nX{f~Odb?;SroM%=p+v5^CXC%^f%gvlI zTDg)9-cz@9bz}95IH6E@h+uKj4R-+)UCYjNtkw&zOHZ2CzHq`?cKEVM*d z+hC$#noh0HjOL0XpkyVs?yX=r;+?#`y`7vuYnX>^+MW!_#o0CoZ~pvgC(Ut@hlkMM z=NuBExc9xpr0DxQ3%_4OC7g1|xEC*w00QC7ZPQw6#l^+Je*NQU@#p7A<)ht!Ills1 z6B9o&iD)|hr1I%*VGmhHnLDArt`5Kt6imX&bNi5>8Xvj*l1|9Q3m(HN7l~vuzCv4G#~Wc7}vRU;0*LU^KM5 zvCyC)VcTML=T67r#L$qml+@qNGP1ITc(($tU6|7B6OmytO81c&w z!+$a?t*#zzR)+UAdw6*n)Trg6U3)71ox( zep^cxSlKD}`z=JNG^K34bq~qciz@>Cyr|^faC;#kq1!?!9f%|sZ{nBig?T}VNdjRY z?Dy;2FQQ4Zyvu$1C7M*uKfjk-E?6OeS!GH{w6cn2xCL~sp-2n)mzb#TTJ!!!_R)`T z-&9WR_IZW*krs^_w3U(0aHZ`+p%rj4csH-G>W(6Tp4IKW z^U8G%D_PR{t@qoa4)(SOw8(1@_p3U&6+_9SsI#2v36mXZE$<5(L{Z|sa#`n$jg6B> z0&8|~*_oL`M1SHYwCk7Ir7CJdQ zgAMkjxTW#L*v*hFP(Tj0>RbDsbxDaFfVj)kO0a44CxRU}J9Nt;BxG-6Kp8eBbgW+U zLwXu2KXNRa2^pka%xOj2xsgj#csw4IDc~Wc?1U~4u94o}+js8VnPz`xpr;33d_t>5 zml-vTxD&L>@DiX_)zxj4*H2C>w(M>_9goUq=8DF;_ycq;bG{h6UnZ-h)Pm@Ep5J_y zNhmB=QNkPk=dAzUK=|RtVD@26b@h4(VQ;d|bDTx&A%FwGr-HgKU25+obf$dtjc{VW ztAjAY6*Chq>ib@{(3y8Tz-u< zj*acrVZY)k$R1X9_8!MBClizN1g}y-BqB8QU^V<`59Fj}J@R0N=V+uQR56Kg{XM(Q z!<_nhxivnqH4fQ=i5!t%lvoN{7uas-+q@{)FZ3SvB+;w&VC%K>o88fYFd;*x`f-3_ zp1KPe=Ixq$qEJ>PraHu#SWx%qxRQ2DN%HExZMg6)r%L50l~cI?4Uwb zG(W!5W?0*a5;e5*Gg_1)%Ve8WX*Ze+f{s9k%3)ou`wT=_ zBFQyl9yv-wn)1Hxl5sc(3lCcSc1hw}`qcIJWHQ;LNT2yu|C^gV8XsMkKnTSoDCrp( zn46g?T}OXvId`kHw6tY^U3V%N9P-e&g{FdN+){1uEEZLWj=7$6lQfDr7g?z6IS=;; zM@T|Tb7N!1#GC19L_n~k<6I^ST>c5of6H}~HC^0N=-{dxJbbD#@FS<&6n7i&A)$3| zV)dS-B{))VEsd%<$TRi=JmY#>ORF>Ulw83?l1OMo=q21^EdX&xM@7e)+syNJO~u(_ zL)W{7!QSnF=n^s_qZHpnkwyuP2*<70R2+BGq=cTgUla1hK3H_TFSD>p`(+a`aQB!HDo0F4}AaP^)qslfT;ZdDq&r6>)GO$B`x$4_I&9|c(n80dN z{;pHFfeXa*x8gMI5r?lyG)N@!aGY=`tEk8suerTE?kvp_W7Qea{O9j8zX1aDh9Yz@ z8+M6%U_;ydym@LVHZ}HZf4@GuPpH5HCG!=I2d28oZJ>i&825?bP4`k62Uui#Y1D7# z%URjvsqcS4q^)aIQ}s!_Hw`u?v$)e-P$f4A9K^(&&eC59z|fM`KA+@~mX*ECN}o|! z??vbjTgblA8Ih$J_#(Hs{ggQwY(%|hKb4l0$b0{U5X{z=W8d432z#8Ri)=62-*pqX z5{jL0koTEZ2PNtsF`_qj=xVZ*!&|_orpABnYnoTnn&vbgn845`a1kZ?ZHY>^K;R%1 zgy*p^shND|^Ao63F1^!}=Frn2pkMmQe04Q0XLg_=F1#Yi7r~d*?phghoD`DF#k%tVD`I9ev)|i z%J;#+JmV4o+5fnsHUzjB<>chbOiOzYZ%eodlyMmGo`3e7K~JE$+&D#P`#$db_d>HW zVA#b)k)cF4tq8(u{oO0ldfOzD1F`5VfV0D=9(4%LoxH=B1P=_XzgI4c?gO}&JuNpb zF7AEnJ)|V`2JohGLK=5*(!M*5N3^fWTDon_!5JDe!F`H`eo9uJJAsLbX?3!B+(TB3l|DSC~`4^)0-^%fkKu}fw2fH zL))vq`MNq;eYtl&ccY@BB*IP-@Qdy3G;#yr5QMRlggTgaT+S;m@AHto#*k+yBJ$k0 z46m72Ra=Wk)?+4CA|g&KQp-?5aJJ8sqGQ=%QMWE-4|Ed0xYcH~f-A$T1l7TsKOfwr z^#C>AZPXEzu0E&VD=Pq8)DQo@2!+~h3LHc`pP*>|f86r_zyA#24VC_PU_J4OI-avJ z&g1W*Qt;n^pufgle~0`2jtcg^j^F{2lDsM}E-580C1-l|s)Dqvf{eVFq@;qRWQhiK z-~S@;^m1@@3i|&Oj6g9yfZ!Zu1rskP|G@jcjt~=<2mbz!zV?s5od#nNZ4G_(id%M% F{|kIs<(mKi diff --git a/docs/images/SequenceStar.png b/docs/images/SequenceStar.png index bf411822d6899423ecb25d92d36b6d52e287c409..fc3e700f074f7ff2edde5e87316b71bd9ec25981 100644 GIT binary patch literal 4640 zcmYLNcQ71ov|U8>wxWfQU(6#0$5CEWQQ-M6!@tE5;@o~AQRNEH7 z*csn5Bib&1mr=Q$=7qA^RCHKqH#)%|iOh{G6Ugmkl`KM{q(;tI{r0*{*7w+vtb}dZ zpH@B*y-AD}Yli@p=eIh!lw$#^pQ429fx!N?NKV`$o9y_wY#JvPvw+n-%S3ONmzNk# zw#~zIr}tawh%A78pB?}BD2@LM&4Eh&l=ACBdNTJ)%PYp6%3FIjw>0^!N z{p_mW`G?Y5?sFXD|1tg}0i~RGwt|)NF;PMewj|_n8Ajit)&33%hlJp!v|uo7$M%U2 z9GhHU`=QSr#y{UZ>PYq}*5&LG5kM~*@Ow7um$ta;^3Q_e{FDj2b~qJz&M}^3%&Meg z5!8-wH2w|u8bmd}^u8V{R68VXX*F~56RpXwQyYplXX}>N-yJ)6QpRWq*#*J*fW!sZ z)CZ?uHuHYXCzpQZc#gIT0jn##aC*w~6H|bf-~MoTlwej(y%y;>^Z_WL8%gZh;PqLm z{Ms$}Rw$rj%*>fp>HZ;JWnF}B)NB5`?FGm1?T=stqzpm$A#Fc34xM|?| zdkcdVOb_e;HE$JaEL<@JP-7v%CYwZPANEUM4P=#>M80iqaCdO0=%y|F_}k%f^#oQ< zLcOP}!b+EmSSq~y0ng3RYag3k@T3QY<@beuQz;k%9+z* zDo$^9Tib0cOs(a6i5#TExcqu^lI0|xUUSl5x`CU1@+qRL`Chgo>>oDQKz#=qX|G>E zVAM2vFCj?_M-e6az5zqsPeZ)HUQ~}Y7EG3mn~4p68uE%r0YJ1=G6LoJh4nzUo;LvVC$Epy&DQ;kGDMnvW$DZ@~~+rVqe z$=>&$iLCKez1C)v|FXq+G^+&)3|4v4t~K({s{ilSTf@GNCA(S*UG)Oz=iw#SBf~DV zYAzNwb1`0j2cu>x45XTN*FnyfBhxR^TyWFnBLHiW(LZ8n<9x!Z28(*4~B4V447(} z8`G28Z3nb4rUV0%7iS`!48oMl+)pk3ga3rz!o_5fhkHHsYGOca=zmX3emtaJlye#> z@(#+h5^WukpufCFH)vc~R&!^_v=U{l+R0Ak)x(*>^U~r&rJmY{G=(X4QLi4B6dwFY z;2xckaUmd_r^~dm$NGa&WZoW~j4_uW7*(wo<(QVqS$Nm0hd5=xhM%`ekK8d$4Oui~ ziW#=9icP)TquV#8Z>|Z7YRO9*#03{%?Axp=N;y7E(1?ix7pf>&GUFj%)!E11y7EYy zd~oC^#jQrg)RwQs&O@A&R23p2CG&%MtV}#mK3kpI&rDU|8hRTb0v3gvV$!Wn(3#JR6 z63MszYlXweCDd>P_xH z8(Q{p$JlG(x}ihtWl<1WJt<+QWrX=f_wRFEu@y^0^#+DD{{k;tU%mIfathcc-d}Y9 zYVo_vwP{bx@u05d7i_#e{QDm2R|?v{kuGFIg54Wu9Jl32h}v6(0TPEF^!1@N_LiX^ z@vNCQ;I4Nlpmn1-g@0OPNyMCPU3dIT$$7#XY%EUqlI$i}#-tg>56;ct7TI4e2Iw-D zaz=6Gs!vWJobSnV8`7y!X{qCe@1l*?BMkQW;$(4-FJq_h0W%U5jOOmyQHVRE%RiC@ zG+dOBITLmO2t$ynB;dR!gzo`@1(yMMY{oxKaWrnOQJj?9COx3D7ho>@yfya_vG-QC zsdMG6Y73JNc8z?rF;vqpDkpd*y zK{TGidw$&hLSwVhO7MjuuyD`GwBm-u(f*Odc}flL^%}0{+crUO>kQtgjnDin4FZrJ zGO_B%h7Wjp%r4&!W#KiwXz#(MFXA8x9z~0= zu;(&L48 zbn&mn3)_AhCCb{G)#?_lzX0Cs%_HBi$sM^*n@qx3Z(a%_-;0S8l1IKeb4R5R6Vq?9 z2Yi*Bc7CRm!uxqQh6rY`=-@rlH0eQy>db4Qo4GgS*#zpD4Cz_V%51f>w?=kNB;9-* z*lhNj_0XCA={j`UR0Gk86|>mk%hG9C8~#PL$1p7R6%&>jE`yfFUP01*W;votgRI$y z_`ip2HCew6DLCPjWD_fg72^w1#L{ygy$@1d9C+o@=0Gw0`|g8dF}oA*@!7?{{LO7$ z>vRLYEnohw0nZxNa?WzM^~Z&^1AZ2)ECh7kki5FmB5Y=eT9wp5;;T4O{vIPQ>l*GAyG->Ci0R+r4cm5i}zoTi-o3Mj5UK7(p`8C(bLN$~I>ir@wV30r8^DQNvx zW{E+e-f<&}byuTD+eSYkUJX#mW|=OY{nS_u3)7HO23%r}${NnBD4cVkYq%%ujfVz# z;gGK_TrK@FuP=2*6T%|T=7>SCO8If={YElWqrs`cN58I4YksW?<@M6RUi({One}@D z|B%YONo7s0aDpCdeiLH}LUthbO(u4XSU0m*qXG9x;4If-adn5mCE3SkLLkI?%Io0x ze&Ch2?YGqKYs!ay$?p0ur2VyMz;9~+8cvJ%JUE2)oQ9zs6G4Qw3kh#$in^JF9uPU# z><*u%sgp+z@*VYKZ2Fp{4zN7ICV7wiw8HbPv;y4qIVtb`;Tq5)lzmm_H)9yp4+wO%a34w}06Qz5LUGkIE8NOcs17JxFQ5=gcok@oe2jut}?eZCiJpAydc* ztsVFgv83r))t{c6A-b@MNMZy}OxGpESnP(QIGsOUS_R(d{?yRb(V0p`kHas;wojSp z)u{&0@7JW9>4paTnc&djC|b&Dm5NuGU7z!Bhd*Y0k+ZyfD?`0#8Fk;fFaxrSV--8Y zxuF(mgYzTq`kwP^neTGT;6x{rsqc<_ZzpKiZ!2u@0)EWHQ=`G&VL(x?Hc2DzW6!) zd$~F+q=#XHG`GUM9Zo|QS%IcAgDIlnG$fI7XgUZ?u^%2s6q$pjGlnVlz~cy^05qL9 zOtAwVM*#IlgI>WVH>!yPK#m*n-z!Rv4DPf8S)2#v^d`^2XmgV62CKtTUT^wgWPhiz z>anipGcrAWD@%cb%Mx%-FbB9wBqiQQH)f=hlD;7g`m2?<8*WY*2}Bnt!048%kpW6P z8(PH`B3J{D_PmGA#nXCH7vN*$W3=(ksjk2?GJY_xP|BrGQsBti`*)c~CgM7MLE;8W zGZN>2pCba>mQIKYC`#Uu6*@e+j%9!6)|$}dApFM%y7qq^otZfhgPi}kdA)Y$Z{Enl zD*^%Yxv#(qcHS(q6;lm1#{#P^g7SNh&-Wh8&RKcmc6Q_J2Jz4SFc;Sqw1OzJ)-|^F z;|8gj=W@Bg+c1()wp}uZdplJ1Mh{hEw_hk#iR+p(ZN(gkBjo%)A3E2`Cq5jHj<7;}venc>kl>1^oKT4ee|xzj2~k7;3c-fVeU?(TYV zI+Ze6yHm{W1Gxi^88Ip*oX||yFnqukN<&BMExdy~URRW;)TQ8J5?lxtw z!)X_o`B~4hB&o0?eQzgqw0Ej|CjEbVR28d^BdrQ%=xNQ0td}LZownnrz0vG5hv{H` zf?CN6YX53QLtI+bWpQ-aW2ZgQlO0>d-4GIjyGBRe6NOtVgMH(@7kXx!wGZ+{^DneP zHF&oD4n|*NYELtFS|kKy>xT3Ys-5v?#55QqOJHvc(@Tg$A?Rz1I%Jb=YQ8mh7N}1+$ZD_P1g6$=tBDpE5C6LWN07$Pq&ncOF-4?Dyh!NZeYp6`WGqU| zucy>*o-+hnd_5YGGdC|YT>54IKydzeBT!t40d`lMpk9uu9q;J3biKO=13xTvPE+ov zFszN}(m5YD(Yqu(9fMW1gEntSiBpg>fy0LY2etr5^}UcH1EHWIKljP28|Lq z-^4d>^3jn#D7_zejFV!f#N{Rvab#jg-qDHNU@ZJ!W11(V%r%n!k^c^GrO1W_;p2 zy=DP;TE`BrW>ncDQ*30Y zT7~YuUf4_d>#U{}Cr;O#@Hxj`Amf-jt#w4CJ4F2PO;xG&pB@a~R8h_Geb8KDsP(p% zm|k~2gc(~GRM7vHUkv33LWEHuDytJ%u^J-(CLu!lj9|5YLBn@LH8B_?J}gHb_TT77 NMM(ovu3+}*e*kl32$}!@ literal 8066 zcmZ`;1z1$=wjK)s5e0`*k&w=jjuE6ox+NW2Lb``g7!eVWlI{|4NQogt1`!Z}ACWHU zZfOSYH~RnQo^zgiXP#&Fp1s%CE8cglFby?@tHd{nArQz_B}G{+2;|&baQ}($JotSl z_B{h!F4{<`Nte2*j5K0tpI%K#stpphXD80|tRCKZZcW5+M*O z=hQk)ICw!|{!l>{a)$qAHWtJ}Ab0$gWTkYxN7mBpHMDK+ghm)k1*u%Md~)^U^4214iNDy#5uV>^t=rHER^sehp@j|!)#c%o1#FsSDTU1% z<#yrm9=9Jd7|l?|a|k;I5wiR5%P@U;lNw^rbCSN~j>R;H9xmLETJYj=Vgt(xxPl^w zKr+E>gRo$R#1|kB5a5bB2Z2BdAP^1e-_IayB!7hddG-LYb8z^~hVbI~Rc;9Jj%b;U z@AF<;*(}fqC4~TeXix*uKYxgWv7rA<7#j)b{m&mD<385t=e55+9u^ixMn>i!W~l3H0>g2_EVoMypTVnszn7VXx1a}-+5 zUA(<(HQ2_=Ekaw(%e#&ibD~0|5w^Cr($dl%9)fb3A=g*V=nf=S^K0!Qvfo{}Oq!dU z8xk5Sd9vAZ>Cz>CfB!vuv|$wo9G=>#iwNS>YeZ8Un# ze@ik8IBXSq$P!ysRW*FNy1uTas95$f;Ap8JidNiu@}&`~_k+CV57ZSZhsviD4Kz1y zSoq_9Xsi404cm}9eiyieI>+XKV1Ir6``}bT@B``D|O7n`f)a3!r=1R7wXWfnu~p(bY(%ssC$~`T6;)w}ik1Sz-@| zETS5B2aH-;TBHWhJyJReF3NE5_~QBIP`ZFc&z9eNFh(zmtJ6N!@xd$AznR4YgsFaF z;5l$qB)}+u`Qa@D7#jZ1|7}I!aVAXi=;RYWzTE4l%SJS|<57~l)gX81liHL~E!*Z*u2ONY( zt&>#pi;6g+6`3f*?d|MVZO#FE-LUyGJ#9`I9-ollwYT~xnYqf)QB93Bv_+F6UNHgK zp+p>wpRX_6xbrcL-sC*!+1&cq?c9f;>15aI^k8=)Fq@pDUbi{)_6f%Fx8r)YQ<>P~@3()*Cf?%J54!HV;pL*|fK}E8OvsWsDwrtH}nf z_J~)`Q_d?wqx)BOX=!P}{+{B}G*5Rk-e$Y9DL>Gp3>$U|p(2xcxd91*4E=QjRefV)V^howoGljWdS>3HiHFA)8;n ze%V%yeEs?riFVmT$17uu zdC0@4NnRLmb$51Z7wV|0s>2h>*w5zK7@Iio;HMDI;PEJmV3CNH~$j{t0BE>r=HR!;^M2S`*P*DReJ+Q@( z9wn(2tgNl=uAIM0N?KiA{Wc+CR3ZWFiCvW`T=FWu(E!w%FUii%4s4&u?MOu?4j!HX zTY+c3(=9-SBYASNvvakU_SQxh&PZ`uh3la_DMl#V9gq73!R(->`{nHGg7fr^N>4qAV^e z(jz1`^Q{dT%Uu*)#glfb*&n0&=nQm&C4(5V%H~_>%C$>%aW5x4LMW< z-0xjFIWWpO6p1q%-@l6LMF^#Ie*Ic&T%w$}J+~4jA?@eq2V#q~^mD!9t8ftbWKEIL z$bDLjU&2_O94Rd$4Nbs_RWI^38`lG9ey{Dt^HNe$=hDSe$${@WjMAul65`~2>eR0K6GtM*O47ruD@cr9iku2dX>9D_*}<077qJQBg(Y7%W_&bYiX0#bvg*G_^;}KbeU&wy&UL z6LycfeWc2Au*45UO~&hQ-cp+Lku|1o9{w(`_Ohtvo6(=@a8$G))nbQA5 z_Kr`8fDm~sP({l=7GYJe389V;)mT{7W1`7ikA>KISd3~U$}Fu}4kyo?q4N)k`EN!T z^VBpnAlJK>xULgizC7oO(cwr#EBn?I2nk##4TYb?PoL=gd{fCDJ<@huv1K8qF-r-?r7fx$o zXl`Z_NxXO|S}vSWE;=*QuQEG_uHF8^g}--U%Voj-UQ%w;WVvc`zO6)LOSMU(va6et z!)l`~&Fzy<^-+=12#K7si3!tdI62J&8f9LCZw0=~&B3!s-BcEp_q9Mo z#<7FY_mWp^Bn)etoP8)ly1^Jvo)=?WFV973E+h#Xq}sc{_U-hYQNC6o+;DhYUtzfU zF)T!SYNfPkLJ|{>vG=6+1uOWqkc_en)BgB#rR~c_cP8=UiT40v1OSMU;V`CHV#X>XGdrskljv=B`47HejgnA~qznA% zE}^O|K&QaQWVnX=oE#&~!O^}66Aes%Z*UHEScK)^vLBnXz`Nof1>PAUJ{-1XYxU_Wl7Y6CM?W@gnp!?+)X+UoGF5L}9$p59l>if7NBbk$t6|Q=WR2%gPEwp$v87GOsD_#SqFFcQh+Hva zzS+*tI00OC%Pt!kF*IUJDZ)A!V_dB|VwlyaYF%dJzkN>o0pNLc+tZIH+Yd*v3=9lS zLuOs+0#;qgg2%?jOc^JUl;Ku~+jD@x^(PD3uinjCDA;K_J3R(&!GE*)GCyxkha~_} z{Kz4~KO6msi}Fs?!W80pBQJm@AAtwS%3_G^_;q@`@sNpJU+TN(hy*ipUUs&*xA(!x z;SO+kW!zj);wr9@Uep=2Xt{kMJ7za(8vg5{PfdFGSb3g zhGpe`0J*Sjg+*t!*E2w9i8fT_`_c;+mX|$OUo!B z;pJ&UxpYJJ+Xc?vyhjXmEKT{Cx&9q;Rdwccrv{v%_K{d-Ss`G`*}b;4#_J$JG#&(7 z@ShIGyn6lG0YJ?G0_q5PjB$EgoItpw`>YOvbVe6*lYvt(zTudMhMGPnXLhAj>1j#I z+lD0fd4fEK{SHhndC~lU2kiW2fE>n%+I$mxP_ZE}pxuL!F|!O4nQwvHyU- zEP<6WlP=r7h>x^lb(PoB!kIuNRB1d9dT&wtOAN8Yx$n zTN`CVaUVgiN5m;2nQM9+@y0yDoSYzQLS&&enz2)%C(jbwKRDR)#0svN$O?MJNWbNB zscdLTd?X;Hm4i96k!iuvi{3!_h{z_a33e@7^l|p8L}HB{8;Xg&w>=&p_;nN4xYR)| z!O$@I0X-WpuUUJOgC&l3?EQPLm8~VN^vaAZtZ~Gf_;|UG2hT~alEsEKoJmA0j&W_k ztlx4*-ey2b^sa1NyKF69`b&sO-Y^r0V52Radqp6=Y0CsiyEk~ z|FI$xPDJF=P-xCVyyN_mXVgBqw++tQ>%ji4|H~+^P=DzK;uI^?uv)C3pdbYW1<}Rx z&mL$1v;FY{>fMxRUv2;l4p0ria?c&|qB9clG;;dy$g`Us8AaeIs4nJPkGjuD7y`fMWojIB}nd5YNI&p!3eQdVnRR zr+1r|d&AR>c_u+jme1Mx8XX?$4$=^Uf@@6D%4_;l_{_=<8g>}~eh;xU24-jVpos>0Mk7(44urwzgJX1*oPWdIIBS zqp2Bf%#)zV1P+UdNtXUPFwcd#x%jtli$I=AZ-rNQ9nTndDzL`AeSLic1Avwl6%~Q- zO?>4Fo}b@fVrG6+O1ub>%ch~{Bq z`{{~djDA;JD?-1qbWVeM^C2MQrlmFGkqKaX04oi=QH2}AfVIud&G991ad0Se#IKKG zc2d8>t<38i!yqN@RGXJ-#LRSP> z3DSSREDLfqhx{4kS;h^jKP|2&in^TpJvSLOlGN1NHxw^&iBJrz(ui|}F)Yv*sf4KC zYZN8>yI)4=KLU>#SX7a?_Am`tn-`xw2vW|DIo0jBlm$~S`We5u zs6A>SaC4mUt1#!1{ecrRu3R0j9WujX zCR~)Abf=r4HW~iaz)&pt0N^ue^sNHc+l7Wkz@Za!ljM+L+Ojr~iIEW8zZFvJEiN^tMZv0Vg;-0J2 z{$4Ki$`97P-!X9zp?tFHVM!{L!zz`ZmivnV+F7l~0+h8_A3myk-nC5zzo>6l#!=0W zK_XWKiQ8k98g|(G^eM=3{nIB%N>}~{&r^M(cG_$4vdmd9UiSom??G}}w2;dau0tLV z$e$S^@a%XJq;l2!O!P`k(Y>|~ePA58sBM86GriXzsfNEy0A0w_dgAF>ZCcs{V0f!J z#%IUc-@g%kKH@*``3+S0!dN+sPsG-Mzr*IJ}o%*eN>1Lnu|82-Vki~>k1}h&~fSCt@6@-Ay?W#BA@9R6JAnacz zWiweZ8besUAy6g&yi1ts7XRP{2z=)of8g=xB+>@ILmi@MCg^+!0GXtref|A&;^S65 z>G!9mru_C+T}G1qQ$Q-Qyu6(BT7tKI+fJeKNK`=Uzv%hoWR$X6j(T#}JeaLG!0B)} za%;MkFX?@Gc`qlJOX_9^YX1;v4+-*TJC*J53+~eg+f+I3Rp&BFQFwOBt-06@GTIgQu0N z1t&9fXV(cY0-XZcWT0PrW>Ljtabn`)8Gh@S#l^+ea4M&vvaFgKuMuKTj_B0X zv5ARwJp^6giAzAhN8VL$3Ehs4&i(y;1zFk57;W_I`gr}EtEhk40y;(`@dl_}oE}e} zjhs3-I6w(6g3LTiY++s=9@_7zKdHSb#V#s(INK3>_wL;qr%4_jo{2h-mD%;_DUl|p zhOIBn!Iy~`z=Hf|B81006F_V^IPm_na?*e3mJ; z=0UY*t!EOq?p2+tPAKZRnux2cNPnH_zR*p3CrY?6aO=yLFCeiAbP%m@wev0aty{O; z{3b#=ERV2}3)=Ci4eHz84Pd2Y@u_yqG$b!@Zz%4hcc$b3JML~`I9|tES6;q+*)fom zgv6WAyraKZAJ`ixc%c0rIy-Ovs(UCS(}H&jqZy$7u}Ax(%?qAUl#AQW$;nCJHS6x^ z@Bw)&U}{{D;N0fNi3qP~d?I>#q{^N$ycHxx^^%sQj*oU%XstzQWm~5*P1vAEiYHrX z%4!puAa!rRMadyrFXfufNrV!W^eECRHlh6>EF|R1x2R=lncHDm@$q!KlQ+$is%EUt z!yd3N087gyPt7VUJ3u_L9XJB?cV~MWiD=tNQx-Eh1r;HnitlE1I5GBvJjs2BJI25d z5M>~@mDJQC{m)*8hl_hG|M=^#zY4Vrz{$dC+}Zz&QYD(=Jyy>{-o{zjR$hW>GBP;v zKB)hRJO2y<%JNZL3D3loZ^i$*T{(O*8>{|wxMFU5t`qDU$h)7N?l(CK>wa^?>nX{# zYoONE-K{nn2h!7Xoe4&~kM;HR01+Ct#@v)z!lJGe78W892&6>d#zbS^3J*vr!Cj_9 zT0Y-kRa5yW_3g|4WZ;Ilu;q~&GcBW*t?fGvHXV-mJ=R1Gr5+j@nqh!@6q!KK_X8<` z0N}0w^zq39y5r`#F#%E+YwiO{{5GIW&=WAUy6TYO%S8bE-NFYTp#X(K@thY>$uW#u zM@Pp-!;acd-6sKe)a3s-Ph#!jekCO(P#gtB^WD35)O2)hAedx>#*=Ig3_%R$zavOX zqmj1J>t1^FPVp7lLAox5S6nvT8 z Date: Fri, 13 Mar 2020 16:45:25 +0000 Subject: [PATCH 017/163] [ImgBot] Optimize images *Total -- 44.02kb -> 40.42kb (8.19%) /robmosys_conformant_logo.png -- 20.66kb -> 18.53kb (10.33%) /docs/images/ReactiveSequence.png -- 5.96kb -> 5.46kb (8.34%) /docs/images/SequenceStar.png -- 4.53kb -> 4.22kb (6.96%) /docs/images/ReactiveFallback.png -- 6.11kb -> 5.73kb (6.26%) /docs/images/SequenceNode.png -- 6.75kb -> 6.48kb (4.09%) Signed-off-by: ImgBotApp --- docs/images/ReactiveFallback.png | Bin 6260 -> 5868 bytes docs/images/ReactiveSequence.png | Bin 6105 -> 5596 bytes docs/images/SequenceNode.png | Bin 6916 -> 6633 bytes docs/images/SequenceStar.png | Bin 4640 -> 4317 bytes robmosys_conformant_logo.png | Bin 21158 -> 18972 bytes 5 files changed, 0 insertions(+), 0 deletions(-) diff --git a/docs/images/ReactiveFallback.png b/docs/images/ReactiveFallback.png index 7ddb2a5664be988682c8f802846915d3f92c1063..62025561c0cc4ba15809f86c425b294c987bcd65 100644 GIT binary patch literal 5868 zcma)A2{hDS`=3^oB_#V&$tcSh46;W=Ok|LK-(?+?T_Rd-lNdvOLSvU@LbB9k8B_M1 z$WFHG*~WXP^ZUJT@BjS&=lsu{bMKw|z0ZB_z0dY}p2xRzH0V!po`OIi^fxrsP!PzW zYhYY|;xK5L4!=wQ-BBl%n<@}UNi6N2%`x!*oSi1>CIk`)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 literal 6260 zcmaJ`XIN9)wvB=mr3r!*K@p5dZvs+815!grItU2TK_P z6N)quLYFEv^j_Z5bMJTG_ul*7{;}6)XU$dinsbaXCy~0^s&%R3l4Vf2A-H?ikYUHQRB>0m7@xTOO;PC|EW8-NLF>rj2K-haee%(V2 zfv_^DE8jPKF}#w2)MauwX}cOkmHqU_m-p-Sp&{h7seNh^K6+;Ad4>AU^NG<4<(Nf7 zexLamX&#21PqpQOldlcd=#i-SfUuM2N<%Gmt%*R|RJw*5VKdlI_7b z4FdV6Nv44$SCJnQ*U8Bz(+`Af#hjdBx8by?XBEfH(V>o*0*bBDGcO4c2i*=PEkIZI+oTK%anp_#mbLY;7%6`i4vp#93WTL)BO1H8Tt7=d@s(%wJ zXX20nYN2lk?wd%k7#I~bHTU^*`&$N{TfcPr;y8IW=b2u;RLiv+k(xp>s>_tP>=DQ}gnMsO5h6^t8ZqTT#WhsF=`=)ZW;5Y8va|GHD#qnln6Fa@WkvQCWGSh@gy0 zC?F`y$vG*JS$FsVbSSld;3Dh7a=a)o+DyykjO>o}0rQEw0>VcT%Mk63H(w-`ZPmuH1ML z6HwjSnrOce$&{l|sil>pPT_t{30fTV1F*+X^pY+qll>htvZoScfn#)e0{OtE=o{>vIqMW4$m zp#2vwWk`hUYdCc0CUfS(vl6R7id>t-Qp=ZArz` zHv8aLDi3b`dZm&MHVr|wQMU)9mn zbn+;h_XP8RKEz67f{gBh6?~`SvC@_GgSoUn2YvBKhR_z*KQq(# zFely_BPpLA7OGeBj-4h^-*1jaOFNI7TT<#>&{n)Z^ihy{k_I~?tkt&OLFdtXWmxd* zpn%E|=ty<1Q~$4Ow^h06a)b!fpIH71{;eZN{}wG>9;5oi_?t;q%ZZ-v%J$;*UN_-f zs%Hz3V=C9;C(#r~Osi;$r=HIosQw!W04(^QAr9H&I@z({i?%O1=E~?l)tXirv5}FHV`F2?%*<|X zZs2+8M~R&OjvzlJlv4H`&^n8gqs?x`-BGU_H*ORZ z+={>j7Wc++o~+^NH#awpOD*>2(mbM+uhUTMVDvuBFv z+{BYVtb9_9rRHvKZWh5Ed0JXpT3J~+IW0`bDW2?%c#OD8edmT#H2(a=!5*7eTf6tY z(10r2Mtn^@+%leEN0oi?W-x(+J`NJnvT??4&A}mKs<@cyfb~3-m z#@oDPV1Fh)^}BHs9|o&}fOjE1qHJ_zAw3bOi}axRJr!6Ol|rjl*q`-Yq4>Q|9xl+> zcp?Q^qQ~5EUh{7ToH0aKZ|sv#M7ECHeV_kSBEE!Dw7f4H})rV2d&1qzmtQQfXFV z@yw_=$%eI2#{Ir9S~FL_&VuX86?tZ1o=9c!tq#YHt-nKH*~ss>R@+`@jFRFxCNDkN zD|D5_fZ6t>N{4PKDXCO24p9(AnDMN$5Oy#%Dm47s+PW^QaHKG!s9b8*&@Oa|g#~nq zZUxJp^{j(K4frm3&2`3i%m#UF@5vhME6ei&B*b=SDwyl(*@&ksE-kr9r5&A`)_KmR z-|?~&Cw_=}s(d}ZO@|@BpAblq()A>`d2PMzYFgKmSNHzX<@@f8QOQwPSC5Q{cxl*# zoSIo(U0qyUjEXv+(`#aG-tlN@bFK?Tusbn~luBC}t@9cf7=WS*>+8*+C@0C({H!3^ z8#h{g!bbzjeO7d6YJ3!SplR^Dgak%l|L9SfE}tZOSE6%ay0!xdw1*Fq2zKJ^vDf3( zN{p5e^^cAhjT;{VB92NO9U9u(pU)yq;2vFL__clT{ktK?EEc;6c2rzcq@k%9tMb^) zY`8s104-=b#WZjh71&`1Q*G-?llJoR8gRbdQIRI?QCeJ_WBoFUpO3F+0YQWR_z2hd z`Ex)5>63{dS0FS8*Yq`QWuykT_T>Wo&wH83lYLG(Z<^y{EiEm)>^YtZTzh+at|t0? z=ogI3AUjRi;VwyOFuP}TG(9b?SijKZT^E7iQW@@Bg{z|@Uq^+hsj0O4C@YGr?!~$-9NsyG^=Tu_G{ryvfEIbw=sqUfV1-;6 z#&q93TqZhXWn8cPm=kVK)Jl^Y`2IZ+jjq99Zt(IRZI>ZeR#$g=@$2ttMK(XouKmPc zxGW4;Q=2ppmyjSkdzN27U}R)OKtP}_QS6qcFuK^VC`UE!Zj6LjqVUw$SPr%@LRZ(y z;v$Sp&X1j)-O6{CIbO}s#6+g>;5N@M%UxXh-X+-IH?so3k-%WE%okIUsGB;gV_0c! zZf-%r2A&Zl6yn}N~ z|53SZEAC`lWH51U?dhOZANbll*RR)p+*uisMxGq?^z^VvJo&uQF5r#L5OEnSwG`~2 zASYj&M-VIQ#l*zGqyz#1eD?W1#lz*w&dyHiRm%w+5;^}Z<9fWKxDQnzy1u?1oKgGi zMj7s8_>or7T#AFR)#st!-gN-L;OHJiv#b|uqJ?Lr#ZutFwSl`?MLj@+1XjJpWm^S{fx^CC1UmYZ)t>kF)aJ-gmQjA z@PS%7fxqp<-F<(432kj{J<<%PzpAaS&K66sv9Za>$SA!97Qvqs2f~bZlkh}mmRpYp2=JRHcU^%^UJNu+LC|Z+2~Onv$7ebIXU=l zc+lG9E0_8aeq5(0T=&mqZGCN5=uK18z17@>{``r?z!A)nT;Rc0Z?Yf*)hK-YlMQ~V zHCn`?wr61AAqesQg^J3`x&S|ae@g!M`T1?zx#{Uw!fd2mht@zqp8|eFeX(Gqu8kUwz#+_ z`BfHh_=h7CCwYTQ`8rvRE`!32KAcytDvCWG1W|T9zM!DM(IPx=+wV9}D{Yh!d3rdp zw0&@KJow<0iu`N}{2dC_PbA*ikTYwWIt+a9;DOitH`)sq42lQFkqaB1g2-JG{V6H38v+jtyibg6; z2nwAW@xaX*XlKe3L}R+1aM)`O_4j+79PQuGeE0d}V2Qrcas}t+=Xa1I;jlX1kcLL* z>+*$(=Ls=Tm0Dt@28Qi|n;DpyADWmr){Fo;YPMF>(U~Wk9vT|j*w}dU<_)+H4Vk#N z2uMhH4HP{D&Po?P-4e-^K0XRvUtiD7&2{H|oY~;NTTfT5rvaj4e|$Ui!exZ)mxllF=Z{jt>TLZ=$07wt7_o zvIT99gS#Wa` z4&da?Bn@yHmSyDFu|~gb=hc>5N$r7$JL_yg`?F}q$dE%~putj2vz_nVfxd#Os!IyWjXes|nI&SSGJ zX=`hX8fz{gBlDuxa!Jl-^^@RI(Yqx`1Dcw`{rOyH3RtX!!#4zH%hj$?vI*=QW~+jO zOpB|Qd1jW6MaZlru>I+!%a^fkhd<0c3Jr_E2sF9k9PI2C0!&byTVMO^!fY($q{wW_ zO~l2;ZEbC9PaJf0-xiaVl5JT*S!KLQ{)ETl_eWU4PZpbq4n^?YL_|DlbD)4g~h&s;q>7vbQ zJUuxapO65wW{LHF?(O~K#}6nJ>L*6*AP>HbQWf3pQDkbc%F4^i)$*b9G$?B6OzJj>JS`Rl5E2 zo5EK2%-;Gm;K*?w{PfJLwiFr>RXttZYb?=}siEvqgwep~8o8df9z!97Ao~pldy2>B z^2ItTm`?1Olb6k*^g;A_YP|d+B7@Et?fgw0gwv$RCakvN}6cy z<0n)%H{*F!Sp-dVEiGfsIK0xe=Q9=j85tQ{Y{hoRRK8QQvM3!}g{bisef%i@bn@Pl zCv*KeiVct3=;Y;{KJo!w^4ZtR$HzxcFJ2|*e&|cF%usem@0kpr@r&m}NuM|Af*_8G z>59m^LPA=6mjJPPRXl`#PktK4d^2usw^WFwLMTHkI1Cz$BYJecjEG%Y% zEDcsT8$5;KMR+CxinS~|ckUcW8f7!I^ZRr2^0bLICaY(BfFPgN8$4{! zv9sPtlpYK*|H0bB-(DRXl|?tk+S}8RJJtxM5q)deUTv6eT|P z*jy%7Zf|dUV=aZz0!bR7uxwqv%zzE`FdHZ`khrpQaBu(|KDlddc-X9x2&dBHyTqRa zLRM$i@hnt_88rqJEU*U@E0NZfJ`%#9?HaGf%NRK|HB}o*os#Y3;!;U;1=@dcpm_9b zP1Y#o+dpZDM(zgTW>yQ$6?kSJ)ZcZr)}7zsO{?usmU=Aq!S#3(L6*9ERFToq(^52a zbaNgu(Gd}AL)BjUPdki?2Npm94d{guBY|ChdShW@pqFjSlMh8u1ORYk9ya1|F5jAT zre$#UpFOnmQK+{_vWf2_E8Ze?Vl+$_FE)3GTsj{LJTrlHdnGY%UC=-bEY69 z8$=*TEPJ5A1pin1qO6Z+MZsv#{zqLixf4E16iKEDh{?>%1gS@7nzV?#ygWa@GmyXF zDtKpYcxFwgqM`yQaGzg2*?W6?04o8VmzdXpOri3ZCE29r6+Ba6R&D$kc)w=<6pC>=u`oK>}m)`NcYr>E*$OaR&xq**5AQ+RqsdEbo>{R>-;725g5g@r$j)6&xH#Z%A-_sz#`Z|YbQ zQ&SfOpwk?ete1g@J@z*!=KvhYf9n?DUZA9$U0ekC`447Akc8)P`%8DA&^!!gU|^-G zscC$C{8e9Fm$|t)ICHd;i%T&aihaKHLxwZ-PjdbEp&sk{*+x|aVyn2U5fDWgBP=Q^ z%F2HQb8z5SvnzAu&D`9aY2_1IF-{&U2%Hzl8^xnFrPHnaOuxlny*Wxc^93J2&Y-~p zE}cK8@)$fqS7JpjP+2%aqJB5>)5zk0V^0Ime~_}f3BBfmuc z@znq2uz%496km){V2M6Q@5^!Cw*1A%iZ6kKkiUFr|6Lmg?)x84|84(I+1*-xU(siv XEcLyC@fYxa1Bm(qZRJv!_3Qrv3p+Y7 diff --git a/docs/images/ReactiveSequence.png b/docs/images/ReactiveSequence.png index 36266259515bb0836e51dd5606e5e672b80e6669..7626603f2c3ad9a364487e68b05090fc6e1ace91 100644 GIT binary patch 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 literal 6105 zcmZ9Qby!s0x5o!T89GEjx|9(|V$_!gC8ZHW5Re?Y8|m&)X^?J^F6ojXB^>GQl5*(0 z+xPd}-*cb4|2T8zoU`}YXYI8<>$`TSvZ6E*J`Fwu0wI!lC7}X=V2OeAQ0Ogi981W9 zf*))LF_|||D0F&JX#xBtb(GX_RJAd7bkVmrf~cB0IXW8I8~P37K_FC4G7>M}xK8b) zdMn>Gq3PCrAVytJqd!u;#%)@?aKL(Ln-g{`o3hC6MdTBW0`83(-cI?Q)YQ&+oz$v` zxxyF1iU&b&_p7(4@uAv_IR1v3W}$3RgUbEyBMl2)v$m46LCMHvqBLx zd@(Hn=)6TWXM+GS`)$f({l0$cZC^~*$j3zLXV@ZdSpRk*jpgxUf*Ioc+ZQ2)!uPlv zlo7G>i2Xde{{ahG?*QBEtYXIWoKB?;5$xV21>%9VT?zB&C9!g;M>t*BF%GS80CH= z;`*UITN?XAV`F@>|x{+$O|q?EX4K#yIisiTX;k#C1h*Aj&BJo{3IFz1NvO8BEHsj7C~b&4r_J zWqO85%LA;J?V5#1r z+b2tDLQwy#1;+w{ddPO1c7 z`0noh{vtQh5`iV@`}X3iu`0#kF|nN^O*2DSI5R7@m{{956%9>L&+6vcjDxFI%75Ou z&>Pe4KxB?{yp$0kO&Ij;j+nNv@JcXa&lmoci3(peDb{+2;KP#`cBLM4K8}yj2Qesf zVIlIsAWP*_i^xwj2L1^(>**@(;=ro%h~LhSR7~*;lU6OM`Z#lx;_|BG+=t-H9h;oO zP^3xB;UTmAB*Po`b4ODGq3}op!?0-ELn10v#{moJS@lOQ+I}6IvYLKn$HN>zK^5aNcmGwL^C4AeIBV-A zLZYfP(- zFBb|UF$Z3>DE|B$@CEnQf~4kpps z&B?*}ZeZ(lJCn5K)PQMZoJw0e&3*Cv{-g=F;T@0Tq}5(RH%CZ8v4143{;{R4OR!|P z-ih_bE`xx&J~K4XzsdIJHuHnqP0j72_r4qOIc?RWt7>_V$KUwVv`>{Pqq6mBCVp4=sOFm;`9F{R5!707SaEu)nAJJ9}*!}lP>3Nf0{m=r;B|k_Dwa% z4?hs5(nNdX4L?{p-QMK!JRIqMYTV>_x<7w@e$K8s^7TqT*gW=k4_W1@Uf**kncFe?-U5KR0 zsw!-3>@yE92L}f?H-TWo`_U`5e4Cq_Po6ws`2=HQL!Ru;($mwM3LHj~;oAF;njghI zRzKdE?p{97_~&?k|MU>8l#-I-B#_$LdNY4>eR6&6Rn2^k3Nfs2ug!j2EPA;w9x3Ip zztDbq>RQbXZeZ89cV;y-2rw}*2?#Wdc-Xt(cp4%NW*79yXlaX83O~oh@LEoM{QNm< z#B{i4gO)XF>CQB=JarPAHMdl&GAcxkZqW*y&xvoUmTbAGT#dzuG&SW8l(LH`ybm8#mxCjN+#OW`Cb4K$$}F zX2HJRVSO<7gozXiFBN9}GdQT2J@P8NDLdQW`cI@3t0$D^oOHm~G>{-rEG(-$EP|Hr z&qyzFW@N0;ivrxTqefG=VxblfgMdvO~=R1zrXl+w$jy6sq5;__r|aT257)JIXF7(j=6|a zl@t~8VCL(Csi#h2U{!4q);2an{rz{LI2L1H3rkC-SSxJ-$p!}G!?JQzHbKA-GdZ{G zaRcH8cP|?m87*Q4%Z+B{<`i4ea*B#5T-s>>!QP=Es!$0sGP1jZWkhbD6eE>kbR`k1 z_Vq8AT=$w!_Vtaw$Hv8-ot??#{sh4$--D-7j62vb@y`CT-f26&rr!iT42|hMY{zBH z$;qLhq+}3wqnIy@NCYg5la(a7(}q>&jMX?srj^q4m;eXR5~i_&2}j`7`J23RW;dj<~R_g0{9cVEAWH z#9PGR;9z_&k|WL>v-ZQZkf-6v4JQ3YUS1yl=+R4mCRUXBcx_Qp(dDH_oNU)RW<=gl z+R?FE{$b23wg6H~PBQnoNbk#o?w#p6^*3)ag1UWykF2k+vp;;u5hq)X+DQ7xil#5o z(b3UzqMVtFi^TnQG%c`~pv$hjj0{hbJhA)d4<9~gbMkU=4He$IW{FWnnVFe|hKAZS zAC0Y8uLQxP&hEfzr~Ba-$2%Ad=3*sAiEhjQIIVOP-6IYT`>kye{>JZ36Z5Z_NDmJW z2{ot44oQ;>TvjtPGeOd${G0iJ%hytM$5&3Ppvqd#`{w7<`&T)&Y9n$_vV8hrNJ4g26~bC7v1&Xq4-<1Kv-fH`Vz0`EU8^O;wx88@znk z-VsP(GLTqdyV&77=M!s7OG{~K zDPZ5c=gDm7U3SVRnk&1zE%vK@>E74(A;~Ezx*t~W#q=WQVt!3eUo3V8JO93Zsq?$2 z#$vpb%;nJG3n$m@+qbo9Eh}DmV1DpM(+e8UXHBYXIc<*t!w9<_ZfuNX11i9^{+wO< z`Q5^eJ-FCwy%|;4#cBhi&3oT?5)cfei?+73%;|CWtlBd&GB#k<#4DDCg@)F9Ui?!P zQ`UN|$wc~Vbkxbo34jBz6SF>qE(T`g)M+{e!$(C$MMOjZ7eQ~v#l>;8UfN4a2Da;& znwiPS$mlz_AbUT9EbrewJT=t-=9QDfrd66MXp!1LmIO;?l^h#+UMQ9i7#|@lJloRz4K5d#lw?+d+ggvO zsi{d$PTthq3?MHqE(8G*2%GvNx8{Tds;5!*8eRIW6^RMI zG~XpUEF8GP6F9)S^YDy}ATL1<_wn(Wo6~`~p6)M}d0%aJM>D2q`Fx^-#Ky-f2HyV3|toA1)#K$KWC%2qw4Np!!B86_umo*)VPL7*{R9vz$U_g= zTVwnq8HJKE9!(W=kzgT9&8@FbQna+NsM0`kI(m9Gr>D=O^OZKc3JPE~n!>e+sF0BI zF`3b(mY|>@1_8%{l9H0Tx)ZQ;^VMcCvnc|!T7vO;*4}bF@N_+e66LGlAq5m zC(s;bO+jrulr}pyX54ZBaJV^76KRajQ<$5ZtKQPq*4_XMb@Gx?0gqWJP3V60R;BuD zi+Wg?z1`oIB;qMRkN@}BjKw_;z`c^wr~ z;l7%vE3B%hF*MtXmCbE!6|GwL@qy&3@PAz*{Loo35s?dre2j~`$G|W*Ioaz~nAjM( z+`}g#GPhKT>h6wKK~VOkX_f$PB)J#$Lr&LVOYufWV?hdz2A-72AcH}5sgaxV5Y^%N00dLh2MkCCI)rwU>ZqEUnzXbuNlD2= zDmilti}4aIUif|N7mA95fQvVm>!Q(JFC_a_y+Qh0T3QNHBk;aHTYpz&Jo&%VR97FL zsdv!Q()x?AaG8!EH9A@wINYe>)30A|9K7eqkaTo(9*Z5f!@m1 z(?yk)?NRA^w5M7BI2}Mya(zioP8Jgv2hr{6;X%wOVwqN#lOqAAY;0)24-~^JSN0@! z?HLw&9UUF<@bEk}83eu>9U59#QbJ!E0Ui<(5^@xnb?y09Q31Z4_-u}klXDk%X5EPC zGipMRYBIAC$5vZGMi2iJRX}v`lKi{!a~c|b2K}?A?f$p`M)KY5(OuP8V||i&6DBT` zg#`tAX;dg}lw)2?#TJZiRaZaD9)TtFv#+unlHoScJ{_*A*g84~@l!Nv zUOi>X=eRN47x(x9c`p#4uRD8AdlN}JmJbxuMVf&;2T_xkn|pP-9BtaTC?W|oFqdX^ z!Pl?9K^OOv-L7?-@79DTt7`7<7a+_)i6AC+%PaDSR5*au!I?*ehNVb|Nmc_3(_lEg zNSCpqk`f8V>P@|NlqP*_qsyMLk*XMcbHqik*hm#&mQlVM-=h^Xn&$q70=5fqr@p=_L-oB(5;ord@#7#Ky^=g;Ix z@~A~y5Q;zryuUnWLl95AL=n0*w=^|f4kSI5%|!?ZXmZ3U-WEPNInix!+yoavCVm(b znzkf}K#*@!F2y2@xoIN7Hz1O}wzQ;;VE|(S#1@f=FFIwdj+-h#*curm(5f7#`9@zrfE3n<`6%<)&;gW;*;u(MkH|wiIy+fGLDA7cS4;Ihl9snrr@812$36Tm za1IL#0|EiGu&|Ca+MYMD6@j83mQj&Fi0Bl)`RCa)PzEhxfC|xtQK(Qn7g^6nZ$6{> z0Te}zW(kT=B%P6zl$3#ilQP`j-=9Y(Fe73zt=a6JSz0#|!PAiklVu_uPGe6Wa&d6T z_8#`kgoRbQ%If?bI_Znn+V(`%$ZoGG8;J%?4c4_>bjn4 zY~%_*Tm}6QwN*_unopkCq$=i*ns1sBCNhG0^7=DOIB+&Y@L+#G0|qQNe4--oQ>u=@ zL&SS`rXDE9&w=y*Zu}^s9G_wRck}xHZ3q3mj+DiS3J=F=NpC)i0h{v>8A(NnQZYTh F{{gZY4CMd- diff --git a/docs/images/SequenceNode.png b/docs/images/SequenceNode.png index 657a5ccacf115e62f950f7da68bbc19a068869e8..cc8b9ace9846f144d1cdba687c878e8d5ecaf137 100644 GIT binary patch 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_K34z76rE3t3GpEbI$#9Zhfp zjK9T9KZ7qqmlyi(SXj3xum7;IQqyUH5Z^;VMGk)%hnSR*`*_DH4GW7dS3&lfw$Jo- zMxeUZOH3!}dosnEXfpe0oBJ>IGkV&17FKSS z&6G-P>TY>(@5nrmD4wsPWbxUl#q_N^+eUFOn6p>Y$O@C;@$FTu8i;zU^N~#S=4%R1eDso|CVUgXHWyJ+HBJuzKht_AeWw3BnwW%yxZ-u=z zYKalRIy!o`=5ROvbajbwnc?XXnE2n2Lked7e}>jPw_OI`OHVG|*4+ zh*Y6=JIIvZ*<<~x_wQxdc%v`Y)!J9+rjB+Rz>oIMPh#%f3%^L=xD4k{zMa!K=gY~( zS$4gU$0LvE?n|*+l6N~lA&u$jV`Cv#P+-1ur&;ax8#5VfGGU@H*m+^Wa3b|!nlk$j zGi;%hwN|Xx&V{{+$O#kwx}xl0ZmLncyvxg~qKJW1xs=X_H4)z&L={;>3kpX%<)=|< z4L{a?cvjV&E)@I_KWnF~s!2RSkDPe@aLtX)@o~HSfeOA6M<~k}nzjaiqL8m?pe;+v zkheOhmE>Th<;2(IV!mu?%b~-~$j5K2s0PP8W0sPG=RTHM>xg1abNZd5pg@`g4@_)E z&#eiHMZR4NnWvEB>ewbB6D%qUYSH_1@>%Gv$?+LRK67*1!(*7Ir>$qY4W3UEj#Eh^V9xs**?2_p%7HbMtT5ig>k~)jp6CFg zcp0BmK2c1Obs0Z$S2dt9JYiN2n@rYh`K?=6GdxKAprYP) z8ND>)3>~kniQ#eo-1+nE&Ag&lM?I~PH<-u-+HSTvDoabGF-WU!d-+{SU7k4@7%7W5 z2h}0WvLYgmy2&?O)C=S3ZhQPa2v3u`7^;jjG*X@@%{4Y2UC(2LDUXamJCDQ^mt1b7 zrmktJAcjw_XC?MGx25MK3bEY(+<}Bt++Tv_^{i+wc`6M~&-p9_K4^ zXj1R1`cNbhiUSXcFW~kJm;6l}JyoYcoeZ8lUu&`y$dLD7xXzc{)>e);YdBa~|Mx(E z+h}l?AR~r^6jrH@B}zzsYa^73$cP7InhfK@6E-1HQ9I!@@NsZ(kiNP&wC+uOJze#x zBk~T#iE}v?lh0n85LVsV_V#NhC*iby`P_=?YMoppXF|`}*;%P!ZS(QCA$P*YbhU$h zwYao23_NIGO-GJH7KkNtJFS0wc-Z1GUBAs?!h@HIJo-6f_LY^D)dr;<7F^uie!ER* zAhf79fSpvr?@&=S?zP>juC68~Cgw|0DxaXCqO!8Jjgn=Nr2rn2aq1Q)Y$GKy2JR~* zu6g_@DdCBhr=&b|p&GRktcV;eaTSHg$;nw%)P4P`$U|*dIu0!S@k2bSBWGkid8fsQ z59)(0%lL+?bH%N?rbbZGFCM{09px#0ZzT6+k+vn8vG~+ctmSO1ywAq{_3P5bt0wKj z5q(or)X5lGd;*#q9 z8G?`AMVad82zlXGPW4@2d3boN9s4zzknYj|N0K=^#VZ_RGYb#Sv;*EfvK=TfZm6lM z@;Lm{&*1%S%F%Wpy{NeO5nc3N(6zl;KNs51Hp>sR1MoVhd3ktd8@&0uUJT67n<*(N zsi+V)ngT#(dU`5afmuvieDvYF*WYyEf5KJ~jCe(S*6CJ6bhTIDjep8%Ra#ZI^0=gK zg;#G<`m}&BU`g7SsE98=y)9L03~xOLflWq^i;T$N?y#MIwS7?E5sbdYbjDPYOu*q~ ze+T~4)FDYNYyR@adnp1*_UVW_Zx<_th+C(R3IFMou^mp=Ti}%H^(pz!Y)n+_sE9jR zz%tZ-|4FNrO1$E&PQW`e{e}Rium2`X))Px}gk%IR7OYzPcV*iCqjT@~i}`jL zAn2Z6aWC%iY4P;*3?&0IUcSdu<)K2+XWIcM=G8L9$A*Tmc4=}LxmqK_7SBDaL%&pS z#?Q@}*z6T%XJgOt%Sz9_p}f_>NSf`meSly+#4)R!y7v8f9V-q8btEHC+b^JV>2iE@ zG+CMbTEkGC)dJAX@!kc*(kw(oL}X%Y?B{vd+N}z%HlRd}#2f_1D~oHVwFuMoI5DFp zK@0ZVXShHcOw(ET`suLelZFieWw_T9&U-(&cIKv1s9u8<2qz@t?oHfl-Q2RDt9w_y zAmBN;b8j#(lT?FcWO`-f%L1?vdTlpp<))a$zsQU>LWW-poXvpei7X@M(Mv{36!K-`4Ek&6Zp#L zjgOx`wefMVv9WP*#PXunJ-*XDe)8mrVo17b;cutfDaXDEpt4B2C+J>fmS)lL@US+w zPJ7I)n-8FZDSb<=oN$PzhsV*$$vfQ`O)V|onpOpdjX1@8=F$9a1Y&_?NxNfe-Gj)! zWAjj`g=($be@MimC7y2Uz0+F!M~6BO?QzvxsH6^UlPa!9+BBnBS# zi}ba{u|i999iY%~nQZkUZN+@eQr*D}iI@4BVJo4G%bbmb%pEkM%-b=_S!<*uBsDcP z!XhGR$_3!N;dj{?Y`n}^!h6RkUz3Z|(1<zvK+EwUHvWvhl0r{GDRf8*MwoL=}Zyq`(O*!gvCx~Y_ zAwJ#L*Voq?z9}Dro4{&LvKvY*!!SqKp?6dNNQGT1Ft7<}=jh;|RXir1!IyKU%a_z^ zQBhS@1u_5>w|GRA0jPI7JqZuOD6yCA1l@5TzFiA1Tr;hA%m4oU`;Q+6Y!r8>sTZ?3 z-T|)?6BFOP!^=f}nb@2tGfqoN645b#7E{0mC1ZWxY$gX+zgpkf;p62Uv#)lm4_F<@ zNa8cjX;sSV>FsrQchA>cPvkXBO-*G#ERM_N>Wh=fCfI6iO|{Z1F_nXztr!0N`6SFc{#*c2G?p{gAwyitK7uBb2w zAv09Ua6T9Ze{pe<1R_et6S%LN)g>4*c6Eyb$q0d59Kx^CGcz&Wtg(H`4=q=E67WLI zS!7`>GLpRH;{u@Esg^p3HetXWlUtuw0Gm^)!-rj~!rTs9^&o)ylko{QAh z*5)y)6VNN{*T{k*p=vNHdJ(69{SKNdbjuYn2}#iTc5PQI06XJ@X$GF+RR zmzOu}Gp>@Zu;V0CJR$}nM)5gQ)QznQ;#%9Pl*DIkZLOh5!=oo)zZ|WDE7LvW+>()+ zN=HwB-uGxQT^fdgUtO%Gi@7f@Ex}=!zYY^+`}{7B-kHz637Da=48~P<8b(I5OR>_; z=D+YjPCH3@ZhV%{1=*Y?>3=fUq21sCo3v1XJ+v@TO;Gl6VbIrX9-n zrDrZKE)EXdPNL>~S2L1K{1ikbFGoj56BDUnmTrsfg!M*qlarGZ6BCn@oJqZEaH;+Z zlOf5=?Ck8eHkl07iK(fGPHET2LP7|u?->%_ctaVoF}P{0G1NX+n80d-z}-1X#r5r( zTG+)BBdP_4%3U*U4oK18Szo_C>m=mD$Ll93}Lzsh#k*Ha!^;&u52 zM>dNH5dzXDRlL-UPt9!!+zyPxhY%uppaGA?pzap%Y`66zw=DZ>r4p(ByvukwqW@at*si|R`W)0T&>dt0KV~Z zQ)&B^v*XRFzsH!9qd@8xTp3`so<9#c$C5LX3=H}CF*(_1xtl!v*Mf&QG2X9(mEOxH ze&3~N5l~Dqr(M!``DnWK%pfnXll`TxZLjmob94*lY!e`Af11eo2SfxVhfRO#7|1#l z3Ncu9 zcAU`I4S9KNUdrR;8)Py)Jw2ZlR{+}B4rX5NH0=5{G&hZfN#c9oa^guzNonxfUL3d! zjp>9}mz9;JJhJtJyq?cIS*=)vB!$*SIGF|>j}5{whwbg{P{u%yv9CHicLP>4yln$0HEnhq5`KWpJ6Q41! zpa7&!zol^Cz#k7&%g1!?Zf+D56aa6*MWbYM`+h}vxf&1k%(ho{L=XsouR6sbUC0?3 zr9lhxyTP0E_U*k0ME3J=u$C4U7V^f3x$#()E~=;?P+N~TCjxt*^75T1kiVIknf~aV zOTd>*n*426vK!+B7jw696oYtXf0pvuGwV+k zYB}xT7d_B0F!(yMUgzE!m%DFUT3oEeLw)#A_*8p#=Kjxz*{{LL03+;TAB}>cW@Z{J zyJC0^YXmmw>FB74!u*LQ+r-)iT&b?|a6jfEd?lZ9Y8o0gxGr^?5#C*d;38uqBKC!y z=I0E8j&d2JGuSz+e9fq%tmhhi9T6ZrEh9U)c_kgGymEO2K@veY0UQk4HZKOYCU<~2w9kBA@(VfHjO3?f_yy>i45a_;|B9_=& zTHie2L#ggzy7_G+oDG?zn7_qKA0DtZU9H5OfH_ENDJdzjA`ZkJ!0GMo7D!S4tXVnL z=(E50ruaF5E9|JKu#n^7L)R^*Yiro=-v=~tCm`Tt$`-)GarH9PS!B>_}WS4{# zm&i)*$8;*5p4DpS=;H}fXGce6B_+TfGeB_$$rr#taqr%?YtzU&zzC0eqhG&%eJE%! zoXIVK`J@wHV^Ry|xIFYDhKYtGHTlZ$q z*%G@3NE{1IyjRn_(M`VRGqUR;{<1_bSY0`geHNfRpu=E~8jq*Tj2liSEn|^S3vsQi zt?!9@ydTtn}hqb(eR z392{RITY%Kh|vLhYtoeZ`Sa++#Og~mu*PEVyzTAnXO|EpyMWPuOR;xyvQe6+{jxyN zFu0IG*hB7@6+hxHmmVU}_?)Z1ug?Q5Eh%i)WCAuv2>jwZ1a0yzacf8=lQ~JmT;TD>)#F?o;$a76vgE%8F0N!-CbzZ&V3J(At z0EP+9VT!bW_#NB-$$+(`x&Q8ev$UYCj zW_p@aFO*+U@Mp>vE|k{)w)CmC_UMS3bdxhm>W{G*b7=3%*Dqg^AKAvpWSg1HZ8{TX zf65)Qz7V_dbgk06Q`6YERGkwr*f&Wv_~ao!vp~zlt)q^i5V|K|w)Q)>A;grz&mVVyc+k*e)R00@bpA&mCS>8$96V2I&L?4I4-U z8q)v`Hi`w?M4YG&O+aCdjd_!Lui1OhrC){KlWf#`2%$6-i@;kMWeEQQY6+N_CC+i` z`%2}Y)UVxDPN%uXde~J^wE-`6l#-$%yR>X~+@3q`Q-Y%-sCn&7EQ6$hiHVe`X!7;h zVOm;7#=VMo2p&Fuzm2=4W$sV2Zw95HPYDYP^Y!)BnnB9Pgu+>|*rWF&o6kSq82R`? zK367tXx+oFN$SCa2V2hZ#(YT~7Umn^j1h!@N%_R)abIQmTXCJ`7pG!3n5<-B+BgnQ zPEK}q-}J5vp?HRBF0v0UZCa%L4m!H!b-oIRIaM1F!M%85)yQ&Te;$I`-L63zF%!y>jxqX1$vWm8#i#3$3exA(2z#L`8UPcPUg zB4j~7&qe{JOi*O>-+Blxl6rwk7ZoPx|GtR{#X%DM_pQvoS2O?ja5{K}z4YKUx#d)! RF*u;cQjk-XEt4^O`#&dxoAv+z diff --git a/docs/images/SequenceStar.png b/docs/images/SequenceStar.png index fc3e700f074f7ff2edde5e87316b71bd9ec25981..889e95d0582be6f93262196dd3097df505708041 100644 GIT binary patch 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@h`2^Cf?ru=RN;>o-g;_^E~&%eZJf~dn=bejz3HGxzEWz+N z3%3E3m3=lF!_FWKCw7`yC~Uy~!|!HEuhKAIr3nh53JUq&8vGAd)~#077>U0yP7AhN z3=%4(>f(+Oe&=r7`kUTYmd+??;D4HC_+kI%`2eG6Cpa&KIB64HtzNDEeeoP4CvQX^iO?R_k|w?#rdhDBrPZg z+MELt`Pe0Smm;_$`B1_$!DX0se#v#C-Z1^p^!cT%vA4_?KacF`ux`kvCtqB?3#AS- zk@Jc}^Fc|oi1AmhKka9L#=|q9jKsx3EpTa37{y9|a%c(i0f3!>h-mTm)pdH*Bk&uL z#C8m&cfHR$g|Z8ekiSZS-xqJB9657al3LwY2;jki0yqUg(kd*sx=3=wK$wMq+o+2= z!8zh*eFG0&k^o;xsG8-jBdGehTD6Tko(yg-A>Lr01n(kz=&FV-aZ;&br~9`0Hj6H? z5eJ|47OF-8f{L6@M_aj_p#Y^qMA;3Y%l)$-`XNbQ6Kk1e3dadZP5r%rlH#4NPx2-1 zMvJD*QKtpk8^&`N{Z&fiOfos#4`8sznR4_S*YCq3xD}ZFf8(d$twQSDz^+lO`1x#6 z7QK&`BDI=X6Ea$^&$gOd>}@QOs+|nT#I7l4tiLKkxVl_P5^+^@aK{+}547m^W{vH2GmFETsT~Ff%BL zm5~-+^H3nnR_$=Nyk~YhzC2&`6nWO5A6pknWWhE~`w}g6lZ@EWS!2{}lX3HW&>R%m z?e~D36w*?%d0<@UO%z!`BgeM`3suWb#@NB*UW^gQQ>>Q z%YJ(WW;CO3kE$-CdD(p|wJcKkM4w0X!#ex^lpZ7~MC(qA-rzsK{=a4ay7oyN&G~%T zk`FXLk0hlI6Mm{!eLA}aZAD|05OB)|iTLgcLUsEm z9=KgxFbUMKe6QCcaYIq*z;tSVEV@rk$L6%EGI4O1^~r~H?@I?;b5>JFrb)Q)-xgI= zQq#xQIw*{PwZ~G=+MJczaU-yaJv9WJGB+9JY7(wl>Um^i&I(XF{*L%tFQ$pw+wQ1) zBm*Xd{WrB0CBYa)yQNcOuJl?~;E<7t#tYjleddLw)mQp0D|(UIt-K6A9sH?64{csm z7(IHGt~Smq?bE@PDnuFu-exf~F9byhwOLklAYYk9h>A2Fl=?}W80FX4MN$|NHT zo~@+g%1VHJ)Zra|?k=Qg@ybP%nz$4lTT`|iHv>Bjnm#}C>#Ie5e(BNBpItP<@!FL6 zX+r32h4gSI+CoJN{5v$v!zZNQ$$5n1t76k{-F)E8?nWRL5SQ2=^a$CeR*WEy4+3lTD@Jpix)>EwOdh9rhI#^ zq?jr`CX6Qzs4JBcQtc&;iT=Hp9=|P;opbywnG9}Ud}w0BVL1t@y6KyVkUQ8XT3&uQ zvDmoDZkd;i~8>}4~v3n>Zr+EZ6mEu+kc%H$}HNN z>eRC>2Nd`?_#3_SS5YH02>+}FG0I+Ds7b$LO#*i>JLM7X5Z&?8IakyFg?UZWFW$a- z%=dR56-7&vBuH-Wm9a6r+Q~NT4GEHS73F?~4qiJ%RQsnzlT69)(RL-EgccBrsJFK{ z+D>*H+m&8^R1>`hM_F?|tZwi0QwBNDGn zba@yzP70coqhq)B%#KE18Cv+7BBuLV1CulA2!gQ%Ys-U9IzmNmpt*>dpxaiW162Eq zE6S7F=H})zEu*ON2t6298R$M-dmtF?e-SG3qbF(N`EhVyI!nUTzLV*#E^M;=9V}z! z{QMA6!DEdT)Y=KMmb~AbyNBL>uH4YN_*}b*!+@|XI8d7dNacqNdU!1}Ssh_bYcfAh zy=?#zB`G+PWgRRel&zO;pBqOsuLP) z20h$4P*TgtUL_M1?v3gZTduJ?-Rc`A*UqeAU4>7%p8g5Mh}U`L^JgJIvF-&IJH z{HW3h^Z}kZq>s9Q(*_SY)yWq>d$?--4}-&YJ*ANBW{s2-?i!NDi%Q=h7fCs_gh!t) zv#~A~;(;Cek3p#;AVu=rZZDd&rzHI21OZvb+*Iz@hD~$6v+ADJ+24n^;&RN#(KwU$ z75jfmh?67!0)EQ)f)Mp3C#h!6GwzYXYO6#TX@g#3+N|$`FAyd)TFw` zb5_X>bn$S~{7!3MNU=9_EhE#@*5FzOMo~`09DW*NQHq_Ja;LF?C8@%`?hbx+lVK|G zQ-{G&!{O_wu$a4ic=C$!*JuhGeqO8x0ePP?F-UKs_?xlS=eKA z>a}%ti#Gs*VnK4*D8{$1;e#whPDtG*Jf)&Q9or=>d5p<_p2=}HqThtx?xoW`S2hw` znr{ol>Q_peT;o%uv6=dEpa9$9L^dZ&uU?t^7f!fm<@%c{xUf9Ta;E${k}#S&dA1Ch zimJ1G?ub)qa5atC+wk?83h_H+ml+8Xn}(zpvV{QlmsygsgH?@T(aHnx<@OBb8IQ`o z=Y+)=g8TBJIOe5{EIDn|<73a>R7y(LHQvCF@)K_NG*X4%ZN*X`Oy-<@2OGw`SbAIY znph^U^?Nr!I>tgfR^DedJ31jTZKKJTZ+g}mfhjM8i68F$M-A05gE$$RO_BEoP0Is6 z8MXno0hy2Z@T>?WoFd^Imf<(W7hMvJ&eG$S=<$Q-&xe6{m}172JOr ztUcHB_%+sz8wmb2p4fB=rM-6fDjL zwq8;_KG!2}WQ$&s*Ts-(xzhg{rd-jYZ5aa|#ym5$7yAMXIc=`DDfOHynOnv`RZ(4p z#J415GAt}WYvCP1Dd6VnPEGq5;C2?_I!A5^bBAKKqA`x^PUhe7$h<=pWP z-KFqwT@_8x8GgUC{@9MrEeF0#yu&KBcu^(BA}7JdGbH2Iw(CpI3u) zUFWWO@ktuF4#4?FgUKCc6Q55O0qvX;Hz?eyw+4>Vb!emdME1M!_FWAMy9A*Si@aNa zUPQi~UZAHjKmE1e0zG=<%HJ1-2S{eGe-ML$dW{6kWZx$nKHe!qe#0p@KRRs3)HU*k zt;Mp}e(dziPL+hU+wSSyP;?h;Y~yv!4VTkO5niWaHFBk2AE$&^Z~SzW03QDSPTKok zT0KSlreYtxiHMu1G~K-wd+`Rna-I#t6}Bu1Gn{_V8}$5B@5=6sluYT_HFPpNbabLN zG1g`)qL<(8&6!=$rQr`ak&12w*|PMf5V$S80_$ z#&7wZeA@du<&T*X7Fq1?1aL|^{@`-|V z_wUu3%-(XY2Hr*15yr*BQ2CQ0NEai=mzanhRZbOCN&9CVOG#$0fjx`CWu?5hc3xdY zIQ5rglX`^*&E+g%rAT|Yu0RmvE6&iavW`0=%MUG5!#eq@EpsrBEu~ZanTQEgI+SYRgnd~DFx{=@+Q5OK_dOaTV>?^1g0s)ioDe=} zrBrHypJD7^D?Mv{I{as|a68JHJPM2}P(!dRRAB-&gjV&6%cTe=UM+by-HIoS6i%TB znA%_Bpxdo-d@VTsf;zvQ67<(DtA_AO)$x`Jg*<|pM&{@h0gVdoDi3g|w+peb~| zbrHw=0`O=~Y;czR?FV1}-?e9D4aQ?;-mG0LU-^?aIQy7P%zFAGxSUt`JRfTe2JS|@s53@$G3NGop-; z?$`OeCY+;L5iyq;Jh-$POvX)>qe>UA2}xezY*l5!_BvS>tx{#jBmCA4m0iAtrKb-w zV`IS#QM*^t9UuwS#fmixtE| zq0aI4$&CNIV72VN@9ULw!jGyKm3?e!9raz_ZVzQ2J5Pj&lGVtUGX_+tn-bG2&x&Kh zZ@X?wA8tCRZ-r8kT{YYH9W7j6?CTooJT|a02SjEDBAXFq!5|vdj^g5&0mod+X-hPmAGb8K9%YafUyXP<$~InKM13 zG*I$kXIFgYU^PfqgAH+2maI;Np@n4smtvi#7n>*|ZThLoeqlHkpg42OCysW`OHRZR zv>oA%s|vDov>ecge$cK1$VF#6w8%svxCrnZJHO;?S^N{&y7)dsp%=ol;a_iUN zrB=jcubUm;XVGr}{lc54U!F7{aIbu=*E=i8-@&VRC+)#A-|`<_aDlvSV-;d!m>O=G zD>eEQ&F!;;7Ai#5dewQ()I~0yGyfYgo}=QvYTt&c`tJfJhf9?y7Gm(V1!x^c?;HPU z*}hjmE_Rh7A9}GAcQ3z2cw`x=bDH`)KRVd}0Iq|lnUzkMRC^_cW{Im$X17!SxINN{ zmt|>8e3#=SmU$qU-aIJP9x8kLva$sEy8|yWUQ~T>9WtF1hTPDTF>23;aT02S3%Z|+ z%Jc#dbT}QlqAHP_peyz7S0Z7|4t?|wOd^*IqkXZm11hxPpueG|p$jWhBei<_9}?IT A*8l(j diff --git a/robmosys_conformant_logo.png b/robmosys_conformant_logo.png index 1b77abe9ddeb18c163cf7fbce12b3f5460c702ed..12d5ef5ed165cabcf1f3caf6c73ad655caf223e6 100644 GIT binary patch literal 18972 zcmY&_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 literal 21158 zcma%DQ;;aZk{#PN?%1~P*tTukwr$(i9ox2T+cR(8Mr`cwc0_l5WOr3ZN9vr+>To$3 zQCKJ}C;$KeSaC5Sh2L@W_xynX`n{q8(8>G`z>a^#l^`G>Huhw90RRX9#DxTu+;pz8 z!QF61;%~$cvzYjWfb_u99H)_l!;w&{FB3^P#Nk|JUaqH?A6#8|cep;RK*7aT(8Lu{ z9OK9pCOJ&~#Du0ffW3OQNJ9hD*M_bQ1oZsZY{zWp78Vp0zi!Se&d<;D*=)CQ3Vfa5 z9?9U?pU4cHG@Rft*z*DvMg)2e{NToYR!BGnILV!19=YI7^DbSr3y_O`h5Y{~r2X;- zeU)%_HTOM*fHudl_*7F{3$gG9laO1To10r+UY?(yUteF}-rinYD;Hb{q3xV#1rRkg zHDx;(+1lC~8XCIBxWbkL8pJv%t*?*Y;rw&MSm*J|E(d|8t*y<&!_(E(1q=-A?d6q~ zby)%h*EP`(Ij5$hqobt-gVVRK?c)K@CD@}q1z1FS3X&QhAO9S1yai11T3KB^H8xgW zQ?p!OcC9T+2bjUYz#uO#|9QICu}LELhd@$N(sr|LZgX=}Fyd+Bg9bcpIWRErV1FMW zou@wN8jO4n%imC59x)}FBBUVx@sLG|r80FR8yHM9{LZk#7y%O>A0Gw9s4->jA`c{9 zU0vPS*cfBwe1(7U0gilP)!vMZlXi*vT$MyG-e(ZQ%)+9gveIyS;Zg-AZ*XuhE)HRX zv&psEwrpl%VnK))E_ilUuBa^DH;p5=fJvbJ8-#t!L43i0;3lx_r)f8^u z!pVs!{j*Jo(k$pN)~RlW&H1PLyvRo<{S5Ajfr26&Qci~QoRk(FRDs4l^>=U zf4AsDqM|RGvBqPOXU^B8;HO%jCj%j{ic-t4u&|?~mK0|+aw;k+1y|$ceR+WK2-O$y z%Pt9mi>3|3R>DS<+yZKUO|<+oYL}_eQ+7L*kBFbKpv??d|QcdMZ|XkaRid+5?0Sc!kv|A@~I;Y#f_}U82gVC@WLo zg};D1OwH!&VqxF_r0VPIN4NsQXYjfx)^1YeDYf~#vC>j`@3Ss}16Sc-Yw2Hym8nnY zHmdTMKLZg^(3G0yk>(ZYbCaK{s&yUj)cneI`s@3uZF6i!{z2hjV|Tp% z!HM*-ELX0yun#LG>adJ9FM^j!}e0TGN#p8XPopNB~H-GTM24G83R?_OoK}JKmJYHUKy9Dfoh1L}S zFAk1sD8|}gcD>@jz{JBsF_Q#IrHREsc=d8r?1j(}QhkkM%^8s>`(&4*cN7q?%TARu(qf%_sai0(1Qw3tJt-6RX>& z1RaXt#o1h+`%4$tt-dV!mt{$VZd`0UW*Lee+u&1?FXNH>z#a!zvD#Z&rc&ZBcXNdW zRz?l96xK#r?=8zMEv?&M%uHNt)=KB2NyN^eU4wt&P7~(;ia0AqQ-_4c=C0K}O#txq za4?b9mzkY|rSz{cY|Sn%uCBtwh{FWXEo@9A)_RPsDiHy9Xn_}dzqjVqy(Z4I05uH0 z>Yo{kSg?+By4jnr6<4OOG(JE{j$2q+DV7D! z!+FEDwD`8)Xqd2C)1>nW(vaREqb4U^t$Oc{jxh-j89%{B_p0LQh=T-%c4*qk?G`=G zz0m2ha}&0NGQhgHRd!qc1vi#;hi{qI?tEYRE(9qBef^-#U=l=xU0h#pd6~U)<<-bd z)ipcUf8D^&%)o|@ut7n|=JdS#*zvF!53&zr-Iir@lG+^AKuEr&Avm;IAeQZXD}@DyP%t6|J6*UqxP{ z#;v-oWvI9?a?$G3-~)YLs2mH}XY1S4UDG`gBUhoU+8+<_f^EduX`^sAq!#G*Akl{RVKH?i6=BE znw6DyOGPI?u%VP2N9aXWdBtX}UDabRek?q}GlAo!KRIf=0xw*A&LLL*DvqZ>QbO|| zta=!0dU7V6jfprZAuHHT>uY0ocYa-4Q+3x?N=e5yGRp4Gg9uIyC~i`V6K40=z{m^` zuf3z1ot)chHi{d0lFQw3-7^Ljk`c5woKGyAL?ssjgF6XPB%J`pz6k;*77jVf;C+*xQ{zL;$)R{F;7HgkZ7BwzqF0K;n)wn_7<>l3&EmK*bk#pg z0_9}^b8Xv}=4M~-+cdkhNUrqq_@sN4G)J=HXmNa|05$Oo4SdER&ygsM@67{v5n&hw z2FMX7ISp{^%|ua|ti&Bb91$@)zXDWU-5XPUO;pVCNps6@eLc6uu)Uq{V`M`SQuy^Y z7Tly`fdc!d-Fn5r?@>BCQn}r$W}I>ye^H3{THo*Ux-tmKe&_NTpH0xllCI~(n`rE0 z&NM_w_$LBg*u!+n{<%ia9sMC?I$2k0>?uu!gniwQA*x)TmaECPiR2}gdvV^I$45>W~YP;#VJ$#c~nbvAc zNK}>6Q4hAvhAF@h+}6=~9X>GlBU%h++6@N>QzuknVBXy7T9+9B&-Xea>Lvw?O$h`% ziC{QX`E0I?o1{|rGkVuZAOI-Q!k=aiw1`y3;CMa=X3IfghL;Kx1##sa3Z9{1g^$rhz%8CH&SW1>7I@2@8s-S zE$vxeQxg}=#n#9SxkVs{F8+;8CIM>Rst`7+e(+hK)D#{0zl3z>Jqc1zS4zrCP$ zK`$p47j`ZV5|Y8GG)5nV_0!Wb2wi+SwiW-l4CmW`hWsvuQbMv>8v0e5(XDn*X*j}E z3P)Ke0s}hF7q>eRfAc|ImFZ~jP+1&KpJNdpL`{;VJkt^xN$jWH2$F-5C>*zPb}$NZ zE*qDuD()`AAIEpDK_22|OSMi{ts+w)KTW^T#?Z{f%n7-Ze8G?wr?v-LW%6^vN97KP2{g zqrxn;U_|8UVG|h>vZ~qU=k%93?Q>}}FJeOsw&*tmD}Lm)We~BqaxZfD=r>f&D?po{ zrlC_s8YU{V=`=|=IGjbH49FNfLOP71_*~B4t7DGTQxRuNmV;YvVo;CB>ayEC5_646PEf6;7J?y9q)||e5sDWgD~fP)v-E8gPN3;H ze*wxdVhE_ODFka-T{E|jAuKL8E!`Fe4)DN~h-+(mn+q4K@M9UM0*i0`0X7W&q`5rc z@I0fe6e@{H7stipGknfU$t&uIyOErl4u#e@8SeO3pbm37qX%*nUZFU-g63jb*0Cq0 z@)_yuyxvjQ9JemL@#@5Cwb7-2fv&8~q99kYkB4tNpS8l^^;3Yfj-JL})jQ0yT)w!#*wM!e0P&CRU^!(fh@%t8z>-@86VxJr(7L>i&C z*zR@p{$a^$YDn9!(1@0@u!=|#%hNee!)-rs^zZzbYw28*%hhz z$18+@d+4Xh{BSj;lBri1DayN&KM;hKT&YB&NLKX!e z(a3xXl>&F2#VJ|jW*L|#S9y)EdB7yuSjTuR+!pHEnqN;L)Kk1EP+QqBG4?4r9DP~~ z<0W;|)Z~DVXAh}Ax2f>qsw-Ch&yW+Z%L}p8Sv=KMLuZMK%EhoEl_jRRRTVAk$8f&z zCpjz&Y_41t>vPC9`TvGIhN{B4Mb(x~G7QW^D}xT1St>V=hd0tvEiKNa@?nK?+U?$6 zd_Cxhs8k!_l6E0|k2GazGS~{s%ujV?lu}lK<3;*IvS^lP*(N)!e%hHa1R!4o1S@p! zyX0S9+tVWN?4210+2~I!s*X0V1^1nq8`b>9_BX#zre11J(wz86hTuKl-bPHMGm}&| z-tO8n#z`%YFR%HXO3K!fddfRAKVIJnKuNSl3K=QPKF3c{yG!iPjF`K^nJt<2y7wpn zky)I_9}`D~8CyTEt6#>*jVeNs_YJxqK9Lv5qUow`HeIT_+os_#Sq^8$Yt1Xol+a4`n^v-Ep z#QjFak%v`UH$N#W2|Fs9PdtkD)vL4FYL!>h!e&v{TuZ&=0+G-ckUS`wG> zIMD`SxBQZAuo$yEOGl$sKW3wc9Z9BC*4EMf z0J9Yb{-XrvB0tlUHH{Ukg)nh+Hf@BEA%rSR2kyAz`o#zJp1MTLW8P z-^NBp=~0GA;w@|)^=t@d2dt0v_JC)It_s9uJ2g8gFe0gO1x%cwPOMFA5T6vZELbZ( ztDJ_%lQso?k&>{0ywk(%kXiATd^7YW(NNB=azgj}oaCWR&PZh? zu;cHnz>5$E#*VF+Nl7Wnd7?;qcYPVrmm18<$VuEy24k!8rhU)Ih=ITeoR~=JA4e@$m z;n?k(EA#e;B8J+LJY5M0e3X-4{)pZByjA{O^nctDe^VP`V{K1wOHrzg@zv;F9}5?? zN`Fbnv-?`@nQh-g;?Nj#mAtqjbUMD5HZg&0`L*%$7H{V2*ryk#)lmYD9Va+ijZ6F?s1`su1;PA46IaMb!Vn|nt2D4bU44zjZ1b%nS<{d_nUBkV?urw&z(z1p zF`?sn(AZz1c@kXy_9vOSnJtAm_0QGlvgvTJO-b-*SlwzGx%{4kd*t%A4U?;@FQgnC zy*S4ye|XtMRZn-lo}-AiN$Un7ztG0i^JfW=PaUYHSjV;gpGtqbXc%Zn=q_iR=_N+b z4EB8vFmVpMNAUqJSXw!xAeZ*%aZ@%{lSS=Tka#dTmzI1dprfQB5M5ikN(6CZyGbx% z|KphHOm~)Na1yQ|oGs0o-E#sUk}z&f=j+7H=JsfJv_D8Dh-H1$Gc{WGS21ETO=wAY zcs6tKd;QF$hb`OR`iX*3oW;#fPZ#gN7uHgZ8KYv18u_9Lc%x1BPAZzvu1YN`&O0*|SWDI{!qUQ% zy9=Zx_Gm%p|Js36RaO6b2uI(Gd;}(>h-V5+#>3hGIy$|aHTV6YSOXHFW!X^MTHO}A z&QF;}y4N5~ETwAPXD&(yk|0Y#x%{nWF3It6m zLKVA{es-GMCRnC%gwBAH%#=+3Q}6tn_W!G&sqaV*LvrWV&b&WTaZX9kuhkmkt%97?{uy(SNDl)-!ChTw& zuOl4y+>n^AvLYeG&bN=Td4%~R7Z4>bfK1Yi^w|#QOk${0r+G_Xt6%sjA_Je!*-y8G zLVHJ|UEUG08VLoT&EVb{Oh%TNs}zAFm}!W8z=~DmVsx}+ zWs#;T)o^2nl$of**URGfAi)mzXZCetWhvB=utL+4cl7(zL$HNZ`9lI;3NGjL>Wam< zUu}O9IzocEatu0pgqQiit#o#!Yekq}@ncHRJsJ>CMzNqv3x}~i+21`7I;m*Tjs00b z1+GiGlRKMdOgFevtowj#bHLkpG9uQ2m&Tf5@R^c#bvM=d*f*&9H0v6xA2T7iW;+x6kYh=8w-q zH}=%$jqdIi4Gt_(EOxk-DxsGW7FmSfJF@WIzPtOvaEhDj``YcVCX5OT*tG5w6nCg? zjhT;jDLDqG5%v41?(`%na!oafi{$UmGsX|*LbA}#8kN8@MXUKx%&(Bp%m-?HrtHka zTXM2Kb&bdoOBcxYlm8%|i!Qb-W!G?OE@%kiDk#_gh-i!I1jvY20Ldqy7#+Cl6Y5MG z4s0C&YYBE`eW~TlBem5`3(o)HE`T+d=NA6@I@ea{`ryKDIvoI;pDc~2>(uakvd|tj zY7G|x;JNR;uiEsIvZ`ixUO0w? z*k6VC6Nsh3wZ^Tpyed#o^>10mE72{WWEdvMG1p1XVwazik;ER06AL~WU;GYx`jc0G zbF}!uv}U7eL8%{YdZt5OZBm)_eYYa&*>$SC!6`n2q$EDy20rRBvR90e5I{T_K*66P z`6gy%3}@ofUOKni`q02+>nRbnv|dk)xz20uvYseW+8<2!`00{6UOUhVZ47N@S1AYa z;_X!JM@-i-1lp63eT`ypf@IXuFAM`Wi8TNz_vkvI%c>VNQjHsavyq;izE?>z3syr% z9X3EaE0hskvtb+K@T}9U?PVO%2N=wvB(0EkMWFmRyqM(BXhW+mIjB-dZ90ebY^38HxkJkhncVGt@Yx$0&d(!-KeI2C__>=6^B5# zCpGm1xl%Q5NTQK-L=czVA>pTeygXdozslM|rBgW#<&u?h(y$jl-zox>lU&+5yVt&*+;PIk8Qp?6NP+1Xjk!Py1K@t6jQ+UcQe$!pM$Vo_jip{B~L zd{gnAWo!*bB(`-0Ue`y3X+1$L-@4-^vKV(WdanC81!s-JynpeUq8ZM<2W~va1=(ie z7YxIt;G&VS5>e#3KLR466`6TF#PF~*gXy0g9dpz62R52W^JMBUxKAze0GIu8Q@EUo z)<|tM>c;{I3ASd>kKyoJt;D^$n1Vsj-Zy=Q-0;28kd9=vMdhaO$L-iTr+LhvFc;$& z>lZDk*KInsVQ|Ba?FM(7A1TvBW`c9$$JwnxB;q6|Bx&5S8}y#=`)``Rq}DEzVn;#q zeRkE0*c@1nm$!G0yVcTo@dN79!+m5ouT$3F^C&|aE;&uL^MrYrT<{MPgH`S<_PF7q z08uP_)^{ zQ@`FRjKMb7&qmKz=9VrW9i419LX=WiWTQcC)7Dviy8zJQ+6XYICc9R9;-Qi&t4-jd zUTYpjU!v%Htl5Q?^|=`uI7h-lu5_%`FO3cgE}{2gx38!#4_SH%!3bd(2>~q~g+Hv& z7MrQ4>}V=b?Vx)(itrM|&&FhWv-Tr2A0G*l4HSm|(FM6_ zQoI2jrrbTmoV{xqo7I*6!DqXBj4M6|@xlEy{l?XBv=iKmgZ+igIjt3y9fqPn_blMT zg06!2hSSt=dxk8?>4KPEV@XHoX9UypIH7Eq&Z@PzjZ`}*4%{qsGn6c6x(K{t zQ64j^-ZHb9(~BqdvNXbLLI@4gi@EXvo~^A1s0cOZP8S~2zw4)UaRj#~H+xdE#A-Mg zC)|$+N&j*iTIr+tvk{WM#V!Sn2q!B}#K;7>Nz4INw>nPWY`IbRs51ilcizmp?BJi! z5M$PA;KsMFTKQl6AO#NUXYDcK(}DBFW``5pnRLC+&YI@Rv($dxTDEAafytVSwA;$N z3iMJ-o-%y)k- z+Q9Z=&Y-q8N(J6ypdvmm-1N{}t_RV*;L=hu2z8t9aQ~Kb<(`dmKVIGHg?N1~MbbmO6zbv(s)hFx1JGv9rhi@hyfsS-VXPtxSz2*G|X{_)}E9%b7_|QvaFfkIGV??YyOvEEZ%>MV{MrTtIb;&@(CH&Vsp&CTDjxIA*0YgAFA&`6F`z>ZD zzQWZD?Z(t+SclfaLQvF(Ld5j(eRg%2nkC~uEQQ=e$01XsEB~4juGIj}VJ*OU$p!uv znGPD(S6XgdSZG?l<+_Om77+{jh*B{&XiIGlzpc|tV|U~3E&*(A{78OdAsLEo(LX-( zsu}Ikl*Ya?kXnZu{%@) zSW=+pZeT)d@r1XQ_p69IRty&6JR$^E4^Xg}G%(uR0~~WGMv-}FJ|`c{e3GwOBBR{C z8*>{TY}_F7m?MnB>}~=`ya+0?Rsz+$oB>GLo~&X1-U2qGiCz;2Ie+;nCD9)ketX<` z>Gvf6xe>S*w12ttd;hFdG)@uv;F1f|9=yBBaTI0WZTn)rm=S;Mm;^gFnhMt6;eS(wY4-faINVG&2xBF!nBIGu& z&b=tpP|x>!X$Dcz3we|3gf|fd>Y^c_RBjHd$)w%*8ik^!rtkh>vE_*;XK~mh4der2!3~Wb{6a>M4Xn<`{Z&s z3Inl0QNgw}nXO*lr(B$4IXFOJSe22BvADXf?Ct_sb*$QKJZ=}xDtqel~y4&Rp8 z#dhF%I<1{8q|W4agbWQd9bE43UmeLSso|kw4io7mJ!+|{p6m@69{B{GpL4PkkWsU+ z_feZE58=llt*62+20a;sHmk!ji^^xQtk~X8hOl30LCskG|Ajho>j2vvQ?5H^& zIiO`wZIT6pjuDm0;J!>UQ56;ru(X5C1_pd;X=&G(Zs!5nltiL40+7h^IiEK;NqYTt z(ibpSS5Gz}LSYP&$?9ygxvHtE!e;+-_-H7^gvQIuzz+x=njjqeY3B>GI8=Eyx5_Br;?1K&_=GmD3wkZeI5D=pWE$yH=k)DWqQ#| zeFN$Pl)Mjo+guvF*^Npm3zh0PY)?%^OPm1hlZLNfh&+VkycrG>Fcbz z`G8$-a7HwdOG=PjB#Z|kYMt0P%*xuF%j58}A5<|h@nDgy00{;gEnHzpTdTUFN}zm* zy0WJWhd)qWe!Y>8{a7HA^{Tppd6SBFv_(8oBs3V*Kk(N%ipzkJ2Fdbm#b;yy6qP}S z&{yyeyg{$z$w^~G8)o{x9U)HEt~ru&-@SI7#_WcKyB&?YJILvDB>dX$<0>YJvxeM3H%dNC@n1|EAb9WF5LxC1t@zk zuYjl1MQptZ!Eo(*%{h2Ux)m_}c&PZYP!pdMM@mH+u*{R}PBnJZ*7tJJyQMI!2f=+jQ{GU(Z+cPuxsG7R` zj##+;zaA*%dF9?NkEi|LFI|5=Kwa;06$8(^N;++XA*_I zkYYJ$E+vj9BMWq7PrpyK*2uBByL<1n-m#hG$qfHf9G=h{l;_-&VQfZsG|7@wtncli z6hL}ZuRl2I_nlKRHOa3*byjM3cAbN6Qq*(A0}1Q(`W7Efm|}3bMwZ6MH5yDQazKwT z4l>!Uyw8qA&C{Q6G&yeQe7`%CtVd!3Wx4Bt%A>4l>!E>$qr^qNcyU#hj$7w-We=```tN3q%Zhwms50MwoEbkT#sLJ4^o z{*upi*FU-gt52GRUV!jwkT-g9=u%C$b#ZW!9EU(tM8`xl4?!%RSA=yxfI@zTT2{<- zDibtSu9yn)r#(^xW+68`&^EuPtu2xcdB)O6sEi=+#~f3D%0I!R4^}P(4TT_?bCtFZ zluX0i92CcpRc~80Erc5yxTmCrw|B?SZEzz)wv{Lf6r7)_g4hr~TVNk@o4g6M-fX(J zE?=Vd!Lh z7Smo!-G+in1c$tH^^u67(~3W*?7PUx@JhMo@3EKG7|{zIp_)b53JMZc@#i!9XwnC| zy%z{C#EpB^Tcu^}csar{b$sds(&#EflT*OJJc@Q3ghWEgHT?9NgYnysRde7XgR3e@ zMfIJGhnByElU)ask(cvhu236^6(-?7g1#eBS;M5^f1P6LvySE3Jly<7Vga6;nN!_% z2i|VH_Amo1?~7`dp4XvP1WJJEnHf#2+RZRVI1l2OJjnd;i8X(?qOt7ZkdpTe9V9$e zZS6`wIv3PkBE-z&D*|{$B|iln!i01l?$yP4ID|n$g4$Sj=-nV#aLn1fTSo@?x~wp; zw*&kiv_9(YMWG`-Oc*RP*kuMj?w8LB?++Q5r(L@v6%RIgHrMOJt&UiUklk-@vNW&E zObrkoKtSHa(x~`N@lA*e9k)IGBzz$0pshf{Au83CMV2j>VnPA?f_w-W9^Xy}e&rO}I`(qhWZp!-T28yh#5Lz1B(RMlD&=sS24 zjC(el%{f^=A}nGL3pY0igYi=nTV%QkHRCIQate*Yx}sHj-lJ%u7GNM-nn}jqH0$~K zYj!Rs#(RKzC457#%QT~M784hY{(cafx4Q#Hd@sAZ8K38VzMqFkzVExn8D3Am0)c;s z35S;b4nS5PTd~B&Zh%f#w%!+ex!;#RW2GD=@Ryn5$f8VJ1QPamd-KRodt1L4V+>h# z6Idc`ciY!Du|PHLK&l>W1t#9AExWPt0g<(jRbqzJ!wOMgGT{Xu!^O9{u^ zj8d%(X7?r!m?*6Dq8jRCJ9NAn_XjfD^)^xN_%n>3-tffKxT$E^=pdjmTT$pi9JHJJ ze!ePRyIrMVYMbiLs`J9wmMZneY}X@HVj_(uKg|dh{`QK{mW&);B;2GUAJBL$jTWbr zPw#X)jL*N6ikJfs0(EwKO0Q8jQTo))0Lz#hCfn=ll3$kZXo~|QqWIc1w{8cStBoh@ zSj17D*X`g4*a-qq2N>`D63N@S;qZ~)-yi51Kxhdp^rO0u#W?YcBUb@l#;{x5Y@)GP zF^7pOgjGTX5)V39BbRQMb4LrNMUpHG_40Fe{n$Y4HkNf#YmUb<9`9$#30r}jcjuL| z{s3>-0vxUkSVv((BKuOWE52W>aPAzKn`ucXfq3P0#br#U(?VlIeYuNXpLd=HFmrgV zN($>g?-$5F_jI*CkEK6>NEGhaauz*bSE5I72vg{-6?L}6Bnp7DVnGce1+xQcTq0Rs z^^x%&qT>IY-rkR>)Nf;A-mYJAc0=dj75tr&+=5mM@5;(%)f-8X76@`Kndqba#;v?~`-%@PrDz@5fNnw2<7L@`Y%eiwNM~iD@Jnc(Wr?Ibpenc z%>cLssG@8n`IdN2$#g$cvkfO5(55Qc3i;<9x>>npXCqo{H+D9c2qaY_5l*nLaCg8|A z0Z9rCrsreKAqzq3BZvhCneLIhzn^`8y011kFd?Uh#*oYNy3ecKW%l*{frZL_U6|Mi z^e0vhq}-i+V57#%z>*+?kLfZjy8LLYRlP^q6=nzQ__r$c7I{gLk_07PbD0=y~ z;l=2OHMP02MnVvDIh=n8XN7htt_FuhsX(yz6>+cpo8hSZwt}HCUp>^(hx&rBA>ejH z3cU|cPv^vg0Ml}D4!11!Yz3A4gOzD&U3Pl`#}M{t-<_wkIPN#nZ4P6PcmVy!`9?6c z#Wh|x_7=3_=N$|~(VT3jwZuw(& zejQ^Zlo`c-7ys?^)rYQcm!#j4YxhGM^LbOw5C>Knc!+2p6ht7mh9ITnTu4L*6ciLA z7GBPqzQPE2573wo=aq}??3VP+qvvYJm0lSg@cqnjNQ7aeou`)?=*Kr9JA^fsr zdig%3Oc*@LvW5sBj=3h=94mL@ziQu~Cq0FQM0Jso<7!f=Ts^Z~cdixgRLS%yQ3*?0 zyN&4^)@_Syc}@OuUuc;eeh|Ihn#(M_%1y&%YISxNMu*kPIGOnRJJ`;0>#4b4^(;n3 zp(+Hia;fNa8Tyo7MYTF2;KsW4-`70oTfk)K6S03Ej{B1IBn;@c9A~U((^qtF@bX)8 zivsVjA3EW4UN0Nr5$Xv$#XxQfW07Qn!TlDAwkWS%bG2}jy80cpSTDo6PI5Tzpz;D$^N^DvlPgT~kQ zN2adF8Wm{#qc;qFLektJ(MXt`c8 z5(R9DKN_P8#=AU>^x{5US!Z*L1qNtn3dza>c4YvFiaB#Bdd< zV_ZN&4ryJOTw%gI6dMv+-OYP=MIK#C6@PJYZ>sX1b#;Co(m!14L}4QNJPal9poXzDLoz}ne{XC*T9*u(d7lBan0mLSppRk{6wdVG2MDy3-LXz*% z_8J5pH5fMzYOuw%EWLnsolPS*viZwX*bqv*_x zi;f+D`x6o85+N z&>vU;bm4|x7`m9nHsK;y(7v*?#FQtWQzw{y0AYp1VN50^HVcEtB>SS>0cGj+)p=*j z6t@UJl#ti|FjJk-q9qTGwtcsYp|+k}dWgyx6s3s^BF42!J7{0iW=qQz2SaGn%4aiN zwIpVo1uWgLr9Ub^g(7y2ex^zi3YSe=TSkNjO$UBJ!(g8_+LI?<6rE>eMw#kyc_}04ZEXz< zQ5ynln)BB>T%Z?YWbwtTo^HNRfLn?UE(ngr-6O90ODI`IZ#G=dWqmb5<0ra-iYO@Z zZl!tKEb>Pu3iFU1xj0F^w$`)py*o)*StF7x4@DYpwevtu8*d-ZN;j~uGS)PDE0{mx z#1>e5zYo)y$Oean>(M_FWm}lI#TbUZ8?LzE_Hml)zP=TwR#tfa^rM4jBgUjwH#F>b zy?o0|^6|oULP2S1fJ=nX(HbaRCMThl6bmDqRE4KYn%O__l5X8(%+-7xi{aZ2i3%SeV81k(;)ScD0Ck8xBB;2AP{xJ(4~ozVVl0C zGCF^*AoGZq;MSmm?1YmH`deKw;Ls3>|NQ)Vx^|N~(?iCk}-akAsRwk!=Jn>SoMbPvC$cQ;agxx~JJdTe~ ze@^*+J$3B3C%}>+ITFl8Tpm0Wk3~UhPK$tf_?;z?(GHo_bWla zrZMkgr^X??3V>di2O*izj?M2=KEQ*aX@G>04MD{amgnA<8sr?D8THzEAu}dd>S=7p zyQVuIJm1 zIC1QLg+zpeMR~ViQhplKR?gc*N^q<{So(ka&o>_sP@{lSun`KWAw_KnrLrC zl!e{9Mx`X-gyJVh6y)|Pnf@KXqA3Uq3rb5X%D4!trP1lyE<0^%Wr;0Y-Nrm$G-vhA z?tDGt`orxSf;N|zS2s0vH#N1iq;xX5CRis*iw`boLP_M&B+1=PSD`4YvfWLMk~_Md z^tvG(K?q^-yWbOsVs8qNq4U1#x%L>R$fRv?@XtCaE@X4xHpza|^ZF$edl?m(08vro z3@ONE6kr#zvLzZ+Ox*D%C%ejMb$B0SC)!G}6sKO`AmG$3zAwKOJMPxl^MfC08#aFv zNOH_BoNY`xj_Qv302@Gr;Sqf2RaBHzRjn_^mo*6z0G-f)gn}UCjK&KUlO%5zU>1o@ z{5ecnJ~uX9g)pdV9zB*d16|Hq%@XG5V;>YW8(z%c(Hkx&GL;WrbL$PDp2N7T^H19^ zaByb9B4Y*hI3&dS<6HDODacWnH`P`>((838{RT;WZ!xGI!Bfq;@Pk_sFz=GH(fu}UYO-0=nxDnnMC2} zQL@KeeO;UV9(K<@nbL0hiO%;;`*n0| zOh`Q9K0HyR=e0T%urh<<@nzkaYh{A*LopO&$w*6w-WN)sEe`xk$#CSrH1}$~`6901 z2Sak_>-r!|iUg~av5z-PU@;XGTS63Nr`TUCy{e-2Up3e zIs1$Le4l$nPyW>)ulC1)YlR#?N0A)ET` zu>U{+gkl{248hgesp;S>K?5Kl>!L4TB#L}+CY?!jZRhH8UkctHYlZLYFw88M9dzH zeM3hbPgqIXV&9|#005H6fBy?0$gFJ*;5r<2H~QC%h&&Bh4JG=PjH88P2i>Qo6+ABG z0N(dit=k$WJsKhiX^3!sG(J3WI8NW!O@Uf%W^|Oa0qzCXK39p9ij|=d26evW0Rn?| zTR5wuuq40GGRDpsR5(0a0Mhk80q+qI?p}Nmgv~^}ajNyfgJ;-AO%`OjfkDZ>=DG7G zr^?cs)0Z#5{Mhp4v#8I8d^Vf1-3N5i4eW4zVAVp>l5?W(Yp=aUIvxe-2uQk)7pAgN#hMYahia#=v&I=0iBZd9y)k_IY z2TYtfSA6?WSgFBv>voEhR-BB9E;xH-)dLGjWOY3=Z^P$bsgEFLQzg4**_FnwS-GOZ zl*+w~!=mDHk{xKi3x$gpPbZpz!^jwfoP)tEq?WkiUgBx^F>P8Jhu3mamZ=7%a`Gbm z^e4~r3LF%~SrCjFR0t>}e|C68$dt)r=FFKC72PG(DzhK2Pl|ta*nCn!;p zIO&7=0v0fgIN?G*v2sih$RjTW!cRP&5r%-|#7U}s^wHL>TlWzdD=tyOj(vKac?Sk@ z2yj+b0Ta6XP1u=FFf2ziakviqvdz4tbP4>iz-p!@D1Yv`RpclG=zspxI{6N3Bh$Yq zDXsj;KYbH9LE?&y8~2FLmKx+hSt-;dH>Z%K7i86kA!Ej-?EdO#W!LlhxQp#n9LmW# zU%S6NLKv^q4u>+at@i5G927WHphQ!I+t7oCz(x*&w;9H!0LT1(`C`_Tsbf)-;D9MD zRuF&`M^cd9mt&ybc;i#}EG2KJgBbsev17+BFiPc|WC$@anrE*W&dV>^)B28#3Y|VZ z9VK$-u7i8_98;)zJQYnD)=P(4BJr4@qd1cHLeU_6KXmX6mjJ~4`BS?+x|NuAc99E% z$u2{frr$4Pw%>h+UsNc`Os|XPGx;)uOU66t1`vC7^$lvvLn4D_ zAAE2jJ^?0H=9B&VPr%j5lgE&w%M=qhff@L+`-d~5ynRfbTV>qOna=(Y#2(t0q&KUZ z6-$EZ@}8I24U}kINIrxIJW|`snuMaK<8EO1a$bRE1qxBFj~_cv<7lfP!M9u_Qe~8t zH{V=K56zsB&e=1j8j;GW$);n)m-Anx3e1}b2J{5AJtWm(?+$Y`J|;$>nI}RsYBUo) zR&#D%p{9EX++zr`cb@&G!pQ}NBS$5%#gT)pG<`JUi5yGCkmeL#jCV@d{m49ya7EuW zMG|~QK_akb>5>`A!%gmi4h{~)nE*7|!>LeCOtmb^d0$2sIcn5jxy5O|5pmUSIwb>L zcn29_YJsmoiowU`h2o6br0@_aDq{^$!Yr?uFMj|2lbp?nk&98!T&C$qlp4e=_|1R) zSkeC3Ggp80t2Zg+6)@)s8>pv#9av?CV-?2i}HJL=Paya^m&HVfKorKrwI#LPx z07o$^DoAo2`k{vji*OY)jUf4iS4F-5ntamp=1t;W@)|IT*w#pr=?_2La_Zz|Q}ZBT zJ%1sCqb8Rvp9Ls!sEr>#5-F8u9EzGB40eV>dNvG;lxlFqoM*nKJ)h~u38StZZtNc+Jv+>CKl_a zGDPqWxJc+=&C@jGRN|H7PrRO{@-kv0@7;R>HJ`2}6Qr5@ zx=7z+rV)TEHV_l`qNr9}T*kal3oHS|#YHloGLR6fni{io?}hUj1qCG-F62Z-RmFVS zxM>d=R!z}>HHPMc50%9QsZM@=>4_7U@S!rZV_lij>G5!Z#n^|JzVzaw@>3^NR@%GMt&9 zIlEDx>{g^F;DjBJro`SRgzg z>Z_sz9hrXOh3Qu_0}hwo{{5%06~6I}d(C7?F!dCvob?;z9AVfv`6i4qdakiUiB9CiAO zUwrEqzj#slE?YK}Uf^_`xcDejw^NQQ@vEBoL-7lf= zh&jqqP>x7V=$44Q8^!n?=u{M5GkqZ0VpPVAg^zGY(};m_I5Nq!i%dOx?y9LN3Bstr zT!u8lpUnK#Evcp|U@m|vvaC#;FiKN}MLA(n3TiK0%#gdgH5;s|szcv3*d+_6vBaub zM-&=T0p2JI3iNMkA}wHse1%DV7bLOZMDiAlC!{j@h2>wCUhsM{GABT(ZX0OEkc*R8j)(^|LZLfK^!3>AR zEIgX;5;Lp;9CQhjBYAtt3Z$q><2aTVFPg@R$lg82OhHF}7tR{2mXu_i|1eO)P!p9= z$ku$i17|fWbtHW-WffsL;fy3nJI) zdFLdu_a8WgI>EquaMdDad9^YI5|GwYr`|e8+6+G}zeMko3XhWvxTPCSQEC)?@I_5F z^B9H~ODwFuu<;0dvBBGd6#lx05|#^<^s_-sOr{Qe4;7l-*^A^ zIi5=z;XLk7KG_DOXqk?|3CD^k&J>Io)OoZ8Gm={(jHP^d!UD<4mGgJ(I4D2*UBO9K zWf^$Pn`YdT2HQM+WO+q3%ZZxKudJ;6%*`79$|}^1JE@4SH~${@?%mr&nJ2Mq2ual+<{m zwLp|mJ4->~VZo%6ZEb1Wvh{2EyMPcfw{z-%`URotx##{_T`rXXkF>NAQrdY-K}k0= zJ|^uudGx4;b4&g_gu#FO`(N=pz!y?!@g&3yLJ>utNr9Cv#G$-CZ~LGB@iq(m_phAK zS_^&8d=2!GF$8@P=BW1KGHO``DKD>77|4j34?fsDY0?_OG z@o3Zl)KfIw*|R5c1PO@5Y)9S`54vgdUi3~y$Ss~GR5VB;wXwSWoSecvdydkb(`TfS zb`aYZuM4PR;F3G~9>)S(Wo7lQorln6nL`8tR2CW9)%1uG z&DAVJ$boB z=1rf$%y<3WO>ux_(xuC0F=cbI8|I3_8)^$E#gl+0>NatQ_$FB>L(ws8b}?S#j188; zcbLScwyClh&IANkA9!cb2Sm-z8W@TlSly+HsACa0G5)y*#i(Q3XXbO(v z4J>sDnR#EH;p5}USE_^dT2awudCJ?{Jt#=y%sDg7>X#gp0~qP~`8ff`b1bC~n{@sB zH1;=ZzN4kfjG8x_D)jN`LJ-wBf6!EAy?lUifMtt@hA#6YauLsy<*(T*pd_7wf`ZCQ zHqLfQf@L|0dQHdT0DX-{C#M-9B@TSC@I`tBln81C5yZnntA#Y_)f|@th@RqNWrn@b z&`|SAq~d*h1(ax+XtnYu30i@sdI839J3yyg!2vqAtgK8icjNI13$rd>xK}_4tqcxD zq!xKwOG-*~fBQg%GKj3NC-S^lp{JqCd1&o^&u1-!fT3mRzMcWYMcl8!1@k%1J6~0O0c5-q^MN*+p;*Nqg3+d#n-`w0> z=5B?F6HEw+zafaks!wl$5+ab4(4^3C8yg$1UcJhY(&urj`l;Vm7PI!nix-)=6^O(Q z6cG_2KRVXJx3I&Cj+rN+^Ip4lt)@mJS`14lIy#zJUMziDWu2LMqJHTva6n9SK#(cB zyu6&_LDjpBnYd$PV`E}s#0EvHsOnu%LOpKt%*;##q?#B~te`dL5Jkmy9ZK2|CrIYLIvH0DFCc zfrhbjA|k@7B^(74?gl6YE?E-Az9}p$)J>cL21My~Sjmfvi^IU};f!~eKq=@3j%Xo3 z6T!)EU1|;tbOJ%NFFb%)u1LzB+pKpLl%fw%M}Q{YN_1qbHqfbXB@B$N8rW|E@&p!H zt-(}f0S{}nhXPXKSRa6rXCos~lkufvmGco=vo1UPKaRm7A50mH7=$7~WU0l Date: Sat, 14 Mar 2020 11:37:32 +0900 Subject: [PATCH 018/163] Fix error message --- src/behavior_tree.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index 9fc8809d4..ee060378a 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -20,7 +20,7 @@ void applyRecursiveVisitor(const TreeNode* node, { if (!node) { - throw LogicError("One of the children of a DecoratorNode or ControlNode is nulltr"); + throw LogicError("One of the children of a DecoratorNode or ControlNode is nullptr"); } visitor(node); @@ -42,7 +42,7 @@ void applyRecursiveVisitor(TreeNode* node, const std::function& { if (!node) { - throw LogicError("One of the children of a DecoratorNode or ControlNode is nulltr"); + throw LogicError("One of the children of a DecoratorNode or ControlNode is nullptr"); } visitor(node); From b6ccb8388d95f152cdc98f25697ffa5e28975099 Mon Sep 17 00:00:00 2001 From: renan028 Date: Tue, 17 Mar 2020 23:29:09 -0300 Subject: [PATCH 019/163] add unittest switch_node --- tests/CMakeLists.txt | 1 + tests/gtest_switch.cpp | 210 +++++++++++++++++++++++++++++++++++++++++ 2 files changed, 211 insertions(+) create mode 100644 tests/gtest_switch.cpp diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 1227f3137..4a3e6200f 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -15,6 +15,7 @@ set(BT_TESTS gtest_blackboard.cpp navigation_test.cpp gtest_subtree.cpp + gtest_switch.cpp ) if (NOT MINGW) diff --git a/tests/gtest_switch.cpp b/tests/gtest_switch.cpp new file mode 100644 index 000000000..80d61b7ad --- /dev/null +++ b/tests/gtest_switch.cpp @@ -0,0 +1,210 @@ +#include +#include "action_test_node.h" +#include "condition_test_node.h" +#include "behaviortree_cpp_v3/behavior_tree.h" +#include "behaviortree_cpp_v3/tree_node.h" + +using BT::NodeStatus; +using std::chrono::milliseconds; + +struct SwitchTest : testing::Test +{ + + std::unique_ptr> root; + BT::AsyncActionTest action_1; + BT::AsyncActionTest action_2; + BT::AsyncActionTest action_3; + BT::Blackboard::Ptr bb = BT::Blackboard::create(); + BT::NodeConfiguration simple_switch_config_; + + SwitchTest() : + action_1("action_1", milliseconds(100)), + action_2("action_2", milliseconds(100)), + action_3("action_3", milliseconds(100)) + { + BT::PortsRemapping input; + input.insert(std::make_pair("case_1", "1")); + input.insert(std::make_pair("case_2", "2")); + + BT::NodeConfiguration simple_switch_config_; + simple_switch_config_.blackboard = bb; + simple_switch_config_.input_ports = input; + + root = std::make_unique> + ("simple_switch", simple_switch_config_); + root->addChild(&action_1); + root->addChild(&action_2); + root->addChild(&action_3); + } + ~SwitchTest() + { + root->halt(); + } +}; + +TEST_F(SwitchTest, DefaultCase) +{ + BT::NodeStatus state = root->executeTick(); + + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(milliseconds(110)); + + // Switch Node does not halt action after success ? + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, action_3.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); +} + +TEST_F(SwitchTest, Case1) +{ + bb->set("variable", "1"); + BT::NodeStatus state = root->executeTick(); + + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(milliseconds(110)); + + ASSERT_EQ(NodeStatus::SUCCESS, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); +} + +TEST_F(SwitchTest, Case2) +{ + bb->set("variable", "2"); + BT::NodeStatus state = root->executeTick(); + + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(milliseconds(110)); + + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::SUCCESS, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); +} + +TEST_F(SwitchTest, CaseNone) +{ + bb->set("variable", "none"); + BT::NodeStatus state = root->executeTick(); + + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(milliseconds(110)); + + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, action_3.status()); + ASSERT_EQ(NodeStatus::SUCCESS, state); +} + +TEST_F(SwitchTest, CaseSwitchToDefault) +{ + bb->set("variable", "1"); + BT::NodeStatus state = root->executeTick(); + + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(milliseconds(10)); + state = root->executeTick(); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + // Switch Node feels changes only when tick ? (no while loop inside, + // not reactive) + std::this_thread::sleep_for(milliseconds(10)); + bb->set("variable", ""); + std::this_thread::sleep_for(milliseconds(10)); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, root->status()); + + std::this_thread::sleep_for(milliseconds(10)); + state = root->executeTick(); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(milliseconds(110)); + + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::SUCCESS, action_3.status()); + ASSERT_EQ(NodeStatus::SUCCESS, root->status()); +} + +TEST_F(SwitchTest, CaseSwitchToAction2) +{ + bb->set("variable", "1"); + BT::NodeStatus state = root->executeTick(); + + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + bb->set("variable", "2"); + std::this_thread::sleep_for(milliseconds(10)); + state = root->executeTick(); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + std::this_thread::sleep_for(milliseconds(110)); + + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::SUCCESS, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::SUCCESS, root->status()); +} + +TEST_F(SwitchTest, ActionFailure) +{ + bb->set("variable", "1"); + BT::NodeStatus state = root->executeTick(); + + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, state); + + // Switch Node does not halt after failure ? + std::this_thread::sleep_for(milliseconds(10)); + action_1.setStatus(NodeStatus::FAILURE); + state = root->executeTick(); + ASSERT_EQ(NodeStatus::FAILURE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::FAILURE, state); + + state = root->executeTick(); + state = root->executeTick(); + ASSERT_EQ(NodeStatus::FAILURE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::FAILURE, state); +} \ No newline at end of file From f9fec0afda356d035becdb50a64af0f9175df8cf Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Mar 2020 15:55:00 +0100 Subject: [PATCH 020/163] halt the SwitchNode correctly --- .../controls/switch_node.h | 24 ++++++++++++++----- 1 file changed, 18 insertions(+), 6 deletions(-) diff --git a/include/behaviortree_cpp_v3/controls/switch_node.h b/include/behaviortree_cpp_v3/controls/switch_node.h index 929719b04..eed9c058e 100644 --- a/include/behaviortree_cpp_v3/controls/switch_node.h +++ b/include/behaviortree_cpp_v3/controls/switch_node.h @@ -61,6 +61,9 @@ 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; " @@ -76,10 +79,18 @@ NodeStatus SwitchNode::tick() // check each case until you find a match for (unsigned index = 0; index < NUM_CASES; ++index) { - char case_str[20]; - sprintf(case_str, "case_%d", index+1); + 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); + } - if (getInput(case_str, value) && variable == value) + if (found && variable == value) { child_index = index; break; @@ -90,18 +101,19 @@ NodeStatus SwitchNode::tick() // if another one was running earlier, halt it if( running_child_ != -1 && running_child_ != child_index) { - halt(); + children_nodes_[running_child_]->halt(); } - NodeStatus ret = children_nodes_[child_index]->executeTick(); + auto& selected_child = children_nodes_[child_index]; + NodeStatus ret = selected_child->executeTick(); if( ret == NodeStatus::RUNNING ) { running_child_ = child_index; } else{ + selected_child->halt(); running_child_ = -1; } - return ret; } From 59094736c86505c7aa94e4f04aab2194324c7116 Mon Sep 17 00:00:00 2001 From: renan028 Date: Wed, 18 Mar 2020 11:59:03 -0300 Subject: [PATCH 021/163] fix unittest switch should halt --- tests/gtest_switch.cpp | 28 ++++++++++++++++------------ 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/tests/gtest_switch.cpp b/tests/gtest_switch.cpp index 80d61b7ad..d4d602a56 100644 --- a/tests/gtest_switch.cpp +++ b/tests/gtest_switch.cpp @@ -52,11 +52,11 @@ TEST_F(SwitchTest, DefaultCase) ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); + state = root->executeTick(); - // Switch Node does not halt action after success ? ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::SUCCESS, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); } @@ -71,8 +71,9 @@ TEST_F(SwitchTest, Case1) ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); + state = root->executeTick(); - ASSERT_EQ(NodeStatus::SUCCESS, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); ASSERT_EQ(NodeStatus::IDLE, action_3.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); @@ -89,9 +90,10 @@ TEST_F(SwitchTest, Case2) ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); + state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::SUCCESS, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); ASSERT_EQ(NodeStatus::IDLE, action_3.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); } @@ -107,10 +109,11 @@ TEST_F(SwitchTest, CaseNone) ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); + state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::SUCCESS, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); } @@ -131,8 +134,8 @@ TEST_F(SwitchTest, CaseSwitchToDefault) ASSERT_EQ(NodeStatus::IDLE, action_3.status()); ASSERT_EQ(NodeStatus::RUNNING, state); - // Switch Node feels changes only when tick ? (no while loop inside, - // not reactive) + // Switch Node does not feels changes. Only when tick. + // (not reactive) std::this_thread::sleep_for(milliseconds(10)); bb->set("variable", ""); std::this_thread::sleep_for(milliseconds(10)); @@ -149,10 +152,11 @@ TEST_F(SwitchTest, CaseSwitchToDefault) ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); + state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::SUCCESS, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_3.status()); ASSERT_EQ(NodeStatus::SUCCESS, root->status()); } @@ -175,9 +179,10 @@ TEST_F(SwitchTest, CaseSwitchToAction2) ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); + state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::SUCCESS, action_2.status()); + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); ASSERT_EQ(NodeStatus::IDLE, action_3.status()); ASSERT_EQ(NodeStatus::SUCCESS, root->status()); } @@ -192,19 +197,18 @@ TEST_F(SwitchTest, ActionFailure) ASSERT_EQ(NodeStatus::IDLE, action_3.status()); ASSERT_EQ(NodeStatus::RUNNING, state); - // Switch Node does not halt after failure ? std::this_thread::sleep_for(milliseconds(10)); action_1.setStatus(NodeStatus::FAILURE); state = root->executeTick(); ASSERT_EQ(NodeStatus::FAILURE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); ASSERT_EQ(NodeStatus::IDLE, action_3.status()); - ASSERT_EQ(NodeStatus::FAILURE, state); + ASSERT_EQ(NodeStatus::IDLE, state); state = root->executeTick(); state = root->executeTick(); ASSERT_EQ(NodeStatus::FAILURE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_2.status()); ASSERT_EQ(NodeStatus::IDLE, action_3.status()); - ASSERT_EQ(NodeStatus::FAILURE, state); + ASSERT_EQ(NodeStatus::IDLE, state); } \ No newline at end of file From 3678297d0ae0e5f581c6d866fbd79ae5f5b86fe8 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Mar 2020 17:21:39 +0100 Subject: [PATCH 022/163] change API of haltChildren() --- include/behaviortree_cpp_v3/control_node.h | 6 +++-- .../controls/switch_node.h | 4 ++-- src/control_node.cpp | 23 +++++++++++-------- src/controls/fallback_node.cpp | 4 ++-- src/controls/parallel_node.cpp | 4 ++-- src/controls/reactive_fallback.cpp | 9 +++++--- src/controls/reactive_sequence.cpp | 10 +++++--- src/controls/sequence_node.cpp | 4 ++-- src/controls/sequence_star_node.cpp | 10 +++++--- 9 files changed, 46 insertions(+), 28 deletions(-) diff --git a/include/behaviortree_cpp_v3/control_node.h b/include/behaviortree_cpp_v3/control_node.h index f036eb1f8..09d8605a6 100644 --- a/include/behaviortree_cpp_v3/control_node.h +++ b/include/behaviortree_cpp_v3/control_node.h @@ -43,8 +43,10 @@ class ControlNode : public TreeNode virtual void halt() override; - /// call halt() for all the children in the range [i, childrenCount() ) - void haltChildren(size_t i); + + void haltChildren(); + + void haltChild(size_t i); virtual NodeType type() const override final { diff --git a/include/behaviortree_cpp_v3/controls/switch_node.h b/include/behaviortree_cpp_v3/controls/switch_node.h index eed9c058e..0ca9a2eb9 100644 --- a/include/behaviortree_cpp_v3/controls/switch_node.h +++ b/include/behaviortree_cpp_v3/controls/switch_node.h @@ -101,7 +101,7 @@ NodeStatus SwitchNode::tick() // if another one was running earlier, halt it if( running_child_ != -1 && running_child_ != child_index) { - children_nodes_[running_child_]->halt(); + haltChild(running_child_); } auto& selected_child = children_nodes_[child_index]; @@ -111,7 +111,7 @@ NodeStatus SwitchNode::tick() running_child_ = child_index; } else{ - selected_child->halt(); + haltChildren(); running_child_ = -1; } return ret; diff --git a/src/control_node.cpp b/src/control_node.cpp index 4babae91b..bd954f188 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -32,7 +32,7 @@ size_t ControlNode::childrenCount() const void ControlNode::halt() { - haltChildren(0); + haltChildren(); setStatus(NodeStatus::IDLE); } @@ -41,16 +41,21 @@ const std::vector& ControlNode::children() const return children_nodes_; } -void ControlNode::haltChildren(size_t i) +void ControlNode::haltChild(size_t i) { - for (size_t j = i; j < children_nodes_.size(); j++) + auto child = children_nodes_[i]; + if (child->status() == NodeStatus::RUNNING) { - auto child = children_nodes_[j]; - if (child->status() == NodeStatus::RUNNING) - { - child->halt(); - } - child->setStatus(NodeStatus::IDLE); + child->halt(); + } + child->setStatus(NodeStatus::IDLE); +} + +void ControlNode::haltChildren() +{ + for (size_t i = 0; i < children_nodes_.size(); i++) + { + haltChild(i); } } diff --git a/src/controls/fallback_node.cpp b/src/controls/fallback_node.cpp index cbe32ee44..f54ca0a4d 100644 --- a/src/controls/fallback_node.cpp +++ b/src/controls/fallback_node.cpp @@ -42,7 +42,7 @@ NodeStatus FallbackNode::tick() } case NodeStatus::SUCCESS: { - haltChildren(0); + haltChildren(); current_child_idx_ = 0; return child_status; } @@ -62,7 +62,7 @@ NodeStatus FallbackNode::tick() // The entire while loop completed. This means that all the children returned FAILURE. if (current_child_idx_ == children_count) { - haltChildren(0); + haltChildren(); current_child_idx_ = 0; } diff --git a/src/controls/parallel_node.cpp b/src/controls/parallel_node.cpp index 7bbef7776..b85533f14 100644 --- a/src/controls/parallel_node.cpp +++ b/src/controls/parallel_node.cpp @@ -83,7 +83,7 @@ NodeStatus ParallelNode::tick() if (success_childred_num == threshold_) { skip_list_.clear(); - haltChildren(0); + haltChildren(); return NodeStatus::SUCCESS; } } break; @@ -99,7 +99,7 @@ NodeStatus ParallelNode::tick() if (failure_childred_num > children_count - threshold_) { skip_list_.clear(); - haltChildren(0); + haltChildren(); return NodeStatus::FAILURE; } } break; diff --git a/src/controls/reactive_fallback.cpp b/src/controls/reactive_fallback.cpp index 251d6820f..700a76046 100644 --- a/src/controls/reactive_fallback.cpp +++ b/src/controls/reactive_fallback.cpp @@ -28,7 +28,10 @@ NodeStatus ReactiveFallback::tick() { case NodeStatus::RUNNING: { - haltChildren(index+1); + for(int i=index+1; i < childrenCount(); i++) + { + haltChild(i); + } return NodeStatus::RUNNING; } @@ -39,7 +42,7 @@ NodeStatus ReactiveFallback::tick() case NodeStatus::SUCCESS: { - haltChildren(0); + haltChildren(); return NodeStatus::SUCCESS; } @@ -52,7 +55,7 @@ NodeStatus ReactiveFallback::tick() if( failure_count == childrenCount() ) { - haltChildren(0); + haltChildren(); return NodeStatus::FAILURE; } diff --git a/src/controls/reactive_sequence.cpp b/src/controls/reactive_sequence.cpp index 8d11d6f3c..340b43ad9 100644 --- a/src/controls/reactive_sequence.cpp +++ b/src/controls/reactive_sequence.cpp @@ -30,13 +30,17 @@ NodeStatus ReactiveSequence::tick() case NodeStatus::RUNNING: { running_count++; - haltChildren(index+1); + + for(int i=index+1; i < childrenCount(); i++) + { + haltChild(i); + } return NodeStatus::RUNNING; } case NodeStatus::FAILURE: { - haltChildren(0); + haltChildren(); return NodeStatus::FAILURE; } case NodeStatus::SUCCESS: @@ -53,7 +57,7 @@ NodeStatus ReactiveSequence::tick() if( success_count == childrenCount()) { - haltChildren(0); + haltChildren(); return NodeStatus::SUCCESS; } return NodeStatus::RUNNING; diff --git a/src/controls/sequence_node.cpp b/src/controls/sequence_node.cpp index 2630a9798..2ca0adee6 100644 --- a/src/controls/sequence_node.cpp +++ b/src/controls/sequence_node.cpp @@ -51,7 +51,7 @@ NodeStatus SequenceNode::tick() case NodeStatus::FAILURE: { // Reset on failure - haltChildren(0); + haltChildren(); current_child_idx_ = 0; return child_status; } @@ -71,7 +71,7 @@ NodeStatus SequenceNode::tick() // The entire while loop completed. This means that all the children returned SUCCESS. if (current_child_idx_ == children_count) { - haltChildren(0); + haltChildren(); current_child_idx_ = 0; } return NodeStatus::SUCCESS; diff --git a/src/controls/sequence_star_node.cpp b/src/controls/sequence_star_node.cpp index b20ac4870..e0363501d 100644 --- a/src/controls/sequence_star_node.cpp +++ b/src/controls/sequence_star_node.cpp @@ -42,8 +42,12 @@ NodeStatus SequenceStarNode::tick() } case NodeStatus::FAILURE: { - // DO NOT reset on failure - haltChildren(current_child_idx_); + // DO NOT reset current_child_idx_ on failure + for(int i=current_child_idx_; i < childrenCount(); i++) + { + haltChild(i); + } + return child_status; } case NodeStatus::SUCCESS: @@ -62,7 +66,7 @@ NodeStatus SequenceStarNode::tick() // The entire while loop completed. This means that all the children returned SUCCESS. if (current_child_idx_ == children_count) { - haltChildren(0); + haltChildren(); current_child_idx_ = 0; } return NodeStatus::SUCCESS; From 3e7e6d3cae0948cd649cf3e1393b5c48620360e4 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Mar 2020 20:45:46 +0100 Subject: [PATCH 023/163] cosmetic: names changed --- src/xml_parsing.cpp | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 2d3be9761..6ec962abe 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -471,7 +471,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, instance_name = element->Attribute("ID"); } - PortsRemapping remapping_parameters; + PortsRemapping parameters_map; if (element_name != "SubTree") // in Subtree attributes have different meaning... { @@ -480,7 +480,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, const std::string attribute_name = att->Name(); if (attribute_name != "ID" && attribute_name != "name") { - remapping_parameters[attribute_name] = att->Value(); + parameters_map[attribute_name] = att->Value(); } } } @@ -495,12 +495,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& remapping_it: remapping_parameters) + for(const auto& param_it: parameters_map) { - if( manifest.ports.count( remapping_it.first ) == 0 ) + if( manifest.ports.count( param_it.first ) == 0 ) { throw RuntimeError("Possible typo? In the XML, you tried to remap port \"", - remapping_it.first, "\" in node [", ID," / ", instance_name, + param_it.first, "\" in node [", ID," / ", instance_name, "], but the manifest of this node does not contain a port with this name."); } } @@ -511,16 +511,16 @@ 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 = remapping_parameters.find(port_name); - if( remap_it == remapping_parameters.end()) + auto remap_it = parameters_map.find(port_name); + if( remap_it == parameters_map.end()) { continue; } - StringView remapping_value = remap_it->second; - auto remapped_res = TreeNode::getRemappedKey(port_name, remapping_value); - if( remapped_res ) + StringView param_value = remap_it->second; + auto param_res = TreeNode::getRemappedKey(port_name, param_value); + if( param_res ) { - const auto& port_key = nonstd::to_string(remapped_res.value()); + const auto& port_key = nonstd::to_string(param_res.value()); auto prev_info = blackboard->portInfo( port_key ); if( !prev_info ) @@ -545,20 +545,20 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, } // use manifest to initialize NodeConfiguration - for(const auto& remap_it: remapping_parameters) + for(const auto& param_it: parameters_map) { - const auto& port_name = remap_it.first; + const auto& port_name = param_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( remap_it ); + config.input_ports.insert( param_it ); } if( direction != PortDirection::INPUT ) { - config.output_ports.insert( remap_it ); + config.output_ports.insert( param_it ); } } } From b0ca622748e6e9d7f7b0303ad3018ef2acb9d9f7 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Mar 2020 21:32:56 +0100 Subject: [PATCH 024/163] fix unit tests --- tests/gtest_decorator.cpp | 10 +- tests/gtest_fallback.cpp | 50 +++++----- tests/gtest_parallel.cpp | 4 +- tests/gtest_sequence.cpp | 14 +-- tests/gtest_switch.cpp | 146 +++++++++++++++------------- tests/gtest_tree.cpp | 8 +- tests/include/action_test_node.h | 12 +-- tests/include/condition_test_node.h | 4 +- tests/src/action_test_node.cpp | 26 ++--- tests/src/condition_test_node.cpp | 19 +--- 10 files changed, 145 insertions(+), 148 deletions(-) diff --git a/tests/gtest_decorator.cpp b/tests/gtest_decorator.cpp index 54c9351b2..0e03c73e7 100644 --- a/tests/gtest_decorator.cpp +++ b/tests/gtest_decorator.cpp @@ -118,13 +118,13 @@ TEST_F(DeadlineTest, DeadlineNotTriggeredTest) TEST_F(RetryTest, RetryTestA) { - action.setBoolean(false); + action.setExpectedResult(NodeStatus::FAILURE); root.executeTick(); ASSERT_EQ(NodeStatus::FAILURE, root.status()); ASSERT_EQ(3, action.tickCount() ); - action.setBoolean(true); + action.setExpectedResult(NodeStatus::SUCCESS); action.resetTicks(); root.executeTick(); @@ -134,7 +134,7 @@ TEST_F(RetryTest, RetryTestA) TEST_F(RepeatTest, RepeatTestA) { - action.setBoolean(false); + action.setExpectedResult(NodeStatus::FAILURE); root.executeTick(); ASSERT_EQ(NodeStatus::FAILURE, root.status()); @@ -142,7 +142,7 @@ TEST_F(RepeatTest, RepeatTestA) //------------------- action.resetTicks(); - action.setBoolean(true); + action.setExpectedResult(NodeStatus::SUCCESS); root.executeTick(); ASSERT_EQ(NodeStatus::SUCCESS, root.status()); @@ -152,7 +152,7 @@ TEST_F(RepeatTest, RepeatTestA) // https://github.com/BehaviorTree/BehaviorTree.CPP/issues/57 TEST_F(TimeoutAndRetry, Issue57) { - action.setBoolean( false ); + action.setExpectedResult(NodeStatus::FAILURE); auto t1 = std::chrono::high_resolution_clock::now(); diff --git a/tests/gtest_fallback.cpp b/tests/gtest_fallback.cpp index 0f761e647..f993f0191 100644 --- a/tests/gtest_fallback.cpp +++ b/tests/gtest_fallback.cpp @@ -125,7 +125,7 @@ struct ComplexFallbackWithMemoryTest : testing::Test TEST_F(SimpleFallbackTest, ConditionTrue) { // Ticking the root node - condition.setBoolean(true); + condition.setExpectedResult(NodeStatus::SUCCESS); BT::NodeStatus state = root.executeTick(); ASSERT_EQ(NodeStatus::SUCCESS, state); @@ -137,14 +137,14 @@ TEST_F(SimpleFallbackTest, ConditionChangeWhileRunning) { BT::NodeStatus state = BT::NodeStatus::IDLE; - condition.setBoolean(false); + condition.setExpectedResult(NodeStatus::FAILURE); state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); ASSERT_EQ(NodeStatus::FAILURE, condition.status()); ASSERT_EQ(NodeStatus::RUNNING, action.status()); - condition.setBoolean(true); + condition.setExpectedResult(NodeStatus::SUCCESS); state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); @@ -154,8 +154,8 @@ TEST_F(SimpleFallbackTest, ConditionChangeWhileRunning) TEST_F(ReactiveFallbackTest, Condition1ToTrue) { - condition_1.setBoolean(false); - condition_2.setBoolean(false); + condition_1.setExpectedResult(NodeStatus::FAILURE); + condition_2.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); @@ -164,7 +164,7 @@ TEST_F(ReactiveFallbackTest, Condition1ToTrue) ASSERT_EQ(NodeStatus::FAILURE, condition_2.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - condition_1.setBoolean(true); + condition_1.setExpectedResult(NodeStatus::SUCCESS); state = root.executeTick(); @@ -176,8 +176,8 @@ TEST_F(ReactiveFallbackTest, Condition1ToTrue) TEST_F(ReactiveFallbackTest, Condition2ToTrue) { - condition_1.setBoolean(false); - condition_2.setBoolean(false); + condition_1.setExpectedResult(NodeStatus::FAILURE); + condition_2.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); @@ -186,7 +186,7 @@ TEST_F(ReactiveFallbackTest, Condition2ToTrue) ASSERT_EQ(NodeStatus::FAILURE, condition_2.status()); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - condition_2.setBoolean(true); + condition_2.setExpectedResult(NodeStatus::SUCCESS); state = root.executeTick(); @@ -198,7 +198,7 @@ TEST_F(ReactiveFallbackTest, Condition2ToTrue) TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) { - condition.setBoolean(false); + condition.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); @@ -208,14 +208,14 @@ TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) { - condition.setBoolean(false); + condition.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); ASSERT_EQ(NodeStatus::FAILURE, condition.status()); ASSERT_EQ(NodeStatus::RUNNING, action.status()); - condition.setBoolean(true); + condition.setExpectedResult(NodeStatus::SUCCESS); state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); @@ -238,7 +238,7 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) TEST_F(ComplexFallbackWithMemoryTest, Condition1False) { - condition_1.setBoolean(false); + condition_1.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); ASSERT_EQ(NodeStatus::SUCCESS, state); @@ -252,8 +252,8 @@ TEST_F(ComplexFallbackWithMemoryTest, Condition1False) TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) { - condition_1.setBoolean(false); - condition_2.setBoolean(false); + condition_1.setExpectedResult(NodeStatus::FAILURE); + condition_2.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); @@ -267,11 +267,11 @@ TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) { - condition_1.setBoolean(false); - condition_2.setBoolean(false); + condition_1.setExpectedResult(NodeStatus::FAILURE); + condition_2.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); - condition_1.setBoolean(true); + condition_1.setExpectedResult(NodeStatus::SUCCESS); state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); @@ -285,11 +285,11 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) { - condition_1.setBoolean(false); - condition_2.setBoolean(false); + condition_1.setExpectedResult(NodeStatus::FAILURE); + condition_2.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); - condition_2.setBoolean(true); + condition_2.setExpectedResult(NodeStatus::SUCCESS); state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); @@ -303,10 +303,10 @@ TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) { - action_1.setBoolean(false); - action_2.setBoolean(true); - condition_1.setBoolean(false); - condition_2.setBoolean(false); + action_1.setExpectedResult(NodeStatus::FAILURE); + action_2.setExpectedResult(NodeStatus::SUCCESS); + condition_1.setExpectedResult(NodeStatus::FAILURE); + condition_2.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); diff --git a/tests/gtest_parallel.cpp b/tests/gtest_parallel.cpp index 4435116e8..688947047 100644 --- a/tests/gtest_parallel.cpp +++ b/tests/gtest_parallel.cpp @@ -192,7 +192,7 @@ TEST_F(ComplexParallelTest, ConditionsTrue) TEST_F(ComplexParallelTest, ConditionRightFalse) { - condition_R.setBoolean(false); + condition_R.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = parallel_root.executeTick(); // All the actions are running @@ -228,7 +228,7 @@ TEST_F(ComplexParallelTest, ConditionRightFalse) TEST_F(ComplexParallelTest, ConditionRightFalseAction1Done) { - condition_R.setBoolean(false); + condition_R.setExpectedResult(NodeStatus::FAILURE); parallel_left.setThresholdM(4); diff --git a/tests/gtest_sequence.cpp b/tests/gtest_sequence.cpp index 7eac9ffbc..e6327efd7 100644 --- a/tests/gtest_sequence.cpp +++ b/tests/gtest_sequence.cpp @@ -230,7 +230,7 @@ TEST_F(SimpleSequenceTest, ConditionTrue) TEST_F(SimpleSequenceTest, ConditionTurnToFalse) { - condition.setBoolean(false); + condition.setExpectedResult(NodeStatus::FAILURE); BT::NodeStatus state = root.executeTick(); state = root.executeTick(); @@ -322,7 +322,7 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse) { BT::NodeStatus state = root.executeTick(); - condition_1.setBoolean(false); + condition_1.setExpectedResult(NodeStatus::FAILURE); state = root.executeTick(); @@ -337,7 +337,7 @@ TEST_F(ComplexSequenceTest, ComplexSequenceConditions2ToFalse) { BT::NodeStatus state = root.executeTick(); - condition_2.setBoolean(false); + condition_2.setExpectedResult(NodeStatus::FAILURE); state = root.executeTick(); @@ -366,7 +366,7 @@ TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse) ASSERT_EQ(NodeStatus::SUCCESS, condition.status()); ASSERT_EQ(NodeStatus::RUNNING, action.status()); - condition.setBoolean(false); + condition.setExpectedResult(NodeStatus::FAILURE); state = root.executeTick(); ASSERT_EQ(NodeStatus::RUNNING, state); @@ -391,7 +391,7 @@ TEST_F(ComplexSequenceWithMemoryTest, Conditions1ToFase) { BT::NodeStatus state = root.executeTick(); - condition_1.setBoolean(false); + condition_1.setExpectedResult(NodeStatus::FAILURE); state = root.executeTick(); // change in condition_1 does not affect the state of the tree, // since the seq_conditions was executed already @@ -408,7 +408,7 @@ TEST_F(ComplexSequenceWithMemoryTest, Conditions2ToFalse) { BT::NodeStatus state = root.executeTick(); - condition_2.setBoolean(false); + condition_2.setExpectedResult(NodeStatus::FAILURE); state = root.executeTick(); // change in condition_2 does not affect the state of the tree, // since the seq_conditions was executed already @@ -425,7 +425,7 @@ TEST_F(ComplexSequenceWithMemoryTest, Action1DoneSeq) { root.executeTick(); - condition_2.setBoolean(false); + condition_2.setExpectedResult(NodeStatus::FAILURE); root.executeTick(); // change in condition_2 does not affect the state of the tree, diff --git a/tests/gtest_switch.cpp b/tests/gtest_switch.cpp index d4d602a56..bc5936daf 100644 --- a/tests/gtest_switch.cpp +++ b/tests/gtest_switch.cpp @@ -3,38 +3,55 @@ #include "condition_test_node.h" #include "behaviortree_cpp_v3/behavior_tree.h" #include "behaviortree_cpp_v3/tree_node.h" +#include "behaviortree_cpp_v3/bt_factory.h" using BT::NodeStatus; using std::chrono::milliseconds; +static const char* xml_text = R"( + + + + + + + + + + + + + )"; + struct SwitchTest : testing::Test { - - std::unique_ptr> root; + using Switch2 = BT::SwitchNode<2>; + std::unique_ptr root; BT::AsyncActionTest action_1; - BT::AsyncActionTest action_2; - BT::AsyncActionTest action_3; + BT::AsyncActionTest action_42; + BT::AsyncActionTest action_def; BT::Blackboard::Ptr bb = BT::Blackboard::create(); BT::NodeConfiguration simple_switch_config_; SwitchTest() : action_1("action_1", milliseconds(100)), - action_2("action_2", milliseconds(100)), - action_3("action_3", milliseconds(100)) + action_42("action_42", milliseconds(100)), + action_def("action_default", milliseconds(100)) { BT::PortsRemapping input; + input.insert(std::make_pair("variable", "{my_var}")); input.insert(std::make_pair("case_1", "1")); - input.insert(std::make_pair("case_2", "2")); + input.insert(std::make_pair("case_2", "42")); BT::NodeConfiguration simple_switch_config_; simple_switch_config_.blackboard = bb; simple_switch_config_.input_ports = input; - root = std::make_unique> - ("simple_switch", simple_switch_config_); + root = std::make_unique("simple_switch", simple_switch_config_); + root->addChild(&action_1); - root->addChild(&action_2); - root->addChild(&action_3); + root->addChild(&action_42); + root->addChild(&action_def); } ~SwitchTest() { @@ -47,168 +64,165 @@ TEST_F(SwitchTest, DefaultCase) BT::NodeStatus state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::RUNNING, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); } TEST_F(SwitchTest, Case1) { - bb->set("variable", "1"); + bb->set("my_var", "1"); BT::NodeStatus state = root->executeTick(); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); } TEST_F(SwitchTest, Case2) { - bb->set("variable", "2"); + bb->set("my_var", "42"); BT::NodeStatus state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); } TEST_F(SwitchTest, CaseNone) { - bb->set("variable", "none"); + bb->set("my_var", "none"); BT::NodeStatus state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::RUNNING, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::SUCCESS, state); } TEST_F(SwitchTest, CaseSwitchToDefault) { - bb->set("variable", "1"); + bb->set("my_var", "1"); BT::NodeStatus state = root->executeTick(); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(10)); state = root->executeTick(); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); // Switch Node does not feels changes. Only when tick. // (not reactive) std::this_thread::sleep_for(milliseconds(10)); - bb->set("variable", ""); + bb->set("my_var", ""); std::this_thread::sleep_for(milliseconds(10)); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, root->status()); std::this_thread::sleep_for(milliseconds(10)); state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::RUNNING, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::SUCCESS, root->status()); } TEST_F(SwitchTest, CaseSwitchToAction2) { - bb->set("variable", "1"); + bb->set("my_var", "1"); BT::NodeStatus state = root->executeTick(); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); - bb->set("variable", "2"); + bb->set("my_var", "42"); std::this_thread::sleep_for(milliseconds(10)); state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::RUNNING, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); std::this_thread::sleep_for(milliseconds(110)); state = root->executeTick(); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::SUCCESS, root->status()); } TEST_F(SwitchTest, ActionFailure) { - bb->set("variable", "1"); + bb->set("my_var", "1"); BT::NodeStatus state = root->executeTick(); ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); - std::this_thread::sleep_for(milliseconds(10)); - action_1.setStatus(NodeStatus::FAILURE); + action_1.setExpectedResult(NodeStatus::FAILURE); + // halt the running node + action_1.halt(); + std::this_thread::sleep_for(milliseconds(20)); state = root->executeTick(); - ASSERT_EQ(NodeStatus::FAILURE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); - ASSERT_EQ(NodeStatus::IDLE, state); - state = root->executeTick(); - state = root->executeTick(); - ASSERT_EQ(NodeStatus::FAILURE, action_1.status()); - ASSERT_EQ(NodeStatus::IDLE, action_2.status()); - ASSERT_EQ(NodeStatus::IDLE, action_3.status()); - ASSERT_EQ(NodeStatus::IDLE, state); -} \ No newline at end of file + ASSERT_EQ(NodeStatus::FAILURE, state); + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); + ASSERT_EQ(NodeStatus::IDLE, action_42.status()); + ASSERT_EQ(NodeStatus::IDLE, action_def.status()); + +} diff --git a/tests/gtest_tree.cpp b/tests/gtest_tree.cpp index 3245f7451..7a81d3c28 100644 --- a/tests/gtest_tree.cpp +++ b/tests/gtest_tree.cpp @@ -51,8 +51,8 @@ struct BehaviorTreeTest : testing::Test TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) { - condition_1.setBoolean(false); - condition_2.setBoolean(true); + condition_1.setExpectedResult(NodeStatus::FAILURE); + condition_2.setExpectedResult(NodeStatus::SUCCESS); BT::NodeStatus state = root.executeTick(); @@ -65,8 +65,8 @@ TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True) TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True) { - condition_2.setBoolean(false); - condition_1.setBoolean(true); + condition_2.setExpectedResult(NodeStatus::FAILURE); + condition_1.setExpectedResult(NodeStatus::SUCCESS); BT::NodeStatus state = root.executeTick(); diff --git a/tests/include/action_test_node.h b/tests/include/action_test_node.h index f64975305..e5e0ef9ec 100644 --- a/tests/include/action_test_node.h +++ b/tests/include/action_test_node.h @@ -12,7 +12,7 @@ class SyncActionTest : public SyncActionNode BT::NodeStatus tick() override; - void setBoolean(bool boolean_value); + void setExpectedResult(NodeStatus res); int tickCount() const { @@ -25,14 +25,14 @@ class SyncActionTest : public SyncActionNode } private: - bool boolean_value_; + NodeStatus expected_result_; int tick_count_; }; class AsyncActionTest : public AsyncActionNode { public: - AsyncActionTest(const std::string& name, BT::Duration deadline_ms); + AsyncActionTest(const std::string& name, BT::Duration deadline_ms = std::chrono::milliseconds(100) ); ~AsyncActionTest(); @@ -44,7 +44,7 @@ class AsyncActionTest : public AsyncActionNode // The method used to interrupt the execution of the node virtual void halt() override; - void setBoolean(bool boolean_value); + void setExpectedResult(NodeStatus res); int tickCount() const { @@ -59,9 +59,9 @@ class AsyncActionTest : public AsyncActionNode private: // using atomic because these variables might be accessed from different threads BT::Duration time_; - std::atomic_bool boolean_value_; + std::atomic expected_result_; std::atomic tick_count_; - std::atomic_bool stop_loop_; + bool stop_loop_; }; } diff --git a/tests/include/condition_test_node.h b/tests/include/condition_test_node.h index ecc05ae00..03080504f 100644 --- a/tests/include/condition_test_node.h +++ b/tests/include/condition_test_node.h @@ -11,7 +11,7 @@ class ConditionTestNode : public ConditionNode ConditionTestNode(const std::string& name); - void setBoolean(bool boolean_value); + void setExpectedResult(NodeStatus res); // The method that is going to be executed by the thread virtual BT::NodeStatus tick() override; @@ -22,7 +22,7 @@ class ConditionTestNode : public ConditionNode } private: - bool boolean_value_; + NodeStatus expected_result_; int tick_count_; }; } diff --git a/tests/src/action_test_node.cpp b/tests/src/action_test_node.cpp index 4e0812a70..a36936f10 100644 --- a/tests/src/action_test_node.cpp +++ b/tests/src/action_test_node.cpp @@ -17,7 +17,7 @@ BT::AsyncActionTest::AsyncActionTest(const std::string& name, BT::Duration deadline_ms) : AsyncActionNode(name, {}) { - boolean_value_ = true; + expected_result_ = NodeStatus::SUCCESS; time_ = deadline_ms; stop_loop_ = false; tick_count_ = 0; @@ -32,7 +32,7 @@ BT::NodeStatus BT::AsyncActionTest::tick() { using std::chrono::high_resolution_clock; tick_count_++; - stop_loop_ = false; + auto initial_time = high_resolution_clock::now(); while (!stop_loop_ && high_resolution_clock::now() < initial_time + time_) @@ -40,14 +40,8 @@ BT::NodeStatus BT::AsyncActionTest::tick() std::this_thread::sleep_for(std::chrono::milliseconds(1)); } - if (!stop_loop_) - { - return boolean_value_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; - } - else - { - return NodeStatus::IDLE; - } + stop_loop_ = false; + return expected_result_; } void BT::AsyncActionTest::halt() @@ -60,9 +54,9 @@ void BT::AsyncActionTest::setTime(BT::Duration time) time_ = time; } -void BT::AsyncActionTest::setBoolean(bool boolean_value) +void BT::AsyncActionTest::setExpectedResult(BT::NodeStatus res) { - boolean_value_ = boolean_value; + expected_result_ = res; } //---------------------------------------------- @@ -71,16 +65,16 @@ BT::SyncActionTest::SyncActionTest(const std::string& name) : SyncActionNode(name, {}) { tick_count_ = 0; - boolean_value_ = true; + expected_result_ = NodeStatus::SUCCESS; } BT::NodeStatus BT::SyncActionTest::tick() { tick_count_++; - return boolean_value_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE; + return expected_result_; } -void BT::SyncActionTest::setBoolean(bool boolean_value) +void BT::SyncActionTest::setExpectedResult(NodeStatus res) { - boolean_value_ = boolean_value; + expected_result_ = res; } diff --git a/tests/src/condition_test_node.cpp b/tests/src/condition_test_node.cpp index f40b64c97..98f4b8d1c 100644 --- a/tests/src/condition_test_node.cpp +++ b/tests/src/condition_test_node.cpp @@ -16,28 +16,17 @@ BT::ConditionTestNode::ConditionTestNode(const std::string& name) : ConditionNode::ConditionNode(name, {}) { - boolean_value_ = true; + expected_result_ = NodeStatus::SUCCESS; tick_count_ = 0; } BT::NodeStatus BT::ConditionTestNode::tick() { tick_count_++; - - // Condition checking and state update - if (boolean_value_) - { - setStatus(NodeStatus::SUCCESS); - return NodeStatus::SUCCESS; - } - else - { - setStatus(NodeStatus::FAILURE); - return NodeStatus::FAILURE; - } + return expected_result_; } -void BT::ConditionTestNode::setBoolean(bool boolean_value) +void BT::ConditionTestNode::setExpectedResult(NodeStatus res) { - boolean_value_ = boolean_value; + expected_result_ = res; } From ba66795e990749840c27cafecc2476600111b44f Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Mar 2020 22:05:08 +0100 Subject: [PATCH 025/163] fix issue #141 --- sample_nodes/crossdoor_nodes.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/sample_nodes/crossdoor_nodes.cpp b/sample_nodes/crossdoor_nodes.cpp index 42d884069..1b37c8184 100644 --- a/sample_nodes/crossdoor_nodes.cpp +++ b/sample_nodes/crossdoor_nodes.cpp @@ -26,8 +26,11 @@ NodeStatus CrossDoor::IsDoorLocked() NodeStatus CrossDoor::UnlockDoor() { - SleepMS(2000); - _door_locked = false; + if( _door_locked ) + { + SleepMS(2000); + _door_locked = false; + } return NodeStatus::SUCCESS; } @@ -47,10 +50,10 @@ NodeStatus CrossDoor::OpenDoor() { if (_door_locked) { - SleepMS(2000); - _door_open = true; + return NodeStatus::FAILURE; } - + SleepMS(2000); + _door_open = true; return NodeStatus::SUCCESS; } From 92a6155896f636eb7631ac9a1b4e69f73e8a5ca1 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Mar 2020 22:58:29 +0100 Subject: [PATCH 026/163] Fix bug in default port values --- include/behaviortree_cpp_v3/basic_types.h | 8 ---- src/xml_parsing.cpp | 2 +- tests/CMakeLists.txt | 1 + tests/gtest_ports.cpp | 53 +++++++++++++++++++++++ 4 files changed, 55 insertions(+), 9 deletions(-) create mode 100644 tests/gtest_ports.cpp diff --git a/include/behaviortree_cpp_v3/basic_types.h b/include/behaviortree_cpp_v3/basic_types.h index 639487f0e..e6407a41b 100644 --- a/include/behaviortree_cpp_v3/basic_types.h +++ b/include/behaviortree_cpp_v3/basic_types.h @@ -296,14 +296,6 @@ template inline return out; } -template inline - std::pair OutputPort(StringView name, const T& default_value, StringView description) -{ - auto out = CreatePort(PortDirection::OUTPUT, name, description ); - out.second.setDefaultValue( BT::toStr(default_value) ); - return out; -} - template inline std::pair BidirectionalPort(StringView name, const T& default_value, StringView description) { diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 6ec962abe..955e5f504 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -569,7 +569,7 @@ TreeNode::Ptr XMLParser::Pimpl::createNodeFromXML(const XMLElement *element, const PortInfo& port_info = port_it.second; auto direction = port_info.direction(); - if( direction != PortDirection::INPUT && + if( direction != PortDirection::OUTPUT && config.input_ports.count(port_name) == 0 && port_info.defaultValue().empty() == false) { diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 4a3e6200f..0245d6337 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_ports.cpp navigation_test.cpp gtest_subtree.cpp gtest_switch.cpp diff --git a/tests/gtest_ports.cpp b/tests/gtest_ports.cpp new file mode 100644 index 000000000..6b79b12a7 --- /dev/null +++ b/tests/gtest_ports.cpp @@ -0,0 +1,53 @@ +#include +#include "behaviortree_cpp_v3/bt_factory.h" + +using namespace BT; + +class NodeWithPorts: public SyncActionNode +{ + public: + NodeWithPorts(const std::string & name, const NodeConfiguration & config) + : SyncActionNode(name, config) + { + std::cout << "ctor" << std::endl; + } + + NodeStatus tick() + { + int val_A = 0; + int val_B = 0; + if( getInput("in_port_A", val_A) && + getInput("in_port_B", val_B) && + val_A == 42 && val_B == 66) + { + return NodeStatus::SUCCESS; + } + return NodeStatus::FAILURE; + } + + static PortsList providedPorts() + { + return { BT::InputPort("in_port_A", 42, "magic_number"), + BT::InputPort("in_port_B") }; + } +}; + +TEST(PortTest, DefaultPorts) +{ + std::string xml_txt = R"( + + + + + )"; + + BehaviorTreeFactory factory; + factory.registerNodeType("NodeWithPorts"); + + auto tree = factory.createTreeFromText(xml_txt); + + NodeStatus status = tree.root_node->executeTick(); + ASSERT_EQ( status, NodeStatus::SUCCESS ); + +} + From 10f1c39e3cb779f6a537fae2c567ed42f074869b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Mar 2020 23:02:01 +0100 Subject: [PATCH 027/163] 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 6ee45753f..46d06b980 100644 --- a/include/behaviortree_cpp_v3/action_node.h +++ b/include/behaviortree_cpp_v3/action_node.h @@ -149,11 +149,11 @@ class AsyncActionNode : public ActionNodeBase * if the reply has been received and, eventually, analyze the reply to determine * if the result is SUCCESS or FAILURE. * - * -) an IDLE action will call onStart() + * -) an action that was in IDLE state will call onStart() * * -) A RUNNING action will call onRunning() * - * -) if halted, method onHalted() + * -) if halted, method onHalted() is invoked */ class StatefulActionNode : public ActionNodeBase { From 23e19127bd4bdfa9f1d502702cc4f82be89319c2 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Mar 2020 23:06:11 +0100 Subject: [PATCH 028/163] comments --- 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 46d06b980..237494eae 100644 --- a/include/behaviortree_cpp_v3/action_node.h +++ b/include/behaviortree_cpp_v3/action_node.h @@ -174,8 +174,8 @@ class StatefulActionNode : public ActionNodeBase /// method invoked by a RUNNING action. virtual NodeStatus onRunning() = 0; - /// when the method halt() is called by a parent node, this method - /// is invoked to do the cleanup of a RUNNING action. + /// when the method halt() is called and the action is RUNNING, this method is invoked. + /// This is a convenient place todo a cleanup, if needed. virtual void onHalted() = 0; }; From ad78acbed7390c8996a476977cde75e0679eba1d Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Wed, 18 Mar 2020 23:49:37 +0100 Subject: [PATCH 029/163] fix warning --- src/controls/reactive_fallback.cpp | 2 +- src/controls/reactive_sequence.cpp | 2 +- src/controls/sequence_star_node.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/controls/reactive_fallback.cpp b/src/controls/reactive_fallback.cpp index 700a76046..2a38a56d5 100644 --- a/src/controls/reactive_fallback.cpp +++ b/src/controls/reactive_fallback.cpp @@ -28,7 +28,7 @@ NodeStatus ReactiveFallback::tick() { case NodeStatus::RUNNING: { - for(int i=index+1; i < childrenCount(); i++) + for(size_t i=index+1; i < childrenCount(); i++) { haltChild(i); } diff --git a/src/controls/reactive_sequence.cpp b/src/controls/reactive_sequence.cpp index 340b43ad9..be5a8f472 100644 --- a/src/controls/reactive_sequence.cpp +++ b/src/controls/reactive_sequence.cpp @@ -31,7 +31,7 @@ NodeStatus ReactiveSequence::tick() { running_count++; - for(int i=index+1; i < childrenCount(); i++) + for(size_t i=index+1; i < childrenCount(); i++) { haltChild(i); } diff --git a/src/controls/sequence_star_node.cpp b/src/controls/sequence_star_node.cpp index e0363501d..784341697 100644 --- a/src/controls/sequence_star_node.cpp +++ b/src/controls/sequence_star_node.cpp @@ -43,7 +43,7 @@ NodeStatus SequenceStarNode::tick() case NodeStatus::FAILURE: { // DO NOT reset current_child_idx_ on failure - for(int i=current_child_idx_; i < childrenCount(); i++) + for(size_t i=current_child_idx_; i < childrenCount(); i++) { haltChild(i); } From 4f30e3a42ff0c657eb5711d7ae94318fde93bd60 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Mar 2020 00:13:28 +0100 Subject: [PATCH 030/163] [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. --- include/behaviortree_cpp_v3/bt_factory.h | 15 +++++++++++++++ include/behaviortree_cpp_v3/condition_node.h | 1 - include/behaviortree_cpp_v3/tree_node.h | 7 +++++-- src/action_node.cpp | 1 - src/decorators/timeout_node.cpp | 3 +-- 5 files changed, 21 insertions(+), 6 deletions(-) diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index 77a6051e9..57be7243c 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -154,6 +154,21 @@ struct Tree return *this; } + void haltTree() + { + // the halt should propagate to all the node if all the nodes + // are implemented correctly + root_node->halt(); + root_node->setStatus(NodeStatus::IDLE); + + //but, just in case.... this should be no-op + auto visitor = [](BT::TreeNode * node) { + node->halt(); + node->setStatus(BT::NodeStatus::IDLE); + }; + BT::applyRecursiveVisitor(root_node, visitor); + } + ~Tree(); Blackboard::Ptr rootBlackboard(); diff --git a/include/behaviortree_cpp_v3/condition_node.h b/include/behaviortree_cpp_v3/condition_node.h index 86e7b1048..516b83806 100644 --- a/include/behaviortree_cpp_v3/condition_node.h +++ b/include/behaviortree_cpp_v3/condition_node.h @@ -28,7 +28,6 @@ class ConditionNode : public LeafNode //Do nothing virtual void halt() override final { - // just in case, but it should not be needed setStatus(NodeStatus::IDLE); } diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index 179244d91..7d94f6eb3 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -80,8 +80,6 @@ class TreeNode NodeStatus status() const; - void setStatus(NodeStatus new_status); - /// Name of the instance, not the type const std::string& name() const; @@ -153,6 +151,9 @@ class TreeNode virtual BT::NodeStatus tick() = 0; friend class BehaviorTreeFactory; + friend class DecoratorNode; + friend class ControlNode; + friend class Tree; // Only BehaviorTreeFactory should call this void setRegistrationID(StringView ID) @@ -162,6 +163,8 @@ class TreeNode void modifyPortsRemapping(const PortsRemapping& new_remapping); + void setStatus(NodeStatus new_status); + private: const std::string name_; diff --git a/src/action_node.cpp b/src/action_node.cpp index 770b2b529..d2e370679 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -169,7 +169,6 @@ struct CoroActionNode::Pimpl { coroutine::routine_t coro; std::atomic pending_destroy; - }; diff --git a/src/decorators/timeout_node.cpp b/src/decorators/timeout_node.cpp index c59959cf5..7b96840bd 100644 --- a/src/decorators/timeout_node.cpp +++ b/src/decorators/timeout_node.cpp @@ -61,8 +61,7 @@ NodeStatus TimeoutNode::tick() if (!aborted && child()->status() == NodeStatus::RUNNING) { child_halted_ = true; - child()->halt(); - child()->setStatus(NodeStatus::IDLE); + haltChild(); } }); } From 2a1e581b6bb4a25a3d80a30aee72a03d736d364b Mon Sep 17 00:00:00 2001 From: Sebastian Ahlman Date: Thu, 19 Mar 2020 12:30:56 +0200 Subject: [PATCH 031/163] MSVC2015 seems to need an explicit operator== for comparing against literal strings. --- include/behaviortree_cpp_v3/utils/string_view.hpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/include/behaviortree_cpp_v3/utils/string_view.hpp b/include/behaviortree_cpp_v3/utils/string_view.hpp index bcf05d67c..1b1d923b2 100644 --- a/include/behaviortree_cpp_v3/utils/string_view.hpp +++ b/include/behaviortree_cpp_v3/utils/string_view.hpp @@ -891,6 +891,14 @@ nssv_constexpr bool operator== ( 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; +} + template< class CharT, class Traits > nssv_constexpr bool operator!= ( basic_string_view lhs, From f15b8c7869a523896b0dae92a90a801e4487b4cb Mon Sep 17 00:00:00 2001 From: Sebastian Ahlman Date: Thu, 19 Mar 2020 12:31:55 +0200 Subject: [PATCH 032/163] The __cplusplus macro does not work properly prior to MSVC2017 15.7 Preview 3: https://devblogs.microsoft.com/cppblog/msvc-now-correctly-reports-__cplusplus/ --- include/behaviortree_cpp_v3/utils/make_unique.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/behaviortree_cpp_v3/utils/make_unique.hpp b/include/behaviortree_cpp_v3/utils/make_unique.hpp index ced59eb03..175974e88 100644 --- a/include/behaviortree_cpp_v3/utils/make_unique.hpp +++ b/include/behaviortree_cpp_v3/utils/make_unique.hpp @@ -2,7 +2,7 @@ #include -#if defined(_MSC_VER) && __cplusplus == 201103L +#if defined(_MSC_VER) && _MSC_VER >= 1900 // MSVC 2015 or newer. # define MAKE_UNIQUE_DEFINED 1 #endif From c036482969f4d05777a3047590569da2c4f42930 Mon Sep 17 00:00:00 2001 From: Sebastian Ahlman Date: Thu, 19 Mar 2020 13:31:44 +0200 Subject: [PATCH 033/163] Tree is declared as a struct, so it needs to be forward-declared as a struct too. --- include/behaviortree_cpp_v3/tree_node.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index 7d94f6eb3..272a89742 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -153,7 +153,7 @@ class TreeNode friend class BehaviorTreeFactory; friend class DecoratorNode; friend class ControlNode; - friend class Tree; + friend struct Tree; // Only BehaviorTreeFactory should call this void setRegistrationID(StringView ID) From f97f87f4566cde22ae55d38a497316aacbea1df3 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Mar 2020 14:08:07 +0100 Subject: [PATCH 034/163] (issue #163) fix ded code --- src/xml_parsing.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 955e5f504..bea5be4c6 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -321,12 +321,13 @@ void VerifyXML(const std::string& xml_text, } else if (StrEqual(name, "SubTree")) { - for (auto child = node->FirstChildElement(); child != nullptr; - child = child->NextSiblingElement()) + auto child = node->FirstChildElement(); + + if (child) { - if( StrEqual(child->Name(), "remap") ) + if (StrEqual(child->Name(), "remap")) { - ThrowError(node->GetLineNum(), " was deprecated"); + ThrowError(node->GetLineNum(), " was deprecated"); } else{ ThrowError(node->GetLineNum(), " should not have any child"); From 8b32ed7a5268edced9946e93292888b3220bb7f0 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Mar 2020 21:49:27 +0100 Subject: [PATCH 035/163] Fix documentation (noted in issue #116) --- docs/tutorial_04_sequence_star.md | 8 +++++--- include/behaviortree_cpp_v3/bt_factory.h | 4 ++-- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/docs/tutorial_04_sequence_star.md b/docs/tutorial_04_sequence_star.md index 6d478ac18..c0c3ea3fd 100644 --- a/docs/tutorial_04_sequence_star.md +++ b/docs/tutorial_04_sequence_star.md @@ -156,9 +156,11 @@ would be _interrupted_ (_halted_, to be specific). - - - + + + + + diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index 57be7243c..f20653e34 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -156,8 +156,8 @@ struct Tree void haltTree() { - // the halt should propagate to all the node if all the nodes - // are implemented correctly + // the halt should propagate to all the node if the nodes + // have been implemented correctly root_node->halt(); root_node->setStatus(NodeStatus::IDLE); From cdfe773a1fcf9ec9cb84236a2c784db89b962f60 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Mar 2020 21:57:23 +0100 Subject: [PATCH 036/163] Fix issue #140 --- .../loggers/bt_zmq_publisher.h | 5 ++++- src/loggers/bt_zmq_publisher.cpp | 17 ++++++++++++++--- 2 files changed, 18 insertions(+), 4 deletions(-) diff --git a/include/behaviortree_cpp_v3/loggers/bt_zmq_publisher.h b/include/behaviortree_cpp_v3/loggers/bt_zmq_publisher.h index 1f64f2c92..59bc259b1 100644 --- a/include/behaviortree_cpp_v3/loggers/bt_zmq_publisher.h +++ b/include/behaviortree_cpp_v3/loggers/bt_zmq_publisher.h @@ -13,7 +13,10 @@ class PublisherZMQ : public StatusChangeLogger static std::atomic ref_count; public: - PublisherZMQ(const BT::Tree& tree, int max_msg_per_second = 25); + PublisherZMQ(const BT::Tree& tree, + unsigned max_msg_per_second = 25, + unsigned publisher_port = 1666, + unsigned server_port = 1667); virtual ~PublisherZMQ(); diff --git a/src/loggers/bt_zmq_publisher.cpp b/src/loggers/bt_zmq_publisher.cpp index 6c19d27bf..2cde945ca 100644 --- a/src/loggers/bt_zmq_publisher.cpp +++ b/src/loggers/bt_zmq_publisher.cpp @@ -21,7 +21,10 @@ struct PublisherZMQ::Pimpl }; -PublisherZMQ::PublisherZMQ(const BT::Tree& tree, int max_msg_per_second) +PublisherZMQ::PublisherZMQ(const BT::Tree& tree, + unsigned max_msg_per_second, + unsigned publisher_port, + unsigned server_port) : StatusChangeLogger(tree.root_node) , tree_(tree) , min_time_between_msgs_(std::chrono::microseconds(1000 * 1000) / max_msg_per_second) @@ -33,6 +36,10 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, int max_msg_per_second) { throw LogicError("Only one instance of PublisherZMQ shall be created"); } + if( publisher_port == server_port) + { + throw LogicError("The TCP ports of the publisher and the server must be different"); + } flatbuffers::FlatBufferBuilder builder(1024); CreateFlatbuffersBehaviorTree(builder, tree); @@ -40,8 +47,12 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, int max_msg_per_second) tree_buffer_.resize(builder.GetSize()); memcpy(tree_buffer_.data(), builder.GetBufferPointer(), builder.GetSize()); - zmq_->publisher.bind("tcp://*:1666"); - zmq_->server.bind("tcp://*:1667"); + char str[100]; + + sprintf(str, "tcp://*:%d", publisher_port); + zmq_->publisher.bind(str); + sprintf(str, "tcp://*:%d", server_port); + zmq_->server.bind(str); int timeout_ms = 100; zmq_->server.setsockopt(ZMQ_RCVTIMEO, &timeout_ms, sizeof(int)); From 7129fda16fd9f73c59505cac5082edf6b72fb5f7 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Mar 2020 22:44:40 +0100 Subject: [PATCH 037/163] update documentation (issue #148) --- docs/tutorial_05_subtrees.md | 5 +++++ examples/t05_crossdoor.cpp | 13 +++++++++---- 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/docs/tutorial_05_subtrees.md b/docs/tutorial_05_subtrees.md index 39c071624..ab5e3d55a 100644 --- a/docs/tutorial_05_subtrees.md +++ b/docs/tutorial_05_subtrees.md @@ -96,6 +96,11 @@ int main() // This logger stores the execution time of each node MinitraceLogger logger_minitrace(tree.root_node, "bt_trace.json"); +#ifdef ZMQ_INSTALLED + // This logger publish status changes using ZeroMQ. Used by Groot + PublisherZMQ publisher_zmq(tree); +#endif + printTreeRecursively(tree.root_node); //while (1) diff --git a/examples/t05_crossdoor.cpp b/examples/t05_crossdoor.cpp index 6d73fe5ef..02314fbb7 100644 --- a/examples/t05_crossdoor.cpp +++ b/examples/t05_crossdoor.cpp @@ -3,10 +3,9 @@ #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 +#ifdef ZMQ_INSTALLED #include "behaviortree_cpp_v3/loggers/bt_zmq_publisher.h" #endif @@ -68,11 +67,17 @@ int main(int argc, char** argv) // Important: when the object tree goes out of scope, all the TreeNodes are destroyed auto tree = factory.createTreeFromText(xml_text); - // Create some loggers + // This logger prints state changes on console StdCoutLogger logger_cout(tree); - MinitraceLogger logger_minitrace(tree, "bt_trace.json"); + + // 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 From d62c75819cad6b2f01741db8e46991a5a045edd1 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Mar 2020 22:49:50 +0100 Subject: [PATCH 038/163] doc fix --- docs/tutorial_05_subtrees.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/tutorial_05_subtrees.md b/docs/tutorial_05_subtrees.md index ab5e3d55a..f87a97934 100644 --- a/docs/tutorial_05_subtrees.md +++ b/docs/tutorial_05_subtrees.md @@ -96,7 +96,7 @@ int main() // This logger stores the execution time of each node MinitraceLogger logger_minitrace(tree.root_node, "bt_trace.json"); -#ifdef ZMQ_INSTALLED +#ifdef ZMQ_FOUND // This logger publish status changes using ZeroMQ. Used by Groot PublisherZMQ publisher_zmq(tree); #endif From a472bade0588b1b18cb75c7932d5148c07af1763 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Thu, 19 Mar 2020 22:52:10 +0100 Subject: [PATCH 039/163] revert definition name --- examples/t05_crossdoor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/t05_crossdoor.cpp b/examples/t05_crossdoor.cpp index 02314fbb7..cd850771e 100644 --- a/examples/t05_crossdoor.cpp +++ b/examples/t05_crossdoor.cpp @@ -5,7 +5,7 @@ #include "behaviortree_cpp_v3/loggers/bt_file_logger.h" #include "behaviortree_cpp_v3/bt_factory.h" -#ifdef ZMQ_INSTALLED +#ifdef ZMQ_FOUND #include "behaviortree_cpp_v3/loggers/bt_zmq_publisher.h" #endif From 02330ac036621f7ad3c169abde88525ff5463463 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 01:22:01 +0100 Subject: [PATCH 040/163] Boost coroutine (#164) Remove the faulty coroutine that created significant problems in favour of boost::coroutine2 (use older boost::coroutine as a fallback). --- 3rdparty/coroutine/LICENSE | 201 -------------- 3rdparty/coroutine/README.md | 99 ------- 3rdparty/coroutine/coroutine.h | 471 --------------------------------- CMakeLists.txt | 21 +- src/action_node.cpp | 58 ++-- tests/gtest_coroutines.cpp | 25 ++ 6 files changed, 68 insertions(+), 807 deletions(-) delete mode 100644 3rdparty/coroutine/LICENSE delete mode 100644 3rdparty/coroutine/README.md delete mode 100644 3rdparty/coroutine/coroutine.h diff --git a/3rdparty/coroutine/LICENSE b/3rdparty/coroutine/LICENSE deleted file mode 100644 index 8dada3eda..000000000 --- a/3rdparty/coroutine/LICENSE +++ /dev/null @@ -1,201 +0,0 @@ - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "{}" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright {yyyy} {name of copyright owner} - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. diff --git a/3rdparty/coroutine/README.md b/3rdparty/coroutine/README.md deleted file mode 100644 index 721a457e5..000000000 --- a/3rdparty/coroutine/README.md +++ /dev/null @@ -1,99 +0,0 @@ -# C++11 single .h asymmetric coroutine implementation - -### API - -in namespace coroutine: -* routine_t create(std::function f); -* void destroy(routine_t id); -* int resume(routine_t id); -* void yield(); -* TYPE await(TYPE(*f)()); -* routine_t current(); -* class Channel with push()/pop(); - -### OS - -* Linux -* macOS -* Windows - -### Demo - -```cpp -#include "coroutine.h" -#include -#include - -coroutine::Channel channel; - -string async_func() -{ - std::this_thread::sleep_for(std::chrono::milliseconds(3000)); - return "22"; -} - -void routine_func1() -{ - int i = channel.pop(); - std::cout << i << std::endl; - - i = channel.pop(); - std::cout << i << std::endl; -} - -void routine_func2(int i) -{ - std::cout << "20" << std::endl; - coroutine::yield(); - - std::cout << "21" << std::endl; - - //run function async - //yield current routine if result not returned - string str = coroutine::await(async_func); - std::cout << str << std::endl; -} - -void thread_func() -{ - //create routine with callback like std::function - coroutine::routine_t rt1 = coroutine::create(routine_func1); - coroutine::routine_t rt2 = coroutine::create(std::bind(routine_func2, 2)); - - std::cout << "00" << std::endl; - coroutine::resume(rt1); - - std::cout << "01" << std::endl; - coroutine::resume(rt2); - - std::cout << "02" << std::endl; - channel.push(10); - - std::cout << "03" << std::endl; - coroutine::resume(rt2); - - std::cout << "04" << std::endl; - channel.push(11); - - std::cout << "05" << std::endl; - - std::this_thread::sleep_for(std::chrono::milliseconds(6000)); - coroutine::resume(rt2); - - //destroy routine, free resouce allocated - //Warning: don't destroy routine by itself - coroutine::destroy(rt1); - coroutine::destroy(rt2); -} - -int main() -{ - std::thread t1(thread_func); - std::thread t2([](){ - //unsupport coordinating routine crossing threads - }); - t1.join(); - t2.join(); - return 0; -} -``` \ No newline at end of file diff --git a/3rdparty/coroutine/coroutine.h b/3rdparty/coroutine/coroutine.h deleted file mode 100644 index 3b3929e64..000000000 --- a/3rdparty/coroutine/coroutine.h +++ /dev/null @@ -1,471 +0,0 @@ -/* - * Licensed to the Apache Software Foundation (ASF) under one - * or more contributor license agreements. See the NOTICE file - * distributed with this work for additional information - * regarding copyright ownership. The ASF licenses this file - * to you under the Apache License, Version 2.0 (the - * "License"); you may not use this file except in compliance - * with the License. You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, - * software distributed under the License is distributed on an - * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY - * KIND, either express or implied. See the License for the - * specific language governing permissions and limitations - * under the License. - */ - -#ifndef STDEX_COROUTINE_H_ -#define STDEX_COROUTINE_H_ - -#ifndef STACK_LIMIT -#define STACK_LIMIT (1024 * 1024) -#endif - -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -using ::std::string; -using ::std::wstring; - -#ifdef _WIN32 -#include -#else -#if defined(__APPLE__) && defined(__MACH__) -#define _XOPEN_SOURCE -#include -#else -#include -#endif -#endif - -namespace coroutine -{ -typedef unsigned routine_t; - -enum class ResumeResult -{ - INVALID = -1, - FINISHED = -2, - YIELD = 0 -}; - -#ifdef _WIN32 - -struct Routine -{ - std::function func; - bool finished; - LPVOID fiber; - - Routine(std::function f) - { - func = f; - finished = false; - fiber = nullptr; - } - - ~Routine() - { - DeleteFiber(fiber); - } -}; - -struct Ordinator -{ - std::vector routines; - std::list indexes; - routine_t current; - size_t stack_size; - LPVOID fiber; - - Ordinator(size_t ss = STACK_LIMIT) - { - current = 0; - stack_size = ss; - fiber = ConvertThreadToFiber(nullptr); - } - - ~Ordinator() - { - for (auto& routine : routines) - delete routine; - } -}; - -thread_local static Ordinator ordinator; - -inline routine_t create(std::function f) -{ - Routine* routine = new Routine(f); - - if (ordinator.indexes.empty()) - { - ordinator.routines.push_back(routine); - return (routine_t)ordinator.routines.size(); - } - else - { - routine_t id = ordinator.indexes.front(); - ordinator.indexes.pop_front(); - assert(ordinator.routines[id - 1] == nullptr); - ordinator.routines[id - 1] = routine; - return id; - } -} - -inline void destroy(routine_t id) -{ - Routine* routine = ordinator.routines[id - 1]; - assert(routine != nullptr); - - delete routine; - ordinator.routines[id - 1] = nullptr; - ordinator.indexes.push_back(id); -} - -inline void __stdcall entry(LPVOID) -{ - routine_t id = ordinator.current; - Routine* routine = ordinator.routines[id - 1]; - assert(routine != nullptr); - - routine->func(); - - routine->finished = true; - ordinator.current = 0; - - SwitchToFiber(ordinator.fiber); -} - -inline ResumeResult resume(routine_t id) -{ - assert(ordinator.current == 0); - - Routine* routine = ordinator.routines[id - 1]; - if (routine == nullptr) - return ResumeResult::INVALID; - - if (routine->finished) - return ResumeResult::FINISHED; - - if (routine->fiber == nullptr) - { - routine->fiber = CreateFiber(ordinator.stack_size, entry, 0); - ordinator.current = id; - SwitchToFiber(routine->fiber); - } - else - { - ordinator.current = id; - SwitchToFiber(routine->fiber); - } - - return routine->finished ? ResumeResult::FINISHED : ResumeResult::YIELD; -} - -inline void yield() -{ - routine_t id = ordinator.current; - Routine* routine = ordinator.routines[id - 1]; - if (routine == nullptr) - { - throw std::runtime_error("Error in yield of coroutine"); - } - - ordinator.current = 0; - SwitchToFiber(ordinator.fiber); -} - -inline routine_t current() -{ - return ordinator.current; -} - -#if 0 -template -inline typename std::result_of::type -await(Function &&func) -{ - auto future = std::async(std::launch::async, func); - std::future_status status = future.wait_for(std::chrono::milliseconds(0)); - - while (status == std::future_status::timeout) - { - if (ordinator.current != 0) - yield(); - - status = future.wait_for(std::chrono::milliseconds(0)); - } - return future.get(); -} -#endif - -#if 1 -template -inline std::result_of_t()> await(Function&& func) -{ - auto future = std::async(std::launch::async, func); - std::future_status status = future.wait_for(std::chrono::milliseconds(0)); - - while (status == std::future_status::timeout) - { - if (ordinator.current != 0) - yield(); - - status = future.wait_for(std::chrono::milliseconds(0)); - } - return future.get(); -} -#endif - -#else - -struct Routine -{ - std::function func; - char* stack; - bool finished; - ucontext_t ctx; - - Routine(std::function f) - { - func = f; - stack = nullptr; - finished = false; - } - - ~Routine() - { - delete[] stack; - } -}; - -struct Ordinator -{ - std::vector routines; - std::list indexes; - routine_t current; - size_t stack_size; - ucontext_t ctx; - - inline Ordinator(size_t ss = STACK_LIMIT) - { - current = 0; - stack_size = ss; - } - - inline ~Ordinator() - { - for (auto& routine : routines) - delete routine; - } -}; - -thread_local static Ordinator ordinator; - -inline routine_t create(std::function f) -{ - Routine* routine = new Routine(f); - - if (ordinator.indexes.empty()) - { - ordinator.routines.push_back(routine); - return ordinator.routines.size(); - } - else - { - routine_t id = ordinator.indexes.front(); - ordinator.indexes.pop_front(); - assert(ordinator.routines[id - 1] == nullptr); - ordinator.routines[id - 1] = routine; - return id; - } -} - -inline void destroy(routine_t id) -{ - Routine* routine = ordinator.routines[id - 1]; - assert(routine != nullptr); - - delete routine; - ordinator.routines[id - 1] = nullptr; -} - -inline void entry() -{ - routine_t id = ordinator.current; - Routine* routine = ordinator.routines[id - 1]; - routine->func(); - - routine->finished = true; - ordinator.current = 0; - ordinator.indexes.push_back(id); -} - -inline ResumeResult resume(routine_t id) -{ - assert(ordinator.current == 0); - - Routine* routine = ordinator.routines[id - 1]; - if (routine == nullptr) - return ResumeResult::INVALID; - - if (routine->finished) - return ResumeResult::FINISHED; - - if (routine->stack == nullptr) - { - //initializes the structure to the currently active context. - //When successful, getcontext() returns 0 - //On error, return -1 and set errno appropriately. - getcontext(&routine->ctx); - - //Before invoking makecontext(), the caller must allocate a new stack - //for this context and assign its address to ucp->uc_stack, - //and define a successor context and assign its address to ucp->uc_link. - routine->stack = new char[ordinator.stack_size]; - routine->ctx.uc_stack.ss_sp = routine->stack; - routine->ctx.uc_stack.ss_size = ordinator.stack_size; - routine->ctx.uc_link = &ordinator.ctx; - ordinator.current = id; - - //When this context is later activated by swapcontext(), the function entry is called. - //When this function returns, the successor context is activated. - //If the successor context pointer is NULL, the thread exits. - makecontext(&routine->ctx, reinterpret_cast(entry), 0); - - //The swapcontext() function saves the current context, - //and then activates the context of another. - swapcontext(&ordinator.ctx, &routine->ctx); - } - else - { - ordinator.current = id; - swapcontext(&ordinator.ctx, &routine->ctx); - } - - return routine->finished ? ResumeResult::FINISHED : ResumeResult::YIELD; -} - -inline void yield() -{ - routine_t id = ordinator.current; - Routine* routine = ordinator.routines[id - 1]; - assert(routine != nullptr); - - char* stack_top = routine->stack + ordinator.stack_size; - char stack_bottom = 0; - assert(size_t(stack_top - &stack_bottom) <= ordinator.stack_size); - - ordinator.current = 0; - swapcontext(&routine->ctx, &ordinator.ctx); -} - -inline routine_t current() -{ - return ordinator.current; -} - -template -inline typename std::result_of::type await(Function&& func) -{ - auto future = std::async(std::launch::async, func); - std::future_status status = future.wait_for(std::chrono::milliseconds(0)); - - while (status == std::future_status::timeout) - { - if (ordinator.current != 0) - yield(); - - status = future.wait_for(std::chrono::milliseconds(0)); - } - return future.get(); -} - -#endif - -template -class Channel -{ - public: - Channel() - { - _taker = 0; - } - - Channel(routine_t id) - { - _taker = id; - } - - inline void consumer(routine_t id) - { - _taker = id; - } - - inline void push(const Type& obj) - { - _list.push_back(obj); - if (_taker && _taker != current()) - resume(_taker); - } - - inline void push(Type&& obj) - { - _list.push_back(std::move(obj)); - if (_taker && _taker != current()) - resume(_taker); - } - - inline Type pop() - { - if (!_taker) - _taker = current(); - - while (_list.empty()) - yield(); - - Type obj = std::move(_list.front()); - _list.pop_front(); - return std::move(obj); - } - - inline void clear() - { - _list.clear(); - } - - inline void touch() - { - if (_taker && _taker != current()) - resume(_taker); - } - - inline size_t size() - { - return _list.size(); - } - - inline bool empty() - { - return _list.empty(); - } - - private: - std::list _list; - routine_t _taker; -}; - -} // namespace coroutine -#endif //STDEX_COROUTINE_H_ diff --git a/CMakeLists.txt b/CMakeLists.txt index b5f02fa60..c860ab7d0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,10 +12,24 @@ if(MSVC) add_definitions(-D_CRT_SECURE_NO_WARNINGS) endif() -if( MINGW ) - add_definitions(-DBT_NO_COROUTINES) +find_package(Boost COMPONENTS coroutine2 QUIET) + +if(Boost_FOUND) + include_directories(${Boost_INCLUDE_DIRS}) + message(STATUS "Found boost::coroutine2.") + add_definitions(-DBT_BOOST_COROUTINE2) +else() + find_package(Boost COMPONENTS coroutine QUIET) + if(Boost_FOUND) + message(STATUS "Found boost::coroutine.") + include_directories(${Boost_INCLUDE_DIRS}) + add_definitions(-DBT_BOOST_COROUTINE) + else() + add_definitions(-DBT_NO_COROUTINES) + endif() endif() + set(CMAKE_POSITION_INDEPENDENT_CODE ON) set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake") @@ -33,7 +47,8 @@ find_package(ZMQ) list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${CMAKE_THREAD_LIBS_INIT} - ${CMAKE_DL_LIBS} ) + ${CMAKE_DL_LIBS} + ${Boost_LIBRARIES} ) if( ZMQ_FOUND ) message(STATUS "ZeroMQ found.") diff --git a/src/action_node.cpp b/src/action_node.cpp index d2e370679..c1c43e01d 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -163,71 +163,63 @@ NodeStatus SyncActionNode::executeTick() //------------------------------------- #ifndef BT_NO_COROUTINES -#include "coroutine/coroutine.h" + +#ifdef BT_BOOST_COROUTINE2 +#include +using namespace boost::coroutines2; +#endif + +#ifdef BT_BOOST_COROUTINE +#include +using namespace boost::coroutines; +#endif struct CoroActionNode::Pimpl { - coroutine::routine_t coro; - std::atomic pending_destroy; + std::unique_ptr::pull_type> coro; + std::function::push_type & yield)> func; + coroutine::push_type * yield_ptr; }; - CoroActionNode::CoroActionNode(const std::string &name, const NodeConfiguration& config): - ActionNodeBase (name, config), - _p(new Pimpl) + ActionNodeBase (name, config), _p( new Pimpl) { - _p->coro = 0; - _p->pending_destroy = false; + _p->func = [this](coroutine::push_type & yield) { + _p->yield_ptr = &yield; + setStatus(tick()); + }; } CoroActionNode::~CoroActionNode() { - if( _p->coro != 0 ) - { - coroutine::destroy(_p->coro); - } } void CoroActionNode::setStatusRunningAndYield() { setStatus( NodeStatus::RUNNING ); - coroutine::yield(); + (*_p->yield_ptr)(); } NodeStatus CoroActionNode::executeTick() { - if( _p->pending_destroy && _p->coro != 0 ) + if( !(_p->coro) || !(*_p->coro) ) { - coroutine::destroy(_p->coro); - _p->coro = 0; - _p->pending_destroy = false; + _p->coro.reset( new coroutine::pull_type(_p->func) ); + return status(); } - if ( _p->coro == 0) + if( status() == NodeStatus::RUNNING && (bool)_p->coro ) { - _p->coro = coroutine::create( [this]() - { - setStatus(tick()); - } ); + (*_p->coro)(); } - if( _p->coro != 0 ) - { - if( _p->pending_destroy || - coroutine::resume(_p->coro) == coroutine::ResumeResult::FINISHED ) - { - coroutine::destroy(_p->coro); - _p->coro = 0; - _p->pending_destroy = false; - } - } return status(); } void CoroActionNode::halt() { - _p->pending_destroy = true; + _p->coro.reset(); } #endif diff --git a/tests/gtest_coroutines.cpp b/tests/gtest_coroutines.cpp index a0e1c3642..77364856f 100644 --- a/tests/gtest_coroutines.cpp +++ b/tests/gtest_coroutines.cpp @@ -1,6 +1,7 @@ #include "behaviortree_cpp_v3/decorators/timeout_node.h" #include "behaviortree_cpp_v3/behavior_tree.h" #include +#include #include using namespace std::chrono; @@ -146,6 +147,30 @@ TEST(CoroTest, sequence_child) EXPECT_EQ(BT::NodeStatus::FAILURE, executeWhileRunning(timeout) ) << "should timeout"; EXPECT_FALSE( actionA.wasHalted() ); EXPECT_TRUE( actionB.wasHalted() ); +} +TEST(CoroTest, OtherThreadHalt) +{ + BT::NodeConfiguration node_config_; + node_config_.blackboard = BT::Blackboard::create(); + BT::assignDefaultRemapping(node_config_); + + SimpleCoroAction actionA( milliseconds(200), false, "action_A", node_config_); + actionA.executeTick(); + + std::cout << "----- 1 ------ " << std::endl; + auto handle = std::async(std::launch::async, [&](){ + actionA.halt(); + }); + handle.wait(); + std::cout << "----- 2 ------ " << std::endl; + EXPECT_TRUE( actionA.wasHalted() ); + + std::cout << "----- 3------ " << std::endl; + handle = std::async(std::launch::async, [&](){ + actionA.executeTick(); + }); + handle.wait(); + std::cout << "----- 4 ------ " << std::endl; } From 5e8e2da2d93139fdf5f5d188e6dedf4e8180cf15 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 12:10:20 +0100 Subject: [PATCH 041/163] fix compilation and unit tests --- CMakeLists.txt | 3 ++- examples/CMakeLists.txt | 2 +- tests/CMakeLists.txt | 2 +- tests/navigation_test.cpp | 24 ++++++++++++++++-------- 4 files changed, 20 insertions(+), 11 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c860ab7d0..778fcc95e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -18,18 +18,19 @@ if(Boost_FOUND) include_directories(${Boost_INCLUDE_DIRS}) message(STATUS "Found boost::coroutine2.") add_definitions(-DBT_BOOST_COROUTINE2) + set(BT_COROUTINES true) else() find_package(Boost COMPONENTS coroutine QUIET) if(Boost_FOUND) message(STATUS "Found boost::coroutine.") include_directories(${Boost_INCLUDE_DIRS}) add_definitions(-DBT_BOOST_COROUTINE) + set(BT_COROUTINES true) else() add_definitions(-DBT_NO_COROUTINES) endif() endif() - set(CMAKE_POSITION_INDEPENDENT_CODE ON) set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake") diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 827fe815a..cac87d7d0 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -35,7 +35,7 @@ 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} ) -if (NOT MINGW) +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() diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 0245d6337..ca86ba31c 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -19,7 +19,7 @@ set(BT_TESTS gtest_switch.cpp ) -if (NOT MINGW) +if (BT_COROUTINES) list(APPEND BT_TESTS gtest_coroutines.cpp) endif() diff --git a/tests/navigation_test.cpp b/tests/navigation_test.cpp index 96e2df1dc..1f726e461 100644 --- a/tests/navigation_test.cpp +++ b/tests/navigation_test.cpp @@ -110,28 +110,36 @@ class ComputePathToPose: public SyncActionNode, public TestNode } }; -class FollowPath: public CoroActionNode, public TestNode +class FollowPath: public ActionNodeBase, public TestNode { + std::chrono::high_resolution_clock::time_point _initial_time; public: - FollowPath(const std::string& name): CoroActionNode(name, {}), TestNode(name), _halted(false){} + FollowPath(const std::string& name): ActionNodeBase(name, {}), TestNode(name), _halted(false){} NodeStatus tick() override { - _halted = false; - std::cout << "FollowPath::started" << std::endl; - auto initial_time = Now(); + if( status() == NodeStatus::IDLE ) + { + setStatus(NodeStatus::RUNNING); + _halted = false; + std::cout << "FollowPath::started" << std::endl; + _initial_time = Now(); + } // Yield for 1 second - while( Now() < initial_time + Milliseconds(600) ) + while( Now() < _initial_time + Milliseconds(600) || _halted ) + { + return NodeStatus::RUNNING; + } + if( _halted ) { - setStatusRunningAndYield(); + return NodeStatus::IDLE; } return tickImpl(); } void halt() override { std::cout << "FollowPath::halt" << std::endl; _halted = true; - CoroActionNode::halt(); } bool wasHalted() const { return _halted; } From ac383f41cab6dcb96098380221d3f22660680cfb Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 15:43:27 +0100 Subject: [PATCH 042/163] fixed compilation on ROS2 and ubuntu 18.94 --- CMakeLists.txt | 47 +++++++++++++++++++++++++---------------------- package.xml | 17 +++++++++++------ 2 files changed, 36 insertions(+), 28 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 778fcc95e..ea5ecbf36 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,6 +1,11 @@ cmake_minimum_required(VERSION 2.8.12) # version on Ubuntu Trusty project(behaviortree_cpp_v3) +#---- Add the subdirectory cmake ---- +set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake") +list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}") + +#---- Enable C++11 ---- if(NOT CMAKE_VERSION VERSION_LESS 3.1) set(CMAKE_CXX_STANDARD 11) set(CMAKE_CXX_STANDARD_REQUIRED ON) @@ -12,37 +17,36 @@ if(MSVC) add_definitions(-D_CRT_SECURE_NO_WARNINGS) endif() -find_package(Boost COMPONENTS coroutine2 QUIET) - +#---- Include boost to add coroutines ---- +find_package(Boost COMPONENTS coroutine QUIET) if(Boost_FOUND) include_directories(${Boost_INCLUDE_DIRS}) - message(STATUS "Found boost::coroutine2.") - add_definitions(-DBT_BOOST_COROUTINE2) - set(BT_COROUTINES true) -else() - find_package(Boost COMPONENTS coroutine QUIET) - if(Boost_FOUND) - message(STATUS "Found boost::coroutine.") - include_directories(${Boost_INCLUDE_DIRS}) - add_definitions(-DBT_BOOST_COROUTINE) - set(BT_COROUTINES true) - else() - add_definitions(-DBT_NO_COROUTINES) - endif() + if(Boost_VERSION VERSION_GREATER_EQUAL 105900) + message(STATUS "Found boost::coroutine2.") + add_definitions(-DBT_BOOST_COROUTINE2) + set(BT_COROUTINES true) + elseif(Boost_VERSION_STRING VERSION_GREATER_EQUAL 105300) + message(STATUS "Found boost::coroutine.") + include_directories(${Boost_INCLUDE_DIRS}) + add_definitions(-DBT_BOOST_COROUTINE) + set(BT_COROUTINES true) + endif() endif() -set(CMAKE_POSITION_INDEPENDENT_CODE ON) +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_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake") -list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}") +set(CMAKE_POSITION_INDEPENDENT_CODE ON) +#---- project configuration ---- option(BUILD_EXAMPLES "Build tutorials and examples" 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) -############################################################# -# Find packages +#---- Find other packages ---- find_package(Threads) find_package(ZMQ) @@ -62,7 +66,6 @@ endif() set(BEHAVIOR_TREE_LIBRARY ${PROJECT_NAME}) - # Update the policy setting to avoid an error when loading the ament_cmake package # at the current cmake version level if(POLICY CMP0057) @@ -230,7 +233,7 @@ endif() ###################################################### # INSTALL -set(PROJECT_NAMESPACE BehaviorTree) +set(PROJECT_NAMESPACE BehaviorTreeV3) set(PROJECT_CONFIG ${PROJECT_NAMESPACE}Config) INSTALL(TARGETS ${BEHAVIOR_TREE_LIBRARY} diff --git a/package.xml b/package.xml index db4429119..e7d2188d8 100644 --- a/package.xml +++ b/package.xml @@ -1,4 +1,5 @@ - + + behaviortree_cpp_v3 3.1.1 @@ -12,12 +13,16 @@ Michele Colledanchise Davide Faconti - roslib - roslib + catkin + roslib - libzmq3-dev - libzmq3-dev + ament_cmake + rclcpp - catkin + libzmq3-dev + + + ament_cmake + From 75718160a45a9c59d8751bf6e0022bfe1ed4583e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 16:03:45 +0100 Subject: [PATCH 043/163] Moving to c++14 --- CMakeLists.txt | 4 ++-- include/behaviortree_cpp_v3/control_node.h | 4 +++- src/control_node.cpp | 8 ++++++++ 3 files changed, 13 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ea5ecbf36..be4250bf5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -7,10 +7,10 @@ list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}") #---- Enable C++11 ---- if(NOT CMAKE_VERSION VERSION_LESS 3.1) - set(CMAKE_CXX_STANDARD 11) + set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) else() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14") endif() if(MSVC) diff --git a/include/behaviortree_cpp_v3/control_node.h b/include/behaviortree_cpp_v3/control_node.h index 09d8605a6..6885d9abe 100644 --- a/include/behaviortree_cpp_v3/control_node.h +++ b/include/behaviortree_cpp_v3/control_node.h @@ -43,9 +43,11 @@ class ControlNode : public TreeNode virtual void halt() override; - void haltChildren(); + [[deprecated( "deprecated: please use explicitly haltChildren() or haltChild(i)")]] + void haltChildren(size_t first); + void haltChild(size_t i); virtual NodeType type() const override final diff --git a/src/control_node.cpp b/src/control_node.cpp index bd954f188..f55aa164d 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -59,4 +59,12 @@ void ControlNode::haltChildren() } } +void ControlNode::haltChildren(size_t first) +{ + for (size_t i = first; i < children_nodes_.size(); i++) + { + haltChild(i); + } +} + } // end namespace From 3b893cb1ed33455efd8957547daea94f4b43d122 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 16:26:29 +0100 Subject: [PATCH 044/163] root_node removed in favour of a method. tickRoot() added --- docs/tutorial_02_basic_ports.md | 2 +- docs/tutorial_03_generic_ports.md | 2 +- docs/tutorial_04_sequence_star.md | 6 ++-- docs/tutorial_05_subtrees.md | 10 +++--- docs/tutorial_06_subtree_ports.md | 2 +- docs/tutorial_07_legacy.md | 2 +- docs/tutorial_08_additional_args.md | 2 +- docs/tutorial_09_coroutines.md | 2 +- examples/t01_build_your_first_tree.cpp | 2 +- examples/t02_basic_ports.cpp | 2 +- examples/t03_generic_ports.cpp | 2 +- examples/t04_reactive_sequence.cpp | 6 ++-- examples/t05_crossdoor.cpp | 4 +-- examples/t06_subtree_port_remapping.cpp | 2 +- examples/t07_wrap_legacy.cpp | 2 +- examples/t08_additional_node_args.cpp | 2 +- examples/t09_async_actions_coroutines.cpp | 2 +- examples/t10_include_trees.cpp | 4 +-- examples/t11_runtime_ports.cpp | 2 +- include/behaviortree_cpp_v3/bt_factory.h | 35 ++++++++++++++----- .../flatbuffers/bt_flatbuffer_helper.h | 4 +-- .../loggers/abstract_logger.h | 2 +- src/bt_factory.cpp | 4 +-- src/loggers/bt_cout_logger.cpp | 2 +- src/loggers/bt_file_logger.cpp | 2 +- src/loggers/bt_minitrace_logger.cpp | 2 +- src/loggers/bt_zmq_publisher.cpp | 4 +-- src/xml_parsing.cpp | 5 --- tests/gtest_blackboard.cpp | 6 ++-- tests/gtest_factory.cpp | 14 ++++---- tests/gtest_ports.cpp | 2 +- tests/gtest_subtree.cpp | 10 +++--- tests/navigation_test.cpp | 6 ++-- 33 files changed, 85 insertions(+), 71 deletions(-) diff --git a/docs/tutorial_02_basic_ports.md b/docs/tutorial_02_basic_ports.md index 069687b1e..2d841b541 100644 --- a/docs/tutorial_02_basic_ports.md +++ b/docs/tutorial_02_basic_ports.md @@ -204,7 +204,7 @@ int main() auto tree = factory.createTreeFromText(xml_text); - tree.root_node->executeTick(); + tree.tickRoot(); /* Expected output: diff --git a/docs/tutorial_03_generic_ports.md b/docs/tutorial_03_generic_ports.md index c981dafaa..d5d20df08 100644 --- a/docs/tutorial_03_generic_ports.md +++ b/docs/tutorial_03_generic_ports.md @@ -165,7 +165,7 @@ int main() factory.registerNodeType("PrintTarget"); auto tree = factory.createTreeFromText(xml_text); - tree.root_node->executeTick(); + tree.tickRoot(); /* Expected output: diff --git a/docs/tutorial_04_sequence_star.md b/docs/tutorial_04_sequence_star.md index c0c3ea3fd..4c59c0ca5 100644 --- a/docs/tutorial_04_sequence_star.md +++ b/docs/tutorial_04_sequence_star.md @@ -109,15 +109,15 @@ int main() NodeStatus status; std::cout << "\n--- 1st executeTick() ---" << std::endl; - status = tree.root_node->executeTick(); + status = tree.tickRoot(); SleepMS(150); std::cout << "\n--- 2nd executeTick() ---" << std::endl; - status = tree.root_node->executeTick(); + status = tree.tickRoot(); SleepMS(150); std::cout << "\n--- 3rd executeTick() ---" << std::endl; - status = tree.root_node->executeTick(); + status = tree.tickRoot(); std::cout << std::endl; diff --git a/docs/tutorial_05_subtrees.md b/docs/tutorial_05_subtrees.md index f87a97934..766a38787 100644 --- a/docs/tutorial_05_subtrees.md +++ b/docs/tutorial_05_subtrees.md @@ -88,20 +88,20 @@ int main() auto tree = factory.createTreeFromText(xml_text); // This logger prints state changes on console - StdCoutLogger logger_cout(tree.root_node); + StdCoutLogger logger_cout(tree.rootNode()); // This logger saves state changes on file - FileLogger logger_file(tree.root_node, "bt_trace.fbl"); + FileLogger logger_file(tree.rootNode(), "bt_trace.fbl"); // This logger stores the execution time of each node - MinitraceLogger logger_minitrace(tree.root_node, "bt_trace.json"); + MinitraceLogger logger_minitrace(tree.rootNode(), "bt_trace.json"); #ifdef ZMQ_FOUND // This logger publish status changes using ZeroMQ. Used by Groot PublisherZMQ publisher_zmq(tree); #endif - printTreeRecursively(tree.root_node); + printTreeRecursively(tree.rootNode()); //while (1) { @@ -109,7 +109,7 @@ int main() // Keep on ticking until you get either a SUCCESS or FAILURE state while( status == NodeStatus::RUNNING) { - status = tree.root_node->executeTick(); + status = tree.tickRoot(); CrossDoor::SleepMS(1); // optional sleep to avoid "busy loops" } CrossDoor::SleepMS(2000); diff --git a/docs/tutorial_06_subtree_ports.md b/docs/tutorial_06_subtree_ports.md index 4e779bd03..b9c5c0aa8 100644 --- a/docs/tutorial_06_subtree_ports.md +++ b/docs/tutorial_06_subtree_ports.md @@ -77,7 +77,7 @@ int main() // Keep on ticking until you get either a SUCCESS or FAILURE state while( status == NodeStatus::RUNNING) { - status = tree.root_node->executeTick(); + status = tree.tickRoot(); SleepMS(1); // optional sleep to avoid "busy loops" } diff --git a/docs/tutorial_07_legacy.md b/docs/tutorial_07_legacy.md index a81bdeef4..1cee72586 100644 --- a/docs/tutorial_07_legacy.md +++ b/docs/tutorial_07_legacy.md @@ -87,7 +87,7 @@ int main() auto tree = factory.createTreeFromText(xml_text); - tree.root_node->executeTick(); + tree.tickRoot(); return 0; } diff --git a/docs/tutorial_08_additional_args.md b/docs/tutorial_08_additional_args.md index f43fd2a03..367f9a4fd 100644 --- a/docs/tutorial_08_additional_args.md +++ b/docs/tutorial_08_additional_args.md @@ -137,7 +137,7 @@ int main() } } - tree.root_node->executeTick(); + tree.tickRoot(); return 0; } diff --git a/docs/tutorial_09_coroutines.md b/docs/tutorial_09_coroutines.md index 83e22321e..6458e4f7c 100644 --- a/docs/tutorial_09_coroutines.md +++ b/docs/tutorial_09_coroutines.md @@ -148,7 +148,7 @@ int main() //--------------------------------------- // keep executin tick until it returns etiher SUCCESS or FAILURE - while( tree.root_node->executeTick() == NodeStatus::RUNNING) + while( tree.tickRoot() == NodeStatus::RUNNING) { std::this_thread::sleep_for( Milliseconds(10) ); } diff --git a/examples/t01_build_your_first_tree.cpp b/examples/t01_build_your_first_tree.cpp index b287ab004..00269358b 100644 --- a/examples/t01_build_your_first_tree.cpp +++ b/examples/t01_build_your_first_tree.cpp @@ -82,7 +82,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; } diff --git a/examples/t02_basic_ports.cpp b/examples/t02_basic_ports.cpp index 71be12b9f..8e5a7c835 100644 --- a/examples/t02_basic_ports.cpp +++ b/examples/t02_basic_ports.cpp @@ -101,7 +101,7 @@ int main() auto tree = factory.createTreeFromText(xml_text); - tree.root_node->executeTick(); + tree.tickRoot(); /* Expected output: * diff --git a/examples/t03_generic_ports.cpp b/examples/t03_generic_ports.cpp index 38fc99da1..c02c858bb 100644 --- a/examples/t03_generic_ports.cpp +++ b/examples/t03_generic_ports.cpp @@ -124,7 +124,7 @@ int main() factory.registerNodeType("PrintTarget"); auto tree = factory.createTreeFromText(xml_text); - tree.root_node->executeTick(); + tree.tickRoot(); /* Expected output: * diff --git a/examples/t04_reactive_sequence.cpp b/examples/t04_reactive_sequence.cpp index fc9a91635..cec330a5a 100644 --- a/examples/t04_reactive_sequence.cpp +++ b/examples/t04_reactive_sequence.cpp @@ -82,17 +82,17 @@ int main() NodeStatus status; std::cout << "\n--- 1st executeTick() ---" << std::endl; - status = tree.root_node->executeTick(); + status = tree.tickRoot(); Assert(status == NodeStatus::RUNNING); SleepMS(150); std::cout << "\n--- 2nd executeTick() ---" << std::endl; - status = tree.root_node->executeTick(); + status = tree.tickRoot(); Assert(status == NodeStatus::RUNNING); SleepMS(150); std::cout << "\n--- 3rd executeTick() ---" << std::endl; - status = tree.root_node->executeTick(); + status = tree.tickRoot(); Assert(status == NodeStatus::SUCCESS); std::cout << std::endl; diff --git a/examples/t05_crossdoor.cpp b/examples/t05_crossdoor.cpp index cd850771e..53de346dd 100644 --- a/examples/t05_crossdoor.cpp +++ b/examples/t05_crossdoor.cpp @@ -81,7 +81,7 @@ int main(int argc, char** argv) PublisherZMQ publisher_zmq(tree); #endif - printTreeRecursively(tree.root_node); + printTreeRecursively(tree.rootNode()); const bool LOOP = ( argc == 2 && strcmp( argv[1], "loop") == 0); @@ -91,7 +91,7 @@ int main(int argc, char** argv) // Keep on ticking until you get either a SUCCESS or FAILURE state while( status == NodeStatus::RUNNING) { - status = tree.root_node->executeTick(); + status = tree.tickRoot(); CrossDoor::SleepMS(1); // optional sleep to avoid "busy loops" } CrossDoor::SleepMS(1000); diff --git a/examples/t06_subtree_port_remapping.cpp b/examples/t06_subtree_port_remapping.cpp index 50593429c..cc0304ba7 100644 --- a/examples/t06_subtree_port_remapping.cpp +++ b/examples/t06_subtree_port_remapping.cpp @@ -67,7 +67,7 @@ int main() // Keep on ticking until you get either a SUCCESS or FAILURE state while( status == NodeStatus::RUNNING) { - status = tree.root_node->executeTick(); + status = tree.tickRoot(); SleepMS(1); // optional sleep to avoid "busy loops" } diff --git a/examples/t07_wrap_legacy.cpp b/examples/t07_wrap_legacy.cpp index 3a0b55332..25ef67275 100644 --- a/examples/t07_wrap_legacy.cpp +++ b/examples/t07_wrap_legacy.cpp @@ -84,7 +84,7 @@ int main() auto tree = factory.createTreeFromText(xml_text); - tree.root_node->executeTick(); + tree.tickRoot(); return 0; } diff --git a/examples/t08_additional_node_args.cpp b/examples/t08_additional_node_args.cpp index 870521de4..7ef24f597 100644 --- a/examples/t08_additional_node_args.cpp +++ b/examples/t08_additional_node_args.cpp @@ -109,7 +109,7 @@ int main() } } - tree.root_node->executeTick(); + tree.tickRoot(); /* Expected output: diff --git a/examples/t09_async_actions_coroutines.cpp b/examples/t09_async_actions_coroutines.cpp index a40d33104..7170e724d 100644 --- a/examples/t09_async_actions_coroutines.cpp +++ b/examples/t09_async_actions_coroutines.cpp @@ -116,7 +116,7 @@ int main() //--------------------------------------- // keep executin tick until it returns etiher SUCCESS or FAILURE - while( tree.root_node->executeTick() == NodeStatus::RUNNING) + while( tree.tickRoot() == NodeStatus::RUNNING) { std::this_thread::sleep_for( std::chrono::milliseconds(10) ); } diff --git a/examples/t10_include_trees.cpp b/examples/t10_include_trees.cpp index 089e71c71..248350896 100644 --- a/examples/t10_include_trees.cpp +++ b/examples/t10_include_trees.cpp @@ -19,9 +19,9 @@ int main(int argc, char** argv) // all the TreeNodes are destroyed auto tree = factory.createTreeFromFile(argv[1]); - printTreeRecursively( tree.root_node ); + printTreeRecursively( tree.rootNode() ); - tree.root_node->executeTick(); + tree.tickRoot(); return 0; } diff --git a/examples/t11_runtime_ports.cpp b/examples/t11_runtime_ports.cpp index 5ec74a348..96a725a05 100644 --- a/examples/t11_runtime_ports.cpp +++ b/examples/t11_runtime_ports.cpp @@ -64,7 +64,7 @@ int main() factory.registerNodeType("SayRuntimePort", say_ports); auto tree = factory.createTreeFromText(xml_text); - tree.root_node->executeTick(); + tree.tickRoot(); return 0; } diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index f20653e34..b90ccd5f4 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -125,16 +125,17 @@ See examples for more information about configuring CMake correctly * * To tick the tree, simply call: * - * NodeStatus status = my_tree.root_node->executeTick(); + * NodeStatus status = my_tree.tickRoot(); */ -struct Tree +class Tree { - TreeNode* root_node; +public: + std::vector nodes; std::vector blackboard_stack; std::unordered_map manifests; - Tree(): root_node(nullptr) {} + Tree(){} // non-copyable. Only movable Tree(const Tree& ) = delete; @@ -147,7 +148,6 @@ struct Tree Tree& operator=(Tree&& other) { - root_node = std::move(other.root_node); nodes = std::move(other.nodes); blackboard_stack = std::move(other.blackboard_stack); manifests = std::move(other.manifests); @@ -158,20 +158,39 @@ struct Tree { // the halt should propagate to all the node if the nodes // have been implemented correctly - root_node->halt(); - root_node->setStatus(NodeStatus::IDLE); + rootNode()->halt(); + rootNode()->setStatus(NodeStatus::IDLE); //but, just in case.... this should be no-op auto visitor = [](BT::TreeNode * node) { node->halt(); node->setStatus(BT::NodeStatus::IDLE); }; - BT::applyRecursiveVisitor(root_node, visitor); + BT::applyRecursiveVisitor(rootNode(), visitor); + } + + TreeNode* rootNode() const + { + return nodes.empty() ? nullptr : nodes.front().get(); + } + + NodeStatus tickRoot() + { + if(!rootNode()) + { + throw RuntimeError("Empty Tree"); + } + NodeStatus ret = rootNode()->executeTick(); + if( ret == NodeStatus::SUCCESS || ret == NodeStatus::FAILURE){ + rootNode()->setStatus(BT::NodeStatus::IDLE); + } + return ret; } ~Tree(); Blackboard::Ptr rootBlackboard(); + }; /** diff --git a/include/behaviortree_cpp_v3/flatbuffers/bt_flatbuffer_helper.h b/include/behaviortree_cpp_v3/flatbuffers/bt_flatbuffer_helper.h index 6f74e4e6e..1c2a35385 100644 --- a/include/behaviortree_cpp_v3/flatbuffers/bt_flatbuffer_helper.h +++ b/include/behaviortree_cpp_v3/flatbuffers/bt_flatbuffer_helper.h @@ -64,7 +64,7 @@ inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builde { std::vector> fb_nodes; - applyRecursiveVisitor(tree.root_node, [&](BT::TreeNode* node) + applyRecursiveVisitor(tree.rootNode(), [&](BT::TreeNode* node) { std::vector children_uid; if (auto control = dynamic_cast(node)) @@ -135,7 +135,7 @@ inline void CreateFlatbuffersBehaviorTree(flatbuffers::FlatBufferBuilder& builde node_models.push_back(node_model); } - auto behavior_tree = Serialization::CreateBehaviorTree(builder, tree.root_node->UID(), + auto behavior_tree = Serialization::CreateBehaviorTree(builder, tree.rootNode()->UID(), builder.CreateVector(fb_nodes), builder.CreateVector(node_models)); diff --git a/include/behaviortree_cpp_v3/loggers/abstract_logger.h b/include/behaviortree_cpp_v3/loggers/abstract_logger.h index ce1125308..f8aaec802 100644 --- a/include/behaviortree_cpp_v3/loggers/abstract_logger.h +++ b/include/behaviortree_cpp_v3/loggers/abstract_logger.h @@ -17,7 +17,7 @@ typedef std::array SerializedTransition; class StatusChangeLogger { public: - StatusChangeLogger(TreeNode* root_node); + StatusChangeLogger(TreeNode *root_node); virtual ~StatusChangeLogger() = default; virtual void callback(BT::Duration timestamp, const TreeNode& node, NodeStatus prev_status, diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 1aba1a4e0..8299ff890 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -261,8 +261,8 @@ Tree BehaviorTreeFactory::createTreeFromFile(const std::string &file_path, Tree::~Tree() { - if (root_node) { - haltAllActions(root_node); + if (rootNode()) { + haltAllActions(rootNode()); } } diff --git a/src/loggers/bt_cout_logger.cpp b/src/loggers/bt_cout_logger.cpp index f57094343..c91da6915 100644 --- a/src/loggers/bt_cout_logger.cpp +++ b/src/loggers/bt_cout_logger.cpp @@ -4,7 +4,7 @@ namespace BT { std::atomic StdCoutLogger::ref_count(false); -StdCoutLogger::StdCoutLogger(const BT::Tree& tree) : StatusChangeLogger(tree.root_node) +StdCoutLogger::StdCoutLogger(const BT::Tree& tree) : StatusChangeLogger(tree.rootNode()) { bool expected = false; if (!ref_count.compare_exchange_strong(expected, true)) diff --git a/src/loggers/bt_file_logger.cpp b/src/loggers/bt_file_logger.cpp index 8472f43c3..fd83518c4 100644 --- a/src/loggers/bt_file_logger.cpp +++ b/src/loggers/bt_file_logger.cpp @@ -4,7 +4,7 @@ namespace BT { FileLogger::FileLogger(const BT::Tree& tree, const char* filename, uint16_t buffer_size) - : StatusChangeLogger(tree.root_node), buffer_max_size_(buffer_size) + : StatusChangeLogger(tree.rootNode()), buffer_max_size_(buffer_size) { if (buffer_max_size_ != 0) { diff --git a/src/loggers/bt_minitrace_logger.cpp b/src/loggers/bt_minitrace_logger.cpp index 65d518d81..d97d7729c 100644 --- a/src/loggers/bt_minitrace_logger.cpp +++ b/src/loggers/bt_minitrace_logger.cpp @@ -7,7 +7,7 @@ namespace BT std::atomic MinitraceLogger::ref_count(false); MinitraceLogger::MinitraceLogger(const Tree &tree, const char* filename_json) - : StatusChangeLogger(tree.root_node ) + : StatusChangeLogger( tree.rootNode() ) { bool expected = false; if (!ref_count.compare_exchange_strong(expected, true)) diff --git a/src/loggers/bt_zmq_publisher.cpp b/src/loggers/bt_zmq_publisher.cpp index 2cde945ca..872f11d04 100644 --- a/src/loggers/bt_zmq_publisher.cpp +++ b/src/loggers/bt_zmq_publisher.cpp @@ -25,7 +25,7 @@ PublisherZMQ::PublisherZMQ(const BT::Tree& tree, unsigned max_msg_per_second, unsigned publisher_port, unsigned server_port) - : StatusChangeLogger(tree.root_node) + : StatusChangeLogger(tree.rootNode()) , tree_(tree) , min_time_between_msgs_(std::chrono::microseconds(1000 * 1000) / max_msg_per_second) , send_pending_(false) @@ -100,7 +100,7 @@ PublisherZMQ::~PublisherZMQ() void PublisherZMQ::createStatusBuffer() { status_buffer_.clear(); - applyRecursiveVisitor(tree_.root_node, [this](TreeNode* node) { + applyRecursiveVisitor(tree_.rootNode(), [this](TreeNode* node) { size_t index = status_buffer_.size(); status_buffer_.resize(index + 3); flatbuffers::WriteScalar(&status_buffer_[index], node->UID()); diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index bea5be4c6..737a71d8b 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -431,11 +431,6 @@ Tree XMLParser::instantiateTree(const Blackboard::Ptr& root_blackboard) output_tree, root_blackboard, TreeNode::Ptr() ); - - if( output_tree.nodes.size() > 0) - { - output_tree.root_node = output_tree.nodes.front().get(); - } return output_tree; } diff --git a/tests/gtest_blackboard.cpp b/tests/gtest_blackboard.cpp index b9dec94b0..f29b49fc2 100644 --- a/tests/gtest_blackboard.cpp +++ b/tests/gtest_blackboard.cpp @@ -150,7 +150,7 @@ TEST(BlackboardTest, SetOutputFromText) auto bb = Blackboard::create(); auto tree = factory.createTreeFromText(xml_text, bb); - tree.root_node->executeTick(); + tree.tickRoot(); } TEST(BlackboardTest, WithFactory) @@ -179,7 +179,7 @@ TEST(BlackboardTest, WithFactory) auto bb = Blackboard::create(); auto tree = factory.createTreeFromText(xml_text, bb); - NodeStatus status = tree.root_node->executeTick(); + NodeStatus status = tree.tickRoot(); ASSERT_EQ( status, NodeStatus::SUCCESS ); ASSERT_EQ( bb->get("my_input_port"), 44 ); @@ -221,7 +221,7 @@ TEST(BlackboardTest, CheckPortType) )"; auto tree = factory.createTreeFromText(good_one); - ASSERT_NE( tree.root_node, nullptr ); + ASSERT_NE( tree.rootNode(), nullptr ); //----------------------------- std::string bad_one = R"( diff --git a/tests/gtest_factory.cpp b/tests/gtest_factory.cpp index 67164d01c..406c5e22e 100644 --- a/tests/gtest_factory.cpp +++ b/tests/gtest_factory.cpp @@ -80,11 +80,11 @@ TEST(BehaviorTreeFactory, VerifyLargeTree) Tree tree = factory.createTreeFromText(xml_text); - printTreeRecursively(tree.root_node); + printTreeRecursively(tree.rootNode()); - ASSERT_EQ(tree.root_node->name(), "root_selector"); + ASSERT_EQ(tree.rootNode()->name(), "root_selector"); - auto fallback = dynamic_cast(tree.root_node); + auto fallback = dynamic_cast(tree.rootNode()); ASSERT_TRUE(fallback != nullptr); ASSERT_EQ(fallback->children().size(), 3); @@ -121,11 +121,11 @@ TEST(BehaviorTreeFactory, Subtree) Tree tree = factory.createTreeFromText(xml_text_subtree); - printTreeRecursively(tree.root_node); + printTreeRecursively(tree.rootNode()); - ASSERT_EQ(tree.root_node->name(), "root_selector"); + ASSERT_EQ(tree.rootNode()->name(), "root_selector"); - auto root_selector = dynamic_cast(tree.root_node); + auto root_selector = dynamic_cast(tree.rootNode()); ASSERT_TRUE(root_selector != nullptr); ASSERT_EQ(root_selector->children().size(), 2); ASSERT_EQ(root_selector->child(0)->name(), "CrossDoorSubtree"); @@ -217,7 +217,7 @@ TEST(BehaviorTreeFactory, SubTreeWithRemapping) ASSERT_EQ( talk_bb->portInfo("hello_msg")->type(), &typeid(std::string) ); // Should not throw - tree.root_node->executeTick(); + tree.tickRoot(); std::cout << "\n --------------------------------- \n" << std::endl; main_bb->debugMessage(); diff --git a/tests/gtest_ports.cpp b/tests/gtest_ports.cpp index 6b79b12a7..1e654cdef 100644 --- a/tests/gtest_ports.cpp +++ b/tests/gtest_ports.cpp @@ -46,7 +46,7 @@ TEST(PortTest, DefaultPorts) auto tree = factory.createTreeFromText(xml_txt); - NodeStatus status = tree.root_node->executeTick(); + NodeStatus status = tree.tickRoot(); ASSERT_EQ( status, NodeStatus::SUCCESS ); } diff --git a/tests/gtest_subtree.cpp b/tests/gtest_subtree.cpp index 57b830106..4f873d9b9 100644 --- a/tests/gtest_subtree.cpp +++ b/tests/gtest_subtree.cpp @@ -36,7 +36,7 @@ static const char* xml_text = R"( std::cout << "-----" << std::endl; } - auto ret = tree.root_node->executeTick(); + auto ret = tree.tickRoot(); ASSERT_EQ(ret, NodeStatus::SUCCESS ); ASSERT_EQ(tree.blackboard_stack.size(), 3 ); @@ -93,7 +93,7 @@ TEST(SubTree, GoodRemapping) factory.registerNodeType("CopyPorts"); Tree tree = factory.createTreeFromText(xml_text); - auto ret = tree.root_node->executeTick(); + auto ret = tree.tickRoot(); ASSERT_EQ(ret, NodeStatus::SUCCESS ); } @@ -120,7 +120,7 @@ TEST(SubTree, BadRemapping) )"; Tree tree_bad_in = factory.createTreeFromText(xml_text_bad_in); - EXPECT_ANY_THROW( tree_bad_in.root_node->executeTick() ); + EXPECT_ANY_THROW( tree_bad_in.tickRoot() ); static const char* xml_text_bad_out = R"( @@ -139,7 +139,7 @@ TEST(SubTree, BadRemapping) )"; Tree tree_bad_out = factory.createTreeFromText(xml_text_bad_out); - EXPECT_ANY_THROW( tree_bad_out.root_node->executeTick() ); + EXPECT_ANY_THROW( tree_bad_out.tickRoot() ); } TEST(SubTree, SubtreeWrapper) @@ -165,6 +165,6 @@ TEST(SubTree, SubtreeWrapper) )"; Tree tree = factory.createTreeFromText(xml_text); - auto ret = tree.root_node->executeTick(); + auto ret = tree.tickRoot(); ASSERT_EQ(ret, NodeStatus::SUCCESS ); } diff --git a/tests/navigation_test.cpp b/tests/navigation_test.cpp index 1f726e461..71787d7ac 100644 --- a/tests/navigation_test.cpp +++ b/tests/navigation_test.cpp @@ -211,7 +211,7 @@ TEST(Navigationtest, MoveBaseRecovery) while( status == NodeStatus::IDLE || status == NodeStatus::RUNNING ) { - status = tree.root_node->executeTick(); + status = tree.tickRoot(); std::this_thread::sleep_for(Milliseconds(100)); } @@ -248,7 +248,7 @@ TEST(Navigationtest, MoveBaseRecovery) first_stuck_node->setExpectedResult(true); second_stuck_node->setExpectedResult(true); } - status = tree.root_node->executeTick(); + status = tree.tickRoot(); std::this_thread::sleep_for(Milliseconds(100)); } @@ -288,7 +288,7 @@ TEST(Navigationtest, MoveBaseRecovery) while( status == NodeStatus::IDLE || status == NodeStatus::RUNNING ) { - status = tree.root_node->executeTick(); + status = tree.tickRoot(); std::this_thread::sleep_for(Milliseconds(100)); } From 96aac6cb74d7e1a557e3acb91bf52270ac216f9b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 16:32:45 +0100 Subject: [PATCH 045/163] Compilation fixed on Ubunru Xenial --- CMakeLists.txt | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index be4250bf5..c0cd401b2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8.12) # version on Ubuntu Trusty +cmake_minimum_required(VERSION 3.5.2) # version on Ubuntu Xenial project(behaviortree_cpp_v3) #---- Add the subdirectory cmake ---- @@ -6,12 +6,8 @@ set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake") list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}") #---- Enable C++11 ---- -if(NOT CMAKE_VERSION VERSION_LESS 3.1) - set(CMAKE_CXX_STANDARD 14) - set(CMAKE_CXX_STANDARD_REQUIRED ON) -else() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14") -endif() +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD_REQUIRED ON) if(MSVC) add_definitions(-D_CRT_SECURE_NO_WARNINGS) @@ -21,11 +17,11 @@ endif() find_package(Boost COMPONENTS coroutine QUIET) if(Boost_FOUND) include_directories(${Boost_INCLUDE_DIRS}) - if(Boost_VERSION VERSION_GREATER_EQUAL 105900) + if(NOT Boost_VERSION VERSION_LESS 105900) message(STATUS "Found boost::coroutine2.") add_definitions(-DBT_BOOST_COROUTINE2) set(BT_COROUTINES true) - elseif(Boost_VERSION_STRING VERSION_GREATER_EQUAL 105300) + elseif(NOT Boost_VERSION VERSION_LESS 105300) message(STATUS "Found boost::coroutine.") include_directories(${Boost_INCLUDE_DIRS}) add_definitions(-DBT_BOOST_COROUTINE) From 9dff663b1d4ee47bbfe736e018cf3f97304baf3e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 16:37:20 +0100 Subject: [PATCH 046/163] Copyright updated --- CHANGELOG.rst | 94 +++++++++++++++++++ README.md | 4 +- include/behaviortree_cpp_v3/action_node.h | 2 +- .../actions/always_failure_node.h | 2 +- .../actions/always_success_node.h | 2 +- .../actions/set_blackboard_node.h | 2 +- include/behaviortree_cpp_v3/behavior_tree.h | 2 +- include/behaviortree_cpp_v3/bt_factory.h | 2 +- include/behaviortree_cpp_v3/condition_node.h | 2 +- include/behaviortree_cpp_v3/control_node.h | 2 +- .../controls/fallback_node.h | 2 +- .../controls/parallel_node.h | 2 +- .../controls/reactive_fallback.h | 2 +- .../controls/reactive_sequence.h | 2 +- .../controls/sequence_node.h | 2 +- .../controls/sequence_star_node.h | 2 +- .../controls/switch_node.h | 2 +- .../decorators/blackboard_precondition.h | 2 +- .../decorators/force_failure_node.h | 2 +- .../decorators/force_success_node.h | 2 +- .../decorators/inverter_node.h | 2 +- .../decorators/repeat_node.h | 2 +- .../decorators/retry_node.h | 2 +- include/behaviortree_cpp_v3/exceptions.h | 2 +- include/behaviortree_cpp_v3/leaf_node.h | 2 +- include/behaviortree_cpp_v3/tree_node.h | 2 +- src/action_node.cpp | 2 +- src/behavior_tree.cpp | 2 +- src/bt_factory.cpp | 2 +- src/condition_node.cpp | 2 +- src/control_node.cpp | 2 +- src/controls/fallback_node.cpp | 2 +- src/controls/parallel_node.cpp | 2 +- src/controls/reactive_fallback.cpp | 2 +- src/controls/reactive_sequence.cpp | 2 +- src/controls/sequence_node.cpp | 2 +- src/controls/sequence_star_node.cpp | 2 +- src/decorator_node.cpp | 2 +- src/decorators/inverter_node.cpp | 2 +- src/decorators/repeat_node.cpp | 2 +- src/decorators/retry_node.cpp | 2 +- src/decorators/timeout_node.cpp | 2 +- src/tree_node.cpp | 2 +- src/xml_parsing.cpp | 2 +- 44 files changed, 138 insertions(+), 44 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 412acc85a..98a539279 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,100 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* 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 +* 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 + 3.1.1 (2019-11-10) ------------------ * fix samples compilation (hopefully) diff --git a/README.md b/README.md index 0219f8bd2..fcdd39f38 100644 --- a/README.md +++ b/README.md @@ -11,7 +11,7 @@ Question? [![Join the chat at https://gitter.im/BehaviorTree-ROS/Lobby](https:// # About BehaviorTree.CPP -This __C++__ library provides a framework to create BehaviorTrees. +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 @@ -129,7 +129,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-2019 Davide Faconti +Copyright (c) 2018-2020 Davide Faconti Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal diff --git a/include/behaviortree_cpp_v3/action_node.h b/include/behaviortree_cpp_v3/action_node.h index 237494eae..d8d6b0c72 100644 --- a/include/behaviortree_cpp_v3/action_node.h +++ b/include/behaviortree_cpp_v3/action_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/actions/always_failure_node.h b/include/behaviortree_cpp_v3/actions/always_failure_node.h index 2402f50af..495cb44a2 100644 --- a/include/behaviortree_cpp_v3/actions/always_failure_node.h +++ b/include/behaviortree_cpp_v3/actions/always_failure_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/actions/always_success_node.h b/include/behaviortree_cpp_v3/actions/always_success_node.h index 23716611c..5af21986b 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-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/actions/set_blackboard_node.h b/include/behaviortree_cpp_v3/actions/set_blackboard_node.h index 6e3f84998..eaaeab888 100644 --- a/include/behaviortree_cpp_v3/actions/set_blackboard_node.h +++ b/include/behaviortree_cpp_v3/actions/set_blackboard_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index 3ea38a3e1..06656b3dd 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index b90ccd5f4..f7797de57 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -1,5 +1,5 @@ /* Copyright (C) 2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/condition_node.h b/include/behaviortree_cpp_v3/condition_node.h index 516b83806..4dc11aaca 100644 --- a/include/behaviortree_cpp_v3/condition_node.h +++ b/include/behaviortree_cpp_v3/condition_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/control_node.h b/include/behaviortree_cpp_v3/control_node.h index 6885d9abe..558b788d2 100644 --- a/include/behaviortree_cpp_v3/control_node.h +++ b/include/behaviortree_cpp_v3/control_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/controls/fallback_node.h b/include/behaviortree_cpp_v3/controls/fallback_node.h index 351e43722..5492c8b39 100644 --- a/include/behaviortree_cpp_v3/controls/fallback_node.h +++ b/include/behaviortree_cpp_v3/controls/fallback_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/controls/parallel_node.h b/include/behaviortree_cpp_v3/controls/parallel_node.h index ca454c806..0c6c959fe 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-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/controls/reactive_fallback.h b/include/behaviortree_cpp_v3/controls/reactive_fallback.h index 37a134014..14b453c0b 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) 2019 Davide Faconti, Eurecat - All Rights Reserved +/* Copyright (C) 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, diff --git a/include/behaviortree_cpp_v3/controls/reactive_sequence.h b/include/behaviortree_cpp_v3/controls/reactive_sequence.h index 7813aeaba..d621f977b 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) 2019 Davide Faconti, Eurecat - All Rights Reserved +/* Copyright (C) 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, diff --git a/include/behaviortree_cpp_v3/controls/sequence_node.h b/include/behaviortree_cpp_v3/controls/sequence_node.h index aea575c86..20baadce3 100644 --- a/include/behaviortree_cpp_v3/controls/sequence_node.h +++ b/include/behaviortree_cpp_v3/controls/sequence_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/controls/sequence_star_node.h b/include/behaviortree_cpp_v3/controls/sequence_star_node.h index 984b03a1d..611a26f8f 100644 --- a/include/behaviortree_cpp_v3/controls/sequence_star_node.h +++ b/include/behaviortree_cpp_v3/controls/sequence_star_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/controls/switch_node.h b/include/behaviortree_cpp_v3/controls/switch_node.h index 0ca9a2eb9..46dbc818f 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) 2019-2020 Davide Faconti - All Rights Reserved +/* Copyright (C) 2020-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, diff --git a/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h b/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h index 63a520a5a..4cc445d46 100644 --- a/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h +++ b/include/behaviortree_cpp_v3/decorators/blackboard_precondition.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/decorators/force_failure_node.h b/include/behaviortree_cpp_v3/decorators/force_failure_node.h index e7c4bfe04..532beddde 100644 --- a/include/behaviortree_cpp_v3/decorators/force_failure_node.h +++ b/include/behaviortree_cpp_v3/decorators/force_failure_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/decorators/force_success_node.h b/include/behaviortree_cpp_v3/decorators/force_success_node.h index 399372cc9..699d23f8e 100644 --- a/include/behaviortree_cpp_v3/decorators/force_success_node.h +++ b/include/behaviortree_cpp_v3/decorators/force_success_node.h @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/decorators/inverter_node.h b/include/behaviortree_cpp_v3/decorators/inverter_node.h index 2a36e47ed..4d4a10371 100644 --- a/include/behaviortree_cpp_v3/decorators/inverter_node.h +++ b/include/behaviortree_cpp_v3/decorators/inverter_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/decorators/repeat_node.h b/include/behaviortree_cpp_v3/decorators/repeat_node.h index f4ce7009a..35c45945f 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-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/decorators/retry_node.h b/include/behaviortree_cpp_v3/decorators/retry_node.h index c6bcae667..60c4e2409 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-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/exceptions.h b/include/behaviortree_cpp_v3/exceptions.h index 0ea886c66..4ed3fb60b 100644 --- a/include/behaviortree_cpp_v3/exceptions.h +++ b/include/behaviortree_cpp_v3/exceptions.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/leaf_node.h b/include/behaviortree_cpp_v3/leaf_node.h index 3308b919f..e91a97502 100644 --- a/include/behaviortree_cpp_v3/leaf_node.h +++ b/include/behaviortree_cpp_v3/leaf_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index 272a89742..278b9757c 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved -* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/action_node.cpp b/src/action_node.cpp index c1c43e01d..aad8370a1 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index ee060378a..8127f6a29 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 8299ff890..6cab01704 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/condition_node.cpp b/src/condition_node.cpp index b8af5ea52..bd113e316 100644 --- a/src/condition_node.cpp +++ b/src/condition_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/control_node.cpp b/src/control_node.cpp index f55aa164d..ad9e14b51 100644 --- a/src/control_node.cpp +++ b/src/control_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/controls/fallback_node.cpp b/src/controls/fallback_node.cpp index f54ca0a4d..59ab331e3 100644 --- a/src/controls/fallback_node.cpp +++ b/src/controls/fallback_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/controls/parallel_node.cpp b/src/controls/parallel_node.cpp index b85533f14..0ab8cb29a 100644 --- a/src/controls/parallel_node.cpp +++ b/src/controls/parallel_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/controls/reactive_fallback.cpp b/src/controls/reactive_fallback.cpp index 2a38a56d5..98536d43d 100644 --- a/src/controls/reactive_fallback.cpp +++ b/src/controls/reactive_fallback.cpp @@ -1,4 +1,4 @@ -/* Copyright (C) 2019 Davide Faconti, Eurecat - All Rights Reserved +/* Copyright (C) 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, diff --git a/src/controls/reactive_sequence.cpp b/src/controls/reactive_sequence.cpp index be5a8f472..ba6ab50d7 100644 --- a/src/controls/reactive_sequence.cpp +++ b/src/controls/reactive_sequence.cpp @@ -1,4 +1,4 @@ -/* Copyright (C) 2019 Davide Faconti, Eurecat - All Rights Reserved +/* Copyright (C) 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, diff --git a/src/controls/sequence_node.cpp b/src/controls/sequence_node.cpp index 2ca0adee6..800319e25 100644 --- a/src/controls/sequence_node.cpp +++ b/src/controls/sequence_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/controls/sequence_star_node.cpp b/src/controls/sequence_star_node.cpp index 784341697..7bd10ce91 100644 --- a/src/controls/sequence_star_node.cpp +++ b/src/controls/sequence_star_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/decorator_node.cpp b/src/decorator_node.cpp index 0b361c311..6c9967625 100644 --- a/src/decorator_node.cpp +++ b/src/decorator_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/decorators/inverter_node.cpp b/src/decorators/inverter_node.cpp index dc9646d9b..e20e1ed28 100644 --- a/src/decorators/inverter_node.cpp +++ b/src/decorators/inverter_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/decorators/repeat_node.cpp b/src/decorators/repeat_node.cpp index 11dd8396c..3c7493ad7 100644 --- a/src/decorators/repeat_node.cpp +++ b/src/decorators/repeat_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/decorators/retry_node.cpp b/src/decorators/retry_node.cpp index d777c716e..eec561fc6 100644 --- a/src/decorators/retry_node.cpp +++ b/src/decorators/retry_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/decorators/timeout_node.cpp b/src/decorators/timeout_node.cpp index 7b96840bd..69905a980 100644 --- a/src/decorators/timeout_node.cpp +++ b/src/decorators/timeout_node.cpp @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/tree_node.cpp b/src/tree_node.cpp index de36e20b5..74411c92b 100644 --- a/src/tree_node.cpp +++ b/src/tree_node.cpp @@ -1,5 +1,5 @@ /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved - * Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, diff --git a/src/xml_parsing.cpp b/src/xml_parsing.cpp index 737a71d8b..f60ba252d 100644 --- a/src/xml_parsing.cpp +++ b/src/xml_parsing.cpp @@ -1,4 +1,4 @@ -/* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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, From f63bfab5f76f4008b31e4587431085393dff2e7e Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 22:03:01 +0100 Subject: [PATCH 047/163] preparing release 3.2.0 --- CHANGELOG.rst | 4 +- CMakeLists.txt | 2 +- conan/test_package/test_package.cpp | 2 +- examples/broken_sequence.cpp | 2 +- include/behaviortree_cpp_v3/action_node.h | 49 ++++--- include/behaviortree_cpp_v3/behavior_tree.h | 5 - include/behaviortree_cpp_v3/bt_factory.h | 4 + package.xml | 2 +- src/action_node.cpp | 137 ++++++-------------- src/behavior_tree.cpp | 11 -- src/bt_factory.cpp | 4 +- tests/gtest_decorator.cpp | 10 +- tests/gtest_fallback.cpp | 8 +- tests/gtest_parallel.cpp | 3 +- tests/gtest_sequence.cpp | 14 +- tests/gtest_switch.cpp | 8 +- tests/gtest_tree.cpp | 1 - tests/include/action_test_node.h | 7 +- tests/src/action_test_node.cpp | 18 +-- 19 files changed, 107 insertions(+), 184 deletions(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 98a539279..72d34214d 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package behaviortree_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +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 diff --git a/CMakeLists.txt b/CMakeLists.txt index c0cd401b2..04bc81f35 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -5,7 +5,7 @@ project(behaviortree_cpp_v3) set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake") list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}") -#---- Enable C++11 ---- +#---- Enable C++14 ---- set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) diff --git a/conan/test_package/test_package.cpp b/conan/test_package/test_package.cpp index 91083f607..2602eac09 100644 --- a/conan/test_package/test_package.cpp +++ b/conan/test_package/test_package.cpp @@ -62,7 +62,7 @@ int main() std::this_thread::sleep_for(std::chrono::milliseconds(100)); } - haltAllActions(&root); + return 0; } diff --git a/examples/broken_sequence.cpp b/examples/broken_sequence.cpp index b07364cf1..ed0c22387 100644 --- a/examples/broken_sequence.cpp +++ b/examples/broken_sequence.cpp @@ -63,7 +63,7 @@ int main() std::this_thread::sleep_for(std::chrono::milliseconds(100)); } - haltAllActions(&root); + return 0; } diff --git a/include/behaviortree_cpp_v3/action_node.h b/include/behaviortree_cpp_v3/action_node.h index d8d6b0c72..a7ef2aee6 100644 --- a/include/behaviortree_cpp_v3/action_node.h +++ b/include/behaviortree_cpp_v3/action_node.h @@ -16,6 +16,7 @@ #include #include +#include #include "leaf_node.h" namespace BT @@ -96,48 +97,44 @@ class SimpleActionNode : public SyncActionNode }; /** - * @brief The AsyncActionNode uses a different thread where the action will be + * @brief The AsyncActionNode uses a different thread, where the action will be * executed. * - * The user must implement the methods tick() and halt(). + * IMPORTANT: this action is quite hard to implement correctly. Please be sure that you know what you are doing. * - * WARNING: this should probably be deprecated. It is too easy to use incorrectly - * and there is not a good way to halt it in a thread safe way. + * - In your overriden tick() method, you must check periodically + * the result of the method isHaltRequested() and stop your execution accordingly. * - * Use it at your own risk. + * - in the overriden halt() method, you can do some cleanup, but do not forget to + * invoke the base class method AsyncActionNode::halt(); + * + * - 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. */ class AsyncActionNode : public ActionNodeBase { public: - AsyncActionNode(const std::string& name, const NodeConfiguration& config); - virtual ~AsyncActionNode() override; + AsyncActionNode(const std::string& name, const NodeConfiguration& config):ActionNodeBase(name, config) + { + } + + bool isHaltRequested() const + { + return halt_requested_.load(); + } - // This method triggers the TickEngine. Do NOT remove the "final" keyword. + // This method spawn a new thread. Do NOT remove the "final" keyword. virtual NodeStatus executeTick() override final; - void stopAndJoinThread(); + virtual void halt() override; private: - // The method that will be executed by the thread - void asyncThreadLoop(); - - void waitStart(); - - void notifyStart(); - - std::atomic keep_thread_alive_; - - bool start_action_; - - std::mutex start_mutex_; - - std::condition_variable start_signal_; - std::exception_ptr exptr_; - - std::thread thread_; + std::atomic_bool halt_requested_; + std::future thread_handle_; }; /** diff --git a/include/behaviortree_cpp_v3/behavior_tree.h b/include/behaviortree_cpp_v3/behavior_tree.h index 06656b3dd..b376af25c 100644 --- a/include/behaviortree_cpp_v3/behavior_tree.h +++ b/include/behaviortree_cpp_v3/behavior_tree.h @@ -54,11 +54,6 @@ void applyRecursiveVisitor(TreeNode* root_node, const std::function> SerializedTreeStatus; /** diff --git a/include/behaviortree_cpp_v3/bt_factory.h b/include/behaviortree_cpp_v3/bt_factory.h index f7797de57..c0dd233c5 100644 --- a/include/behaviortree_cpp_v3/bt_factory.h +++ b/include/behaviortree_cpp_v3/bt_factory.h @@ -156,6 +156,10 @@ class Tree void haltTree() { + if(!rootNode()) + { + return; + } // the halt should propagate to all the node if the nodes // have been implemented correctly rootNode()->halt(); diff --git a/package.xml b/package.xml index e7d2188d8..a4ec9d765 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.1.1 + 3.2.0 This package provides the Behavior Trees core library. diff --git a/src/action_node.cpp b/src/action_node.cpp index aad8370a1..79fe35ea5 100644 --- a/src/action_node.cpp +++ b/src/action_node.cpp @@ -50,102 +50,6 @@ NodeStatus SimpleActionNode::tick() //------------------------------------------------------- -AsyncActionNode::AsyncActionNode(const std::string& name, const NodeConfiguration& config) - : ActionNodeBase(name, config) -{ - -} - -AsyncActionNode::~AsyncActionNode() -{ - if (thread_.joinable()) - { - stopAndJoinThread(); - } -} - -void AsyncActionNode::waitStart() -{ - std::unique_lock lock(start_mutex_); - while (!start_action_) - { - start_signal_.wait(lock); - } - start_action_ = false; -} - -void AsyncActionNode::notifyStart() -{ - std::unique_lock lock(start_mutex_); - start_action_ = true; - start_signal_.notify_all(); -} - -void AsyncActionNode::asyncThreadLoop() -{ - while (keep_thread_alive_.load()) - { - waitStart(); - - // check keep_thread_alive_ again because the tick_engine_ could be - // notified from the method stopAndJoinThread - if (keep_thread_alive_) - { - // this will execute the blocking code. - try { - setStatus(tick()); - } - catch (std::exception&) - { - std::cerr << "\nUncaught exception from the method tick() of an AsyncActionNode: [" - << registrationName() << "/" << name() << "]\n" << std::endl; - exptr_ = std::current_exception(); - keep_thread_alive_ = false; - } - } - } -} - -NodeStatus AsyncActionNode::executeTick() -{ - //send signal to other thread. - // The other thread is in charge for changing the status - if (status() == NodeStatus::IDLE) - { - if( thread_.joinable() == false) { - keep_thread_alive_ = true; - thread_ = std::thread(&AsyncActionNode::asyncThreadLoop, this); - } - setStatus( NodeStatus::RUNNING ); - notifyStart(); - } - - if( exptr_ ) - { - std::rethrow_exception(exptr_); - } - return status(); -} - -void AsyncActionNode::stopAndJoinThread() -{ - keep_thread_alive_.store(false); - if( status() == NodeStatus::RUNNING ) - { - halt(); - } - else{ - // loop in asyncThreadLoop() is blocked at waitStart(). Unblock it. - notifyStart(); - } - - if (thread_.joinable()) - { - thread_.join(); - } -} - - SyncActionNode::SyncActionNode(const std::string &name, const NodeConfiguration& config): ActionNodeBase(name, config) {} @@ -260,3 +164,44 @@ void StatefulActionNode::halt() } setStatus(NodeStatus::IDLE); } + +NodeStatus BT::AsyncActionNode::executeTick() +{ + //send signal to other thread. + // The other thread is in charge for changing the status + if (status() == NodeStatus::IDLE) + { + setStatus( NodeStatus::RUNNING ); + halt_requested_ = false; + thread_handle_ = std::async(std::launch::async, [this]() { + + try { + setStatus(tick()); + } + catch (std::exception&) + { + std::cerr << "\nUncaught exception from the method tick(): [" + << registrationName() << "/" << name() << "]\n" << std::endl; + exptr_ = std::current_exception(); + thread_handle_.wait(); + } + return status(); + }); + } + + if( exptr_ ) + { + std::rethrow_exception(exptr_); + } + return status(); +} + +void AsyncActionNode::halt() +{ + halt_requested_.store(true); + + if( thread_handle_.valid() ){ + thread_handle_.wait(); + } + thread_handle_ = {}; +} diff --git a/src/behavior_tree.cpp b/src/behavior_tree.cpp index 8127f6a29..f50b23eaf 100644 --- a/src/behavior_tree.cpp +++ b/src/behavior_tree.cpp @@ -107,15 +107,4 @@ void buildSerializedStatusSnapshot(TreeNode* root_node, SerializedTreeStatus& se applyRecursiveVisitor(root_node, visitor); } -void haltAllActions(TreeNode* root_node) -{ - auto visitor = [](TreeNode* node) { - if (auto action = dynamic_cast(node)) - { - action->stopAndJoinThread(); - } - }; - applyRecursiveVisitor(root_node, visitor); -} - } // end namespace diff --git a/src/bt_factory.cpp b/src/bt_factory.cpp index 6cab01704..2a5344e96 100644 --- a/src/bt_factory.cpp +++ b/src/bt_factory.cpp @@ -261,9 +261,7 @@ Tree BehaviorTreeFactory::createTreeFromFile(const std::string &file_path, Tree::~Tree() { - if (rootNode()) { - haltAllActions(rootNode()); - } + haltTree(); } Blackboard::Ptr Tree::rootBlackboard() diff --git a/tests/gtest_decorator.cpp b/tests/gtest_decorator.cpp index 0e03c73e7..b8eaf3cbf 100644 --- a/tests/gtest_decorator.cpp +++ b/tests/gtest_decorator.cpp @@ -30,7 +30,7 @@ struct DeadlineTest : testing::Test } ~DeadlineTest() { - haltAllActions(&root); + } }; @@ -45,7 +45,7 @@ struct RepeatTest : testing::Test } ~RepeatTest() { - haltAllActions(&root); + } }; @@ -60,7 +60,7 @@ struct RetryTest : testing::Test } ~RetryTest() { - haltAllActions(&root); + } }; @@ -78,10 +78,6 @@ struct TimeoutAndRetry : testing::Test timeout_root.setChild(&retry); retry.setChild(&action); } - ~TimeoutAndRetry() - { - haltAllActions(&timeout_root); - } }; /****************TESTS START HERE***************************/ diff --git a/tests/gtest_fallback.cpp b/tests/gtest_fallback.cpp index f993f0191..df0a3a47f 100644 --- a/tests/gtest_fallback.cpp +++ b/tests/gtest_fallback.cpp @@ -34,7 +34,7 @@ struct SimpleFallbackTest : testing::Test } ~SimpleFallbackTest() { - haltAllActions(&root); + } }; @@ -57,7 +57,7 @@ struct ReactiveFallbackTest : testing::Test } ~ReactiveFallbackTest() { - haltAllActions(&root); + } }; @@ -77,7 +77,7 @@ struct SimpleFallbackWithMemoryTest : testing::Test } ~SimpleFallbackWithMemoryTest() { - haltAllActions(&root); + } }; @@ -116,7 +116,7 @@ struct ComplexFallbackWithMemoryTest : testing::Test } ~ComplexFallbackWithMemoryTest() { - haltAllActions(&root); + } }; diff --git a/tests/gtest_parallel.cpp b/tests/gtest_parallel.cpp index 688947047..16d2f5140 100644 --- a/tests/gtest_parallel.cpp +++ b/tests/gtest_parallel.cpp @@ -41,7 +41,7 @@ struct SimpleParallelTest : testing::Test } ~SimpleParallelTest() { - haltAllActions(&root); + } }; @@ -86,7 +86,6 @@ struct ComplexParallelTest : testing::Test } ~ComplexParallelTest() { - haltAllActions(¶llel_root); } }; diff --git a/tests/gtest_sequence.cpp b/tests/gtest_sequence.cpp index e6327efd7..1141a41c2 100644 --- a/tests/gtest_sequence.cpp +++ b/tests/gtest_sequence.cpp @@ -34,7 +34,7 @@ struct SimpleSequenceTest : testing::Test } ~SimpleSequenceTest() { - haltAllActions(&root); + } }; @@ -63,7 +63,7 @@ struct ComplexSequenceTest : testing::Test } ~ComplexSequenceTest() { - haltAllActions(&root); + } }; @@ -89,7 +89,7 @@ struct SequenceTripleActionTest : testing::Test } ~SequenceTripleActionTest() { - haltAllActions(&root); + } }; @@ -126,7 +126,7 @@ struct ComplexSequence2ActionsTest : testing::Test } ~ComplexSequence2ActionsTest() { - haltAllActions(&root); + } }; @@ -146,7 +146,7 @@ struct SimpleSequenceWithMemoryTest : testing::Test } ~SimpleSequenceWithMemoryTest() { - haltAllActions(&root); + } }; @@ -185,7 +185,7 @@ struct ComplexSequenceWithMemoryTest : testing::Test } ~ComplexSequenceWithMemoryTest() { - haltAllActions(&root); + } }; @@ -212,7 +212,7 @@ struct SimpleParallelTest : testing::Test } ~SimpleParallelTest() { - haltAllActions(&root); + } }; diff --git a/tests/gtest_switch.cpp b/tests/gtest_switch.cpp index bc5936daf..06c867c2a 100644 --- a/tests/gtest_switch.cpp +++ b/tests/gtest_switch.cpp @@ -209,20 +209,18 @@ TEST_F(SwitchTest, ActionFailure) bb->set("my_var", "1"); BT::NodeStatus state = root->executeTick(); + action_1.setExpectedResult(NodeStatus::FAILURE); + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_42.status()); ASSERT_EQ(NodeStatus::IDLE, action_def.status()); ASSERT_EQ(NodeStatus::RUNNING, state); - action_1.setExpectedResult(NodeStatus::FAILURE); - // halt the running node - action_1.halt(); - std::this_thread::sleep_for(milliseconds(20)); + std::this_thread::sleep_for(milliseconds(110)); state = root->executeTick(); ASSERT_EQ(NodeStatus::FAILURE, state); ASSERT_EQ(NodeStatus::IDLE, action_1.status()); ASSERT_EQ(NodeStatus::IDLE, action_42.status()); ASSERT_EQ(NodeStatus::IDLE, action_def.status()); - } diff --git a/tests/gtest_tree.cpp b/tests/gtest_tree.cpp index 7a81d3c28..ab07d0530 100644 --- a/tests/gtest_tree.cpp +++ b/tests/gtest_tree.cpp @@ -43,7 +43,6 @@ struct BehaviorTreeTest : testing::Test } ~BehaviorTreeTest() { - haltAllActions(&root); } }; diff --git a/tests/include/action_test_node.h b/tests/include/action_test_node.h index e5e0ef9ec..495b31d8a 100644 --- a/tests/include/action_test_node.h +++ b/tests/include/action_test_node.h @@ -34,7 +34,10 @@ class AsyncActionTest : public AsyncActionNode public: AsyncActionTest(const std::string& name, BT::Duration deadline_ms = std::chrono::milliseconds(100) ); - ~AsyncActionTest(); + virtual ~AsyncActionTest() + { + halt(); + } // The method that is going to be executed by the thread BT::NodeStatus tick() override; @@ -61,7 +64,7 @@ class AsyncActionTest : public AsyncActionNode BT::Duration time_; std::atomic expected_result_; std::atomic tick_count_; - bool stop_loop_; + }; } diff --git a/tests/src/action_test_node.cpp b/tests/src/action_test_node.cpp index a36936f10..77b0042e2 100644 --- a/tests/src/action_test_node.cpp +++ b/tests/src/action_test_node.cpp @@ -19,15 +19,9 @@ BT::AsyncActionTest::AsyncActionTest(const std::string& name, BT::Duration deadl { expected_result_ = NodeStatus::SUCCESS; time_ = deadline_ms; - stop_loop_ = false; tick_count_ = 0; } -BT::AsyncActionTest::~AsyncActionTest() -{ - halt(); -} - BT::NodeStatus BT::AsyncActionTest::tick() { using std::chrono::high_resolution_clock; @@ -35,18 +29,24 @@ BT::NodeStatus BT::AsyncActionTest::tick() auto initial_time = high_resolution_clock::now(); - while (!stop_loop_ && high_resolution_clock::now() < initial_time + time_) + // we simulate an asynchronous action that takes an amount of time equal to time_ + while (!isHaltRequested() && high_resolution_clock::now() < initial_time + time_) { std::this_thread::sleep_for(std::chrono::milliseconds(1)); } - stop_loop_ = false; + // check if we exited the while(9 loop because of the flag stop_loop_ + if( isHaltRequested() ){ + return NodeStatus::IDLE; + } + return expected_result_; } void BT::AsyncActionTest::halt() { - stop_loop_ = true; + // do more cleanup here is necessary + AsyncActionNode::halt(); } void BT::AsyncActionTest::setTime(BT::Duration time) From 3cb8ee03c62b68374b96427f062af030e74cc20b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 22:03:37 +0100 Subject: [PATCH 048/163] 3.3.0 --- package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package.xml b/package.xml index a4ec9d765..006c8c923 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ behaviortree_cpp_v3 - 3.2.0 + 3.3.0 This package provides the Behavior Trees core library. From 8752fa8648fd779d89c5c1dba3d834b894b65ab4 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 22:41:57 +0100 Subject: [PATCH 049/163] readme updated --- CMakeLists.txt | 16 ++++++++-------- README.md | 34 ++++++++++++++++++++++++++++------ examples/CMakeLists.txt | 2 +- sample_nodes/CMakeLists.txt | 2 +- 4 files changed, 38 insertions(+), 16 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 04bc81f35..34972c04f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -229,11 +229,9 @@ endif() ###################################################### # INSTALL -set(PROJECT_NAMESPACE BehaviorTreeV3) -set(PROJECT_CONFIG ${PROJECT_NAMESPACE}Config) INSTALL(TARGETS ${BEHAVIOR_TREE_LIBRARY} - EXPORT ${PROJECT_CONFIG} + EXPORT BehaviorTreeV3Config ARCHIVE DESTINATION ${BEHAVIOR_TREE_LIB_DESTINATION} LIBRARY DESTINATION ${BEHAVIOR_TREE_LIB_DESTINATION} RUNTIME DESTINATION ${BEHAVIOR_TREE_BIN_DESTINATION} @@ -243,13 +241,15 @@ INSTALL( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ DESTINATION ${BEHAVIOR_TREE_INC_DESTINATION} FILES_MATCHING PATTERN "*.h*") -install(EXPORT ${PROJECT_CONFIG} - DESTINATION "${BEHAVIOR_TREE_LIB_DESTINATION}/${PROJECT_NAMESPACE}/cmake" - NAMESPACE ${PROJECT_NAMESPACE}::) +install(EXPORT BehaviorTreeV3Config + DESTINATION "${BEHAVIOR_TREE_LIB_DESTINATION}/$BehaviorTreeV3/cmake" + NAMESPACE BT::) export(TARGETS ${PROJECT_NAME} - NAMESPACE ${PROJECT_NAMESPACE}:: - FILE "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_CONFIG}.cmake") + NAMESPACE BT:: + FILE "${CMAKE_CURRENT_BINARY_DIR}/BehaviorTreeV3Config.cmake") + +export(PACKAGE ${PROJECT_NAME}) ###################################################### # EXAMPLES and TOOLS diff --git a/README.md b/README.md index fcdd39f38..31e18d2a3 100644 --- a/README.md +++ b/README.md @@ -80,19 +80,41 @@ the graphic user interface are used to design and monitor a Behavior Tree. [![MOOD2Be](video_MOOD2Be.png)](https://vimeo.com/304651183) -# How to compile +# How to compile (plain old cmake -On Ubuntu, you must install the following dependencies: +On Ubuntu, you are encourage to install the following dependencies: - sudo apt-get install libzmq3-dev libdw-dev + sudo apt-get install libzmq3-dev libboost-dev -Any other dependency is already included in the __3rdparty__ folder. +Other dependency is already included in the __3rdparty__ folder. -## Catkin and ROS users +To compile and install the library, from the BehaviorTree.CPP folder, execute: + + mkdir build; cd build + cmake .. + make + sudo make install + +Your typical **CMakeLists.txt** file will look like this: + +```cmake +cmake_minimum_required(VERSION 3.5) + +project(hello_BT) + +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD_REQUIRED ON) +find_package(BehaviorTreeV3) + +add_executable(${PROJECT_NAME} "hello_BT.cpp") +target_link_libraries(${PROJECT_NAME} BT3::behaviortree_cpp_v3) +``` + +## ROS1 or ROS2 users (Catkin/Ament) You can easily install the package with the command - sudo apt-get install ros-$ROS_DISTRO-behaviortree-cpp + sudo apt-get install ros-$ROS_DISTRO-behaviortree-cpp-v3 If you want to compile it with catkin, you __must__ include this package to your catkin workspace. diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index cac87d7d0..188ea1a55 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8) +cmake_minimum_required(VERSION 3.5.2) include_directories( ../sample_nodes ) diff --git a/sample_nodes/CMakeLists.txt b/sample_nodes/CMakeLists.txt index 7ff0afb21..e93d850ea 100644 --- a/sample_nodes/CMakeLists.txt +++ b/sample_nodes/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8) +cmake_minimum_required(VERSION 3.5.2) include_directories( ../include ) From 4107ac46ef7d9674ca4f84c75c506e6756e0dd96 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 22:48:19 +0100 Subject: [PATCH 050/163] cleanup --- CMakeLists.ros2 | 231 -- CMakeLists.txt.user.4.9-pre1 | 2093 ----------------- CMakeSettings.json | 30 - README.md | 8 +- RoadmapDiscussion.md | 264 --- behaviortree_schema.xsd | 143 -- .../groot-screenshot.png | Bin .../robmosys_conformant_logo.png | Bin video_MOOD2Be.png => docs/video_MOOD2Be.png | Bin 9 files changed, 4 insertions(+), 2765 deletions(-) delete mode 100644 CMakeLists.ros2 delete mode 100644 CMakeLists.txt.user.4.9-pre1 delete mode 100644 CMakeSettings.json delete mode 100644 RoadmapDiscussion.md delete mode 100644 behaviortree_schema.xsd rename groot-screenshot.png => docs/groot-screenshot.png (100%) rename robmosys_conformant_logo.png => docs/robmosys_conformant_logo.png (100%) rename video_MOOD2Be.png => docs/video_MOOD2Be.png (100%) diff --git a/CMakeLists.ros2 b/CMakeLists.ros2 deleted file mode 100644 index 9140b220f..000000000 --- a/CMakeLists.ros2 +++ /dev/null @@ -1,231 +0,0 @@ -cmake_minimum_required(VERSION 2.8.12) # version on Ubuntu Trusty -project(behaviortree_cpp_v3) - -if(NOT CMAKE_VERSION VERSION_LESS 3.1) - set(CMAKE_CXX_STANDARD 11) - set(CMAKE_CXX_STANDARD_REQUIRED ON) -else() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") -endif() - -if(MSVC) - add_definitions(-D_CRT_SECURE_NO_WARNINGS) -endif() - -set(CMAKE_POSITION_INDEPENDENT_CODE ON) - -set(CMAKE_CONFIG_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake") -list(APPEND CMAKE_MODULE_PATH "${CMAKE_CONFIG_PATH}") - -option(BUILD_EXAMPLES "Build tutorials and examples" ON) -option(BUILD_UNIT_TESTS "Build the unit tests" ON) -option(BUILD_TOOLS "Build commandline tools" ON) - -############################################################# -# Find packages -find_package(Threads REQUIRED) -find_package(ZMQ) - -list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES - ${CMAKE_THREAD_LIBS_INIT} - ${CMAKE_DL_LIBS} ) - -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) -else() - message(WARNING "ZeroMQ NOT found. Skipping the build of [PublisherZMQ] and [bt_recorder].") -endif() - -set(BEHAVIOR_TREE_LIBRARY ${PROJECT_NAME}) - - -# Update the policy setting to avoid an error when loading the ament_cmake package -# at the current cmake version level -if(POLICY CMP0057) - cmake_policy(SET CMP0057 NEW) -endif() - -find_package(ament_cmake QUIET) - -if ( ament_cmake_FOUND ) - # Not adding -DUSING_ROS since xml_parsing.cpp hasn't been ported to ROS2 - - message(STATUS "------------------------------------------") - message(STATUS "BehaviourTree is being built using AMENT.") - message(STATUS "------------------------------------------") - - set(BUILD_TOOL_INCLUDE_DIRS ${ament_INCLUDE_DIRS}) - -elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) - - set(catkin_FOUND 1) - add_definitions( -DUSING_ROS ) - find_package(catkin REQUIRED COMPONENTS roslib) - find_package(GTest) - - message(STATUS "------------------------------------------") - message(STATUS "BehaviourTree is being built using CATKIN.") - message(STATUS "------------------------------------------") - - catkin_package( - INCLUDE_DIRS include # do not include "3rdparty" here - LIBRARIES ${BEHAVIOR_TREE_LIBRARY} - CATKIN_DEPENDS roslib - ) - - list(APPEND BEHAVIOR_TREE_EXTERNAL_LIBRARIES ${catkin_LIBRARIES}) - set(BUILD_TOOL_INCLUDE_DIRS ${catkin_INCLUDE_DIRS}) - -else() - find_package(GTest) - - if(NOT GTEST_FOUND) - message(WARNING " GTest missing!") - endif(NOT GTEST_FOUND) - -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_PACKAGE_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 - -list(APPEND BT_SOURCE - src/action_node.cpp - src/basic_types.cpp - src/behavior_tree.cpp - src/blackboard.cpp - src/bt_factory.cpp - src/decorator_node.cpp - src/condition_node.cpp - src/control_node.cpp - src/shared_library.cpp - src/tree_node.cpp - src/xml_parsing.cpp - - src/decorators/inverter_node.cpp - src/decorators/repeat_node.cpp - src/decorators/retry_node.cpp - src/decorators/subtree_node.cpp - src/decorators/timeout_node.cpp - - src/controls/fallback_node.cpp - src/controls/parallel_node.cpp - src/controls/reactive_sequence.cpp - src/controls/reactive_fallback.cpp - src/controls/sequence_node.cpp - src/controls/sequence_star_node.cpp - - src/loggers/bt_cout_logger.cpp - src/loggers/bt_file_logger.cpp - src/loggers/bt_minitrace_logger.cpp - src/private/tinyxml2.cpp - - 3rdparty/minitrace/minitrace.cpp - ) - -###################################################### -set(CMAKE_DEBUG_POSTFIX "d") - -if (UNIX) - list(APPEND BT_SOURCE src/shared_library_UNIX.cpp ) - add_library(${BEHAVIOR_TREE_LIBRARY} SHARED ${BT_SOURCE} ) -endif() - -if (WIN32) - list(APPEND BT_SOURCE src/shared_library_WIN.cpp ) - add_library(${BEHAVIOR_TREE_LIBRARY} STATIC ${BT_SOURCE} ) -endif() - -target_link_libraries(${BEHAVIOR_TREE_LIBRARY} PUBLIC - ${BEHAVIOR_TREE_EXTERNAL_LIBRARIES}) - -target_compile_definitions(${BEHAVIOR_TREE_LIBRARY} PRIVATE $<$:TINYXML2_DEBUG>) - -target_include_directories(${BEHAVIOR_TREE_LIBRARY} PUBLIC - $ - $ - $ - ${BUILD_TOOL_INCLUDE_DIRS}) - -if( ZMQ_FOUND ) - target_compile_definitions(${BEHAVIOR_TREE_LIBRARY} PUBLIC ZMQ_FOUND) -endif() - -if(MSVC) - target_compile_options(${BEHAVIOR_TREE_LIBRARY} PRIVATE /W4 /WX) -else() - target_compile_options(${BEHAVIOR_TREE_LIBRARY} PRIVATE - -Wall -Wextra -Werror=return-type) -endif() - -###################################################### -# Test -add_subdirectory(tests) - -###################################################### -# INSTALL -set(PROJECT_NAMESPACE BehaviorTree) -set(PROJECT_CONFIG ${PROJECT_NAMESPACE}Config) - -INSTALL(TARGETS ${BEHAVIOR_TREE_LIBRARY} - EXPORT ${PROJECT_CONFIG} - ARCHIVE DESTINATION ${BEHAVIOR_TREE_BIN_DESTINATION} - LIBRARY DESTINATION ${BEHAVIOR_TREE_LIB_DESTINATION} - ) - -INSTALL( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ - DESTINATION ${BEHAVIOR_TREE_INC_DESTINATION} - FILES_MATCHING PATTERN "*.h*") - -install(EXPORT ${PROJECT_CONFIG} - DESTINATION "${BEHAVIOR_TREE_LIB_DESTINATION}/${PROJECT_NAMESPACE}/cmake" - NAMESPACE ${PROJECT_NAMESPACE}::) - -export(TARGETS ${PROJECT_NAME} - NAMESPACE ${PROJECT_NAMESPACE}:: - FILE "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_CONFIG}.cmake") - -###################################################### -# EXAMPLES and TOOLS -if(BUILD_TOOLS) - add_subdirectory(tools) -endif() - -if( BUILD_EXAMPLES ) - add_subdirectory(sample_nodes) - add_subdirectory(examples) -endif() - - diff --git a/CMakeLists.txt.user.4.9-pre1 b/CMakeLists.txt.user.4.9-pre1 deleted file mode 100644 index 91de07f65..000000000 --- a/CMakeLists.txt.user.4.9-pre1 +++ /dev/null @@ -1,2093 +0,0 @@ - - - - - - EnvironmentId - {54116f33-ad05-44df-b3b4-466dc32142b1} - - - ProjectExplorer.Project.ActiveTarget - 0 - - - ProjectExplorer.Project.EditorSettings - - true - false - true - - Cpp - - CppGlobal - - - - QmlJS - - QmlJSGlobal - - - 2 - UTF-8 - false - 4 - false - 80 - true - true - 1 - true - false - 0 - true - true - 0 - 8 - true - 1 - true - true - true - false - - - - ProjectExplorer.Project.PluginSettings - - - true - - - - ProjectExplorer.Project.Target.0 - - Desktop Qt 5.5.1 - Desktop Qt 5.5.1 - {7a57ac93-ba2b-4737-9b6b-30fafaa176d4} - 0 - 0 - 19 - - - CMAKE_BUILD_TYPE:STRING=Debug - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug - - - -j8 - - all - - true - CMake Build - - CMakeProjectManager.MakeStep - - 1 - Build - - ProjectExplorer.BuildSteps.Build - - - - - - clean - - true - CMake Build - - CMakeProjectManager.MakeStep - - 1 - Clean - - ProjectExplorer.BuildSteps.Clean - - 2 - false - - Debug - Debug - CMakeProjectManager.CMakeBuildConfiguration - - - - CMAKE_BUILD_TYPE:STRING=Release - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Release - - - - - all - - true - CMake Build - - CMakeProjectManager.MakeStep - - 1 - Build - - ProjectExplorer.BuildSteps.Build - - - - - - clean - - true - CMake Build - - CMakeProjectManager.MakeStep - - 1 - Clean - - ProjectExplorer.BuildSteps.Clean - - 2 - false - - Release - Release - CMakeProjectManager.CMakeBuildConfiguration - - 2 - - - 0 - Deploy - - ProjectExplorer.BuildSteps.Deploy - - 1 - Deploy Configuration - - ProjectExplorer.DefaultDeployConfiguration - - 1 - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - behaviortree_cpp_test - - CMakeProjectManager.CMakeRunConfiguration.behaviortree_cpp_test -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - bt_log_cat - - CMakeProjectManager.CMakeRunConfiguration.bt_log_cat -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t01_first_tree_dynamic - - CMakeProjectManager.CMakeRunConfiguration.t01_first_tree_dynamic -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t04_sequence_star - - CMakeProjectManager.CMakeRunConfiguration.t04_sequence_star -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t07_wrap_legacy - - CMakeProjectManager.CMakeRunConfiguration.t07_wrap_legacy -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t06_subtree_port_remapping - - CMakeProjectManager.CMakeRunConfiguration.t06_subtree_port_remapping -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t08_async_actions_coroutines - - CMakeProjectManager.CMakeRunConfiguration.t08_async_actions_coroutines -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t09_async_actions_coroutines - - CMakeProjectManager.CMakeRunConfiguration.t09_async_actions_coroutines -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t08_additional_node_args - - CMakeProjectManager.CMakeRunConfiguration.t08_additional_node_args -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t04_reactive_sequence - - CMakeProjectManager.CMakeRunConfiguration.t04_reactive_sequence -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - behaviortree_cpp_v3_test - - CMakeProjectManager.CMakeRunConfiguration.behaviortree_cpp_v3_test -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - behaviortree_cpp_v3_test - behaviortree_cpp_v3_test2 - CMakeProjectManager.CMakeRunConfiguration.behaviortree_cpp_v3_test -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - bt_plugin_manifest - - CMakeProjectManager.CMakeRunConfiguration.bt_plugin_manifest -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - bt_log_cat - bt_log_cat2 - CMakeProjectManager.CMakeRunConfiguration.bt_log_cat -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - bt_plugin_manifest - bt_plugin_manifest2 - CMakeProjectManager.CMakeRunConfiguration.bt_plugin_manifest -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - bt_recorder - bt_recorder2 - CMakeProjectManager.CMakeRunConfiguration.bt_recorder -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t10_include_trees - t10_include_trees2 - CMakeProjectManager.CMakeRunConfiguration.t10_include_trees -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t03_generic_ports - t03_generic_ports2 - CMakeProjectManager.CMakeRunConfiguration.t03_generic_ports -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t02_basic_ports - t02_basic_ports2 - CMakeProjectManager.CMakeRunConfiguration.t02_basic_ports -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t01_first_tree_static - t01_first_tree_static2 - CMakeProjectManager.CMakeRunConfiguration.t01_first_tree_static -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t04_reactive_sequence - t04_reactive_sequence2 - CMakeProjectManager.CMakeRunConfiguration.t04_reactive_sequence -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t09_async_actions_coroutines - t09_async_actions_coroutines2 - CMakeProjectManager.CMakeRunConfiguration.t09_async_actions_coroutines -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t05_crossdoor - t05_crossdoor2 - CMakeProjectManager.CMakeRunConfiguration.t05_crossdoor -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - bt_recorder - - CMakeProjectManager.CMakeRunConfiguration.bt_recorder -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t01_first_tree_dynamic - t01_first_tree_dynamic2 - CMakeProjectManager.CMakeRunConfiguration.t01_first_tree_dynamic -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t07_wrap_legacy - t07_wrap_legacy2 - CMakeProjectManager.CMakeRunConfiguration.t07_wrap_legacy -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t06_subtree_port_remapping - t06_subtree_port_remapping2 - CMakeProjectManager.CMakeRunConfiguration.t06_subtree_port_remapping -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t08_additional_node_args - t08_additional_node_args2 - CMakeProjectManager.CMakeRunConfiguration.t08_additional_node_args -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/lib/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t10_include_trees - - CMakeProjectManager.CMakeRunConfiguration.t10_include_trees -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t03_generic_ports - - CMakeProjectManager.CMakeRunConfiguration.t03_generic_ports -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t02_basic_ports - - CMakeProjectManager.CMakeRunConfiguration.t02_basic_ports -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t09_additional_node_args - - CMakeProjectManager.CMakeRunConfiguration.t09_additional_node_args -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t01_first_tree_static - - CMakeProjectManager.CMakeRunConfiguration.t01_first_tree_static -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - - false - false - 1000 - - true - - false - false - false - false - true - 0.01 - 10 - true - 1 - 25 - - 1 - true - false - true - valgrind - - 0 - 1 - 2 - 3 - 4 - 5 - 6 - 7 - 8 - 9 - 10 - 11 - 12 - 13 - 14 - - 2 - - t05_crossdoor - - CMakeProjectManager.CMakeRunConfiguration.t05_crossdoor -/home/dfaconti/ws_behavior/src/BehaviorTree.CPP/bin/ - - 3768 - false - true - false - false - true - - /home/dfaconti/ws_behavior/src/build-BehaviorTree.CPP-Desktop-Debug/bin - - 34 - - - - ProjectExplorer.Project.TargetCount - 1 - - - ProjectExplorer.Project.Updater.FileVersion - 20 - - - Version - 20 - - diff --git a/CMakeSettings.json b/CMakeSettings.json deleted file mode 100644 index 34dae22b7..000000000 --- a/CMakeSettings.json +++ /dev/null @@ -1,30 +0,0 @@ -{ - "configurations": [ - { - "name": "x64-Release", - "generator": "Ninja", - "configurationType": "Release", - "inheritEnvironments": [ - "msvc_x86_x64" - ], - "buildRoot": "${workspaceRoot}\\build\\${name}", - "installRoot": "${workspaceRoot}\\install\\${name}", - "cmakeCommandArgs": "", - "buildCommandArgs": "-v", - "ctestCommandArgs": "" - }, - { - "name": "x64-Debug", - "generator": "Ninja", - "configurationType": "Debug", - "inheritEnvironments": [ - "msvc_x86_x64" - ], - "buildRoot": "${workspaceRoot}\\build\\${name}", - "installRoot": "${workspaceRoot}\\install\\${name}", - "cmakeCommandArgs": "", - "buildCommandArgs": "-v", - "ctestCommandArgs": "" - } - ] -} diff --git a/README.md b/README.md index 31e18d2a3..e10f2866e 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.0-green.svg) +![Version](https://img.shields.io/badge/version-v3.3-green.svg) Travis (Linux): [![Build Status](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP.svg?branch=master)](https://travis-ci.org/BehaviorTree/BehaviorTree.CPP) @@ -71,14 +71,14 @@ Editing a BehaviorTree is as simple as editing a XML file in your favourite text If you are looking for a more fancy graphical user interface (and I know you do) check [Groot](https://github.com/BehaviorTree/Groot) out. -![Groot screenshot](groot-screenshot.png) +![Groot screenshot](docs/groot-screenshot.png) ## Watch Groot and BehaviorTree.CPP in action Click on the following image to see a short video of how the C++ library and the graphic user interface are used to design and monitor a Behavior Tree. -[![MOOD2Be](video_MOOD2Be.png)](https://vimeo.com/304651183) +[![MOOD2Be](docs/video_MOOD2Be.png)](https://vimeo.com/304651183) # How to compile (plain old cmake @@ -128,7 +128,7 @@ This software is one of the main components of [MOOD2Be](https://eurecat.org/en/ which is one of the six **Integrated Technical Projects (ITPs)** selected from the [RobMoSys first open call](https://robmosys.eu/itp/). Therefore, MOOD2Be has been supported by the European Horizon2020 project RobMoSys. This software is RobMoSys conformant. -![RobMoSys Conformant](./robmosys_conformant_logo.png) +![RobMoSys Conformant](docs/robmosys_conformant_logo.png) # Further readings diff --git a/RoadmapDiscussion.md b/RoadmapDiscussion.md deleted file mode 100644 index 5b0899751..000000000 --- a/RoadmapDiscussion.md +++ /dev/null @@ -1,264 +0,0 @@ -# 1. Roadmap: input/output ports in TreeNode -## (Updated the 2019_01_03) - -One of the goals of this project is to separate the role of the __Component -Developer__ from the __Behavior Designed__ and __System Integrator__. - -Rephrasing: - -- Custom Actions (or, in general, custom TreeNodes) must be reusable building -blocks. - -- To build a BehaviorTree out of TreeNodes, the Behavior Designer must not need to read -nor modify the source code of the a given TreeNode. - -There is a __major design flow__ that undermines this goal: the way -the BlackBoard is currently used to implement dataflow between nodes. - -As described in [issue #18](https://github.com/BehaviorTree/BehaviorTree.CPP/issues/18) -there are several potential problems: - -- To know which entries of the BB are read/written, you should read the source code. -- As a consequence, external tools such as __Groot__ can not know which BB entries are accessed. -- If there is a name clashing (multiple nodes use the same key for different purposes), - the only way to fit it is modifying the source code. - -SMACH solved this problem using [input and output ports](http://wiki.ros.org/smach/Tutorials/User%20Data) -and remapping to connect them. - -In the ROS community, we potentially have the same problem with topics, -but tools such as __rosinfo__ provides introspection at run-time and name -clashing is avoided using remapping. - -# 2. Suggested changes to the library - -Goals of the new design: - -- The `TreeNodeManifest` should contain information about input and outputs ports, -to make this information available to external tools. - -- Avoid name clashing using key remapping. - - -## 2.1 Deprecate TreeNode::blackboard() - -In version 2.x the user is allowed to read and write into any single -entry of the blackboard. - -As a consequence, there is no way to introspect which entries are accessed. - -For this reason, we must deprecate `TreeNode::blackboard()` and use instead -a more sensible API such as `getInput` and `setOutput`. - -The latter methods should access only a limited number of entries, the __ports__. - -## 2.2 NameParameters == Input Ports - -In version 2.X, `NodeParameters` are a mechanism to add "arguments" to a Node. - -A NodeParameter can be either: - -- text that is parsed by the user's code using `convertFromString()` or -- a "pointer" to an entry of the BB. - -After few months, it became clear that the latter case is the rule rather than the exception: -in probably 80-90% of the cases, NodeParameters are passed through the BB. - -Furthermore, `requiredNodeParameters` is already an effective way to -automatically create a manifest. - -For these reasons, we may consider NodeParameters a valid implementation of an -__input port__. - -The implementation would still be the same, what changes is our interpretation, -i.e. NodeParameter __are__ input ports. - -From a practical point of view, we should encourage the use of -`TreeNode::getParam` and deprecate `TreeNode::blackboard()::get`. - -Furthermore, it makes sense, for consistency, to rename `getParam` to __getInput__. - -## 2.3 Output Ports - -We need to add the output ports to the TreeNodeManifest. - -The static method `requiredNodeParameters` should be replaced by -`providedPorts`: - - -```c++ - -enum class PortType { INPUT, OUTPUT, INOUT }; - -typedef std::unordered_map PortsList; - -// New Manifest. -struct TreeNodeManifest -{ - NodeType type; - std::string registration_ID; - PortsList ports; -}; - -// What was previously MyNode::requiredNodeParameters() becomes: -static PortsList MyNode::providedPorts(); - -``` - -Let's consider the problem of __remapping__. - -To avoid name clashing it is sufficient to remap __only for the output ports__. - -We don't need to remap input ports, because the name of the entry is -already provided at run-time (in the XML). - -From the user prospective, `TreeNode::blackboard()::set(key,value)` is replaced -by a new method `TreeNode::setOutput(key,value)`. - -__Example__: - -If the remapping pair __["goal","navigation_goal"]__ is passed and the user invokes - - setOutput("goal", "kitchen"); - -The actual entry to be written will be the `navigation_goal`. - -# 3. Further changes: NodeConfiguration - -### Major (breaking) changes in the signature of TreeNodes - -Since we are breaking the API, it makes sense to add another improvement that -is not backward compatible. - -People want to read/write from/to the blackboard in their constructor. -The callback `onInit()` was a workaround. - -For these reasons, we propose to change the signature of the TreeNode constructor from: - - TreeNode(const string& name, const NodeParameters& params) - -to: - - TreeNode(const string& name, const NodeConfiguration& config) - -where the definition of `NodeConfiguration` is: - -```c++ -typedef std::unordered_map PortsRemapping; - -struct NodeConfiguration -{ - Blackboard::Ptr blackboard; - PortsRemapping input_ports; - PortsRemapping output_ports; -}; -``` - -# 4. Code example - -Let's illustrate these changes with a practical example. - -In this example __path__ is an output port in `ComputePath` but an input port -in `FollowPath`. - -```XML - - - - - -``` - -No distinction is made in the XML between inputs, outputs; -additionally, passing static text parameters is __still__ possible -(see "hello World" in SaySomething). - -The actual entries to be read/written are the one specified in the remapping, -in this case: - - - when application code reads `endpoints`, it is actually reading `navigation_endpoints`. - - when application code reads/writes `path`, it is actually accessing `navigation_path`. - -Since these names are specified in the XML, name clashing can be avoided without -modifying the source code. - -The corresponfing C++ code might be: - -```C++ - -class SaySomething: public SyncActionNode -{ - public: - SaySomething(const std::string& name, const NodeConfiguration& config): - SyncActionNode(name, config){} - - NodeStatus tick() override - { - auto msg = getInput("message"); - if( !msg ) // msg is optional - { - return NodeStatus::FAILURE; - // or... - // throw if you think that this should not happen - // or... - // replace with default value - } - std::cout << msg.value() << std::endl; - return NodeStatus::SUCCESS; - } - static PortsList providedPorts() - { - static PortsList ports_list = { {"message", PortType::INPUT} ); - return ports_list; - } -}; - -class ComputePath: public SyncActionNode -{ - public: - ComputePath(const std::string& name, const NodeConfiguration& config): - SyncActionNode(name, config){} - - NodeStatus tick() override - { - auto end_points = getInput("endpoints"); - // do your stuff - setOutput("path", my_computed_path); - // return result... - } - static PortsList providedPorts() - { - static PortsList ports_list = { {"endpoints", PortType::INPUT}, - {"path", PortType::OUTPUT} }; - return ports_list; - } -}; - -class FollowPath: public AsyncActionNode -{ - public: - FollowPath(const std::string& name, const NodeConfiguration& config): - AsyncActionNode(name, config){} - - NodeStatus tick() override - { - auto path = getInput("path"); - // do your stuff - // return result... - } - static PortsList providedPorts() - { - static PortsList ports_list = { {"path", PortType::INPUT} }; - return ports_list; - } -}; -``` - -The user's code doesn't need to know if inputs where passed as "static text" -or "blackboard pointers". - - - - - diff --git a/behaviortree_schema.xsd b/behaviortree_schema.xsd deleted file mode 100644 index 5a478affb..000000000 --- a/behaviortree_schema.xsd +++ /dev/null @@ -1,143 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/groot-screenshot.png b/docs/groot-screenshot.png similarity index 100% rename from groot-screenshot.png rename to docs/groot-screenshot.png diff --git a/robmosys_conformant_logo.png b/docs/robmosys_conformant_logo.png similarity index 100% rename from robmosys_conformant_logo.png rename to docs/robmosys_conformant_logo.png diff --git a/video_MOOD2Be.png b/docs/video_MOOD2Be.png similarity index 100% rename from video_MOOD2Be.png rename to docs/video_MOOD2Be.png From 081033133050033df0043901f1f9d60397730ca7 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Sun, 22 Mar 2020 22:50:38 +0100 Subject: [PATCH 051/163] Update README.md --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index e10f2866e..ab5ac9799 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.X +# About version 3.3 and above 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 @@ -57,7 +57,7 @@ In practice, this means that: - 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. -Version __3.x__ of this library introduces some dramatic changes in the API, but +Version __3.3+__ of this library introduces some dramatic changes in the API, but it was necessary to reach this goal. If you used version 2.X in the past, you can @@ -107,7 +107,7 @@ set(CMAKE_CXX_STANDARD_REQUIRED ON) find_package(BehaviorTreeV3) add_executable(${PROJECT_NAME} "hello_BT.cpp") -target_link_libraries(${PROJECT_NAME} BT3::behaviortree_cpp_v3) +target_link_libraries(${PROJECT_NAME} BT::behaviortree_cpp_v3) ``` ## ROS1 or ROS2 users (Catkin/Ament) From 64a7fa59b7b3332666507a69e75ce9f26fef8fd7 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 Mar 2020 16:56:22 +0100 Subject: [PATCH 052/163] fix typo --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 34972c04f..13a4076fe 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -242,7 +242,7 @@ INSTALL( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/include/ FILES_MATCHING PATTERN "*.h*") install(EXPORT BehaviorTreeV3Config - DESTINATION "${BEHAVIOR_TREE_LIB_DESTINATION}/$BehaviorTreeV3/cmake" + DESTINATION "${BEHAVIOR_TREE_LIB_DESTINATION}/BehaviorTreeV3/cmake" NAMESPACE BT::) export(TARGETS ${PROJECT_NAME} From 727eb32017ab77f0f807adb8e0ffb2345824861b Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 Mar 2020 17:02:11 +0100 Subject: [PATCH 053/163] fix warning --- include/behaviortree_cpp_v3/tree_node.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/behaviortree_cpp_v3/tree_node.h b/include/behaviortree_cpp_v3/tree_node.h index 278b9757c..1ed6ece23 100644 --- a/include/behaviortree_cpp_v3/tree_node.h +++ b/include/behaviortree_cpp_v3/tree_node.h @@ -153,7 +153,7 @@ class TreeNode friend class BehaviorTreeFactory; friend class DecoratorNode; friend class ControlNode; - friend struct Tree; + friend class Tree; // Only BehaviorTreeFactory should call this void setRegistrationID(StringView ID) From 4c89343ddb410965c40a9619475de971a2667839 Mon Sep 17 00:00:00 2001 From: Davide Faconti Date: Mon, 23 Mar 2020 17:10:05 +0100 Subject: [PATCH 054/163] removed failing compilation from AppVeyor --- .appveyor.yml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.appveyor.yml b/.appveyor.yml index ee68e567d..0bb8c1909 100644 --- a/.appveyor.yml +++ b/.appveyor.yml @@ -2,8 +2,6 @@ clone_depth: 5 environment: matrix: - - GENERATOR : "MinGW Makefiles" - PLATFORM: x86 - GENERATOR : "Visual Studio 15 2017 Win64" APPVEYOR_BUILD_WORKER_IMAGE: Visual Studio 2017 PLATFORM: x64 From c34a79b2ef63fbc9c69a8958647a5da34eda064c Mon Sep 17 00:00:00 2001 From: Alexis Paques Date: Thu, 2 Apr 2020 11:42:04 +0200 Subject: [PATCH 055/163] Fix catkin build for v3 (#169) --- package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/package.xml b/package.xml index 006c8c923..d881df4ef 100644 --- a/package.xml +++ b/package.xml @@ -22,6 +22,7 @@ libzmq3-dev + catkin ament_cmake From d3667ce68932673872a52f526a3b2d461ebecab5 Mon Sep 17 00:00:00 2001 From: Sebastian Ahlman Date: Wed, 8 Apr 2020 10:27:21 +0300 Subject: [PATCH 056/163] Fixed a few typos related to SubtreeWrapper. (#171) --- include/behaviortree_cpp_v3/decorators/subtree_node.h | 2 +- src/basic_types.cpp | 2 +- src/decorators/subtree_node.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/behaviortree_cpp_v3/decorators/subtree_node.h b/include/behaviortree_cpp_v3/decorators/subtree_node.h index 5193f28be..36f6afdd3 100644 --- a/include/behaviortree_cpp_v3/decorators/subtree_node.h +++ b/include/behaviortree_cpp_v3/decorators/subtree_node.h @@ -29,7 +29,7 @@ class SubtreeNode : public DecoratorNode }; /** - * @brief The TransparentSubtreeNode is a way to wrap an entire Subtree. + * @brief The SubtreeWrapperNode is a way to wrap an entire Subtree. * It does NOT have a separated BlackBoard and does not need ports remapping. */ class SubtreeWrapperNode : public DecoratorNode diff --git a/src/basic_types.cpp b/src/basic_types.cpp index 7a98c4bc4..e81697240 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 == "Subtree" ) return NodeType::SUBTREE; + if( str == "SubTree" || str == "SubtreeWrapper" ) return NodeType::SUBTREE; return NodeType::UNDEFINED; } diff --git a/src/decorators/subtree_node.cpp b/src/decorators/subtree_node.cpp index 4b49d0979..7a70b7b78 100644 --- a/src/decorators/subtree_node.cpp +++ b/src/decorators/subtree_node.cpp @@ -20,7 +20,7 @@ BT::NodeStatus BT::SubtreeNode::tick() BT::SubtreeWrapperNode::SubtreeWrapperNode(const std::string &name) : DecoratorNode(name, {} ) { - setRegistrationID("TransparentSubtree"); + setRegistrationID("SubtreeWrapper"); } BT::NodeStatus BT::SubtreeWrapperNode::tick() 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 057/163] 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 058/163] 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 059/163] 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 060/163] 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 061/163] 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 062/163] 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 063/163] 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 064/163] 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 065/163] 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 066/163] 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 067/163] 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 068/163] 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 069/163] 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 070/163] 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 071/163] 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 072/163] 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 073/163] 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 074/163] 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 075/163] 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 076/163] 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 077/163] 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 078/163] 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 079/163] 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 080/163] 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 081/163] [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 082/163] 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 083/163] 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 084/163] 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 085/163] 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 086/163] 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 087/163] 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 088/163] 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 089/163] 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 090/163] 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 091/163] 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 092/163] 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 093/163] 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 094/163] 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 095/163] 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 096/163] 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 097/163] 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 098/163] 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 099/163] 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 100/163] 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 101/163] 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 102/163] 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 103/163] 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 104/163] 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 105/163] 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 106/163] 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 107/163] 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 108/163] 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 109/163] 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 110/163] 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 111/163] 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 112/163] 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 113/163] 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 114/163] 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 115/163] 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 116/163] 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 117/163] 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 118/163] 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 119/163] 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 120/163] 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 121/163] 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 122/163] 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 123/163] 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 124/163] 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 125/163] 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 126/163] 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 127/163] 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 128/163] 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 129/163] 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 130/163] 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 131/163] 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 132/163] 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 133/163] 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 134/163] 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 135/163] 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 136/163] 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 137/163] 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 138/163] 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 139/163] 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 140/163] 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 141/163] 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 142/163] 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 143/163] 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 144/163] 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 145/163] 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 146/163] 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 147/163] 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 148/163] 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 149/163] 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 150/163] 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 151/163] 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 152/163] 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 153/163] 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 154/163] 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 155/163] 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 156/163] 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 157/163] 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 158/163] 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 159/163] 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 160/163] 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 161/163] 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 162/163] 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 163/163] 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");