learning_jockey.cpp
Go to the documentation of this file.
00001 /* Base class for learning jockeys
00002  *
00003  */
00004 
00005 #include <lama_jockeys/learning_jockey.h>
00006 
00007 namespace lama_jockeys
00008 {
00009 
00010 LearningJockey::LearningJockey(const std::string& name) :
00011   Jockey(name),
00012   server_(nh_, name, false)
00013 {
00014   server_.registerGoalCallback(boost::bind(&LearningJockey::goalCallback, this));
00015   server_.registerPreemptCallback(boost::bind(&LearningJockey::preemptCallback, this));
00016 
00017   server_.start();
00018   ROS_DEBUG("Action server '%s' started for Learning", jockey_name_.c_str());
00019 }
00020 
00021 void LearningJockey::goalCallback()
00022 {
00023   lama_jockeys::LearnGoalConstPtr current_goal = server_.acceptNewGoal();
00024   goal_ = *current_goal;
00025 
00026   // Check that preempt has not been requested by the client.
00027   if (server_.isPreemptRequested() || !ros::ok())
00028   {
00029     ROS_INFO("%s: Preempted", jockey_name_.c_str());
00030     // set the action state to preempted
00031     server_.setPreempted();
00032     return;
00033   }
00034 
00035   switch (goal_.action)
00036   {
00037     case lama_jockeys::LearnGoal::LEARN:
00038       ROS_DEBUG("Received action LEARN");
00039       initAction();
00040       onLearn();
00041       break;
00042     case lama_jockeys::LearnGoal::STOP:
00043       ROS_DEBUG("Received action STOP");
00044       onStop();
00045       break;
00046     case lama_jockeys::LearnGoal::INTERRUPT:
00047       ROS_DEBUG("Received action INTERRUPT");
00048       interrupt();
00049       onInterrupt();
00050       break;
00051     case lama_jockeys::LearnGoal::CONTINUE:
00052       ROS_DEBUG("Received action CONTINUE");
00053       resume();
00054       onContinue();
00055       break;
00056   }
00057 }
00058 
00059 void LearningJockey::preemptCallback()
00060 {
00061   ROS_INFO_STREAM(jockey_name_ << ": Preempted");
00062   // set the action state to preempted
00063   server_.setPreempted();
00064 }
00065 
00066 void LearningJockey::initAction()
00067 {
00068   Jockey::initAction();
00069   result_ = LearnResult();
00070 }
00071 
00072 void LearningJockey::onInterrupt()
00073 {
00074   ROS_DEBUG_STREAM(jockey_name_ << ": learning interrupted");
00075 }
00076 
00077 void LearningJockey::onContinue()
00078 {
00079   ROS_DEBUG_STREAM(jockey_name_ << ": learning resumed");
00080 }
00081 
00082 } // namespace lama_jockeys
00083 


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