#include <pick_place.h>
Definition at line 54 of file pick_place.h.
pick_place::PickPlacePlanBase::PickPlacePlanBase |
( |
const PickPlaceConstPtr & |
pick_place, |
|
|
const std::string & |
name |
|
) |
| |
pick_place::PickPlacePlanBase::~PickPlacePlanBase |
( |
| ) |
|
void pick_place::PickPlacePlanBase::emptyQueue |
( |
| ) |
|
|
protected |
void pick_place::PickPlacePlanBase::foundSolution |
( |
| ) |
|
|
protected |
const moveit_msgs::MoveItErrorCodes& pick_place::PickPlacePlanBase::getErrorCode |
( |
| ) |
const |
|
inline |
const std::vector<ManipulationPlanPtr>& pick_place::PickPlacePlanBase::getFailedManipulationPlans |
( |
| ) |
const |
|
inline |
const std::vector<ManipulationPlanPtr>& pick_place::PickPlacePlanBase::getSuccessfulManipulationPlans |
( |
| ) |
const |
|
inline |
void pick_place::PickPlacePlanBase::initialize |
( |
| ) |
|
|
protected |
void pick_place::PickPlacePlanBase::waitForPipeline |
( |
const ros::WallTime & |
endtime | ) |
|
|
protected |
bool pick_place::PickPlacePlanBase::done_ |
|
protected |
boost::condition_variable pick_place::PickPlacePlanBase::done_condition_ |
|
protected |
boost::mutex pick_place::PickPlacePlanBase::done_mutex_ |
|
protected |
moveit_msgs::MoveItErrorCodes pick_place::PickPlacePlanBase::error_code_ |
|
protected |
double pick_place::PickPlacePlanBase::last_plan_time_ |
|
protected |
PickPlaceConstPtr pick_place::PickPlacePlanBase::pick_place_ |
|
protected |
bool pick_place::PickPlacePlanBase::pushed_all_poses_ |
|
protected |
The documentation for this class was generated from the following files: