diff --git a/src/tiago_nav_bt_module.cpp b/src/tiago_nav_bt_module.cpp
index d5a7a066ca567bb3db4b97f6fff7eba86a976ca9..dc81ea5f38364a9b0c7882450b7971ddb4b35fa4 100644
--- a/src/tiago_nav_bt_module.cpp
+++ b/src/tiago_nav_bt_module.cpp
@@ -109,8 +109,8 @@ BT::NodeStatus CTiagoNavModuleBT::async_tiago_nav_go_to_pose(BT::TreeNode& self)
     double x_goal, y_goal, yaw_goal, heading_tol_goal, x_y_pos_tol_goal;
     if (!x || !y || !yaw || (!heading_tol && x_y_pos_tol))
     {
-      ROS_ERROR("CTiagoNavModuleBT::sync_tiago_nav_go_to_pose-> Incorrect or missing input. It needs the following input ports: x(double), y(double), yaw(double), [Optional] heading_tol(double) and [Optional] x_y_pos_tol(double)");
-      ROS_ERROR("CTiagoNavModuleBT::sync_tiago_nav_go_to_pose-> The correct input options are: x + y + yaw, x + y + yaw + heading_tol or x + y + yaw + heading_tol + x_y_pos_tol");
+      ROS_ERROR("CTiagoNavModuleBT::async_tiago_nav_go_to_pose-> Incorrect or missing input. It needs the following input ports: x(double), y(double), yaw(double), [Optional] heading_tol(double) and [Optional] x_y_pos_tol(double)");
+      ROS_ERROR("CTiagoNavModuleBT::async_tiago_nav_go_to_pose-> The correct input options are: x + y + yaw, x + y + yaw + heading_tol or x + y + yaw + heading_tol + x_y_pos_tol");
       return BT::NodeStatus::FAILURE;
     }