lslidar_n301_driver_node.cc
Go to the documentation of this file.
1 /*
2  * This file is part of lslidar_n301 driver.
3  *
4  * The driver is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * The driver is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License
15  * along with the driver. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <ros/ros.h>
20 
21 int main(int argc, char** argv)
22 {
23  ros::init(argc, argv, "lslidar_n301_driver_node");
24  ros::NodeHandle node;
25  ros::NodeHandle private_nh("~");
26 
27  // start the driver
28  lslidar_n301_driver::LslidarN301Driver driver(node, private_nh);
29  if (!driver.initialize()) {
30  ROS_ERROR("Cannot initialize lslidar driver...");
31  return 0;
32  }
33  // loop until shut down or end of file
34  while(ros::ok() && driver.polling()) {
35  ros::spinOnce();
36 
37  }
38 
39  return 0;
40 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)


lslidar_n301_driver
Author(s): Nick Shu
autogenerated on Thu Sep 26 2019 03:58:32