From acd53d337d7ac58ff15798cd7abc613d2ce4c540 Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Fri, 17 Feb 2023 11:30:47 +0100
Subject: [PATCH] Used the constructor argument NodeHandle to initialize the
 private_node_handle_.

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

diff --git a/include/iri_base_driver/iri_base_driver_node.h b/include/iri_base_driver/iri_base_driver_node.h
index 8704418..65e6126 100644
--- a/include/iri_base_driver/iri_base_driver_node.h
+++ b/include/iri_base_driver/iri_base_driver_node.h
@@ -340,7 +340,7 @@ IriBaseNodeDriver<Driver>::IriBaseNodeDriver(const ros::NodeHandle &nh) :
   loop_rate_(DEFAULT_RATE),
   diagnostic_(),
   dsrv_(private_node_handle_),
-  private_node_handle_("~"),
+  private_node_handle_(nh),
   driver_status_standard_diagnostic_("Driver Status", boost::bind(&IriBaseNodeDriver::statusDiagnostic, this, _1))
 {
   ROS_DEBUG("IriBaseNodeDriver::Constructor");
@@ -643,7 +643,7 @@ int main(int argc, char **argv, std::string node_name)
   ros::init(argc, argv, node_name);
 
   // define and launch generic algorithm implementation object
-  ros::NodeHandle nh;
+  ros::NodeHandle nh(ros::this_node::getName());
   DriverType driver(nh);
   driver.spin();
 
-- 
GitLab