Go to the documentation of this file.
44 #include <moveit_msgs/PickupAction.h>
45 #include <moveit_msgs/PlaceAction.h>
46 #include <boost/noncopyable.hpp>
53 class PickPlacePlanBase
68 const moveit_msgs::MoveItErrorCodes&
getErrorCode()
const
101 bool plan(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
const moveit_msgs::PickupGoal& goal);
110 bool plan(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
const moveit_msgs::PlaceGoal& goal);
113 class PickPlace :
private boost::noncopyable,
public std::enable_shared_from_this<PickPlace>
134 const moveit::core::RobotModelConstPtr&
getRobotModel()
const
141 const moveit_msgs::PickupGoal& goal)
const;
145 const moveit_msgs::PlaceGoal& goal)
const;
154 void visualizeGrasps(
const std::vector<ManipulationPlanPtr>& plans)
const;
moveit_msgs::MoveItErrorCodes error_code_
const moveit::core::RobotModelConstPtr & getRobotModel() const
PlacePlan(const PickPlaceConstPtr &pick_place)
bool plan(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal)
void displayProcessedGrasps(bool flag)
const std::vector< ManipulationPlanPtr > & getFailedManipulationPlans() const
Represent the sequence of steps that are executed for a manipulation plan.
const std::vector< ManipulationPlanPtr > & getSuccessfulManipulationPlans() const
planning_pipeline::PlanningPipelinePtr planning_pipeline_
bool display_computed_motion_plans_
MOVEIT_CLASS_FORWARD(ManipulationStage)
ManipulationPipeline pipeline_
double getLastPlanTime() const
const moveit_msgs::MoveItErrorCodes & getErrorCode() const
ros::Publisher display_path_publisher_
PickPlan(const PickPlaceConstPtr &pick_place)
const planning_pipeline::PlanningPipelinePtr & getPlanningPipeline() const
constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_
static const std::string DISPLAY_GRASP_TOPIC
PickPlanPtr planPick(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal) const
Plan the sequence of motions that perform a pickup action.
static const std::string DISPLAY_PATH_TOPIC
void visualizeGrasp(const ManipulationPlanPtr &plan) const
boost::condition_variable done_condition_
PlacePlanPtr planPlace(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal) const
Plan the sequence of motions that perform a placement action.
ros::Publisher grasps_publisher_
static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION
void visualizeGrasps(const std::vector< ManipulationPlanPtr > &plans) const
void displayComputedMotionPlans(bool flag)
const std::vector< ManipulationPlanPtr > & getSuccessfulManipulationPlans() const
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintsSamplerManager() const
void visualizePlan(const ManipulationPlanPtr &plan) const
bool plan(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal)
void waitForPipeline(const ros::WallTime &endtime)
PickPlacePlanBase(const PickPlaceConstPtr &pick_place, const std::string &name)
PickPlace(const planning_pipeline::PlanningPipelinePtr &planning_pipeline)
PickPlaceConstPtr pick_place_
const std::vector< ManipulationPlanPtr > & getFailedManipulationPlans() const
manipulation
Author(s): Ioan Sucan
, Sachin Chitta
autogenerated on Thu Nov 21 2024 03:24:46