18 #ifndef COB_TWIST_CONTROLLER_TASK_STACK_TASK_STACK_CONTROLLER_H
19 #define COB_TWIST_CONTROLLER_TASK_STACK_TASK_STACK_CONTROLLER_H
26 #include <boost/shared_ptr.hpp>
27 #include <Eigen/Dense>
46 Task(
PRIO prio, std::string
id, Eigen::MatrixXd task_jacobian, Eigen::VectorXd task)
69 return ( this->prio_ < other.
prio_ );
74 return ( this->prio_ > other.
prio_ );
79 return ( this->prio_ == other.
prio_ );
88 typedef typename std::vector<Task<PRIO> >::iterator
TypedIter_t;
115 typename std::vector<Task<PRIO> >::iterator
getTasksEnd();
130 template <
typename PRIO>
134 for (
TypedConstIter_t it = this->tasks_.begin(); it != this->tasks_.end(); it++)
148 template <
typename PRIO>
153 for (
TypedIter_t it = this->tasks_.begin(); it != this->tasks_.end(); it++)
155 if (it->id_ ==
t.id_)
158 it->task_jacobian_ =
t.task_jacobian_;
165 if (this->tasks_.end() == mem_it)
167 for (
TypedIter_t it = this->tasks_.begin(); it != this->tasks_.end(); it++)
169 if (
t.prio_ < it->prio_)
176 if (this->tasks_.end() == mem_it)
178 this->tasks_.push_back(
t);
182 this->tasks_.insert(mem_it,
t);
185 this->updateModificationTime(
true);
189 template <
typename PRIO>
193 for (
TypedIter_t it = this->tasks_.begin(); it != this->tasks_.end(); it++)
200 it->is_active_ =
true;
203 this->updateModificationTime(change);
206 template <
typename PRIO>
210 if (this->tasks_.end() != it)
212 this->updateModificationTime(!it->is_active_);
214 ROS_WARN_STREAM(
"Activation of highest prio task in stack: " << it->id_);
215 it->is_active_ =
true;
219 template <
typename PRIO>
222 return this->tasks_.begin();
225 template <
typename PRIO>
228 return this->tasks_.end();
231 template <
typename PRIO>
234 for (
TypedIter_t it = this->tasks_.begin(); it != this->tasks_.end(); it++)
236 if (it->id_ == task_id)
238 this->updateModificationTime(!it->is_active_);
239 it->is_active_ =
true;
245 template <
typename PRIO>
248 if (std::find(this->tasks_.begin(), this->tasks_.end(), it) != this->tasks_.end())
250 this->updateModificationTime(it->is_active_);
251 it->is_active_ =
false;
255 template <
typename PRIO>
258 for (
TypedIter_t it = this->tasks_.begin(); it != this->tasks_.end(); it++)
260 if (it->id_ == task_id)
262 this->updateModificationTime(it->is_active_);
263 it->is_active_ =
false;
269 template <
typename PRIO>
273 for (
TypedIter_t it = this->tasks_.begin(); it != this->tasks_.end(); it++)
280 it->is_active_ =
false;
283 this->updateModificationTime(change);
286 template <
typename PRIO>
291 while (this->tasks_.end() != this->active_task_iter_)
293 if (this->active_task_iter_->is_active_)
295 ret = this->active_task_iter_++;
299 this->active_task_iter_++;
305 template <
typename PRIO>
308 this->active_task_iter_ = this->tasks_.begin();
309 return this->active_task_iter_;
312 template <
typename PRIO>
315 this->tasks_.clear();
316 this->active_task_iter_ = this->tasks_.end();
317 this->updateModificationTime(
true);
320 template <
typename PRIO>
323 return this->modification_time_;
326 template <
typename PRIO>
340 #endif // COB_TWIST_CONTROLLER_TASK_STACK_TASK_STACK_CONTROLLER_H