diff --git a/cfg/TiagoNavModule.cfg b/cfg/TiagoNavModule.cfg
index 8e8cc901129041588df09066be0ef26212fde014..982f9bafb2c51f414842e4fdc87c3ac1e70d5dbc 100755
--- a/cfg/TiagoNavModule.cfg
+++ b/cfg/TiagoNavModule.cfg
@@ -52,7 +52,7 @@ pal_pois.add("use_pal_pois",        bool_t,                 0,
 pal_pois.add("pal_mmap_file",       str_t,                  0,                     "Pal Meta map file",  "")
 pal_pois.add("pal_submap_name",     str_t,                  0,                     "Pal submap name",  "submap_0")
 
-move_base_action=add_nav_module_params(gen,"nav_module")
+move_base_action=add_nav_module_params(gen,"nav")
 
 poi_action=add_module_action_params(gen,"move_poi")
 
diff --git a/src/tiago_nav_client_alg_node.cpp b/src/tiago_nav_client_alg_node.cpp
index de510d186e7a787d6a9cb372780db34b755aa041..9f1a5d89de02956062b329780e378163a06fad94 100644
--- a/src/tiago_nav_client_alg_node.cpp
+++ b/src/tiago_nav_client_alg_node.cpp
@@ -3,7 +3,7 @@
 
 TiagoNavClientAlgNode::TiagoNavClientAlgNode(void) :
   algorithm_base::IriBaseAlgorithm<TiagoNavClientAlgorithm>(),
-  nav("nav_module",ros::this_node::getName())
+  nav("nav",ros::this_node::getName())
 {
   //init class attributes if necessary
   //this->loop_rate_ = 2;//in [Hz]