00001 /* Base class for jockeys 00002 * 00003 */ 00004 00005 #include <lama_jockeys/jockey.h> 00006 00007 namespace lama_jockeys 00008 { 00009 00010 Jockey::Jockey(const std::string& name) : 00011 private_nh_("~"), 00012 jockey_name_(name) 00013 { 00014 map_agent_ = nh_.serviceClient<lama_interfaces::ActOnMap>("/lama_map_agent"); 00015 map_agent_.waitForExistence(); 00016 } 00017 00018 void Jockey::initAction() 00019 { 00020 start_time_ = ros::Time::now(); 00021 interrupted_ = false; 00022 interruption_time_ = ros::Time(0); 00023 resume_time_ = ros::Time(0); 00024 interruptions_duration_ = ros::Duration(0); 00025 } 00026 00027 void Jockey::interrupt() 00028 { 00029 if (!interrupted_) 00030 { 00031 interrupted_ = true; 00032 interruption_time_ = ros::Time::now(); 00033 } 00034 } 00035 00036 void Jockey::resume() 00037 { 00038 if (interrupted_) 00039 { 00040 interrupted_ = false; 00041 resume_time_ = ros::Time::now(); 00042 interruptions_duration_ += resume_time_ - interruption_time_; 00043 } 00044 } 00045 00046 void Jockey::onInterrupt() 00047 { 00048 ROS_DEBUG("Action interrupted"); 00049 } 00050 00051 void Jockey::onContinue() 00052 { 00053 ROS_DEBUG("Action resumed"); 00054 } 00055 00056 ros::Duration Jockey::getCompletionDuration() const 00057 { 00058 return ros::Time::now() - start_time_ - interruptions_duration_; 00059 } 00060 00061 } // namespace lama_jockeys 00062