#include <pick_place.h>
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_ |
Definition at line 56 of file pick_place.h.
pick_place::PickPlacePlanBase::PickPlacePlanBase | ( | const PickPlaceConstPtr & | pick_place, |
const std::string & | name | ||
) |
Definition at line 54 of file pick_place.cpp.
Definition at line 64 of file pick_place.cpp.
void pick_place::PickPlacePlanBase::emptyQueue | ( | ) | [protected] |
Definition at line 75 of file pick_place.cpp.
void pick_place::PickPlacePlanBase::foundSolution | ( | ) | [protected] |
Definition at line 68 of file pick_place.cpp.
const moveit_msgs::MoveItErrorCodes& pick_place::PickPlacePlanBase::getErrorCode | ( | ) | const [inline] |
Definition at line 72 of file pick_place.h.
const std::vector<ManipulationPlanPtr>& pick_place::PickPlacePlanBase::getFailedManipulationPlans | ( | ) | const [inline] |
Definition at line 67 of file pick_place.h.
const std::vector<ManipulationPlanPtr>& pick_place::PickPlacePlanBase::getSuccessfulManipulationPlans | ( | ) | const [inline] |
Definition at line 63 of file pick_place.h.
void pick_place::PickPlacePlanBase::initialize | ( | ) | [protected] |
Definition at line 85 of file pick_place.cpp.
void pick_place::PickPlacePlanBase::waitForPipeline | ( | const ros::WallTime & | endtime | ) | [protected] |
Definition at line 91 of file pick_place.cpp.
bool pick_place::PickPlacePlanBase::done_ [protected] |
Definition at line 88 of file pick_place.h.
boost::condition_variable pick_place::PickPlacePlanBase::done_condition_ [protected] |
Definition at line 90 of file pick_place.h.
boost::mutex pick_place::PickPlacePlanBase::done_mutex_ [protected] |
Definition at line 91 of file pick_place.h.
moveit_msgs::MoveItErrorCodes pick_place::PickPlacePlanBase::error_code_ [protected] |
Definition at line 92 of file pick_place.h.
double pick_place::PickPlacePlanBase::last_plan_time_ [protected] |
Definition at line 87 of file pick_place.h.
Definition at line 84 of file pick_place.h.
Definition at line 85 of file pick_place.h.
bool pick_place::PickPlacePlanBase::pushed_all_poses_ [protected] |
Definition at line 89 of file pick_place.h.