diff --git a/include/iri_ros_tools/module_action.h b/include/iri_ros_tools/module_action.h index 0af4c93f00223d99511e7acd34c03c65d77b5bd6..cc6c7f0f4a7554649e2104a54828d10068272a5c 100644 --- a/include/iri_ros_tools/module_action.h +++ b/include/iri_ros_tools/module_action.h @@ -503,8 +503,6 @@ class CModuleAction template<class action_ros> CModuleAction<action_ros>::CModuleAction(const std::string &name,const std::string &name_space):nh(ros::this_node::getName()+"/"+name_space) { - std::size_t position; - this->name=this->nh.getNamespace()+"/"+name; this->status=ACTION_IDLE; // retry control diff --git a/include/iri_ros_tools/module_dyn_reconf.h b/include/iri_ros_tools/module_dyn_reconf.h index 21f4aff7211ed3c32ceabf68de7948c9a40473f9..091a05190e52fc7f1a71261b2aaee1a4439ddf90 100644 --- a/include/iri_ros_tools/module_dyn_reconf.h +++ b/include/iri_ros_tools/module_dyn_reconf.h @@ -231,6 +231,7 @@ bool CModuleDynReconf::set_parameter(const std::string &name,bool value) case ACT_SRV_FAIL: ROS_ERROR_STREAM("CModuleDynReconf::set_parameters: Request failed on server: " << this->get_name()); return false; break; + default: return false; } } @@ -255,6 +256,7 @@ bool CModuleDynReconf::set_parameter(const std::string &name,int value) case ACT_SRV_FAIL: ROS_ERROR_STREAM("CModuleDynReconf::set_parameters: Request failed on server: " << this->get_name()); return false; break; + default: return false; } } @@ -279,6 +281,7 @@ bool CModuleDynReconf::set_parameter(const std::string &name,std::string &value) case ACT_SRV_FAIL: ROS_ERROR_STREAM("CModuleDynReconf::set_parameters: Request failed on server: " << this->get_name()); return false; break; + default: return false; } } @@ -303,6 +306,7 @@ bool CModuleDynReconf::set_parameter(const std::string &name,double value) case ACT_SRV_FAIL: ROS_ERROR_STREAM("CModuleDynReconf::set_parameters: Request failed on server: " << this->get_name()); return false; break; + default: return false; } } diff --git a/include/iri_ros_tools/module_service.h b/include/iri_ros_tools/module_service.h index 518a927d6771379445aa7022f3fb48204644f250..e05dce26bab49e5d71b9b61b9179aae59179da83 100644 --- a/include/iri_ros_tools/module_service.h +++ b/include/iri_ros_tools/module_service.h @@ -171,8 +171,6 @@ class CModuleService template<class service_msg> CModuleService<service_msg>::CModuleService(const std::string &name,const std::string &name_space):nh(ros::this_node::getName()+"/"+name_space) { - std::size_t position; - this->current_num_retries=0; this->max_num_retries=DEFAULT_SERVICE_MAX_RETRIES; this->service_client=this->nh.template serviceClient<service_msg>(name); diff --git a/src/timeout.cpp b/src/timeout.cpp index 600c9103e6c5156625ed64bb1c6350656676604e..5d003e58720d24ae340647fd890680332d43174c 100644 --- a/src/timeout.cpp +++ b/src/timeout.cpp @@ -44,6 +44,8 @@ bool CROSTimeout::timed_out(void) return false; } } + else + return false; } CROSTimeout::~CROSTimeout()