diff --git a/driver_templates/template_driver.cfg b/driver_templates/template_driver.cfg
index a6e770487e344f24f450b6b3fb1d3056cc64809e..e3f3bae720f4628831127f6b4e2388f21d1bf3e7 100644
--- a/driver_templates/template_driver.cfg
+++ b/driver_templates/template_driver.cfg
@@ -33,7 +33,7 @@
 
 PACKAGE='template'
 
-from driver_base.msg import SensorLevels
+from iri_base_driver.msg import SensorLevels
 from dynamic_reconfigure.parameter_generator_catkin import *
 
 gen = ParameterGenerator()
diff --git a/driver_templates/template_driver.cpp b/driver_templates/template_driver.cpp
index 2a1a2c8905b4c237cb337e6446a9cd3cdb23524f..16f03be85e440cf298b73edd89c9e57e50326a9b 100644
--- a/driver_templates/template_driver.cpp
+++ b/driver_templates/template_driver.cpp
@@ -35,13 +35,13 @@ void TemplateDriver::config_update(Config& new_cfg, uint32_t level)
   // update driver with new_cfg data
   switch(this->getState())
   {
-    case TemplateDriver::CLOSED:
+    case iri_base_driver::CLOSED:
       break;
 
-    case TemplateDriver::OPENED:
+    case iri_base_driver::OPENED:
       break;
 
-    case TemplateDriver::RUNNING:
+    case iri_base_driver::RUNNING:
       break;
   }
 
diff --git a/driver_templates/template_driver_node.cpp b/driver_templates/template_driver_node.cpp
index 5347b09267cd24e31ad538565d471d5fd6c9aed0..091ae6985974cca2f100290596100982c3b2bd9c 100644
--- a/driver_templates/template_driver_node.cpp
+++ b/driver_templates/template_driver_node.cpp
@@ -4,7 +4,7 @@ TemplateNode::TemplateNode(ros::NodeHandle &nh) :
   iri_base_driver::IriBaseNodeDriver<TemplateDriver>(nh)
 {
   //init class attributes if necessary
-  //this->loop_rate_ = 2;//in [Hz]
+  //this->setRate(10);//in [Hz]
 
   // [init publishers]
   
@@ -50,23 +50,15 @@ void TemplateNode::postNodeOpenHook(void)
 {
 }
 
-void TemplateNode::addNodeDiagnostics(void)
-{
-}
-
-void TemplateNode::addNodeOpenedTests(void)
+void TemplateNode::preNodeCloseHook(void)
 {
 }
 
-void TemplateNode::addNodeStoppedTests(void)
-{
-}
-
-void TemplateNode::addNodeRunningTests(void)
+void TemplateNode::addNodeDiagnostics(void)
 {
 }
 
-void TemplateNode::reconfigureNodeHook(int level)
+void TemplateNode::node_config_update(Config& new_cfg, uint32_t level)
 {
 }
 
@@ -78,5 +70,5 @@ TemplateNode::~TemplateNode(void)
 /* main function */
 int main(int argc,char *argv[])
 {
-  return driver_base::main<TemplateNode>(argc, argv, "template_node");
+  return iri_base_driver::main<TemplateNode>(argc, argv, "template_node");
 }
diff --git a/driver_templates/template_driver_node.h b/driver_templates/template_driver_node.h
index 6841b516407606db0768a6c35dbee5efbb3217b2..2b81b8f54eb04a2de1269b92d7b44da91b7d0552 100644
--- a/driver_templates/template_driver_node.h
+++ b/driver_templates/template_driver_node.h
@@ -75,6 +75,8 @@ class TemplateNode : public iri_base_driver::IriBaseNodeDriver<TemplateDriver>
     */
     void postNodeOpenHook(void);
 
+    void preNodeCloseHook(void);
+
   public:
    /**
     * \brief constructor
@@ -134,39 +136,6 @@ class TemplateNode : public iri_base_driver::IriBaseNodeDriver<TemplateDriver>
 
     // [driver test functions]
 
-   /**
-    * \brief open status driver tests
-    *
-    * In this function tests checking driver's functionallity when driver_base 
-    * status=open can be added. Common use tests for all nodes are already called
-    * from IriBaseNodeDriver tests methods. For more details on how ROS tests work,
-    * please refer to the Self Test example in:
-    * http://www.ros.org/wiki/self_test/
-    */
-    void addNodeOpenedTests(void);
-
-   /**
-    * \brief stop status driver tests
-    *
-    * In this function tests checking driver's functionallity when driver_base 
-    * status=stop can be added. Common use tests for all nodes are already called
-    * from IriBaseNodeDriver tests methods. For more details on how ROS tests work,
-    * please refer to the Self Test example in:
-    * http://www.ros.org/wiki/self_test/
-    */
-    void addNodeStoppedTests(void);
-
-   /**
-    * \brief run status driver tests
-    *
-    * In this function tests checking driver's functionallity when driver_base 
-    * status=run can be added. Common use tests for all nodes are already called
-    * from IriBaseNodeDriver tests methods. For more details on how ROS tests work,
-    * please refer to the Self Test example in:
-    * http://www.ros.org/wiki/self_test/
-    */
-    void addNodeRunningTests(void);
-
    /**
     * \brief specific node dynamic reconfigure
     *
@@ -174,7 +143,7 @@ class TemplateNode : public iri_base_driver::IriBaseNodeDriver<TemplateDriver>
     * 
     * \param level integer
     */
-    void reconfigureNodeHook(int level);
+    void node_config_update(Config& new_cfg, uint32_t level);
 
 };