From de195c4476cd7f5f6849124c18847abb7b73db2c Mon Sep 17 00:00:00 2001
From: Alopez <alopez@iri.upc.edu>
Date: Thu, 15 Dec 2022 10:24:08 +0100
Subject: [PATCH] get_goal_tolerance -> get_goal_tolerances

---
 include/iri_nav_module/teb_lp_module.h    |  8 ++++----
 include/iri_nav_module/teb_lp_module_bt.h | 22 +++++++++++-----------
 2 files changed, 15 insertions(+), 15 deletions(-)

diff --git a/include/iri_nav_module/teb_lp_module.h b/include/iri_nav_module/teb_lp_module.h
index 1d2b08c..21a0744 100644
--- a/include/iri_nav_module/teb_lp_module.h
+++ b/include/iri_nav_module/teb_lp_module.h
@@ -64,7 +64,7 @@ class CTEBLPModule : public CNavPlannerModule<ModuleCfg>
      * 
      * \return The status of the operation.
      */
-    dyn_reconf_status_t get_goal_tolerance(double &xy_tol, double &yaw_tol);
+    dyn_reconf_status_t get_goal_tolerances(double &xy_tol, double &yaw_tol);
 
     /**
      * \brief Function to set the both goal tolerances parameters.
@@ -75,7 +75,7 @@ class CTEBLPModule : public CNavPlannerModule<ModuleCfg>
      * 
      * \return The status of the operation.
      */
-    dyn_reconf_status_t set_goal_tolerance(double &xy_tol, double &yaw_tol);
+    dyn_reconf_status_t set_goal_tolerances(double &xy_tol, double &yaw_tol);
 
     /**
      * \brief Function to set the parameter
@@ -205,7 +205,7 @@ class CTEBLPModule : public CNavPlannerModule<ModuleCfg>
   }
 
   template <class ModuleCfg>
-  dyn_reconf_status_t CTEBLPModule<ModuleCfg>::set_goal_tolerance(double &xy_tol, double &yaw_tol)
+  dyn_reconf_status_t CTEBLPModule<ModuleCfg>::set_goal_tolerances(double &xy_tol, double &yaw_tol)
   {
     this->planner_reconf.set_parameter("xy_goal_tolerance",xy_tol);
     if(this->planner_reconf.get_status()==DYN_RECONF_SUCCESSFULL)
@@ -214,7 +214,7 @@ class CTEBLPModule : public CNavPlannerModule<ModuleCfg>
   }
 
   template <class ModuleCfg>
-  dyn_reconf_status_t CTEBLPModule<ModuleCfg>::get_goal_tolerance(double &xy_tol, double &yaw_tol)
+  dyn_reconf_status_t CTEBLPModule<ModuleCfg>::get_goal_tolerances(double &xy_tol, double &yaw_tol)
   {
     if(this->planner_reconf.get_parameter("xy_goal_tolerance",xy_tol))
     {
diff --git a/include/iri_nav_module/teb_lp_module_bt.h b/include/iri_nav_module/teb_lp_module_bt.h
index a639b2d..761acce 100644
--- a/include/iri_nav_module/teb_lp_module_bt.h
+++ b/include/iri_nav_module/teb_lp_module_bt.h
@@ -44,8 +44,8 @@ class CTEBLPModuleBT
     // conditions
 
     // actions
-    BT::NodeStatus set_goal_tolerance(BT::TreeNode& self);
-    BT::NodeStatus get_goal_tolerance(BT::TreeNode& self);
+    BT::NodeStatus set_goal_tolerances(BT::TreeNode& self);
+    BT::NodeStatus get_goal_tolerances(BT::TreeNode& self);
     BT::NodeStatus set_xy_goal_tolerance(BT::TreeNode& self);
     BT::NodeStatus get_xy_goal_tolerance(BT::TreeNode& self);
     BT::NodeStatus set_yaw_goal_tolerance(BT::TreeNode& self);
@@ -86,8 +86,8 @@ class CTEBLPModuleBT
     // Registration of conditions   
 
     //Registration of actions
-    factory.registerSimpleAction(this->name+"teb_set_goal_tolerance", std::bind(&CTEBLPModuleBT::set_goal_tolerance, this, std::placeholders::_1), set_goal_tol_ports);
-    factory.registerSimpleAction(this->name+"teb_get_goal_tolerance", std::bind(&CTEBLPModuleBT::get_goal_tolerance, this, std::placeholders::_1), get_goal_tol_ports);
+    factory.registerSimpleAction(this->name+"teb_set_goal_tolerances", std::bind(&CTEBLPModuleBT::set_goal_tolerances, this, std::placeholders::_1), set_goal_tol_ports);
+    factory.registerSimpleAction(this->name+"teb_get_goal_tolerances", std::bind(&CTEBLPModuleBT::get_goal_tolerances, this, std::placeholders::_1), get_goal_tol_ports);
     factory.registerSimpleAction(this->name+"teb_set_xy_goal_tolerance", std::bind(&CTEBLPModuleBT::set_xy_goal_tolerance, this, std::placeholders::_1), set_xy_goal_tol_ports);
     factory.registerSimpleAction(this->name+"teb_get_xy_goal_tolerance", std::bind(&CTEBLPModuleBT::get_xy_goal_tolerance, this, std::placeholders::_1), get_xy_goal_tol_ports);
     factory.registerSimpleAction(this->name+"teb_set_yaw_goal_tolerance", std::bind(&CTEBLPModuleBT::set_yaw_goal_tolerance, this, std::placeholders::_1), set_yaw_goal_tol_ports);
@@ -108,32 +108,32 @@ class CTEBLPModuleBT
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CTEBLPModuleBT<ModuleCfg>::set_goal_tolerance(BT::TreeNode& self)
+  BT::NodeStatus CTEBLPModuleBT<ModuleCfg>::set_goal_tolerances(BT::TreeNode& self)
   {
-    ROS_DEBUG("CTEBLPModuleBT::set_goal_tolerance-> set_goal_tolerance");
+    ROS_DEBUG("CTEBLPModuleBT::set_goal_tolerances-> set_goal_tolerances");
 
     BT::Optional<double> bt_xy = self.getInput<double>("xy_tolerance");
     BT::Optional<double> bt_yaw = self.getInput<double>("yaw_tolerance");
     if (!bt_xy || !bt_yaw)
     {
-      ROS_ERROR("CTEBLPModuleBT::set_goal_tolerance-> Incorrect or missing input. It needs the following input ports: xy_tolerance(double) yaw_tolerance(double)");
+      ROS_ERROR("CTEBLPModuleBT::set_goal_tolerances-> Incorrect or missing input. It needs the following input ports: xy_tolerance(double) yaw_tolerance(double)");
       return BT::NodeStatus::FAILURE;
     }
     double xy=bt_xy.value();
     double yaw=bt_yaw.value();
-    if(this->module.set_goal_tolerance(xy,yaw)==DYN_RECONF_SUCCESSFULL)
+    if(this->module.set_goal_tolerances(xy,yaw)==DYN_RECONF_SUCCESSFULL)
       return BT::NodeStatus::SUCCESS;
     else
       return BT::NodeStatus::FAILURE;
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CTEBLPModuleBT<ModuleCfg>::get_goal_tolerance(BT::TreeNode& self)
+  BT::NodeStatus CTEBLPModuleBT<ModuleCfg>::get_goal_tolerances(BT::TreeNode& self)
   {
-    ROS_DEBUG("CTEBLPModuleBT::get_goal_tolerance-> get_goal_tolerance");
+    ROS_DEBUG("CTEBLPModuleBT::get_goal_tolerances-> get_goal_tolerances");
 
     double xy,yaw;
-    if(this->module.get_goal_tolerance(xy,yaw)==DYN_RECONF_SUCCESSFULL)
+    if(this->module.get_goal_tolerances(xy,yaw)==DYN_RECONF_SUCCESSFULL)
     {
       self.setOutput("xy_tolerance", xy);
       self.setOutput("yaw_tolerance", yaw);
-- 
GitLab