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