nj_oa_laser_node.cpp
Go to the documentation of this file.
00001 #include <string>
00002 
00003 #include <nj_oa_laser/jockey.h>
00004 
00005 int main(int argc, char **argv)
00006 {
00007   ros::init(argc, argv, "nj_oa_laser");
00008   ros::NodeHandle private_nh("~");
00009   
00010   /* Compulsory parameter: robot radius */
00011   if (!private_nh.hasParam("robot_radius"))
00012   {
00013     ROS_ERROR("Parameter %s/robot_radius not set, exiting", private_nh.getNamespace().c_str());
00014     return 1;
00015   }
00016   double robot_radius;
00017   private_nh.param<double>("robot_radius", robot_radius, 0.0);
00018 
00019   std::string navigating_jockey_name;
00020   private_nh.param<std::string>("navigating_jockey_server_name",
00021       navigating_jockey_name, ros::this_node::getName() + "_server");
00022 
00023   nj_oa_laser::Jockey jockey(navigating_jockey_name, robot_radius);
00024 
00025   ROS_INFO_STREAM(ros::this_node::getName() << " started (with server " << jockey.getName() << ")");
00026   ros::spin();
00027   return 0;
00028 }
00029 


nj_oa_laser
Author(s): Gaël Ecorchard , Karel Košnar
autogenerated on Thu Jun 6 2019 17:50:51