Skip to content
Snippets Groups Projects
Commit acd53d33 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Used the constructor argument NodeHandle to initialize the private_node_handle_.

parent 769c35c7
No related branches found
No related tags found
No related merge requests found
......@@ -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();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment