00001 #ifndef _NLJ_LASER_LJ_LASER_H_ 00002 #define _NLJ_LASER_LJ_LASER_H_ 00003 00004 #include <cstdlib> 00005 #include <ctime> 00006 #include <math.h> // for lround() 00007 00008 #include <sensor_msgs/LaserScan.h> 00009 00010 #include <lama_msgs/DescriptorLink.h> 00011 #include <lama_jockeys/learning_jockey.h> 00012 00013 #include <nlj_laser/SetLaserDescriptor.h> 00014 00015 class LJLaser : public lama_jockeys::LearningJockey 00016 { 00017 public: 00018 00019 LJLaser(const std::string& name, 00020 const std::string& interface_name, 00021 const std::string& set_service_name); 00022 00023 void onLearn(); 00024 void onStop(); 00025 00026 private: 00027 00028 // Name of the interface and setter service as interface to Lama. 00029 std::string interface_name_; 00030 std::string set_service_name_; 00031 00032 ros::Subscriber laser_scan_subscriber_; 00033 00034 bool assigned_; 00035 00036 std::vector<sensor_msgs::LaserScan> descriptor_; 00037 sensor_msgs::LaserScan reference_laser_scan_; 00038 sensor_msgs::LaserScan previous_laser_scan_; 00039 00040 void handleLaser(sensor_msgs::LaserScan msg); 00041 double completion(); 00042 }; 00043 00044 #endif // _NLJ_LASER_LJ_LASER_H_