From ff9dd8ede083b13e5d391fcef2d52238f61c0d1a Mon Sep 17 00:00:00 2001
From: Alopez <alopez@iri.upc.edu>
Date: Tue, 16 May 2023 12:16:00 +0200
Subject: [PATCH] Changed FOLLOW to lower cases

---
 include/iri_nav_module/follow_lp_module.h    | 28 ++++----
 include/iri_nav_module/follow_lp_module_bt.h | 70 ++++++++++----------
 2 files changed, 49 insertions(+), 49 deletions(-)

diff --git a/include/iri_nav_module/follow_lp_module.h b/include/iri_nav_module/follow_lp_module.h
index 3ce6f1f..ec76a21 100644
--- a/include/iri_nav_module/follow_lp_module.h
+++ b/include/iri_nav_module/follow_lp_module.h
@@ -10,14 +10,14 @@
   *
   */
 template <class ModuleCfg>
-class CFOLLOWLPModule : public CNavPlannerModule<ModuleCfg>
+class CFollowLPModule : public CNavPlannerModule<ModuleCfg>
 {
   public:
     /**
       * \brief Constructor
       *
       */
-    CFOLLOWLPModule(const std::string &name,const std::string &name_space=std::string(""));
+    CFollowLPModule(const std::string &name,const std::string &name_space=std::string(""));
 
     /**
      * \brief Function to set the parameter update_dist
@@ -100,25 +100,25 @@ class CFOLLOWLPModule : public CNavPlannerModule<ModuleCfg>
       * \brief Destructor
       *
       */
-    ~CFOLLOWLPModule();
+    ~CFollowLPModule();
   };
 
   template<class ModuleCfg>
-  CFOLLOWLPModule<ModuleCfg>::CFOLLOWLPModule(const std::string &name,const std::string &name_space) : CNavPlannerModule<ModuleCfg>(name,name_space)
+  CFollowLPModule<ModuleCfg>::CFollowLPModule(const std::string &name,const std::string &name_space) : CNavPlannerModule<ModuleCfg>(name,name_space)
   {
 
   }
 
   /* parameter functions */
   template <class ModuleCfg>
-  dyn_reconf_status_t CFOLLOWLPModule<ModuleCfg>::set_update_dist(double &value)
+  dyn_reconf_status_t CFollowLPModule<ModuleCfg>::set_update_dist(double &value)
   {
     this->planner_reconf.set_parameter("update_dist",value);
     return this->planner_reconf.get_status();
   }
 
   template <class ModuleCfg>
-  dyn_reconf_status_t CFOLLOWLPModule<ModuleCfg>::get_update_dist(double &value)
+  dyn_reconf_status_t CFollowLPModule<ModuleCfg>::get_update_dist(double &value)
   {
     if(this->planner_reconf.get_parameter("update_dist",value))
       return DYN_RECONF_SUCCESSFULL;
@@ -127,14 +127,14 @@ class CFOLLOWLPModule : public CNavPlannerModule<ModuleCfg>
   }
 
   template <class ModuleCfg>
-  dyn_reconf_status_t CFOLLOWLPModule<ModuleCfg>::set_follow_dist(double &value)
+  dyn_reconf_status_t CFollowLPModule<ModuleCfg>::set_follow_dist(double &value)
   {
     this->planner_reconf.set_parameter("follow_dist",value);
     return this->planner_reconf.get_status();
   }
 
   template <class ModuleCfg>
-  dyn_reconf_status_t CFOLLOWLPModule<ModuleCfg>::get_follow_dist(double &value)
+  dyn_reconf_status_t CFollowLPModule<ModuleCfg>::get_follow_dist(double &value)
   {
     if(this->planner_reconf.get_parameter("follow_dist",value))
       return DYN_RECONF_SUCCESSFULL;
@@ -143,14 +143,14 @@ class CFOLLOWLPModule : public CNavPlannerModule<ModuleCfg>
   }
 
   template <class ModuleCfg>
-  dyn_reconf_status_t CFOLLOWLPModule<ModuleCfg>::get_follow_restart_dist(double &value)
+  dyn_reconf_status_t CFollowLPModule<ModuleCfg>::get_follow_restart_dist(double &value)
   {
     this->planner_reconf.set_parameter("follow_restart_dist",value);
     return this->planner_reconf.get_status();
   }
 
   template <class ModuleCfg>
-  dyn_reconf_status_t CFOLLOWLPModule<ModuleCfg>::set_follow_restart_dist(double &value)
+  dyn_reconf_status_t CFollowLPModule<ModuleCfg>::set_follow_restart_dist(double &value)
   {
     if(this->planner_reconf.get_parameter("follow_restart_dist",value))
       return DYN_RECONF_SUCCESSFULL;
@@ -159,14 +159,14 @@ class CFOLLOWLPModule : public CNavPlannerModule<ModuleCfg>
   }
 
   template <class ModuleCfg>
-  dyn_reconf_status_t CFOLLOWLPModule<ModuleCfg>::set_spline_dist_samples(int &value)
+  dyn_reconf_status_t CFollowLPModule<ModuleCfg>::set_spline_dist_samples(int &value)
   {
     this->planner_reconf.set_parameter("dist_samples",value);
     return this->planner_reconf.get_status();
   }
 
   template <class ModuleCfg>
-  dyn_reconf_status_t CFOLLOWLPModule<ModuleCfg>::get_spline_dist_samples(int &value)
+  dyn_reconf_status_t CFollowLPModule<ModuleCfg>::get_spline_dist_samples(int &value)
   {
     if(this->planner_reconf.get_parameter("dist_samples",value))
       return DYN_RECONF_SUCCESSFULL;
@@ -175,12 +175,12 @@ class CFOLLOWLPModule : public CNavPlannerModule<ModuleCfg>
   }
 
   template<class ModuleCfg>
-  void CFOLLOWLPModule<ModuleCfg>::dynamic_reconfigure(ModuleCfg &config, const std::string &name)
+  void CFollowLPModule<ModuleCfg>::dynamic_reconfigure(ModuleCfg &config, const std::string &name)
   {
   }
 
   template<class ModuleCfg>
-  CFOLLOWLPModule<ModuleCfg>::~CFOLLOWLPModule()
+  CFollowLPModule<ModuleCfg>::~CFollowLPModule()
   {
 
   }
diff --git a/include/iri_nav_module/follow_lp_module_bt.h b/include/iri_nav_module/follow_lp_module_bt.h
index 442689b..a46b817 100644
--- a/include/iri_nav_module/follow_lp_module_bt.h
+++ b/include/iri_nav_module/follow_lp_module_bt.h
@@ -7,11 +7,11 @@
 #include <iri_nav_module/follow_lp_module.h>
 
 template <class ModuleCfg>
-class CFOLLOWLPModuleBT
+class CFollowLPModuleBT
 {
   private:
     // object of nav_module
-    CFOLLOWLPModule<ModuleCfg> &module;
+    CFollowLPModule<ModuleCfg> &module;
     std::string name;
 
   public:
@@ -19,7 +19,7 @@ class CFOLLOWLPModuleBT
       * \brief Constructor
       *
       */
-    CFOLLOWLPModuleBT(CFOLLOWLPModule<ModuleCfg> &module,const std::string &name);
+    CFollowLPModuleBT(CFollowLPModule<ModuleCfg> &module,const std::string &name);
 
     /**
       * \brief Register all conditions and actions needed for using the module
@@ -39,7 +39,7 @@ class CFOLLOWLPModuleBT
     * This destructor frees all necessary dynamic memory allocated within this
     * this class.
     */
-    ~CFOLLOWLPModuleBT();
+    ~CFollowLPModuleBT();
   protected:
     // conditions
 
@@ -55,7 +55,7 @@ class CFOLLOWLPModuleBT
   };
 
   template <class ModuleCfg>
-  CFOLLOWLPModuleBT<ModuleCfg>::CFOLLOWLPModuleBT(CFOLLOWLPModule<ModuleCfg> &module,const std::string &name) :
+  CFollowLPModuleBT<ModuleCfg>::CFollowLPModuleBT(CFollowLPModule<ModuleCfg> &module,const std::string &name) :
     module(module)
   {
     std::size_t found = name.find_last_of("/\\");
@@ -63,7 +63,7 @@ class CFOLLOWLPModuleBT
   }
 
   template <class ModuleCfg>
-  void CFOLLOWLPModuleBT<ModuleCfg>::init(IriBehaviorTreeFactory &factory)
+  void CFollowLPModuleBT<ModuleCfg>::init(IriBehaviorTreeFactory &factory)
   {
     BT::PortsList set_update_dist_ports = {BT::InputPort<double>("update_dist")};
     BT::PortsList get_update_dist_ports = {BT::OutputPort<double>("update_dist")};
@@ -78,31 +78,31 @@ class CFOLLOWLPModuleBT
     // Registration of conditions   
 
     //Registration of actions
-    factory.registerSimpleAction(this->name+"_follow_set_update_dist", std::bind(&CFOLLOWLPModuleBT::set_update_dist, this, std::placeholders::_1), set_update_dist_ports);
-    factory.registerSimpleAction(this->name+"_follow_get_update_dist", std::bind(&CFOLLOWLPModuleBT::get_update_dist, this, std::placeholders::_1), get_update_dist_ports);
-    factory.registerSimpleAction(this->name+"_follow_set_follow_dist", std::bind(&CFOLLOWLPModuleBT::set_follow_dist, this, std::placeholders::_1), set_follow_dist_ports);
-    factory.registerSimpleAction(this->name+"_follow_get_follow_dist", std::bind(&CFOLLOWLPModuleBT::get_follow_dist, this, std::placeholders::_1), get_follow_dist_ports);
-    factory.registerSimpleAction(this->name+"_follow_get_follow_restart_dist", std::bind(&CFOLLOWLPModuleBT::get_follow_restart_dist, this, std::placeholders::_1), get_follow_restart_dist_ports);
-    factory.registerSimpleAction(this->name+"_follow_set_follow_restart_dist", std::bind(&CFOLLOWLPModuleBT::set_follow_restart_dist, this, std::placeholders::_1), set_follow_restart_dist_ports);
-    factory.registerSimpleAction(this->name+"_follow_set_spline_dist_samples", std::bind(&CFOLLOWLPModuleBT::set_spline_dist_samples, this, std::placeholders::_1), set_spline_dist_samples_ports);
-    factory.registerSimpleAction(this->name+"_follow_get_spline_dist_samples", std::bind(&CFOLLOWLPModuleBT::get_spline_dist_samples, this, std::placeholders::_1), get_spline_dist_samples_ports);
+    factory.registerSimpleAction(this->name+"_follow_set_update_dist", std::bind(&CFollowLPModuleBT::set_update_dist, this, std::placeholders::_1), set_update_dist_ports);
+    factory.registerSimpleAction(this->name+"_follow_get_update_dist", std::bind(&CFollowLPModuleBT::get_update_dist, this, std::placeholders::_1), get_update_dist_ports);
+    factory.registerSimpleAction(this->name+"_follow_set_follow_dist", std::bind(&CFollowLPModuleBT::set_follow_dist, this, std::placeholders::_1), set_follow_dist_ports);
+    factory.registerSimpleAction(this->name+"_follow_get_follow_dist", std::bind(&CFollowLPModuleBT::get_follow_dist, this, std::placeholders::_1), get_follow_dist_ports);
+    factory.registerSimpleAction(this->name+"_follow_get_follow_restart_dist", std::bind(&CFollowLPModuleBT::get_follow_restart_dist, this, std::placeholders::_1), get_follow_restart_dist_ports);
+    factory.registerSimpleAction(this->name+"_follow_set_follow_restart_dist", std::bind(&CFollowLPModuleBT::set_follow_restart_dist, this, std::placeholders::_1), set_follow_restart_dist_ports);
+    factory.registerSimpleAction(this->name+"_follow_set_spline_dist_samples", std::bind(&CFollowLPModuleBT::set_spline_dist_samples, this, std::placeholders::_1), set_spline_dist_samples_ports);
+    factory.registerSimpleAction(this->name+"_follow_get_spline_dist_samples", std::bind(&CFollowLPModuleBT::get_spline_dist_samples, this, std::placeholders::_1), get_spline_dist_samples_ports);
   }
 
   template <class ModuleCfg>
-  CFOLLOWLPModuleBT<ModuleCfg>::~CFOLLOWLPModuleBT(void)
+  CFollowLPModuleBT<ModuleCfg>::~CFollowLPModuleBT(void)
   {
     // [free dynamic memory]
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CFOLLOWLPModuleBT<ModuleCfg>::set_update_dist(BT::TreeNode& self)
+  BT::NodeStatus CFollowLPModuleBT<ModuleCfg>::set_update_dist(BT::TreeNode& self)
   {
-    ROS_DEBUG("CFOLLOWLPModuleBT::set_update_dist-> set_update_dist");
+    ROS_DEBUG("CFollowLPModuleBT::set_update_dist-> set_update_dist");
 
     BT::Optional<double> bt_update_dist = self.getInput<double>("update_dist");
     if (!bt_update_dist)
     {
-      ROS_ERROR("CFOLLOWLPModuleBT::set_update_dist-> Incorrect or missing input. It needs the following input ports: update_dist(double)");
+      ROS_ERROR("CFollowLPModuleBT::set_update_dist-> Incorrect or missing input. It needs the following input ports: update_dist(double)");
       return BT::NodeStatus::FAILURE;
     }
     double xy=bt_update_dist.value();
@@ -113,9 +113,9 @@ class CFOLLOWLPModuleBT
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CFOLLOWLPModuleBT<ModuleCfg>::get_update_dist(BT::TreeNode& self)
+  BT::NodeStatus CFollowLPModuleBT<ModuleCfg>::get_update_dist(BT::TreeNode& self)
   {
-    ROS_DEBUG("CFOLLOWLPModuleBT::get_update_dist-> get_update_dist");
+    ROS_DEBUG("CFollowLPModuleBT::get_update_dist-> get_update_dist");
 
     double update_dist;
     if(this->module.get_update_dist(update_dist)==DYN_RECONF_SUCCESSFULL)
@@ -131,14 +131,14 @@ class CFOLLOWLPModuleBT
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CFOLLOWLPModuleBT<ModuleCfg>::set_follow_dist(BT::TreeNode& self)
+  BT::NodeStatus CFollowLPModuleBT<ModuleCfg>::set_follow_dist(BT::TreeNode& self)
   {
-    ROS_DEBUG("CFOLLOWLPModuleBT::set_follow_dist-> set_follow_dist");
+    ROS_DEBUG("CFollowLPModuleBT::set_follow_dist-> set_follow_dist");
 
     BT::Optional<double> bt_follow_dist = self.getInput<double>("follow_dist");
     if (!bt_follow_dist)
     {
-      ROS_ERROR("CFOLLOWLPModuleBT::set_follow_dist-> Incorrect or missing input. It needs the following input ports: follow_dist(double)");
+      ROS_ERROR("CFollowLPModuleBT::set_follow_dist-> Incorrect or missing input. It needs the following input ports: follow_dist(double)");
       return BT::NodeStatus::FAILURE;
     }
     double follow_dist=bt_follow_dist.value();
@@ -149,9 +149,9 @@ class CFOLLOWLPModuleBT
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CFOLLOWLPModuleBT<ModuleCfg>::get_follow_dist(BT::TreeNode& self)
+  BT::NodeStatus CFollowLPModuleBT<ModuleCfg>::get_follow_dist(BT::TreeNode& self)
   {
-    ROS_DEBUG("CFOLLOWLPModuleBT::get_follow_dist-> get_follow_dist");
+    ROS_DEBUG("CFollowLPModuleBT::get_follow_dist-> get_follow_dist");
 
     double follow_dist;
     if(this->module.get_follow_dist(follow_dist)==DYN_RECONF_SUCCESSFULL)
@@ -167,14 +167,14 @@ class CFOLLOWLPModuleBT
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CFOLLOWLPModuleBT<ModuleCfg>::get_follow_restart_dist(BT::TreeNode& self)
+  BT::NodeStatus CFollowLPModuleBT<ModuleCfg>::get_follow_restart_dist(BT::TreeNode& self)
   {
-    ROS_DEBUG("CFOLLOWLPModuleBT::get_follow_restart_dist-> get_follow_restart_dist");
+    ROS_DEBUG("CFollowLPModuleBT::get_follow_restart_dist-> get_follow_restart_dist");
 
     BT::Optional<double> bt_follow_restart_dist = self.getInput<double>("follow_restart_dist");
     if (!bt_follow_restart_dist)
     {
-      ROS_ERROR("CFOLLOWLPModuleBT::get_follow_restart_dist-> Incorrect or missing input. It needs the following input ports: follow_restart_dist(double)");
+      ROS_ERROR("CFollowLPModuleBT::get_follow_restart_dist-> Incorrect or missing input. It needs the following input ports: follow_restart_dist(double)");
       return BT::NodeStatus::FAILURE;
     }
     double follow_restart_dist=bt_follow_restart_dist.value();
@@ -185,9 +185,9 @@ class CFOLLOWLPModuleBT
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CFOLLOWLPModuleBT<ModuleCfg>::set_follow_restart_dist(BT::TreeNode& self)
+  BT::NodeStatus CFollowLPModuleBT<ModuleCfg>::set_follow_restart_dist(BT::TreeNode& self)
   {
-    ROS_DEBUG("CFOLLOWLPModuleBT::set_follow_restart_dist-> set_follow_restart_dist");
+    ROS_DEBUG("CFollowLPModuleBT::set_follow_restart_dist-> set_follow_restart_dist");
 
     double follow_restart_dist;
     if(this->module.set_follow_restart_dist(follow_restart_dist)==DYN_RECONF_SUCCESSFULL)
@@ -203,14 +203,14 @@ class CFOLLOWLPModuleBT
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CFOLLOWLPModuleBT<ModuleCfg>::set_spline_dist_samples(BT::TreeNode& self)
+  BT::NodeStatus CFollowLPModuleBT<ModuleCfg>::set_spline_dist_samples(BT::TreeNode& self)
   {
-    ROS_DEBUG("CFOLLOWLPModuleBT::set_spline_dist_samples-> set_spline_dist_samples");
+    ROS_DEBUG("CFollowLPModuleBT::set_spline_dist_samples-> set_spline_dist_samples");
 
     BT::Optional<int> bt_dist_samples = self.getInput<int>("dist_samples");
     if (!bt_dist_samples)
     {
-      ROS_ERROR("CFOLLOWLPModuleBT::set_spline_dist_samples-> Incorrect or missing input. It needs the following input ports: dist_samples(int)");
+      ROS_ERROR("CFollowLPModuleBT::set_spline_dist_samples-> Incorrect or missing input. It needs the following input ports: dist_samples(int)");
       return BT::NodeStatus::FAILURE;
     }
     int dist_samples=bt_dist_samples.value();
@@ -221,9 +221,9 @@ class CFOLLOWLPModuleBT
   }
 
   template <class ModuleCfg>
-  BT::NodeStatus CFOLLOWLPModuleBT<ModuleCfg>::get_spline_dist_samples(BT::TreeNode& self)
+  BT::NodeStatus CFollowLPModuleBT<ModuleCfg>::get_spline_dist_samples(BT::TreeNode& self)
   {
-    ROS_DEBUG("CFOLLOWLPModuleBT::get_spline_dist_samples-> get_spline_dist_samples");
+    ROS_DEBUG("CFollowLPModuleBT::get_spline_dist_samples-> get_spline_dist_samples");
 
     int dist_samples;
     if(this->module.get_spline_dist_samples(dist_samples)==DYN_RECONF_SUCCESSFULL)
-- 
GitLab