diff --git a/algorithm_implementation_templates/CMakeLists.txt b/algorithm_implementation_templates/CMakeLists.txt
deleted file mode 100644
index d59a111a501c689921d46b78c59c33e0351812e6..0000000000000000000000000000000000000000
--- a/algorithm_implementation_templates/CMakeLists.txt
+++ /dev/null
@@ -1,43 +0,0 @@
-cmake_minimum_required(VERSION 2.4.6)
-include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
-
-set(PROJECT_NAME template_node)
-
-# Set the build type.  Options are:
-#  Coverage       : w/ debug symbols, w/o optimization, w/ code-coverage
-#  Debug          : w/ debug symbols, w/o optimization
-#  Release        : w/o debug symbols, w/ optimization
-#  RelWithDebInfo : w/ debug symbols, w/ optimization
-#  MinSizeRel     : w/o debug symbols, w/ optimization, stripped binaries
-#set(ROS_BUILD_TYPE RelWithDebInfo)
-
-rosbuild_init()
-
-#set the default path for built executables to the "bin" directory
-set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
-#set the default path for built libraries to the "lib" directory
-set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
-
-#uncomment if you have defined messages
-#rosbuild_genmsg()
-#uncomment if you have defined services
-#rosbuild_gensrv()
-
-# added to include support for dynamic reconfiguration
-rosbuild_find_ros_package(dynamic_reconfigure)
-include(${dynamic_reconfigure_PACKAGE_PATH}/cmake/cfgbuild.cmake)
-gencfg()
-# end dynamic reconfiguration
-
-FIND_PACKAGE(iriutils REQUIRED)
-
-INCLUDE_DIRECTORIES(${iriutils_INCLUDE_DIR} ./include)
-
-#common commands for building c++ executables and libraries
-#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
-#target_link_libraries(${PROJECT_NAME} another_library)
-#rosbuild_add_boost_directories()
-#rosbuild_link_boost(${PROJECT_NAME} thread)
-rosbuild_add_executable(${PROJECT_NAME} src/template_node.cpp)
-
-target_link_libraries(${PROJECT_NAME} ${iriutils_LIBRARY})
diff --git a/algorithm_implementation_templates/template_algorithm_implementation.cfg b/algorithm_implementation_templates/template_algorithm_implementation.cfg
deleted file mode 100644
index d6ff60eec8cdeefdb033e72f142a4a2cc1a5aaaa..0000000000000000000000000000000000000000
--- a/algorithm_implementation_templates/template_algorithm_implementation.cfg
+++ /dev/null
@@ -1,44 +0,0 @@
-#! /usr/bin/env python
-#*  All rights reserved.
-#*
-#*  Redistribution and use in source and binary forms, with or without
-#*  modification, are permitted provided that the following conditions
-#*  are met:
-#*
-#*   * Redistributions of source code must retain the above copyright
-#*     notice, this list of conditions and the following disclaimer.
-#*   * Redistributions in binary form must reproduce the above
-#*     copyright notice, this list of conditions and the following
-#*     disclaimer in the documentation and/or other materials provided
-#*     with the distribution.
-#*   * Neither the name of the Willow Garage nor the names of its
-#*     contributors may be used to endorse or promote products derived
-#*     from this software without specific prior written permission.
-#*
-#*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-#*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-#*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-#*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-#*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-#*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-#*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-#*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-#*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-#*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-#*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-#*  POSSIBILITY OF SUCH DAMAGE.
-#***********************************************************
-
-# Author: 
-
-PACKAGE='template'
-import roslib; roslib.load_manifest(PACKAGE)
-
-from dynamic_reconfigure.parameter_generator import *
-
-gen = ParameterGenerator()
-
-#       Name                       Type       Reconfiguration level            Description                       Default   Min   Max
-#gen.add("velocity_scale_factor",  double_t,  SensorLevels.RECONFIGURE_STOP,   "Maximum velocity scale factor",  0.5,      0.0,  1.0)
-
-exit(gen.generate(PACKAGE, "TemplateAlg", "Template"))
\ No newline at end of file
diff --git a/algorithm_implementation_templates/template_algorithm_implementation.cpp b/algorithm_implementation_templates/template_algorithm_implementation.cpp
deleted file mode 100644
index 22214d79240a64fb267a024a449f8e5b84aba5ae..0000000000000000000000000000000000000000
--- a/algorithm_implementation_templates/template_algorithm_implementation.cpp
+++ /dev/null
@@ -1,40 +0,0 @@
-#include "template_node.h"
-
-TemplateNode::TemplateNode(void)
-{
-}
-
-TemplateNode::~TemplateNode(void)
-{
-}
-
-void TemplateNode::lock(void)
-{
-  this->access_.enter();
-}
-
-void TemplateNode::unlock(void)
-{
-  this->access_.exit();
-}
-
-bool TemplateNode::try_enter(void)
-{
-  return this->access_.try_enter();
-}
-
-void TemplateNode::config_update(Config& new_cfg, uint32_t level)
-{
-  this->lock();
-
-  this->config_ = new_cfg;
-  
-  this->unlock();
-}
-
-int main(int argc, char *argv[])
-{
-  algorithm_base::main< GenericTemplateAlg<TemplateNode> >(argc, argv, "template_node");
-  
-  return 0;
-}
\ No newline at end of file
diff --git a/algorithm_implementation_templates/template_algorithm_implementation.h b/algorithm_implementation_templates/template_algorithm_implementation.h
deleted file mode 100644
index f2bcc79a3c718d9827fcef72f40429114ad476bf..0000000000000000000000000000000000000000
--- a/algorithm_implementation_templates/template_algorithm_implementation.h
+++ /dev/null
@@ -1,142 +0,0 @@
-// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
-// Author 
-// All rights reserved.
-//
-// This file is part of iri-ros-pkg
-// iri-ros-pkg is free software: you can redistribute it and/or modify
-// it under the terms of the GNU Lesser General Public License as published by
-// the Free Software Foundation, either version 3 of the License, or
-// at your option) any later version.
-//
-// This program is distributed in the hope that it will be useful,
-// but WITHOUT ANY WARRANTY; without even the implied warranty of
-// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-// GNU Lesser General Public License for more details.
-//
-// You should have received a copy of the GNU Lesser General Public License
-// along with this program.  If not, see <http://www.gnu.org/licenses/>.
-// 
-// IMPORTANT NOTE: This code has been generated through a script from the 
-// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
-// of the scripts. ROS topics can be easly add by using those scripts. Please
-// refer to the IRI wiki page for more information:
-// http://wikiri.upc.es/index.php/Robotics_Lab
-
-#ifndef _template_node_h_
-#define _template_node_h_
-
-// [include algorithm common interface]
-#include <template_if_pkg/template_if_class>
-
-// [include generic algorithm class]
-#include <template_generic_alg_pkg/template_generic_alg_class>
-
-// [include algorithm config file]
-#include <template_namespace/TemplateConfig.h>
-
-// [include algorithm implementation library]
-// #include "template_library.h"
-
-/**
- * \brief IRI ROS Algorithm Base Node Class
- *
- * This classs implements a common algorithm interface (usually ROS defined).
- * All virtual methods will be implemented to provide an specific behavior to
- * the assossiate generic algorithm. Common features such as message exchange
- * will be already implemented in the generic algoritm class.
- *
- * A Config variable must be defined in order to accomplish dynamic reconfigure
- * requirements. Then parameters defined in the cfg config file will accessible
- * in the config_update method, called whenever there is an update.
- */
-class TemplateNode //: public template_if_pkg::TemplateIFClass
-{
-  public:
-   /**
-    * \brief config type definition
-    *
-    * Definition of the Config object type according to the automatic generated
-    * class from the cfg config file.
-    */
-    typedef template_namespace::TemplateConfig Config;
-
-   /**
-    * \brief config object
-    *
-    * Instantation of the config variable object.
-    */
-    Config config_;
-
-   /**
-    * \brief algorithm mutex
-    *
-    * This variable is used to block access to the algorithm resource. Protected
-    * methods such as lock, unlock and try_enter provide an interface to
-    * avoid multiple concurrent access.
-    */
-    CMutex access_;
-
-  public:
-   /**
-    * \brief constructor
-    *
-    * In this constructor library objects must be initialized if required.
-    */
-    TemplateNode(void);
-
-   /**
-    * \brief destructor
-    *
-    * The destructor must assert proper closing of the library object.
-    */
-    ~TemplateNode(void);
-
-   /**
-    * \brief Lock Algorithm
-    *
-    * Locks access to the driver class
-    */
-    void lock(void);
-
-   /**
-    * \brief Unlock Algorithm
-    *
-    * Unlocks access to the driver class
-    */
-    void unlock(void);
-
-   /**
-    * \brief Tries Access to Algorithm
-    *
-    * Tries access to driver
-    * 
-    * \return true if the lock was adquired, false otherwise
-    */
-    bool try_enter(void);
-
-   /**
-    * \brief config update
-    *
-    * In this function the driver parameters must be updated with the input
-    * config variable. Then the new configuration state will be stored in the 
-    * Config attribute.
-    *
-    * \param new_cfg the new driver configuration state
-    *
-    * \param level level in which the update is taken place
-    */
-    void config_update(Config& new_cfg, uint32_t level=0);
-
-    // [algorithm interface methods]
-
-  protected:
-//   /**
-//    * \brief algorithm library object
-//    *
-//    * This attribute refers to the user algorithm library. Methods and attributes
-//    * from this object may vary depending on implementation.
-//    */
-//    TemplateNodeLibrary lib;
-};
-
-#endif
diff --git a/create_algorithm_implementation.sh b/create_algorithm_implementation.sh
deleted file mode 100755
index 6befdf0d9d1f5335a6c7abfe6e5579f2facc3294..0000000000000000000000000000000000000000
--- a/create_algorithm_implementation.sh
+++ /dev/null
@@ -1,173 +0,0 @@
-#!/bin/bash
-
-# WET
- 
-# check wether the scripts path environment variable has been defined
-scripts_path=`echo "${IRI_ROS_SCRIPTS_PATH}"`
-if [[ -z "${scripts_path}" ]]
-then
-  echo "The scripts path environment varibale has not been defined. Please see the wiki documentation for instructions on how to create it."
-  exit
-else
-  echo "The scripts path environment variable has been properly defined."
-fi
-
-source "${IRI_ROS_SCRIPTS_PATH}/libraries/scripts_library.sh"
-
-check_libraries
-check_templates
-
-echo ""
-echo "/*******************************************************/"
-echo "/*    Creating New IRI_ROS Algorithm Implementation    */"
-echo "/*******************************************************/"
-
-input_name=
-if_path=
-if_basename=
-gen_alg_path=
-gen_alg_basename=
-
-#check for input project name paramenter
-while getopts “:n:p:i:g:c:” OPTION
-do
-  case $OPTION in
-    n)
-       input_name=$OPTARG
-       ;;
-    p)
-       if_path=$OPTARG
-       ;;
-    i)
-       if_basename=$OPTARG
-       ;;
-    g)
-       gen_alg_path=$OPTARG
-       ;;
-    c)
-       gen_alg_basename=$OPTARG
-       ;;
-    ?)
-       echo "invalid argument $OPTION"
-       kill_exit "Usage: ./create_algorithm_implementation.sh -n node_name -p pkg/if_file.h -i if_class_name -g pkg/generic_alg_file.h -c generic_alg_class_name"
-       ;;
-  esac
-done
-
-#check if project parameter is filled up
-if [ ! "${input_name}" ] || [ ! "${if_path}" ] || [ ! "${if_basename}" ] || [ ! "${gen_alg_path}" ] || [ ! "${gen_alg_basename}" ]
-then
-  echo "Wrong input parameters, aborting ..."
-  kill_exit "Usage: ./create_algorithm_implementation.sh -n node_name -p pkg/if_file.h -i if_class_name -g pkg/generic_alg_file.h -c generic_alg_class_name"
-fi
-
-#lowercase input name
-input_name=$(echo ${input_name} | tr "[:upper:]" "[:lower:]")
-
-#create package filename
-project_name="${input_name}"
-
-if [ -e "../${project_name}" ]
-then
-  kill_exit "${project_name} package directory already exists, aborting ..."
-else
-  echo "Generating folder structure for project ${project_name} ..."
-fi
-
-#parse interface path
-parsed_name=$(echo ${if_path}|sed 's/\// /g')
-if_pkg=${parsed_name%% *}
-if_filename=${parsed_name##* }
-
-#check interface path correctness
-if [ ! "${if_pkg}" ] || [ ! "${if_filename}" ] 
-then
-  kill_exit "input parameter pkg/interface.h is bad formed, aborting..."
-fi
-
-#parse generic algorithm path
-parsed_name=$(echo ${gen_alg_path}|sed 's/\// /g')
-gen_alg_pkg=${parsed_name%% *}
-gen_alg_filename=${parsed_name##* }
-
-#check generic algorithm path correctness
-if [ ! "${gen_alg_pkg}" ] || [ ! "${gen_alg_filename}" ] 
-then
-  kill_exit "input parameter pkg/generic_alg_file.h is bad formed, aborting..."
-fi
-
-#create package
-catkin_create_pkg ${project_name} roscpp iri_base_algorithm ${if_pkg} ${gen_alg_pkg}
-
-#create driver filename
-algimpl_filename="${input_name}"
-#echo "driver_filename $driver_filename"
-
-#create cfg filename
-cfg_filename="${input_name}_config"
-#echo "cfg_filename $cfg_filename"
-
-#create basename from pkg name
-create_basename ${input_name}
-
-################################################################################
-# create template algorithm implementation .h and .cpp files
-
-#create algorithm basename
-algimpl_basename="${basename}"
-template_library
-sed -e "s/template_node/${algimpl_filename}/g" \
-    -e "s/TemplateNode/${algimpl_basename}/g" \
-    -e "s/template_namespace/${project_name}/g" \
-    -e "s/TemplateConfig/${basename}Config/g" \
-    -e "s/template_if_pkg/${if_pkg}/g" \
-    -e "s/template_if_class/${if_filename}/g" \
-    -e "s/TemplateIFClass/${if_basename}/g" \
-    -e "s/template_generic_alg_pkg/${gen_alg_pkg}/g" \
-    -e "s/template_generic_alg_class/${gen_alg_filename}/g" <${IRI_ROS_SCRIPTS_PATH}/algorithm_implementation_templates/template_algorithm_implementation.h >"${project_name}/include/${algimpl_filename}.h"
-sed -e "s/template_node/${algimpl_filename}/g" \
-    -e "s/TemplateNode/${algimpl_basename}/g" \
-    -e "s/GenericTemplateAlg/${gen_alg_basename}/g" <${IRI_ROS_SCRIPTS_PATH}/algorithm_implementation_templates/template_algorithm_implementation.cpp >"${project_name}/src/${algimpl_filename}.cpp"
-echo ""
-################################################################################
-
-
-
-################################################################################
-#Set the filename and namespace on the CMakeLists.txt file
-sed -e "s/template_node/${algimpl_filename}/g" \
-    -e "s/template_alg/${algimpl_filename}/g" <${IRI_ROS_SCRIPTS_PATH}/algorithm_implementation_templates/CMakeLists.txt >"${project_name}/CMakeLists.txt"
-echo "Creating ${project_name} CMakeLists.txt file..."
-echo ""
-################################################################################
-
-
-################################################################################
-#create cfg directory
-cfg_dir="${project_name}/cfg"
-if [ -e "$cfg_dir" ]
-then
-  echo "${cfg_dir} directory already exists, skipping ..."
-else
-  echo "Creating ${cfg_dir} directory"
-  mkdir ${cfg_dir}
-fi
-
-#Set the filename and namespace on the template.cfg file
-sed -e "s/template_node/${algimpl_filename}/g" \
-    -e "s/template/${project_name}/g" \
-    -e "s/Template/${basename}/g" <${IRI_ROS_SCRIPTS_PATH}/algorithm_implementation_templates/template_algorithm_implementation.cfg >"${project_name}/cfg/${cfg_filename}.cfg"
-eval "chmod 775 ${project_name}/cfg/${cfg_filename}.cfg"
-echo "Creating ${cfg_filename}.cfg file..."
-################################################################################
-
-echo ""
-echo ""
-echo "Project ${project_name} has been successfully created!!"
-
-pushd "${project_name}"
-change_license_to_LGPL
-popd
-
-cd .. # to catkin work space
-catkin_make --pkg ${project_name}
diff --git a/create_generic_algorithm.sh b/create_generic_algorithm.sh
deleted file mode 100755
index 9fd92502997bf416b1c55e7de6b9ecaeba408569..0000000000000000000000000000000000000000
--- a/create_generic_algorithm.sh
+++ /dev/null
@@ -1,137 +0,0 @@
-#!/bin/bash
-
-# WET
-
-# check wether the scripts path environment variable has been defined
-scripts_path=`echo "${IRI_ROS_SCRIPTS_PATH}"`
-if [[ -z "${scripts_path}" ]]
-then
-  echo "The scripts path environment varibale has not been defined. Please see the wiki documentation for instructions on how to create it."
-  exit
-else
-  echo "The scripts path environment variable has been properly defined."
-fi
-
-source "${IRI_ROS_SCRIPTS_PATH}/libraries/scripts_library.sh"
-
-check_libraries
-check_templates
-
-echo ""
-echo "/*******************************************************/"
-echo "/*      Creating New IRI_ROS Generic Algorithm         */"
-echo "/*******************************************************/"
-
-usage="Usage: ./create_generic_algorithm.sh -n node_name -p pkg/if_file.h [-i]"
-input_name=
-use_prefix=true
-if_path=
-
-#check for input project name paramenter
-while getopts “:n:p:i” OPTION
-do
-  case $OPTION in
-    n)
-       input_name=$OPTARG
-       ;;
-    p)
-       if_path=$OPTARG
-       ;;
-    i)
-       use_prefix=false
-       ;;
-    ?)
-       echo "invalid argument $OPTION"
-       kill_exit "${usage}"
-       ;;
-  esac
-done
-
-#check if project parameter is filled up
-if [ ! "${input_name}" ] || [ ! "${if_path}" ]
-then
-  echo "Wrong input parameters, aborting ..."
-  kill_exit "${usage}"
-fi
-
-#lowercase input name
-input_name=$(echo ${input_name} | tr "[:upper:]" "[:lower:]")
-
-#create package filename
-if [[ ${use_prefix} == true ]]
-then
-  project_name="iri_${input_name}"
-else
-  project_name="${input_name}"
-fi
-
-if [ -e "../${project_name}" ]
-then
-  kill_exit "${project_name} package directory already exists, aborting ..."
-else
-  echo "Generating folder structure for project ${project_name} ..."
-fi
-
-#parse interface path
-parsed_name=$(echo ${if_path} | sed 's/\// /g')
-if_pkg=${parsed_name%% *}
-if_filename=${parsed_name##* }
-
-#check interface path correctness
-if [ ! "${if_pkg}" ] || [ ! "${if_filename}" ] 
-then
-  kill_exit "input parameter pkg/interface.h is bad formed, aborting..."
-fi
-
-#create package
-catkin_create_pkg${project_name} roscpp iri_base_algorithm ${if_pkg}
-
-#create driver filename
-genalg_filename="${input_name}"
-#echo "driver_filename $driver_filename"
-
-#create basename from pkg name
-create_basename ${input_name}
-
-################################################################################
-# create template algorithm implementation .h and .cpp files
-
-#create driver basename
-genalg_basename="${basename}"
-
-sed -e "s/template_node/${genalg_filename}/g" \
-    -e "s/TemplateNode/${genalg_basename}/g" \
-    -e "s/template_if_pkg/${if_pkg}/g" \
-    -e "s/template_if_class/${if_filename}/g" <${IRI_ROS_SCRIPTS_PATH}/generic_algorithm_templates/template_generic_algorithm.h >"${project_name}/include/${project_name}/${genalg_filename}.h"
-echo ""
-################################################################################
-
-
-
-################################################################################
-#Set the filename and namespace on the CMakeLists.txt file
-sed -e "s/template_node/${genalg_filename}/g" <${IRI_ROS_SCRIPTS_PATH}/generic_algorithm_templates/CMakeLists.txt >"${project_name}/CMakeLists.txt"
-echo "Creating ${project_name} CMakeLists.txt file..."
-echo ""
-################################################################################
-
-
-
-################################################################################
-#add export tag to manifest.xml
-line='  <export> \n   <cpp cflags="-I${prefix}/include"\/> \n  </export>'
-comment="<depend package=\"${if_pkg}\"\/>"
-add_line_to_file "${line}" "${comment}" "${project_name}/manifest.xml"
-################################################################################
-
-
-echo ""
-echo ""
-echo "Project ${project_name} has been successfully created!!"
-
-pushd "${project_name}"
-change_license_to_LGPL
-popd
-
-cd .. # to catkin work space
-catkin_make --pkg ${project_name}
diff --git a/create_simple_algorithm_package.sh b/create_simple_algorithm_package.sh
deleted file mode 100755
index a0728c815596099c421218741a7ade54683096cf..0000000000000000000000000000000000000000
--- a/create_simple_algorithm_package.sh
+++ /dev/null
@@ -1,168 +0,0 @@
-#!/bin/bash
-
-# WET
-
-# check wether the scripts path environment variable has been defined
-scripts_path=`echo "${IRI_ROS_SCRIPTS_PATH}"`
-if [[ -z "${scripts_path}" ]]
-then
-  echo "The scripts path environment variable has not been defined. Please see the wiki documentation for instructions on how to create it."
-  exit
-else
-  echo "The scripts path environment variable has been properly defined."
-fi
-
-source "${IRI_ROS_SCRIPTS_PATH}/libraries/scripts_library.sh"
-
-check_libraries
-check_templates
-
-echo ""
-echo "/**********************************************/"
-echo "/* Creating New IRI_ROS Simple Algorithm Node */"
-echo "/**********************************************/"
-
-usage="Usage: ./create_simple_algorithm_package.sh -n node_name [-i]"
-input_name=
-use_prefix=true
-
-#check for input project name paramenter
-while getopts “:n:i” OPTION
-do
-  case $OPTION in
-    n)
-       input_name=$OPTARG
-       ;;
-    i)
-       use_prefix=false
-       ;;
-    ?)
-       echo "invalid argument $OPTION"
-       kill_exit "${usage}"
-       ;;
-  esac
-done
-
-#check if project parameter is filled up
-if [ ! "${input_name}" ]
-then
-  echo "No project name provided, aborting ..."
-  kill_exit "${usage}"
-fi
-
-#lowercase input name
-input_name=$(echo ${input_name} | tr "[:upper:]" "[:lower:]")
-
-#create alg filename
-if [[ ${use_prefix} == true ]]
-then
-  project_name="iri_${input_name}"
-else
-  project_name="${input_name}"
-fi
-
-if [ -e "../${project_name}" ]
-then
-  kill_exit "${project_name} package directory already exists, aborting ..."
-else
-  echo "Generating folder structure for project ${project_name} ..."
-fi
-
-catkin_create_pkg ${project_name} roscpp iri_base_algorithm 
-
-#create alg filename
-alg_filename="${input_name}_alg"
-
-#create node filename
-node_filename="${input_name}_alg_node"
-
-#create cfg filename
-cfg_filename="${input_name}_alg_config"
-
-#create basename from pkg name
-create_basename ${input_name}
-
-#create templates folder path name
-temps_folder="${IRI_ROS_SCRIPTS_PATH}/simple_algorithm_templates/"
-
-################################################################################
-# create template alg .h and .cpp files
-
-#create alg basename
-alg_basename="${basename}Algorithm"
-
-#Set the filename and namespace on the template_alg files
-sed -e "s/template_alg/${alg_filename}/g" \
-    -e "s/TemplateAlg/${alg_basename}/g" \
-    -e "s/template_namespace/${project_name}/g" \
-    -e "s/TemplateConfig/${basename}Config/g" <${temps_folder}/template_alg.h >"${project_name}/include/${alg_filename}.h"
-sed -e "s/template_alg/${alg_filename}/g" \
-    -e "s/TemplateAlg/${alg_basename}/g" <${temps_folder}/template_alg.cpp >"${project_name}/src/${alg_filename}.cpp"
-echo "Creating ${alg_filename} files..."
-echo ""
-################################################################################
-
-
-
-################################################################################
-# create template node .h and .cpp files
-
-#create node basename
-node_basename="${basename}AlgNode"
-#echo "node_basename $node_basename"
-
-#Set the filename and namespace on the template_node files
-sed -e "s/template_alg/${alg_filename}/g" \
-    -e "s/TemplateAlg/${alg_basename}/g" \
-    -e "s/template_node/${node_filename}/g" \
-    -e "s/TemplateNode/${node_basename}/g" <${temps_folder}/template_alg_node.h >"${project_name}/include/${node_filename}.h"
-sed -e "s/template_node/${node_filename}/g" \
-    -e "s/TemplateAlg/${alg_basename}/g" \
-    -e "s/TemplateNode/${node_basename}/g" <${temps_folder}/template_alg_node.cpp >"${project_name}/src/${node_filename}.cpp"
-echo "Creating ${node_filename} files..."
-echo ""
-################################################################################
-
-
-################################################################################
-#Set the filename and namespace on the CMakeLists.txt file
-sed -e "s/template_alg/${alg_filename}/g" \
-    -e "s/template_node/${node_filename}/g" <${temps_folder}/CMakeLists.txt >"${project_name}/CMakeLists.txt"
-echo "Creating ${project_name} CMakeLists.txt file..."
-echo ""
-################################################################################
-
-
-################################################################################
-#create cfg directory
-cfg_dir="${project_name}/cfg"
-if [ -e "$cfg_dir" ]
-then
-  echo "${cfg_dir} directory already exists, skipping ..."
-else
-  echo "Creating ${cfg_dir} directory"
-  mkdir ${cfg_dir}
-fi
-
-#Set the filename and namespace on the template.cfg file
-sed -e "s/template/${project_name}/g" \
-    -e "s/TemplateAlg/${alg_basename}/g" \
-    -e "s/Template/${basename}/g" <${temps_folder}/template_alg.cfg >"${project_name}/cfg/${cfg_filename}.cfg"
-eval "chmod 775 ${project_name}/cfg/${cfg_filename}.cfg"
-echo "Creating ${cfg_filename}.cfg file..."
-################################################################################
-
-echo ""
-echo ""
-echo "Project ${project_name} has been successfully created!!"
-
-pushd "${project_name}"
-change_license_to_LGPL
-popd
-
-# WET
-cd .. # to catkin work space
-
-#rosmake
-# WET
-catkin_make --pkg ${project_name}
diff --git a/generic_algorithm_templates/CMakeLists.txt b/generic_algorithm_templates/CMakeLists.txt
deleted file mode 100644
index 5c3e95829d187e5ed0c36469e4c798a80a84042d..0000000000000000000000000000000000000000
--- a/generic_algorithm_templates/CMakeLists.txt
+++ /dev/null
@@ -1,32 +0,0 @@
-cmake_minimum_required(VERSION 2.4.6)
-include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
-
-set(PROJECT_NAME template_node)
-
-# Set the build type.  Options are:
-#  Coverage       : w/ debug symbols, w/o optimization, w/ code-coverage
-#  Debug          : w/ debug symbols, w/o optimization
-#  Release        : w/o debug symbols, w/ optimization
-#  RelWithDebInfo : w/ debug symbols, w/ optimization
-#  MinSizeRel     : w/o debug symbols, w/ optimization, stripped binaries
-#set(ROS_BUILD_TYPE RelWithDebInfo)
-
-rosbuild_init()
-
-#set the default path for built executables to the "bin" directory
-set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
-#set the default path for built libraries to the "lib" directory
-set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
-
-#uncomment if you have defined messages
-#rosbuild_genmsg()
-#uncomment if you have defined services
-#rosbuild_gensrv()
-
-#common commands for building c++ executables and libraries
-#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
-#target_link_libraries(${PROJECT_NAME} another_library)
-#rosbuild_add_boost_directories()
-#rosbuild_link_boost(${PROJECT_NAME} thread)
-#rosbuild_add_executable(example examples/example.cpp)
-#target_link_libraries(example ${PROJECT_NAME})
diff --git a/generic_algorithm_templates/template_generic_algorithm.h b/generic_algorithm_templates/template_generic_algorithm.h
deleted file mode 100644
index 39209a08a07a3799cbd6b775251b503d78558afe..0000000000000000000000000000000000000000
--- a/generic_algorithm_templates/template_generic_algorithm.h
+++ /dev/null
@@ -1,168 +0,0 @@
-// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
-// Author 
-// All rights reserved.
-//
-// This file is part of iri-ros-pkg
-// iri-ros-pkg is free software: you can redistribute it and/or modify
-// it under the terms of the GNU Lesser General Public License as published by
-// the Free Software Foundation, either version 3 of the License, or
-// at your option) any later version.
-//
-// This program is distributed in the hope that it will be useful,
-// but WITHOUT ANY WARRANTY; without even the implied warranty of
-// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-// GNU Lesser General Public License for more details.
-//
-// You should have received a copy of the GNU Lesser General Public License
-// along with this program.  If not, see <http://www.gnu.org/licenses/>.
-// 
-// IMPORTANT NOTE: This code has been generated through a script from the 
-// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
-// of the scripts. ROS topics can be easly add by using those scripts. Please
-// refer to the IRI wiki page for more information:
-// http://wikiri.upc.es/index.php/Robotics_Lab
-
-#ifndef _template_node_h_
-#define _template_node_h_
-
-#include "iri_base_algorithm/iri_base_algorithm.h"
-
-// [include algorithm common interface]
-#include <template_if_pkg/template_if_class>
-
-// [publisher subscriber headers]
-
-// [service client headers]
-
-// [action server client headers]
-
-/**
- * \brief IRI ROS Specific Driver Class
- *
- * This class inherits from the IRI Core class IriBaseNodeDriver<IriBaseDriver>, 
- * to provide an execution thread to the driver object. A complete framework  
- * with utilites to test the node functionallity or to add diagnostics to  
- * specific situations is also given. The inherit template design form allows  
- * complete access to any IriBaseDriver object implementation.
- *
- * As mentioned, tests in the different driver states can be performed through 
- * class methods such as addNodeOpenedTests() or addNodeRunningTests(). Tests
- * common to all nodes may be also executed in the pattern class IriBaseNodeDriver.
- * Similarly to the tests, diagnostics can easyly be added. See ROS Wiki for
- * more details:
- * http://www.ros.org/wiki/diagnostics/ (Tutorials: Creating a Diagnostic Analyzer)
- * http://www.ros.org/wiki/self_test/ (Example: Self Test)
- */
-template <class Algorithm>
-class TemplateNode : public algorithm_base::IriBaseAlgorithm<Algorithm>
-{
-  private:
-    // [publisher attributes]
-
-    // [subscriber attributes]
-
-    // [service attributes]
-
-    // [client attributes]
-
-    // [action server attributes]
-
-    // [action client attributes]
-
-  public:
-   /**
-    * \brief Constructor
-    * 
-    * This constructor initializes specific class attributes and all ROS
-    * communications variables to enable message exchange.
-    */
-    TemplateNode();
-
-   /**
-    * \brief Destructor
-    * 
-    * This destructor frees all necessary dynamic memory allocated within this
-    * this class.
-    */
-    ~TemplateNode();
-
-  protected:
-   /**
-    * \brief main node thread
-    *
-    * This is the main thread node function. Code written here will be executed
-    * in every node loop while the algorithm is on running state. Loop frequency 
-    * can be tuned by modifying loop_rate attribute.
-    *
-    * Here data related to the process loop or to ROS topics (mainly data structs
-    * related to the MSG and SRV files) must be updated. ROS publisher objects 
-    * must publish their data in this process. ROS client servers may also
-    * request data to the corresponding server topics.
-    */
-    void mainNodeThread(void);
-
-   /**
-    * \brief node add diagnostics
-    *
-    * In this abstract function additional ROS diagnostics applied to the 
-    * specific algorithms may be added.
-    */
-    void addNodeDiagnostics(void);
-
-    // [diagnostic functions]
-    
-    // [test functions]
-};
-
-template <class Algorithm>
-TemplateNode<Algorithm>::TemplateNode(void) :
-  algorithm_base::IriBaseAlgorithm<Algorithm>
-{
-  //init class attributes if necessary
-  //this->loop_rate_ = 2;//in [Hz]
-
-  // [init publishers]
-  
-  // [init subscribers]
-  
-  // [init services]
-  
-  // [init clients]
-  
-  // [init action servers]
-  
-  // [init action clients]
-}
-
-template <class Algorithm>
-TemplateNode<Algorithm>::~TemplateNode(void)
-{
-  // [free dynamic memory]
-}
-
-template <class Algorithm>
-void TemplateNode<Algorithm>::mainNodeThread(void)
-{
-  // [fill msg structures]
-  
-  // [fill srv structure and make request to the server]
-  
-  // [fill action structure and make request to the action server]
-
-  // [publish messages]
-}
-
-/*  [subscriber callbacks] */
-
-/*  [service callbacks] */
-
-/*  [action callbacks] */
-
-/*  [action requests] */
-
-template <class Algorithm>
-void TemplateNode<Algorithm>::addNodeDiagnostics(void)
-{
-}
-
-#endif
diff --git a/simple_algorithm_templates/CMakeLists.txt b/simple_algorithm_templates/CMakeLists.txt
deleted file mode 100644
index 80d7b59837a3aa5d412409ed1f3a66c529feb9e6..0000000000000000000000000000000000000000
--- a/simple_algorithm_templates/CMakeLists.txt
+++ /dev/null
@@ -1,43 +0,0 @@
-cmake_minimum_required(VERSION 2.4.6)
-include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
-
-set(PROJECT_NAME template_node)
-
-# Set the build type.  Options are:
-#  Coverage       : w/ debug symbols, w/o optimization, w/ code-coverage
-#  Debug          : w/ debug symbols, w/o optimization
-#  Release        : w/o debug symbols, w/ optimization
-#  RelWithDebInfo : w/ debug symbols, w/ optimization
-#  MinSizeRel     : w/o debug symbols, w/ optimization, stripped binaries
-#set(ROS_BUILD_TYPE RelWithDebInfo)
-
-rosbuild_init()
-
-#set the default path for built executables to the "bin" directory
-set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
-#set the default path for built libraries to the "lib" directory
-set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
-
-#uncomment if you have defined messages
-#rosbuild_genmsg()
-#uncomment if you have defined services
-#rosbuild_gensrv()
-
-# added to include support for dynamic reconfiguration
-rosbuild_find_ros_package(dynamic_reconfigure)
-include(${dynamic_reconfigure_PACKAGE_PATH}/cmake/cfgbuild.cmake)
-gencfg()
-# end dynamic reconfiguration
-
-FIND_PACKAGE(iriutils REQUIRED)
-
-INCLUDE_DIRECTORIES(${iriutils_INCLUDE_DIR} ./include)
-
-#common commands for building c++ executables and libraries
-#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
-#target_link_libraries(${PROJECT_NAME} another_library)
-#rosbuild_add_boost_directories()
-#rosbuild_link_boost(${PROJECT_NAME} thread)
-rosbuild_add_executable(${PROJECT_NAME} src/template_alg.cpp src/template_node.cpp)
-
-target_link_libraries(${PROJECT_NAME} ${iriutils_LIBRARY})
diff --git a/simple_algorithm_templates/template_alg.cfg b/simple_algorithm_templates/template_alg.cfg
deleted file mode 100644
index 2df02f59b9e9ae3d8a40292c295f7b261c87b8fe..0000000000000000000000000000000000000000
--- a/simple_algorithm_templates/template_alg.cfg
+++ /dev/null
@@ -1,44 +0,0 @@
-#! /usr/bin/env python
-#*  All rights reserved.
-#*
-#*  Redistribution and use in source and binary forms, with or without
-#*  modification, are permitted provided that the following conditions
-#*  are met:
-#*
-#*   * Redistributions of source code must retain the above copyright
-#*     notice, this list of conditions and the following disclaimer.
-#*   * Redistributions in binary form must reproduce the above
-#*     copyright notice, this list of conditions and the following
-#*     disclaimer in the documentation and/or other materials provided
-#*     with the distribution.
-#*   * Neither the name of the Willow Garage nor the names of its
-#*     contributors may be used to endorse or promote products derived
-#*     from this software without specific prior written permission.
-#*
-#*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-#*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-#*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-#*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-#*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-#*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-#*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-#*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-#*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-#*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-#*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-#*  POSSIBILITY OF SUCH DAMAGE.
-#***********************************************************
-
-# Author: 
-
-PACKAGE='template'
-import roslib; roslib.load_manifest(PACKAGE)
-
-from dynamic_reconfigure.parameter_generator import *
-
-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)
-
-exit(gen.generate(PACKAGE, "TemplateAlg", "Template"))
diff --git a/simple_algorithm_templates/template_alg.cpp b/simple_algorithm_templates/template_alg.cpp
deleted file mode 100644
index 90ace932a9a0a4d0409babcacae3e0468896e213..0000000000000000000000000000000000000000
--- a/simple_algorithm_templates/template_alg.cpp
+++ /dev/null
@@ -1,21 +0,0 @@
-#include "template_alg.h"
-
-TemplateAlg::TemplateAlg(void)
-{
-}
-
-TemplateAlg::~TemplateAlg(void)
-{
-}
-
-void TemplateAlg::config_update(Config& new_cfg, uint32_t level)
-{
-  this->lock();
-
-  // save the current configuration
-  this->config_=new_cfg;
-  
-  this->unlock();
-}
-
-// TemplateAlg Public API
\ No newline at end of file
diff --git a/simple_algorithm_templates/template_alg.h b/simple_algorithm_templates/template_alg.h
deleted file mode 100644
index 63e433a26dcc607ef65c935fee55783fde24a4b3..0000000000000000000000000000000000000000
--- a/simple_algorithm_templates/template_alg.h
+++ /dev/null
@@ -1,126 +0,0 @@
-// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
-// Author 
-// All rights reserved.
-//
-// This file is part of iri-ros-pkg
-// iri-ros-pkg is free software: you can redistribute it and/or modify
-// it under the terms of the GNU Lesser General Public License as published by
-// the Free Software Foundation, either version 3 of the License, or
-// at your option) any later version.
-//
-// This program is distributed in the hope that it will be useful,
-// but WITHOUT ANY WARRANTY; without even the implied warranty of
-// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-// GNU Lesser General Public License for more details.
-//
-// You should have received a copy of the GNU Lesser General Public License
-// along with this program.  If not, see <http://www.gnu.org/licenses/>.
-// 
-// IMPORTANT NOTE: This code has been generated through a script from the 
-// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
-// of the scripts. ROS topics can be easly add by using those scripts. Please
-// refer to the IRI wiki page for more information:
-// http://wikiri.upc.es/index.php/Robotics_Lab
-
-#ifndef _template_alg_h_
-#define _template_alg_h_
-
-#include <template_namespace/TemplateConfig.h>
-#include "mutex.h"
-
-//include template_alg main library
-
-/**
- * \brief IRI ROS Specific Driver Class
- *
- *
- */
-class TemplateAlg
-{
-  protected:
-   /**
-    * \brief define config type
-    *
-    * Define a Config type with the TemplateConfig. All driver implementations
-    * will then use the same variable type Config.
-    */
-    CMutex alg_mutex_;
-
-    // private attributes and methods
-
-  public:
-   /**
-    * \brief define config type
-    *
-    * Define a Config type with the TemplateConfig. All driver implementations
-    * will then use the same variable type Config.
-    */
-    typedef template_namespace::TemplateConfig Config;
-
-   /**
-    * \brief config variable
-    *
-    * This variable has all the driver parameters defined in the cfg config file.
-    * Is updated everytime function config_update() is called.
-    */
-    Config config_;
-
-   /**
-    * \brief constructor
-    *
-    * In this constructor parameters related to the specific driver can be
-    * initalized. Those parameters can be also set in the openDriver() function.
-    * Attributes from the main node driver class IriBaseDriver such as loop_rate,
-    * may be also overload here.
-    */
-    TemplateAlg(void);
-
-   /**
-    * \brief Lock Algorithm
-    *
-    * Locks access to the Algorithm class
-    */
-    void lock(void) { alg_mutex_.enter(); };
-
-   /**
-    * \brief Unlock Algorithm
-    *
-    * Unlocks access to the Algorithm class
-    */
-    void unlock(void) { alg_mutex_.exit(); };
-
-   /**
-    * \brief Tries Access to Algorithm
-    *
-    * Tries access to Algorithm
-    * 
-    * \return true if the lock was adquired, false otherwise
-    */
-    bool try_enter(void) { return alg_mutex_.try_enter(); };
-
-   /**
-    * \brief config update
-    *
-    * In this function the driver parameters must be updated with the input
-    * config variable. Then the new configuration state will be stored in the 
-    * Config attribute.
-    *
-    * \param new_cfg the new driver configuration state
-    *
-    * \param level level in which the update is taken place
-    */
-    void config_update(Config& new_cfg, uint32_t level=0);
-
-    // here define all template_alg interface methods to retrieve and set
-    // the driver parameters
-
-   /**
-    * \brief Destructor
-    *
-    * This destructor is called when the object is about to be destroyed.
-    *
-    */
-    ~TemplateAlg(void);
-};
-
-#endif
diff --git a/simple_algorithm_templates/template_alg_node.cpp b/simple_algorithm_templates/template_alg_node.cpp
deleted file mode 100644
index 4de5bdd79eb916c5061247abdcce874a7bb6e49a..0000000000000000000000000000000000000000
--- a/simple_algorithm_templates/template_alg_node.cpp
+++ /dev/null
@@ -1,61 +0,0 @@
-#include "template_node.h"
-
-TemplateNode::TemplateNode(void) :
-  algorithm_base::IriBaseAlgorithm<TemplateAlg>()
-{
-  //init class attributes if necessary
-  //this->loop_rate_ = 2;//in [Hz]
-
-  // [init publishers]
-  
-  // [init subscribers]
-  
-  // [init services]
-  
-  // [init clients]
-  
-  // [init action servers]
-  
-  // [init action clients]
-}
-
-TemplateNode::~TemplateNode(void)
-{
-  // [free dynamic memory]
-}
-
-void TemplateNode::mainNodeThread(void)
-{
-  // [fill msg structures]
-  
-  // [fill srv structure and make request to the server]
-  
-  // [fill action structure and make request to the action server]
-
-  // [publish messages]
-}
-
-/*  [subscriber callbacks] */
-
-/*  [service callbacks] */
-
-/*  [action callbacks] */
-
-/*  [action requests] */
-
-void TemplateNode::node_config_update(Config &config, uint32_t level)
-{
-  this->alg_.lock();
-
-  this->alg_.unlock();
-}
-
-void TemplateNode::addNodeDiagnostics(void)
-{
-}
-
-/* main function */
-int main(int argc,char *argv[])
-{
-  return algorithm_base::main<TemplateNode>(argc, argv, "template_node");
-}
diff --git a/simple_algorithm_templates/template_alg_node.h b/simple_algorithm_templates/template_alg_node.h
deleted file mode 100644
index c0d884cc4a00a465c20abd3a1c4acd4c22e3dec6..0000000000000000000000000000000000000000
--- a/simple_algorithm_templates/template_alg_node.h
+++ /dev/null
@@ -1,115 +0,0 @@
-// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
-// Author 
-// All rights reserved.
-//
-// This file is part of iri-ros-pkg
-// iri-ros-pkg is free software: you can redistribute it and/or modify
-// it under the terms of the GNU Lesser General Public License as published by
-// the Free Software Foundation, either version 3 of the License, or
-// at your option) any later version.
-//
-// This program is distributed in the hope that it will be useful,
-// but WITHOUT ANY WARRANTY; without even the implied warranty of
-// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-// GNU Lesser General Public License for more details.
-//
-// You should have received a copy of the GNU Lesser General Public License
-// along with this program.  If not, see <http://www.gnu.org/licenses/>.
-// 
-// IMPORTANT NOTE: This code has been generated through a script from the 
-// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
-// of the scripts. ROS topics can be easly add by using those scripts. Please
-// refer to the IRI wiki page for more information:
-// http://wikiri.upc.es/index.php/Robotics_Lab
-
-#ifndef _template_node_h_
-#define _template_node_h_
-
-#include <iri_base_algorithm/iri_base_algorithm.h>
-#include "template_alg.h"
-
-// [publisher subscriber headers]
-
-// [service client headers]
-
-// [action server client headers]
-
-/**
- * \brief IRI ROS Specific Algorithm Class
- *
- */
-class TemplateNode : public algorithm_base::IriBaseAlgorithm<TemplateAlg>
-{
-  private:
-    // [publisher attributes]
-
-    // [subscriber attributes]
-
-    // [service attributes]
-
-    // [client attributes]
-
-    // [action server attributes]
-
-    // [action client attributes]
-
-  public:
-   /**
-    * \brief Constructor
-    * 
-    * This constructor initializes specific class attributes and all ROS
-    * communications variables to enable message exchange.
-    */
-    TemplateNode(void);
-
-   /**
-    * \brief Destructor
-    * 
-    * This destructor frees all necessary dynamic memory allocated within this
-    * this class.
-    */
-    ~TemplateNode(void);
-
-  protected:
-   /**
-    * \brief main node thread
-    *
-    * This is the main thread node function. Code written here will be executed
-    * in every node loop while the algorithm is on running state. Loop frequency 
-    * can be tuned by modifying loop_rate attribute.
-    *
-    * Here data related to the process loop or to ROS topics (mainly data structs
-    * related to the MSG and SRV files) must be updated. ROS publisher objects 
-    * must publish their data in this process. ROS client servers may also
-    * request data to the corresponding server topics.
-    */
-    void mainNodeThread(void);
-
-   /**
-    * \brief dynamic reconfigure server callback
-    * 
-    * This method is called whenever a new configuration is received through
-    * the dynamic reconfigure. The derivated generic algorithm class must 
-    * implement it.
-    *
-    * \param config an object with new configuration from all algorithm 
-    *               parameters defined in the config file.
-    * \param level  integer referring the level in which the configuration
-    *               has been changed.
-    */
-    void node_config_update(Config &config, uint32_t level);
-
-   /**
-    * \brief node add diagnostics
-    *
-    * In this abstract function additional ROS diagnostics applied to the 
-    * specific algorithms may be added.
-    */
-    void addNodeDiagnostics(void);
-
-    // [diagnostic functions]
-    
-    // [test functions]
-};
-
-#endif