step_queue.cpp
Go to the documentation of this file.
00001 #include <vigir_step_control/step_queue.h>
00002 
00003 
00004 
00005 namespace vigir_step_control
00006 {
00007 StepQueue::StepQueue()
00008 {
00009 }
00010 
00011 StepQueue::~StepQueue()
00012 {
00013 }
00014 
00015 void StepQueue::reset()
00016 {
00017   boost::unique_lock<boost::shared_mutex> lock(queue_mutex_);
00018   step_plan_.clear();
00019 }
00020 
00021 bool StepQueue::empty() const
00022 {
00023   boost::unique_lock<boost::shared_mutex> lock(queue_mutex_);
00024   return step_plan_.empty();
00025 }
00026 
00027 size_t StepQueue::size() const
00028 {
00029   boost::shared_lock<boost::shared_mutex> lock(queue_mutex_);
00030   return step_plan_.size();
00031 }
00032 
00033 bool StepQueue::updateStepPlan(const msgs::StepPlan& step_plan, int min_step_index)
00034 {
00035   if (step_plan.steps.empty())
00036     return true;
00037 
00039   msgs::ErrorStatus status = isConsistent(step_plan);
00040   if (!isOk(status))
00041   {
00042     ROS_ERROR("[StepQueue] updateStepPlan: Consistency check failed!");
00043     ROS_ERROR("%s", toString(status).c_str());
00044     return false;
00045   }
00046 
00047   unsigned int step_plan_start_index = std::max(min_step_index, step_plan.steps.front().step_index);
00048 
00049   boost::unique_lock<boost::shared_mutex> lock(queue_mutex_);
00050 
00051   // step index has to start at 0, when step queue is empty
00052   if (this->step_plan_.empty())
00053   {
00054     if (step_plan_start_index != 0)
00055     {
00056       ROS_ERROR("[StepQueue] updateStepPlan: Current step queue is empty. Expected step plan starting with index 0!");
00057       return false;
00058     }
00059   }
00060   else
00061   {
00062     msgs::Step old_step;
00063     msgs::Step new_step;
00064 
00065     // check if queue and given step plan has overlapping steps
00066     if (!this->step_plan_.getStep(old_step, step_plan_start_index))
00067     {
00068       ROS_ERROR("[StepQueue] updateStepPlan: Can't merge plan due to non-overlapping step indices of current step plan (max queued index: %i, needed index: %u)!", this->step_plan_.getLastStepIndex(), step_plan_start_index);
00069       return false;
00070     }
00071     // check if input step plan has needed overlapping steps
00072     else if (!StepPlan::getStep(new_step, step_plan, step_plan_start_index))
00073     {
00074       ROS_ERROR("[StepQueue] updateStepPlan: Can't merge plan due to non-overlapping step indices of new step plan (max index: %u, needed index: %u)!", step_plan.steps.back().step_index, step_plan_start_index);
00075       return false;
00076     }
00077     // check if overlapping indeces have the same foot index
00078     else if (old_step.foot.foot_index != new_step.foot.foot_index)
00079     {
00080       ROS_ERROR("[StepQueue] updateStepPlan: Step %u has wrong foot index!", step_plan_start_index);
00081       return false;
00082     }
00083     // check if start foot position is equal
00084     else
00085     {
00086       geometry_msgs::Pose p_old = old_step.foot.pose;
00087       geometry_msgs::Pose p_new = new_step.foot.pose;
00088       if (p_old.position.x != p_new.position.x || p_old.position.y != p_new.position.y || p_old.position.z != p_new.position.z)
00089       {
00090         ROS_WARN("[StepQueue] updateStepPlan: Overlapping step differs in position!");
00091       }
00092       if (p_old.orientation.x != p_new.orientation.x || p_old.orientation.y != p_new.orientation.y || p_old.orientation.z != p_new.orientation.z || p_old.orientation.w != p_new.orientation.w)
00093       {
00094         ROS_WARN("[StepQueue] updateStepPlan: Overlapping step differs in orientation!");
00095       }
00096     }
00097   }
00098 
00100   status += this->step_plan_.stitchStepPlan(step_plan, step_plan_start_index);
00101   this->step_plan_.removeSteps(step_plan.steps.rbegin()->step_index+1);
00102 
00103   return isOk(status);
00104 }
00105 
00106 bool StepQueue::getStep(msgs::Step& step, unsigned int step_index)
00107 {
00108   boost::shared_lock<boost::shared_mutex> lock(queue_mutex_);
00109   return step_plan_.getStep(step, step_index);
00110 }
00111 
00112 bool StepQueue::getStepAt(msgs::Step& step, unsigned int position)
00113 {
00114   boost::shared_lock<boost::shared_mutex> lock(queue_mutex_);
00115   return step_plan_.getStepAt(step, position);
00116 }
00117 
00118 std::vector<msgs::Step> StepQueue::getSteps(unsigned int start_index, unsigned int end_index) const
00119 {
00120   boost::shared_lock<boost::shared_mutex> lock(queue_mutex_);
00121 
00122   std::vector<msgs::Step> steps;
00123 
00124   for (unsigned int i = start_index; i <= end_index; i++)
00125   {
00126     msgs::Step step;
00127     if (step_plan_.getStep(step, i))
00128       steps.push_back(step);
00129   }
00130 
00131   return steps;
00132 }
00133 
00134 void StepQueue::removeStep(unsigned int step_index)
00135 {
00136   boost::unique_lock<boost::shared_mutex> lock(queue_mutex_);
00137   step_plan_.removeStep(step_index);
00138 }
00139 
00140 void StepQueue::removeSteps(unsigned int from_step_index, int to_step_index)
00141 {
00142   boost::unique_lock<boost::shared_mutex> lock(queue_mutex_);
00143   step_plan_.removeSteps(from_step_index, to_step_index);
00144 }
00145 
00146 bool StepQueue::popStep(msgs::Step& step)
00147 {
00148   boost::unique_lock<boost::shared_mutex> lock(queue_mutex_);
00149   return step_plan_.popStep(step);
00150 }
00151 
00152 bool StepQueue::popStep()
00153 {
00154   msgs::Step step;
00155   return popStep(step);
00156 }
00157 
00158 int StepQueue::firstStepIndex() const
00159 {
00160   boost::shared_lock<boost::shared_mutex> lock(queue_mutex_);
00161 
00162   msgs::Step step;
00163   if (step_plan_.getfirstStep(step))
00164     return step.step_index;
00165   else
00166     return -1;
00167 }
00168 
00169 int StepQueue::lastStepIndex() const
00170 {
00171   boost::shared_lock<boost::shared_mutex> lock(queue_mutex_);
00172 
00173   msgs::Step step;
00174   if (step_plan_.getLastStep(step))
00175     return step.step_index;
00176   else
00177     return -1;
00178 }
00179 } // namespace


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