diff --git a/CMakeLists.txt b/CMakeLists.txt
index 32f34fb674db5c49156338ed7c0ca5cc5eb7871f..9f6d802e25f7d965942a502d0e615887db491547 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -79,7 +79,7 @@ find_package(catkin REQUIRED COMPONENTS behaviortree_cpp_v3)
 catkin_package(
   INCLUDE_DIRS include
   LIBRARIES ${PROJECT_NAME}
-  CATKIN_DEPENDS behaviortree_cpp_v3 
+  CATKIN_DEPENDS behaviortree_cpp_v3
 )
 
 ###########
@@ -95,7 +95,8 @@ 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)
+add_library(${PROJECT_NAME} src/iri_async_action.cpp src/iri_bt_factory.cpp
+              src/iri_bt_basic_nodes.cpp)
 target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
 
 ## Declare a cpp executable
diff --git a/README.md b/README.md
index 4098da0a6d86aa10815600c8a20de26fe1f6d560..87144a27f1c5810d67871edec0dccc9dcaa020b6 100644
--- a/README.md
+++ b/README.md
@@ -6,9 +6,11 @@ IRI BehaviorTree
 It's a library to adapt the [behaviortree](https://github.com/BehaviorTree/BehaviorTree.CPP) library to the use
 of [IRI modules](https://gitlab.iri.upc.edu/labrobotica/ros/iri_core/iri_ros_tools).
 
-It provides the possibility of creating asynchronous actions without the need of creating a class. Its *tick* 
+It provides the possibility of creating asynchronous actions without the need of creating a class. Its *tick*
 function is called from the main thread. There isn't implemented any *halt* function.
 
+Additionally, it provides some basic common BT nodes.
+
 ## ROS dependencies
 
 - [behaviortree_cpp_v3](https://github.com/BehaviorTree/BehaviorTree.CPP)
@@ -21,5 +23,7 @@ function is called from the main thread. There isn't implemented any *halt* func
 
 ## How to use it
 
-Substitute the *BehaviorTreeFactory* object with an *IriBehaviorTreeFactory* object. To add an *IriAsyncActionNode* 
-just call *registerIriAsyncAction* on the same way that a *registerSimpleAction* would be called.
\ No newline at end of file
+Substitute the *BehaviorTreeFactory* object with an *IriBehaviorTreeFactory* object. To add an *IriAsyncActionNode*
+just call *registerIriAsyncAction* on the same way that a *registerSimpleAction* would be called.
+
+To register the basic BT nodes just create an object of *IriBehaviorTreeBasicNodes* and call its *init* function.
diff --git a/include/iri_bt_basic_nodes.h b/include/iri_bt_basic_nodes.h
new file mode 100644
index 0000000000000000000000000000000000000000..e9b87f70d719d13c420b31131c207e091a5184dd
--- /dev/null
+++ b/include/iri_bt_basic_nodes.h
@@ -0,0 +1,38 @@
+#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
new file mode 100644
index 0000000000000000000000000000000000000000..d4e2c5e541e28fff2b2dbf31fbe44e1ca5e45af9
--- /dev/null
+++ b/src/iri_bt_basic_nodes.cpp
@@ -0,0 +1,11 @@
+#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;
+}