step_controller_plugin.cpp
Go to the documentation of this file.
00001 #include <vigir_step_control/step_controller_plugin.h>
00002 
00003 
00004 
00005 namespace vigir_step_control
00006 {
00007 std::string toString(const StepControllerState& state)
00008 {
00009   switch (state)
00010   {
00011     case NOT_READY:   return "NOT_READY";
00012     case READY:       return "READY";
00013     case ACTIVE:      return "ACTIVE";
00014     case PAUSED:      return "PAUSED";
00015     case FINISHED:    return "FINISHED";
00016     case FAILED:      return "FAILED";
00017     default:          return "UNKNOWN";
00018   }
00019 }
00020 
00021 StepControllerPlugin::StepControllerPlugin()
00022   : vigir_pluginlib::Plugin("step_controller")
00023   , state_(NOT_READY)
00024 {
00025   step_queue_.reset(new StepQueue());
00026 
00027   reset();
00028 }
00029 
00030 StepControllerPlugin::~StepControllerPlugin()
00031 {
00032 }
00033 
00034 void StepControllerPlugin::setStepPlanMsgPlugin(vigir_footstep_planning::StepPlanMsgPlugin::Ptr plugin)
00035 {
00036   boost::unique_lock<boost::shared_mutex> lock(plugin_mutex_);
00037 
00038   if (plugin)
00039     step_plan_msg_plugin_ = plugin;
00040   else
00041     ROS_ERROR("[StepControllerPlugin] Null pointer to StepPlanMsgPlugin rejected! Fix it immediately!");
00042 }
00043 
00044 StepControllerState StepControllerPlugin::getState() const
00045 {
00046   boost::shared_lock<boost::shared_mutex> lock(plugin_mutex_);
00047   return state_;
00048 }
00049 
00050 int StepControllerPlugin::getNextStepIndexNeeded() const
00051 {
00052   boost::shared_lock<boost::shared_mutex> lock(plugin_mutex_);
00053   return next_step_index_needed_;
00054 }
00055 
00056 int StepControllerPlugin::getLastStepIndexSent() const
00057 {
00058   boost::shared_lock<boost::shared_mutex> lock(plugin_mutex_);
00059   return last_step_index_sent_;
00060 }
00061 
00062 const msgs::ExecuteStepPlanFeedback& StepControllerPlugin::getFeedbackState() const
00063 {
00064   boost::shared_lock<boost::shared_mutex> lock(plugin_mutex_);
00065   return feedback_state_;
00066 }
00067 
00068 void StepControllerPlugin::reset()
00069 {
00070   step_queue_->reset();
00071 
00072   msgs::ExecuteStepPlanFeedback feedback;
00073   feedback.last_performed_step_index = -1;
00074   feedback.currently_executing_step_index = -1;
00075   feedback.first_changeable_step_index = -1;
00076   setFeedbackState(feedback);
00077 
00078   setNextStepIndexNeeded(-1);
00079   setLastStepIndexSent(-1);
00080 
00081   setState(READY);
00082 }
00083 
00084 void StepControllerPlugin::setState(StepControllerState state)
00085 {
00086   boost::unique_lock<boost::shared_mutex> lock(plugin_mutex_);
00087   ROS_INFO("[StepControllerPlugin] Switching state from '%s' to '%s'.", toString(this->state_).c_str(), toString(state).c_str());
00088   this->state_ = state;
00089   feedback_state_.controller_state = state;
00090 }
00091 
00092 void StepControllerPlugin::setNextStepIndexNeeded(int index)
00093 {
00094   boost::unique_lock<boost::shared_mutex> lock(plugin_mutex_);
00095   next_step_index_needed_ = index;
00096 }
00097 
00098 void StepControllerPlugin::setLastStepIndexSent(int index)
00099 {
00100   boost::unique_lock<boost::shared_mutex> lock(plugin_mutex_);
00101   last_step_index_sent_ = index;
00102 }
00103 
00104 void StepControllerPlugin::setFeedbackState(const msgs::ExecuteStepPlanFeedback& feedback)
00105 {
00106   boost::unique_lock<boost::shared_mutex> lock(plugin_mutex_);
00107   this->feedback_state_ = feedback;
00108 }
00109 
00110 void StepControllerPlugin::updateQueueFeedback()
00111 {
00112   boost::unique_lock<boost::shared_mutex> lock(plugin_mutex_);
00113   feedback_state_.queue_size = static_cast<int>(step_queue_->size());
00114   feedback_state_.first_queued_step_index = step_queue_->firstStepIndex();
00115   feedback_state_.last_queued_step_index = step_queue_->lastStepIndex();
00116 }
00117 
00118 bool StepControllerPlugin::updateStepPlan(const msgs::StepPlan& step_plan)
00119 {
00120   if (step_plan.steps.empty())
00121     return true;
00122 
00123   // Reset controller if previous execution was finished or has failed
00124   StepControllerState state = getState();
00125   if (state == FINISHED || state == FAILED)
00126     reset();
00127 
00128   // Allow step plan updates only in READY and ACTIVE state
00129   state = getState();
00130   if (state == READY || state == ACTIVE)
00131   {
00132     msgs::ExecuteStepPlanFeedback feedback = getFeedbackState();
00133 
00134     if (step_queue_->updateStepPlan(step_plan, feedback.first_changeable_step_index))
00135     {
00136       // resets last_step_index_sent counter to trigger (re)executing steps in process()
00137       if (state == ACTIVE)
00138         setLastStepIndexSent(feedback.first_changeable_step_index-1);
00139 
00140       updateQueueFeedback();
00141 
00142       ROS_INFO("[StepControllerPlugin] Updated step queue. Current queue has steps in range [%i; %i].", step_queue_->firstStepIndex(), step_queue_->lastStepIndex());
00143 
00144       return true;
00145     }
00146   }
00147 
00148   setState(FAILED);
00149   return false;
00150 }
00151 
00152 void StepControllerPlugin::preProcess(const ros::TimerEvent& /*event*/)
00153 {
00154   // check if new walking request has been done
00155   if (getState() == READY && !step_queue_->empty())
00156   {
00157     // check consisty
00158     if (step_queue_->firstStepIndex() != 0)
00159     {
00160       ROS_ERROR("[StepControllerTestPlugin] Step plan doesn't start with initial step (step_index = 0). Execution aborted!");
00161       setState(FAILED);
00162     }
00163     else
00164     {
00165       initWalk();
00166     }
00167   }
00168 }
00169 
00170 void StepControllerPlugin::process(const ros::TimerEvent& /*event*/)
00171 {
00172   // execute steps
00173   if (getState() == ACTIVE)
00174   {
00175     // spool all requested steps
00176     while (getLastStepIndexSent() < getNextStepIndexNeeded())
00177     {
00178       // check if queue isn't empty
00179       if (step_queue_->empty())
00180       {
00181         ROS_ERROR("[StepControllerTestPlugin] Step %i required but not in queue. Execution aborted!", getNextStepIndexNeeded());
00182         setState(FAILED);
00183         return;
00184       }
00185 
00186       // determine next step index
00187       int next_step_index = getLastStepIndexSent()+1;
00188       msgs::Step step;
00189 
00190       // retrieve next step
00191       if (!step_queue_->getStep(step, next_step_index))
00192       {
00193         ROS_ERROR("[StepControllerTestPlugin] Missing step %i in queue. Execution aborted!", next_step_index);
00194         setState(FAILED);
00195         return;
00196       }
00197 
00198       // sent step to walking engine
00199       if (!executeStep(step))
00200       {
00201         ROS_ERROR("[StepControllerTestPlugin] Error while execution request of step %i. Execution aborted!", next_step_index);
00202         setState(FAILED);
00203         return;
00204       }
00205 
00206       // increment last_step_index_sent
00207       setLastStepIndexSent(next_step_index);
00208 
00209       msgs::ExecuteStepPlanFeedback feedback = getFeedbackState();
00210 
00211       // garbage collection: remove already executed steps
00212       if (feedback.last_performed_step_index >= 0)
00213         step_queue_->removeSteps(0, feedback.last_performed_step_index);
00214 
00215       // update feedback
00216       updateQueueFeedback();
00217     }
00218   }
00219 }
00220 
00221 void StepControllerPlugin::stop()
00222 {
00223   boost::unique_lock<boost::shared_mutex> lock(plugin_mutex_);
00224 
00225   ROS_INFO("[StepControllerTestPlugin] Stop requested. Resetting walk controller.");
00226   reset();
00227 }
00228 } // namespace


vigir_step_control
Author(s): Alexander Stumpf
autogenerated on Fri Jul 14 2017 02:42:09