#include <pick_place.h>
Public Member Functions | |
PlacePlan (const PickPlaceConstPtr &pick_place) | |
bool | plan (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal) |
Public Member Functions inherited from pick_place::PickPlacePlanBase | |
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 () | |
Additional Inherited Members | |
Protected Member Functions inherited from pick_place::PickPlacePlanBase | |
void | emptyQueue () |
void | foundSolution () |
void | initialize () |
void | waitForPipeline (const ros::WallTime &endtime) |
Protected Attributes inherited from pick_place::PickPlacePlanBase | |
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 102 of file pick_place.h.
pick_place::PlacePlan::PlacePlan | ( | const PickPlaceConstPtr & | pick_place | ) |
bool pick_place::PlacePlan::plan | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const moveit_msgs::PlaceGoal & | goal | ||
) |