From 2056f177d7533f7d187faa954ad56873af5583e1 Mon Sep 17 00:00:00 2001 From: Alopez <alopez@iri.upc.edu> Date: Fri, 27 Jan 2023 16:01:41 +0100 Subject: [PATCH] tf listener related variables from private to protected --- include/iri_nav_module/nav_module.h | 32 ++++++++++++++--------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/include/iri_nav_module/nav_module.h b/include/iri_nav_module/nav_module.h index c867aa6..6aba9cf 100644 --- a/include/iri_nav_module/nav_module.h +++ b/include/iri_nav_module/nav_module.h @@ -120,59 +120,59 @@ class CNavModule : public CModule<ModuleCfg> * */ bool path_available; - // tf listener + // costmaps /** * \brief * */ - tf2_ros::Buffer tf2_buffer; + CModuleService<std_srvs::Empty,ModuleCfg> clear_costmaps; /** * \brief * */ - tf2_ros::TransformListener tf2_listener; + ros::Timer clear_costmaps_timer; /** * \brief * */ - double tf_timeout_time_s; - // costmaps + void clear_costmaps_call(const ros::TimerEvent& event); /** * \brief * */ - CModuleService<std_srvs::Empty,ModuleCfg> clear_costmaps; + bool enable_auto_clear; /** * \brief * */ - ros::Timer clear_costmaps_timer; + double auto_clear_rate_hz; /** * \brief * */ - void clear_costmaps_call(const ros::TimerEvent& event); + CNavCostmapModule<ModuleCfg> local_costmap; /** * \brief * */ - bool enable_auto_clear; + CNavCostmapModule<ModuleCfg> global_costmap; + protected: + // tf listener /** * \brief * */ - double auto_clear_rate_hz; + tf2_ros::Buffer tf2_buffer; /** * \brief * */ - CNavCostmapModule<ModuleCfg> local_costmap; + tf2_ros::TransformListener tf2_listener; /** * \brief * */ - CNavCostmapModule<ModuleCfg> global_costmap; - protected: + double tf_timeout_time_s; /** * \brief * @@ -588,11 +588,11 @@ class CNavModule : public CModule<ModuleCfg> this->lock(); switch(this->clear_costmaps.call(clear_costmaps_req)) { - case ACT_SRV_SUCCESS: ROS_INFO("CNavModule: Costmaps cleared sucessfully"); + case ACT_SRV_SUCCESS: ROS_INFO("CNavModule: Costmaps cleared sucessfully (auto clear)"); break; - case ACT_SRV_PENDING: ROS_WARN("CNavModule: Costmaps not yet cleared"); + case ACT_SRV_PENDING: ROS_WARN("CNavModule: Costmaps not yet cleared (auto clear)"); break; - case ACT_SRV_FAIL: ROS_ERROR("CNavModule: Impossible to clear costmaps"); + case ACT_SRV_FAIL: ROS_ERROR("CNavModule: Impossible to clear costmaps (auto clear)"); break; } this->unlock(); -- GitLab