From 298f3dca91d86bfffe691f6c9ad87d4f375c734e Mon Sep 17 00:00:00 2001
From: Alopez <alopez@iri.upc.edu>
Date: Tue, 16 May 2023 17:48:20 +0200
Subject: [PATCH] Removed base_bt_functions

---
 CMakeLists.txt               |  3 +--
 README.md                    |  7 -------
 include/iri_bt_basic_nodes.h | 38 ------------------------------------
 src/iri_bt_basic_nodes.cpp   | 11 -----------
 4 files changed, 1 insertion(+), 58 deletions(-)
 delete mode 100644 include/iri_bt_basic_nodes.h
 delete mode 100644 src/iri_bt_basic_nodes.cpp

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 9f6d802..6231ae8 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -95,8 +95,7 @@ include_directories(${catkin_INCLUDE_DIRS})
 # add_library(iri_behaviortree
 #   src/${PROJECT_NAME}/iri_behaviortree.cpp
 # )
-add_library(${PROJECT_NAME} src/iri_async_action.cpp src/iri_bt_factory.cpp
-              src/iri_bt_basic_nodes.cpp)
+add_library(${PROJECT_NAME} src/iri_async_action.cpp src/iri_bt_factory.cpp)
 target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
 
 ## Declare a cpp executable
diff --git a/README.md b/README.md
index ed826a9..e201280 100644
--- a/README.md
+++ b/README.md
@@ -12,13 +12,6 @@ This library is intendend to expand the [behaviortree](https://github.com/Behavi
 
   This is acomplished with the definition of the new class **IriBehaviorTreeFactory**. This class just implements the *registerIriAsyncAction* function to register any *IriAsyncActionNode* in the same way a *SimpleActionNode* would be registered using *registerSimpleAction*.
 
-* It also provides a set of basic BehaviorTree nodes (BT nodes) and the function to register them.
-
-  This is acomplished with the definition of a new class **IriBehaviorTreeBasicNodes** that implements this basic BT nodes and provides a function called *init* to register these BT nodes.
-
-  The basic nodes provided are:
-  * **NOP:** Action that always return running.
-
  On the following image a general overview of the inheritance is shown:
 
 <img src="doc/images/general_overview.png" alt="Image: General overview">
diff --git a/include/iri_bt_basic_nodes.h b/include/iri_bt_basic_nodes.h
deleted file mode 100644
index e9b87f7..0000000
--- a/include/iri_bt_basic_nodes.h
+++ /dev/null
@@ -1,38 +0,0 @@
-#ifndef IRI_BT_BASIC_NODES_H
-#define IRI_BT_BASIC_NODES_H
-
-#include "iri_bt_factory.h"
-
-class IriBehaviorTreeBasicNodes
-{
-  public:
-    IriBehaviorTreeBasicNodes()
-    {
-
-    }
-
-    /**
-      * \brief Register all basic conditions and actions
-      *
-      * This function registers all basic conditions and actions needed for
-      * any generic application.
-      *
-      * \param factory (IriBehaviorTreeFactory)
-      *
-      */
-    void init(IriBehaviorTreeFactory &factory);
-
-  protected:
-    /**
-      * \brief Does nothing
-      *
-      * This function does nothing and it is useful for synchronous functions
-      * in order to wait for the action to finish (checking is_finished())
-      *
-      * \return a BT:NodeStatus::RUNNING always
-      *
-      */
-    BT::NodeStatus NOP();
-};
-
-#endif
diff --git a/src/iri_bt_basic_nodes.cpp b/src/iri_bt_basic_nodes.cpp
deleted file mode 100644
index d4e2c5e..0000000
--- a/src/iri_bt_basic_nodes.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-#include "iri_bt_basic_nodes.h"
-
-void IriBehaviorTreeBasicNodes::init(IriBehaviorTreeFactory &factory)
-{
-  factory.registerIriAsyncAction("NOP",  std::bind(&IriBehaviorTreeBasicNodes::NOP, this));
-}
-
-BT::NodeStatus IriBehaviorTreeBasicNodes::NOP()
-{
-    return BT::NodeStatus::RUNNING;
-}
-- 
GitLab