diff --git a/cfg/TiagoGripperBtClient.cfg b/cfg/TiagoGripperBtClient.cfg
index bf98b3735d50a6a06174991876a9bdd478c2b6f3..fdf8fcf2a577b7f607125d9ee672b1da349461fe 100755
--- a/cfg/TiagoGripperBtClient.cfg
+++ b/cfg/TiagoGripperBtClient.cfg
@@ -41,7 +41,5 @@ gen = ParameterGenerator()
 #       Name                       Type       Reconfiguration level            Description                       Default   Min   Max
 #gen.add("velocity_scale_factor",  double_t,  0,                               "Maximum velocity scale factor",  0.5,      0.0,  1.0)
 add_bt_client_params(gen)
-gen.add("START",                    bool_t,     0,                              "synchronous start",                       False)
-gen.add("RESTART",                  bool_t,     0,                              "asynchronous restart of BT",              False)
 
 exit(gen.generate(PACKAGE, "TiagoGripperModuleBtClientAlgNode", "TiagoGripperBtClient"))
diff --git a/include/tiago_gripper_module/tiago_gripper_module_bt.h b/include/tiago_gripper_module/tiago_gripper_module_bt.h
index cabf30b0ba3b12aafc40061d01ae93eacec3abb9..8658c17385ae2a0fc07efa88141a4219c95e9c93 100644
--- a/include/tiago_gripper_module/tiago_gripper_module_bt.h
+++ b/include/tiago_gripper_module/tiago_gripper_module_bt.h
@@ -253,7 +253,7 @@ class CTiagoGripperModuleBT
       *
       *   distance (double): Distance between fingers.
       *
-      *   duration (std::vector<double>): Time from start to move the gripper. 
+      *   duration (double): Time from start to move the gripper. 
       *
       * \param self node with the required inputs ports:
       *
@@ -275,7 +275,7 @@ class CTiagoGripperModuleBT
       *
       *   distance (double): Distance between fingers.
       *
-      *   duration (std::vector<double>): Time from start to move the gripper.  
+      *   duration (double): Time from start to move the gripper.  
       *
       * It also has a bidirectional port:
       *
diff --git a/src/tiago_gripper_bt_client_alg_node.cpp b/src/tiago_gripper_bt_client_alg_node.cpp
index 0346c97bd1b51c94ee2f6572c5ae1eb1f125c40c..00a05fd3cefde48e6ae85dc9ba17683a03672a50 100644
--- a/src/tiago_gripper_bt_client_alg_node.cpp
+++ b/src/tiago_gripper_bt_client_alg_node.cpp
@@ -37,18 +37,6 @@ void TiagoGripperModuleBtClientAlgNode::node_config_update(tiago_gripper_module:
 {
   this->lock();
 
-  if(config.START)
-  {
-    this->core.start_tree();
-    config.START=false;
-  }
-
-  if(config.RESTART)
-  {
-    this->core.stop_tree();
-    config.RESTART=false;
-  }
-
   this->config_=config;
   this->unlock();
 }
diff --git a/src/tiago_gripper_module.cpp b/src/tiago_gripper_module.cpp
index 0cf34fcccbf353e775cf97b4ecc69fdc5c5dacbf..248b32fd1f6e6f0a42f368f15fac9cbd693fa7b3 100644
--- a/src/tiago_gripper_module.cpp
+++ b/src/tiago_gripper_module.cpp
@@ -87,34 +87,28 @@ void CTiagoGripperModule::state_machine(void)
                                 case ACTION_SUCCESS: ROS_INFO("CTiagoGripperModule : action ended successfully");
                                                      this->state=TIAGO_GRIPPER_MODULE_IDLE;
                                                      this->status=TIAGO_GRIPPER_MODULE_SUCCESS;
-                                                     this->gripper_action.stop_timeout();
                                                      break;
                                 case ACTION_TIMEOUT: ROS_ERROR("CTiagoGripperModule : action did not finish in the allowed time");
                                                      this->gripper_action.cancel();
                                                      this->state=TIAGO_GRIPPER_MODULE_IDLE;
                                                      this->status=TIAGO_GRIPPER_MODULE_TIMEOUT;
-                                                     this->gripper_action.stop_timeout();
                                                      break;
                                 case ACTION_FB_WATCHDOG: ROS_ERROR("CTiagoGripperModule : No feeback received for a long time");
                                                          this->gripper_action.cancel();
                                                          this->state=TIAGO_GRIPPER_MODULE_IDLE;
                                                          this->status=TIAGO_GRIPPER_MODULE_FB_WATCHDOG;
-                                                         this->gripper_action.stop_timeout();
                                                          break;
                                 case ACTION_ABORTED: ROS_ERROR("CTiagoGripperModule : Action failed to complete");
                                                      this->state=TIAGO_GRIPPER_MODULE_IDLE;
                                                      this->status=TIAGO_GRIPPER_MODULE_ABORTED;
-                                                     this->gripper_action.stop_timeout();
                                                      break;
                                 case ACTION_PREEMPTED: ROS_ERROR("CTiagoGripperModule : Action was interrupted by another request");
                                                        this->state=TIAGO_GRIPPER_MODULE_IDLE;
                                                        this->status=TIAGO_GRIPPER_MODULE_PREEMPTED;
-                                                       this->gripper_action.stop_timeout();
                                                        break;
                                 case ACTION_REJECTED: ROS_ERROR("CTiagoGripperModule : Action was interrupted by another request");
                                                       this->state=TIAGO_GRIPPER_MODULE_IDLE;
                                                       this->status=TIAGO_GRIPPER_MODULE_REJECTED;
-                                                      this->gripper_action.stop_timeout();
                                                       break;
                               }
                               if(this->cancel_pending)
diff --git a/src/tiago_gripper_module_bt.cpp b/src/tiago_gripper_module_bt.cpp
index b28e934b61527f9d20281b27c6efb7d3dbfc2798..daac2ebb334ea2aac09f60cff6a26762a9ed8efe 100644
--- a/src/tiago_gripper_module_bt.cpp
+++ b/src/tiago_gripper_module_bt.cpp
@@ -16,8 +16,8 @@ void CTiagoGripperModuleBT::init(IriBehaviorTreeFactory &factory)
   BT::PortsList sync_move_fingers_ports = {BT::InputPort<double>("left_finger"), BT::InputPort<double>("right_finger"), BT::InputPort<double>("duration")};
   BT::PortsList async_move_fingers_ports = {BT::InputPort<double>("left_finger"), BT::InputPort<double>("right_finger"), BT::InputPort<double>("duration"), BT::BidirectionalPort<bool>("new_goal")};
 
-  BT::PortsList sync_move_fingers_multi_ports = {BT::InputPort<std::vector<std::string>>("left_finger"), BT::InputPort<std::vector<double>>("right_finger"), BT::InputPort<std::vector<double>>("duration")};
-  BT::PortsList async_move_fingers_multi_ports = {BT::InputPort<std::vector<std::string>>("left_finger"), BT::InputPort<std::vector<double>>("right_finger"), BT::InputPort<std::vector<double>>("duration"), BT::BidirectionalPort<bool>("new_goal")};
+  BT::PortsList sync_move_fingers_multi_ports = {BT::InputPort<std::vector<double>>("left_finger"), BT::InputPort<std::vector<double>>("right_finger"), BT::InputPort<std::vector<double>>("duration")};
+  BT::PortsList async_move_fingers_multi_ports = {BT::InputPort<std::vector<double>>("left_finger"), BT::InputPort<std::vector<double>>("right_finger"), BT::InputPort<std::vector<double>>("duration"), BT::BidirectionalPort<bool>("new_goal")};
 
   BT::PortsList sync_fingers_distance_ports = {BT::InputPort<double>("distance"), BT::InputPort<double>("duration")};
   BT::PortsList async_fingers_distance_ports = {BT::InputPort<double>("distance"), BT::InputPort<double>("duration"), BT::BidirectionalPort<bool>("new_goal")};
@@ -97,6 +97,7 @@ BT::NodeStatus CTiagoGripperModuleBT::async_close_tiago_gripper(BT::TreeNode& se
 
   if (new_goal)
   {
+    self.setOutput("new_goal", false);
     if (!duration)
       this->tiago_gripper_module.close();
     else
@@ -114,8 +115,6 @@ BT::NodeStatus CTiagoGripperModuleBT::async_close_tiago_gripper(BT::TreeNode& se
     else
       return BT::NodeStatus::FAILURE;
   }
-  if (new_goal)
-    self.setOutput("new_goal", false);
   return BT::NodeStatus::RUNNING;
 }
 
@@ -149,6 +148,7 @@ BT::NodeStatus CTiagoGripperModuleBT::async_open_tiago_gripper(BT::TreeNode& sel
 
   if (new_goal)
   {
+    self.setOutput("new_goal", false);
     if (!duration)
       this->tiago_gripper_module.open();
     else
@@ -166,8 +166,6 @@ BT::NodeStatus CTiagoGripperModuleBT::async_open_tiago_gripper(BT::TreeNode& sel
     else
       return BT::NodeStatus::FAILURE;
   }
-  if (new_goal)
-    self.setOutput("new_goal", false);
   return BT::NodeStatus::RUNNING;
 }
 
@@ -215,6 +213,7 @@ BT::NodeStatus CTiagoGripperModuleBT::async_move_fingers_tiago_gripper(BT::TreeN
 
   if (new_goal)
   {
+    self.setOutput("new_goal", false);
     if (!left_finger || !right_finger)
     {
       ROS_ERROR("CTiagoGripperModuleBT::async_move_fingers_tiago_gripper-> Incorrect or missing input. It needs the following input ports: left_finger(double), right_finger(double) and duration(double)");
@@ -242,8 +241,6 @@ BT::NodeStatus CTiagoGripperModuleBT::async_move_fingers_tiago_gripper(BT::TreeN
     else
       return BT::NodeStatus::FAILURE;
   }
-  if (new_goal)
-    self.setOutput("new_goal", false);
   return BT::NodeStatus::RUNNING;
 }
 
@@ -285,6 +282,7 @@ BT::NodeStatus CTiagoGripperModuleBT::async_move_fingers_multi_tiago_gripper(BT:
 
   if (new_goal)
   {
+    self.setOutput("new_goal", false);
     if (!left_finger || !right_finger || !duration)
     {
       ROS_ERROR("CTiagoGripperModuleBT::async_move_fingers_multi_tiago_gripper-> Incorrect or missing input. It needs the following input ports: left_finger(std::vector<double>), right_finger(std::vector<double>) and duration(std::vector<double>)");
@@ -306,8 +304,6 @@ BT::NodeStatus CTiagoGripperModuleBT::async_move_fingers_multi_tiago_gripper(BT:
     else
       return BT::NodeStatus::FAILURE;
   }
-  if (new_goal)
-    self.setOutput("new_goal", false);
   return BT::NodeStatus::RUNNING;
 }
 
@@ -352,6 +348,7 @@ BT::NodeStatus CTiagoGripperModuleBT::async_fingers_distance_tiago_gripper(BT::T
 
   if (new_goal)
   {
+    self.setOutput("new_goal", false);
     if (!distance)
     {
       ROS_ERROR("CTiagoGripperModuleBT::async_fingers_distance_tiago_gripper-> Incorrect or missing input. It needs the following input ports: distance(double) and duration(double)");
@@ -378,8 +375,6 @@ BT::NodeStatus CTiagoGripperModuleBT::async_fingers_distance_tiago_gripper(BT::T
     else
       return BT::NodeStatus::FAILURE;
   }
-  if (new_goal)
-    self.setOutput("new_goal", false);
   return BT::NodeStatus::RUNNING;
 }
 
@@ -403,7 +398,10 @@ BT::NodeStatus CTiagoGripperModuleBT::async_close_grasp_tiago_gripper(BT::TreeNo
     new_goal = new_goal_in.value();
 
   if (new_goal)
+  {
+    self.setOutput("new_goal", false);
     this->tiago_gripper_module.close_grasp();
+  }
   if (this->tiago_gripper_module.is_finished())
   {
     tiago_gripper_module_status_t tiago_gripper_module_status = this->tiago_gripper_module.get_status();
@@ -412,8 +410,6 @@ BT::NodeStatus CTiagoGripperModuleBT::async_close_grasp_tiago_gripper(BT::TreeNo
     else
       return BT::NodeStatus::FAILURE;
   }
-  if (new_goal)
-    self.setOutput("new_goal", false);
   return BT::NodeStatus::RUNNING;
 }
 
@@ -429,13 +425,7 @@ BT::NodeStatus CTiagoGripperModuleBT::async_cancel_tiago_gripper_action(void)
   ROS_DEBUG("CTiagoNavModuleBT::async_cancel_tiago_gripper_action-> async_cancel_tiago_gripper_action");
   this->tiago_gripper_module.stop();
   if (this->tiago_gripper_module.is_finished())
-  {
-    tiago_gripper_module_status_t tiago_gripper_module_status = this->tiago_gripper_module.get_status();
-    if (tiago_gripper_module_status == TIAGO_GRIPPER_MODULE_SUCCESS)
-      return BT::NodeStatus::SUCCESS;
-    else
-      return BT::NodeStatus::FAILURE;
-  }
+    return BT::NodeStatus::SUCCESS;
   return BT::NodeStatus::RUNNING;
 }
 
diff --git a/src/xml/bt_definitions.xml b/src/xml/bt_definitions.xml
new file mode 100644
index 0000000000000000000000000000000000000000..cbab01c1fbf0e8ce0b3eb14442153da0d4c3d6c4
--- /dev/null
+++ b/src/xml/bt_definitions.xml
@@ -0,0 +1,108 @@
+<?xml version="1.0"?>
+<root main_tree_to_execute="BehaviorTree">
+    <!-- ////////// -->
+    <BehaviorTree ID="BehaviorTree">
+        <Action ID="RUNNING"/>
+    </BehaviorTree>
+    <!-- ////////// -->
+    <TreeNodesModel>
+        <!-- basic_nodes -->
+        <Action ID="RUNNING"/>
+        <Action ID="is_variable_true">
+            <input_port name="variable"> (bool): Bool variable to check.</input_port>
+        </Action>
+        <Action ID="is_variable_false">
+            <input_port name="variable"> (bool): Bool variable to check.</input_port>
+        </Action>
+        <Action ID="transform_pose">
+            <input_port name="pose_in"> (geometry_msgs::PoseStamped): Pose to be transformed.</input_port>
+            <input_port name="target_frame"> (std::string): Frame to transform the pose.</input_port>
+            <output_port name="pose_out"> (geometry_msgs::PoseStamped): Transformed pose.</output_port>
+        </Action>
+        <Action ID="compute_distance">
+            <input_port name="pose1"> (geometry_msgs::PoseStamped): Pose 1.</input_port>
+            <input_port name="pose2"> (geometry_msgs::PoseStamped): Pose 2.</input_port>
+            <output_port name="distance"> (double): Distance.</output_port>
+        </Action>
+        <Action ID="compare_bigger">
+            <input_port name="value1"> (double): Value 1.</input_port>
+            <input_port name="value2"> (double): Value 2.</input_port>
+        </Action>
+        <Action ID="compare_smaller">
+            <input_port name="value1"> (double): Value 1.</input_port>
+            <input_port name="value2"> (double): Value 2.</input_port>
+        </Action>
+        <Action ID="print_msg">
+            <input_port name="msg"> (std::string): Msg to print.</input_port>
+            <input_port name="type"> (std::string): It must be info, warn, error or debug.</input_port>
+        </Action>
+        <!-- gripper module -->
+        <Action ID="sync_cancel_tiago_gripper_action"/>
+        <Action ID="async_cancel_tiago_gripper_action"/>
+        <Action ID="async_is_tiago_gripper_finished"/>
+        <Action ID="sync_close_tiago_gripper">
+            <input_port name="duration"> Time from start to close the gripper (double)</input_port>
+        </Action>
+        <Action ID="async_close_tiago_gripper">
+            <input_port name="duration"> Time from start to close the gripper (double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
+        </Action>
+        <Action ID="sync_open_tiago_gripper">
+            <input_port name="duration"> Time from start to open the gripper (double)</input_port>
+        </Action>
+        <Action ID="async_open_tiago_gripper">
+            <input_port name="duration"> Time from start to open the gripper (double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
+        </Action>
+        <Action ID="sync_move_fingers_tiago_gripper">
+            <input_port name="left_finger"> Left finger position (double)</input_port>
+            <input_port name="right_finger"> Right finger position (double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (double)</input_port>
+        </Action>
+        <Action ID="async_move_fingers_tiago_gripper">
+            <input_port name="left_finger"> Left finger position (double)</input_port>
+            <input_port name="right_finger"> Right finger position double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
+        </Action>
+        <Action ID="sync_move_fingers_multi_tiago_gripper">
+            <input_port name="left_finger"> Left finger positions (std::vector double)</input_port>
+            <input_port name="right_finger"> Right finger positions (std::vector double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (std::vector double)</input_port>
+        </Action>
+        <Action ID="async_move_fingers_multi_tiago_gripper">
+            <input_port name="left_finger"> Left finger positions (std::vector double)</input_port>
+            <input_port name="right_finger"> Right finger positions (std::vector double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (std::vector double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
+        </Action>
+        <Action ID="sync_fingers_distance_tiago_gripper">
+            <input_port name="distance"> Distance between fingers (double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (double)</input_port>
+        </Action>
+        <Action ID="async_fingers_distance_tiago_gripper">
+            <input_port name="distance"> Distance between fingers (double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
+        </Action>
+        <Action ID="sync_close_grasp_tiago_gripper"/>
+        <Action ID="async_close_grasp_tiago_gripper">
+            <inout_port default="True" name="new_goal"> If it's a new_goal (bool)</inout_port>
+        </Action>
+        <Condition ID="is_tiago_gripper_finished"/>
+        <Condition ID="is_tiago_gripper_module_running"/>
+        <Condition ID="is_tiago_gripper_module_success"/>
+        <Condition ID="is_tiago_gripper_module_action_start_fail"/>
+        <Condition ID="is_tiago_gripper_module_timeout"/>
+        <Condition ID="is_tiago_gripper_module_fb_watchdog"/>
+        <Condition ID="is_tiago_gripper_module_aborted"/>
+        <Condition ID="is_tiago_gripper_module_preempted"/>
+        <Condition ID="is_tiago_gripper_module_rejected"/>
+        <Condition ID="is_tiago_gripper_module_failed_grasp"/>
+        <!-- Client -->
+        <SubTree ID="set_fingers_pos_blackboard"/>
+    </TreeNodesModel>
+    <!-- ////////// -->
+</root>
+
+
diff --git a/src/xml/bt_test.xml b/src/xml/bt_test.xml
index a82d2eba0fc822b3f0459374d4e6f1373e60167e..6a8d66819f05aef2ffeb173d84c34b0d127b8819 100644
--- a/src/xml/bt_test.xml
+++ b/src/xml/bt_test.xml
@@ -3,14 +3,13 @@
     <!-- ////////// -->
     <BehaviorTree ID="BehaviorTree">
         <SequenceStar>
-            <Action ID="async_is_start_tree"/>
             <SetBlackboard output_key="duration" value="1.0"/>
             <SetBlackboard output_key="new_goal" value="True"/>
             <Action ID="async_close_tiago_gripper" duration="{duration}" new_goal="{new_goal}"/>
             <SetBlackboard output_key="distance" value="0.2"/>
             <Action ID="async_fingers_distance_tiago_gripper" distance="{distance}" duration="{duration}" new_goal="{new_goal}"/>
-            <SubTree ID="set_fingers_pos_blackboard" left_finger="left_finger" right_finger="right_finger" duration="duration" new_goal="new_goal"/>
-            <Action ID="async_move_fingers_tiago_gripper" left_finger="{left_finger}" right_finger="{right_finger}" duration="{duration}" new_goal="{new_goal}"/>
+            <!--<SubTree ID="set_fingers_pos_blackboard" left_finger="left_finger" right_finger="right_finger" duration="duration" new_goal="new_goal"/>
+            <Action ID="async_move_fingers_tiago_gripper" left_finger="{left_finger}" right_finger="{right_finger}" duration="{duration}" new_goal="{new_goal}"/>-->
         </SequenceStar>
     </BehaviorTree>
     <!-- ////////// -->
@@ -25,67 +24,87 @@
     <!-- ////////// -->
     <TreeNodesModel>
         <!-- basic_nodes -->
-        <Action ID="NOP"/>
-        <Action ID="is_not_start_tree"/>
-        <Condition ID="async_is_start_tree"/>
-        <Action ID="is_not_stop_tree"/>
-        <Condition ID="async_is_stop_tree"/>
-        <Action ID="set_start_tree"/>
-        <Action ID="set_stop_tree"/>
-        <Action ID="reset_start_tree"/>
-        <Action ID="reset_stop_tree"/>
+        <Action ID="RUNNING"/>
+        <Action ID="is_variable_true">
+            <input_port name="variable"> (bool): Bool variable to check.</input_port>
+        </Action>
+        <Action ID="is_variable_false">
+            <input_port name="variable"> (bool): Bool variable to check.</input_port>
+        </Action>
+        <Action ID="transform_pose">
+            <input_port name="pose_in"> (geometry_msgs::PoseStamped): Pose to be transformed.</input_port>
+            <input_port name="target_frame"> (std::string): Frame to transform the pose.</input_port>
+            <output_port name="pose_out"> (geometry_msgs::PoseStamped): Transformed pose.</output_port>
+        </Action>
+        <Action ID="compute_distance">
+            <input_port name="pose1"> (geometry_msgs::PoseStamped): Pose 1.</input_port>
+            <input_port name="pose2"> (geometry_msgs::PoseStamped): Pose 2.</input_port>
+            <output_port name="distance"> (double): Distance.</output_port>
+        </Action>
+        <Action ID="compare_bigger">
+            <input_port name="value1"> (double): Value 1.</input_port>
+            <input_port name="value2"> (double): Value 2.</input_port>
+        </Action>
+        <Action ID="compare_smaller">
+            <input_port name="value1"> (double): Value 1.</input_port>
+            <input_port name="value2"> (double): Value 2.</input_port>
+        </Action>
+        <Action ID="print_msg">
+            <input_port name="msg"> (std::string): Msg to print.</input_port>
+            <input_port name="type"> (std::string): It must be info, warn, error or debug.</input_port>
+        </Action>
         <!-- gripper module -->
         <Action ID="sync_cancel_tiago_gripper_action"/>
         <Action ID="async_cancel_tiago_gripper_action"/>
         <Action ID="async_is_tiago_gripper_finished"/>
         <Action ID="sync_close_tiago_gripper">
-            <input_port name="duration"> Time from start to close the gripper</input_port>
+            <input_port name="duration"> Time from start to close the gripper (double)</input_port>
         </Action>
         <Action ID="async_close_tiago_gripper">
-            <input_port name="duration"> Time from start to close the gripper</input_port>
-            <input_port name="new_goal"> If it's a new_goal</input_port>
+            <input_port name="duration"> Time from start to close the gripper (double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
         </Action>
         <Action ID="sync_open_tiago_gripper">
-            <input_port name="duration"> Time from start to open the gripper</input_port>
+            <input_port name="duration"> Time from start to open the gripper (double)</input_port>
         </Action>
         <Action ID="async_open_tiago_gripper">
-            <input_port name="duration"> Time from start to open the gripper</input_port>
-            <input_port name="new_goal"> If it's a new_goal</input_port>
+            <input_port name="duration"> Time from start to open the gripper (double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
         </Action>
         <Action ID="sync_move_fingers_tiago_gripper">
-            <input_port name="left_finger"> Left finger position</input_port>
-            <input_port name="right_finger"> Right finger position</input_port>
-            <input_port name="duration"> Time from start to move the fingers</input_port>
+            <input_port name="left_finger"> Left finger position (double)</input_port>
+            <input_port name="right_finger"> Right finger position (double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (double)</input_port>
         </Action>
         <Action ID="async_move_fingers_tiago_gripper">
-            <input_port name="left_finger"> Left finger position</input_port>
-            <input_port name="right_finger"> Right finger position</input_port>
-            <input_port name="duration"> Time from start to move the fingers</input_port>
-            <input_port name="new_goal"> If it's a new_goal</input_port>
+            <input_port name="left_finger"> Left finger position (double)</input_port>
+            <input_port name="right_finger"> Right finger position double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
         </Action>
         <Action ID="sync_move_fingers_multi_tiago_gripper">
-            <input_port name="left_finger"> Left finger positions</input_port>
-            <input_port name="right_finger"> Right finger positions</input_port>
-            <input_port name="duration"> Time from start to move the fingers</input_port>
+            <input_port name="left_finger"> Left finger positions (std::vector double)</input_port>
+            <input_port name="right_finger"> Right finger positions (std::vector double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (std::vector double)</input_port>
         </Action>
         <Action ID="async_move_fingers_multi_tiago_gripper">
-            <input_port name="left_finger"> Left finger positions</input_port>
-            <input_port name="right_finger"> Right finger positions</input_port>
-            <input_port name="duration"> Time from start to move the fingers</input_port>
-            <input_port name="new_goal"> If it's a new_goal</input_port>
+            <input_port name="left_finger"> Left finger positions (std::vector double)</input_port>
+            <input_port name="right_finger"> Right finger positions (std::vector double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (std::vector double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
         </Action>
         <Action ID="sync_fingers_distance_tiago_gripper">
-            <input_port name="distance"> Distance between fingers</input_port>
-            <input_port name="duration"> Time from start to move the fingers</input_port>
+            <input_port name="distance"> Distance between fingers (double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (double)</input_port>
         </Action>
         <Action ID="async_fingers_distance_tiago_gripper">
-            <input_port name="distance"> Distance between fingers</input_port>
-            <input_port name="duration"> Time from start to move the fingers</input_port>
-            <input_port name="new_goal"> If it's a new_goal</input_port>
+            <input_port name="distance"> Distance between fingers (double)</input_port>
+            <input_port name="duration"> Time from start to move the fingers (double)</input_port>
+            <inout_port name="new_goal"> If it's a new_goal (bool)</inout_port>
         </Action>
         <Action ID="sync_close_grasp_tiago_gripper"/>
         <Action ID="async_close_grasp_tiago_gripper">
-            <input_port default="True" name="new_goal"> If it's a new_goal</input_port>
+            <inout_port default="True" name="new_goal"> If it's a new_goal (bool)</inout_port>
         </Action>
         <Condition ID="is_tiago_gripper_finished"/>
         <Condition ID="is_tiago_gripper_module_running"/>
@@ -97,7 +116,7 @@
         <Condition ID="is_tiago_gripper_module_preempted"/>
         <Condition ID="is_tiago_gripper_module_rejected"/>
         <Condition ID="is_tiago_gripper_module_failed_grasp"/>
-        <!-- Tree -->
+        <!-- Client -->
         <SubTree ID="set_fingers_pos_blackboard"/>
     </TreeNodesModel>
     <!-- ////////// -->