From 5e0bc0cbdb65073af4ef4f7bdff2adbc58749f4c Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Wed, 10 Nov 2021 12:19:39 +0100
Subject: [PATCH] Used the public node handle for the dynamic reconfigure
 server instead of the private one.

---
 include/iri_base_driver/iri_base_driver_node.h | 2 +-
 1 file changed, 1 insertion(+), 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 8704418..7006c2f 100644
--- a/include/iri_base_driver/iri_base_driver_node.h
+++ b/include/iri_base_driver/iri_base_driver_node.h
@@ -339,7 +339,7 @@ IriBaseNodeDriver<Driver>::IriBaseNodeDriver(const ros::NodeHandle &nh) :
   public_node_handle_(nh),
   loop_rate_(DEFAULT_RATE),
   diagnostic_(),
-  dsrv_(private_node_handle_),
+  dsrv_(public_node_handle_),
   private_node_handle_("~"),
   driver_status_standard_diagnostic_("Driver Status", boost::bind(&IriBaseNodeDriver::statusDiagnostic, this, _1))
 {
-- 
GitLab