From 355eeb08b30584bb136ab2eb5587915fbd34b8fd Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Mon, 8 Jun 2020 10:56:08 +0200
Subject: [PATCH] Set the diagnostic_period in the constructor. Used its value
 to control the sleep in the local spin function.

---
 include/iri_base_driver/iri_base_driver_node.h | 5 ++++-
 1 file changed, 4 insertions(+), 1 deletion(-)

diff --git a/include/iri_base_driver/iri_base_driver_node.h b/include/iri_base_driver/iri_base_driver_node.h
index 7225f9c..18437db 100644
--- a/include/iri_base_driver/iri_base_driver_node.h
+++ b/include/iri_base_driver/iri_base_driver_node.h
@@ -351,6 +351,9 @@ IriBaseNodeDriver<Driver>::IriBaseNodeDriver(const ros::NodeHandle &nh) :
   // initialize class attributes
   // allow Ctrl+C management
   signal(SIGHUP, &IriBaseNodeDriver<Driver>::hupCalled);
+
+  // set the diagnostic updater period
+  this->private_node_handle_.setParam("diagnostic_period",0.1);
 }
 
 template <class Driver>
@@ -536,7 +539,7 @@ int IriBaseNodeDriver<Driver>::spin(void)
     // update diagnostics
     this->diagnostic_.update();
 
-    ros::WallDuration(0.1).sleep();
+    ros::WallDuration(this->diagnostic_.getPeriod()).sleep();
   }
 
   // try to go to the closed state
-- 
GitLab