jockey.h
Go to the documentation of this file.
00001 /* Base class for jockeys
00002  */
00003 
00004 #ifndef _LAMA_INTERFACES_JOCKEY_H_
00005 #define _LAMA_INTERFACES_JOCKEY_H_
00006 
00007 #include <string>
00008 
00009 #include <ros/ros.h>
00010 
00011 #include <lama_interfaces/ActOnMap.h>
00012 #include <lama_msgs/DescriptorLink.h>
00013 #include <lama_msgs/LamaObject.h>
00014 
00015 namespace lama_jockeys
00016 {
00017 
00018 class Jockey
00019 {
00020   public:
00021 
00022     std::string getName() const {return jockey_name_;}
00023 
00024   protected:
00025 
00026     Jockey(const std::string& name);
00027 
00028     virtual void onInterrupt();
00029     virtual void onContinue();
00030 
00031     bool isInterrupted() const {return interrupted_;}
00032     ros::Time getStartTime() const {return start_time_;}
00033     ros::Time getInterruptionTime() const {return interruption_time_;}
00034     ros::Time getResumeTime() const {return resume_time_;}
00035     ros::Duration getInterruptionsDuration() const {return interruptions_duration_;}
00036     ros::Duration getCompletionDuration() const;
00037 
00038     ros::NodeHandle nh_;
00039     ros::NodeHandle private_nh_;
00040     std::string jockey_name_;
00041     ros::ServiceClient map_agent_;
00042 
00043     void initAction();
00044     void interrupt();
00045     void resume();
00046 
00047   private:
00048 
00049     bool interrupted_;  
00050     ros::Time start_time_;  
00051     ros::Time interruption_time_;  
00052     ros::Time resume_time_;  
00053     ros::Duration interruptions_duration_;  
00054 };
00055 
00056 } // namespace lama_jockeys
00057 
00058 #endif // _LAMA_INTERFACES_JOCKEY_H_


jockeys
Author(s): Gaël Ecorchard , Karel Košnar
autogenerated on Sat Jun 8 2019 19:03:15