@@ -76,6 +76,7 @@ class RPlidarNode {
7676 bool inverted;
7777 bool angle_compensate;
7878 ros::NodeHandle nh;
79+ ros::NodeHandle nh_private;
7980 // publications
8081 ros::Publisher scan_pub;
8182 // services
@@ -91,7 +92,8 @@ RPlidarNode::RPlidarNode() :
9192 frame_id(),
9293 inverted(),
9394 angle_compensate(),
94- nh(" ~" ),
95+ nh(),
96+ nh_private(" ~" ),
9597 // publications
9698 scan_pub(nh.advertise<sensor_msgs::LaserScan>(" scan" , 1000 )),
9799 // services
@@ -101,11 +103,11 @@ RPlidarNode::RPlidarNode() :
101103 " start_motor" , &RPlidarNode::start_motor, this ))
102104{
103105
104- nh .param <std::string>(" serial_port" , serial_port, " /dev/ttyUSB0" );
105- nh .param <int >(" serial_baudrate" , serial_baudrate, 115200 );
106- nh .param <std::string>(" frame_id" , frame_id, " laser_frame" );
107- nh .param <bool >(" inverted" , inverted, false );
108- nh .param <bool >(" angle_compensate" , angle_compensate, true );
106+ nh_private .param <std::string>(" serial_port" , serial_port, " /dev/ttyUSB0" );
107+ nh_private .param <int >(" serial_baudrate" , serial_baudrate, 115200 );
108+ nh_private .param <std::string>(" frame_id" , frame_id, " laser_frame" );
109+ nh_private .param <bool >(" inverted" , inverted, false );
110+ nh_private .param <bool >(" angle_compensate" , angle_compensate, true );
109111
110112 printf (" RPLIDAR running on ROS package rplidar_ros\n "
111113 " SDK Version: " RPLIDAR_SDK_VERSION" \n " );
0 commit comments