diff --git a/include/iri_base_driver/iri_base_driver_node.h b/include/iri_base_driver/iri_base_driver_node.h index 870441858735183647b52539dbaa142b09aa11e4..65e61269bf8445828b97404e4db82b288e10114c 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();