43 : name_(name), nthreads_(nthreads), verbose_(false), stop_processing_(true)
64 static const ManipulationStagePtr empty;
75 static const ManipulationStagePtr empty;
91 for (std::size_t i = 0; i <
stages_.size(); ++i)
113 for (std::size_t i = 0; i <
stages_.size(); ++i)
122 for (std::size_t i = 0; i <
stages_.size(); ++i)
146 bool inc_queue =
false;
160 ManipulationPlanPtr g =
queue_.front();
171 g->error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
174 bool res =
stages_[i]->evaluate(g);
175 g->processing_stage_ = i + 1;
181 <<
stages_[i]->getName() <<
"' on thread " 186 if (g->error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
188 g->processing_stage_++;
199 catch (std::exception& ex)
222 ManipulationPlanPtr plan =
failed_.back();
227 <<
name_ <<
"'. Queue is now of size " <<
queue_.size());
boost::function< void()> empty_queue_callback_
#define ROS_DEBUG_STREAM_NAMED(name, args)
std::vector< ManipulationStagePtr > stages_
void processingThread(unsigned int index)
Represent the sequence of steps that are executed for a manipulation plan.
std::vector< ManipulationPlanPtr > failed_
boost::mutex queue_access_lock_
boost::mutex result_lock_
#define ROS_INFO_STREAM_NAMED(name, args)
virtual ~ManipulationPipeline()
const ManipulationStagePtr & getLastStage() const
void setVerbose(bool flag)
const ManipulationStagePtr & getFirstStage() const
std::vector< boost::thread * > processing_threads_
std::deque< ManipulationPlanPtr > queue_
ManipulationPipeline(const std::string &name, unsigned int nthreads)
void push(const ManipulationPlanPtr &grasp)
std::vector< ManipulationPlanPtr > success_
boost::function< void()> solution_callback_
unsigned int empty_queue_threads_
#define ROS_ERROR_NAMED(name,...)
ManipulationPipeline & addStage(const ManipulationStagePtr &next)
boost::condition_variable queue_access_cond_
void reprocessLastFailure()