Skip to content
Snippets Groups Projects
Commit 2056f177 authored by Alejandro Lopez Gestoso's avatar Alejandro Lopez Gestoso
Browse files

tf listener related variables from private to protected

parent b0ba1521
No related branches found
No related tags found
No related merge requests found
......@@ -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();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment