37 #ifndef MOVEIT_PLAN_EXECUTION_PLAN_WITH_SENSING_ 38 #define MOVEIT_PLAN_EXECUTION_PLAN_WITH_SENSING_ 57 PlanWithSensing(
const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution);
66 unsigned int max_look_attempts,
double max_safe_path_cost);
116 bool lookAt(
const std::set<collision_detection::CostSource>& cost_sources,
const std::string& frame_id);
unsigned int max_cost_sources_
void setMaxSafePathCost(double max_safe_path_cost)
bool lookAt(const std::set< collision_detection::CostSource > &cost_sources, const std::string &frame_id)
unsigned int getMaxCostSources() const
void setMaxCostSources(unsigned int value)
double discard_overlapping_cost_sources_
unsigned int getMaxLookAttempts() const
double getMaxSafePathCost() const
std::unique_ptr< pluginlib::ClassLoader< moveit_sensor_manager::MoveItSensorManager > > sensor_manager_loader_
boost::function< bool(ExecutableMotionPlan &plan)> ExecutableMotionPlanComputationFn
The signature of a function that can compute a motion plan.
ros::Publisher cost_sources_publisher_
unsigned int default_max_look_attempts_
double getDiscardOverlappingCostSources() const
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & getTrajectoryExecutionManager() const
moveit_sensor_manager::MoveItSensorManagerPtr sensor_manager_
bool computePlan(ExecutableMotionPlan &plan, const ExecutableMotionPlanComputationFn &motion_planner, unsigned int max_look_attempts, double max_safe_path_cost)
void displayCostSources(bool flag)
boost::function< void()> before_look_callback_
void setDiscardOverlappingCostSources(double value)
double default_max_safe_path_cost_
bool display_cost_sources_
ros::NodeHandle node_handle_
This namespace includes functionality specific to the execution and monitoring of motion plans...
MOVEIT_CLASS_FORWARD(PlanExecution)
A generic representation on what a computed motion plan looks like.
void setBeforeLookCallback(const boost::function< void()> &callback)
PlanWithSensing(const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
void setMaxLookAttempts(unsigned int attempts)
DynamicReconfigureImpl * reconfigure_impl_
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_