nj_laser.h
Go to the documentation of this file.
00001 #ifndef _NLJ_LASER_NJ_LASER_H_
00002 #define _NLJ_LASER_NJ_LASER_H_
00003 
00004 #include <cstdlib>
00005 #include <ctime>
00006 
00007 #include <lama_jockeys/navigating_jockey.h>
00008 
00009 #include <nlj_laser/GetLaserDescriptor.h>
00010 #include <nlj_laser/LaserDescriptor.h>
00011 
00012 #include <sensor_msgs/LaserScan.h>
00013 
00014 
00015 class NJLaser : public lama_jockeys::NavigatingJockey
00016 {
00017   public:
00018 
00019     NJLaser(const std::string& name, const std::string& get_service_name);
00020 
00021     virtual void onTraverse();
00022     virtual void onStop();
00023     virtual void onInterrupt();
00024     virtual void onContinue();
00025 
00026   private:
00027 
00028     // Name of the getter service as interface to Lama.
00029     std::string get_service_name_;
00030                 
00031     ros::Subscriber laser_scan_subscriber_; 
00032     ros::Publisher cmd_vel_publisher_; 
00033     
00034     const double mean_traversing_time_;
00035     const double max_traversing_delta_;
00036     nlj_laser::LaserDescriptor actual_trajectory_descriptor_; 
00037     
00038     bool assigned_; 
00039     int navigation_index_;  
00040     sensor_msgs::LaserScan reference_laser_scan_; 
00041 
00042     bool completed_;
00043 
00044     void handleLaser(sensor_msgs::LaserScan msg); 
00045     double completion();
00046 };
00047 
00048 #endif // _NLJ_LASER_NJ_LASER_H_


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