From e5aac8627bf4b0eac1ed4a3fefbdb928d397340f Mon Sep 17 00:00:00 2001 From: Sergi Hernandez Juan <shernand@iri.upc.edu> Date: Wed, 14 Jul 2021 09:55:39 +0200 Subject: [PATCH] Solved a bug with the module rate handle functions: It is a ros::Rate object but it was handled as a double. --- include/iri_ros_tools/module.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/iri_ros_tools/module.h b/include/iri_ros_tools/module.h index 46b7d7f..12e8981 100644 --- a/include/iri_ros_tools/module.h +++ b/include/iri_ros_tools/module.h @@ -278,13 +278,13 @@ void CModule<ModuleCfg>::set_rate(double rate_hz) if(rate_hz<=0.0) throw CModuleException(_HERE_,"Module rate must be positive",this->name); else - this->module_rate=rate_hz; + this->module_rate=ros::Rate(rate_hz); } template<class ModuleCfg> double CModule<ModuleCfg>::get_rate(void) { - return this->module_rate; + return 1.0/(this->module_rate.expectedCycleTime().toSec()); } template<class ModuleCfg> -- GitLab