From 812545baaa0246211ac4d8d716e2e69d63fe08ae Mon Sep 17 00:00:00 2001 From: Sergi Hernandez Juan <shernand@iri.upc.edu> Date: Fri, 6 Nov 2020 15:46:28 +0100 Subject: [PATCH] Solved a bug in the handling of the dynamic reconfigure parameters. --- CMakeLists.txt | 2 +- include/iri_ros_tools/module_action.h | 14 ++++++++------ package.xml | 1 + src/iri_ros_tools/dyn_params.py | 6 +++--- 4 files changed, 13 insertions(+), 10 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 72267f2..adca6f3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -77,7 +77,7 @@ catkin_python_setup() catkin_package( INCLUDE_DIRS include LIBRARIES ${PROJECT_NAME} - CATKIN_DEPENDS roscpp + CATKIN_DEPENDS roscpp rospy ) ########### diff --git a/include/iri_ros_tools/module_action.h b/include/iri_ros_tools/module_action.h index 4397ff5..e968d46 100644 --- a/include/iri_ros_tools/module_action.h +++ b/include/iri_ros_tools/module_action.h @@ -602,12 +602,11 @@ void CModuleAction<action_ros,dyn_reconf_config>::dynamic_reconfigure(dyn_reconf boost::any value; params=dyn_reconf_config::__getParamDescriptions__(); - for(typename std::vector<typename dyn_reconf_config::AbstractParamDescriptionConstPtr>::iterator param=params.begin();param!=params.end();param++) { + (*param)->getValue(config,value); if((*param)->name==(name+"_num_retries")) { - (*param)->getValue(config,value); if(value.type()==typeid(int)) this->set_max_num_retries(boost::any_cast<int &>(value)); } @@ -621,15 +620,13 @@ void CModuleAction<action_ros,dyn_reconf_config>::dynamic_reconfigure(dyn_reconf enable_timeout=false; } } - if((*param)->name==(name+"_timeout_s")) + else if((*param)->name==(name+"_timeout_s")) { - (*param)->getValue(config,value); if(value.type()==typeid(double)) timeout=boost::any_cast<double &>(value); } - if((*param)->name==(name+"_feedback_watchdog_time_s")) + else if((*param)->name==(name+"_feedback_watchdog_time_s")) { - (*param)->getValue(config,value); if(value.type()==typeid(double)) watchdog=boost::any_cast<double &>(value); } @@ -660,6 +657,8 @@ void CModuleAction<action_ros,dyn_reconf_config>::dynamic_reconfigure(dyn_reconf this->disable_timeout(); if(enable_watchdog) this->enable_watchdog(watchdog); + else + this->disable_watchdog(); } @@ -740,7 +739,10 @@ bool CModuleAction<action_ros,dyn_reconf_config>::is_watchdog_active(void) } } else + { + this->action_access.exit(); return false; + } } template<class action_ros,class dyn_reconf_config> diff --git a/package.xml b/package.xml index cf2f794..dfc607c 100644 --- a/package.xml +++ b/package.xml @@ -14,6 +14,7 @@ <buildtool_depend>catkin</buildtool_depend> <depend>roscpp</depend> + <depend>rospy</depend> <!-- The export tag contains other, unspecified, tags --> <export> diff --git a/src/iri_ros_tools/dyn_params.py b/src/iri_ros_tools/dyn_params.py index 93ce21b..bf54e48 100644 --- a/src/iri_ros_tools/dyn_params.py +++ b/src/iri_ros_tools/dyn_params.py @@ -14,9 +14,9 @@ def add_module_action_params(gen,name): new_group.add(name+"_num_retries", int_t, 0,"Number of times an action will be called before reporting an error",1, 1, 10) new_group.add(name+"_enable_timeout", bool_t, 0,"Enable or disable the timeout feature", True) - new_group.add(name+"_timeout_s", double_t,0,"Maximum time in second to wait for the action to complete", 10.0, 1.0, 600.0) - new_group.add(name+"_enable_iwatchdog", bool_t, 0,"Enable or disable the watchdog feature", True) - new_group.add(name+"_feedback_watchdog_time_s",double_t,0,"Maximum time in second between two consecutive feedback topics", 2.0, 1.0, 100.0) + new_group.add(name+"_timeout_s", double_t,0,"Maximum time in second to wait for the action to complete", 10.0, 0.1, 600.0) + new_group.add(name+"_enable_watchdog", bool_t, 0,"Enable or disable the watchdog feature", True) + new_group.add(name+"_feedback_watchdog_time_s",double_t,0,"Maximum time in second between two consecutive feedback topics", 2.0, 0.1, 100.0) new_group.add(name+"_enabled", bool_t, 0,"Enable or disable the actual action request", True) return new_group -- GitLab