nj_laser_node.cpp
Go to the documentation of this file.
00001 
00007 #include <string>
00008 
00009 #include <ros/ros.h>
00010 #include <ros/console.h> // to change the log level to debug
00011 
00012 #include <nj_laser/jockey.h>
00013 
00014 int main(int argc, char **argv)
00015 {
00016   ros::init(argc, argv, "laser_jockey");
00017   ros::NodeHandle private_nh("~");
00018   
00019   // Debug log level
00020   if(ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug))
00021   {
00022     ros::console::notifyLoggerLevelsChanged();
00023   }
00024 
00025   /* Minimal frontier width */
00026   if (!private_nh.hasParam("frontier_width"))
00027   {
00028     ROS_ERROR("Parameter frontier_width not set, exiting.");
00029     return 1;
00030   }
00031   double frontier_width;
00032   private_nh.param<double>("frontier_width", frontier_width, 0.0);
00033 
00034   std::string navigating_jockey_name;
00035   private_nh.param<std::string>("navigating_jockey_server_name",
00036       navigating_jockey_name, ros::this_node::getName() + "_server");
00037 
00038   nj_laser::Jockey jockey(navigating_jockey_name, frontier_width);
00039 
00040   ROS_INFO("%s started (with server %s)", ros::this_node::getName().c_str(), jockey.getName().c_str());
00041   ros::spin();
00042   return 0;
00043 }
00044 


nj_laser
Author(s): Gaël Ecorchard , Karel Košnar , Vojtěch Vonásek
autogenerated on Thu Jun 6 2019 17:50:54