00001 00006 #include <ros/ros.h> 00007 #include <ros/console.h> 00008 00009 #include <nlj_laser/nj_laser.h> 00010 #include <nlj_laser/lj_laser.h> 00011 00012 #include <lama_interfaces/AddInterface.h> 00013 00014 ros::Publisher pub; 00015 00016 int main(int argc, char **argv) 00017 { 00018 if( ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug) ) { 00019 ros::console::notifyLoggerLevelsChanged(); 00020 } 00021 ros::init(argc, argv, "laser_jockey"); 00022 ros::NodeHandle n; 00023 00024 // Create the getter and setter services for Laser descriptors. 00025 ros::ServiceClient client = n.serviceClient<lama_interfaces::AddInterface>("interface_factory"); 00026 client.waitForExistence(); 00027 ROS_DEBUG("setting descriptor services"); 00028 lama_interfaces::AddInterface srv; 00029 srv.request.interface_name = "laser_descriptor"; 00030 srv.request.interface_type = lama_interfaces::AddInterfaceRequest::SERIALIZED; 00031 srv.request.get_service_message = "nlj_laser/GetLaserDescriptor"; 00032 srv.request.set_service_message = "nlj_laser/SetLaserDescriptor"; 00033 ROS_DEBUG("setting descriptor services ...."); 00034 if (!client.call(srv)) 00035 { 00036 ROS_ERROR("Failed to create the Lama interface %s", srv.request.interface_name.c_str()); 00037 return 1; 00038 } 00039 00040 ROS_DEBUG("starting jockeys ...."); 00041 // Run the jockeys. 00042 LJLaser loc_jockey("localizing_jockey", srv.request.interface_name, srv.response.set_service_name); 00043 NJLaser nav_jockey("navigating_jockey", srv.response.get_service_name); 00044 ROS_DEBUG("jockeys started"); 00045 00046 // ros::Subscriber laserHandler = n.subscribe<sensor_msgs::LaserScan> ("base_scan", 50 , handleLaser); 00047 // pub = n.advertise<geometry_msgs::Twist> ("nav_cmd",1,false); 00048 00049 00050 00051 ROS_DEBUG("laser_jockey started"); 00052 ros::spin(); 00053 return 0; 00054 } 00055