Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
pick_place::PickPlacePlanBase Class Reference

#include <pick_place.h>

Inheritance diagram for pick_place::PickPlacePlanBase:
Inheritance graph
[legend]

Public Member Functions

const moveit_msgs::MoveItErrorCodes & getErrorCode () const
 
const std::vector< ManipulationPlanPtr > & getFailedManipulationPlans () const
 
const std::vector< ManipulationPlanPtr > & getSuccessfulManipulationPlans () const
 
 PickPlacePlanBase (const PickPlaceConstPtr &pick_place, const std::string &name)
 
 ~PickPlacePlanBase ()
 

Protected Member Functions

void emptyQueue ()
 
void foundSolution ()
 
void initialize ()
 
void waitForPipeline (const ros::WallTime &endtime)
 

Protected Attributes

bool done_
 
boost::condition_variable done_condition_
 
boost::mutex done_mutex_
 
moveit_msgs::MoveItErrorCodes error_code_
 
double last_plan_time_
 
PickPlaceConstPtr pick_place_
 
ManipulationPipeline pipeline_
 
bool pushed_all_poses_
 

Detailed Description

Definition at line 54 of file pick_place.h.

Constructor & Destructor Documentation

pick_place::PickPlacePlanBase::PickPlacePlanBase ( const PickPlaceConstPtr &  pick_place,
const std::string &  name 
)

Definition at line 53 of file pick_place.cpp.

pick_place::PickPlacePlanBase::~PickPlacePlanBase ( )

Definition at line 60 of file pick_place.cpp.

Member Function Documentation

void pick_place::PickPlacePlanBase::emptyQueue ( )
protected

Definition at line 71 of file pick_place.cpp.

void pick_place::PickPlacePlanBase::foundSolution ( )
protected

Definition at line 64 of file pick_place.cpp.

const moveit_msgs::MoveItErrorCodes& pick_place::PickPlacePlanBase::getErrorCode ( ) const
inline

Definition at line 69 of file pick_place.h.

const std::vector<ManipulationPlanPtr>& pick_place::PickPlacePlanBase::getFailedManipulationPlans ( ) const
inline

Definition at line 64 of file pick_place.h.

const std::vector<ManipulationPlanPtr>& pick_place::PickPlacePlanBase::getSuccessfulManipulationPlans ( ) const
inline

Definition at line 60 of file pick_place.h.

void pick_place::PickPlacePlanBase::initialize ( )
protected

Definition at line 81 of file pick_place.cpp.

void pick_place::PickPlacePlanBase::waitForPipeline ( const ros::WallTime endtime)
protected

Definition at line 87 of file pick_place.cpp.

Member Data Documentation

bool pick_place::PickPlacePlanBase::done_
protected

Definition at line 84 of file pick_place.h.

boost::condition_variable pick_place::PickPlacePlanBase::done_condition_
protected

Definition at line 86 of file pick_place.h.

boost::mutex pick_place::PickPlacePlanBase::done_mutex_
protected

Definition at line 87 of file pick_place.h.

moveit_msgs::MoveItErrorCodes pick_place::PickPlacePlanBase::error_code_
protected

Definition at line 88 of file pick_place.h.

double pick_place::PickPlacePlanBase::last_plan_time_
protected

Definition at line 83 of file pick_place.h.

PickPlaceConstPtr pick_place::PickPlacePlanBase::pick_place_
protected

Definition at line 80 of file pick_place.h.

ManipulationPipeline pick_place::PickPlacePlanBase::pipeline_
protected

Definition at line 81 of file pick_place.h.

bool pick_place::PickPlacePlanBase::pushed_all_poses_
protected

Definition at line 85 of file pick_place.h.


The documentation for this class was generated from the following files:


manipulation
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Oct 18 2020 13:18:24