00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2012, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 /* Author: Ioan Sucan */ 00036 00037 #ifndef MOVEIT_PLAN_EXECUTION_PLAN_WITH_SENSING_ 00038 #define MOVEIT_PLAN_EXECUTION_PLAN_WITH_SENSING_ 00039 00040 #include <moveit/plan_execution/plan_representation.h> 00041 #include <moveit/trajectory_execution_manager/trajectory_execution_manager.h> 00042 00043 #include <moveit/planning_scene_monitor/trajectory_monitor.h> 00044 #include <moveit/sensor_manager/sensor_manager.h> 00045 #include <pluginlib/class_loader.h> 00046 #include <boost/scoped_ptr.hpp> 00047 00048 namespace plan_execution 00049 { 00050 00051 class PlanWithSensing 00052 { 00053 public: 00054 00055 PlanWithSensing(const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution); 00056 ~PlanWithSensing(); 00057 00058 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& getTrajectoryExecutionManager() const 00059 { 00060 return trajectory_execution_manager_; 00061 } 00062 00063 bool computePlan(ExecutableMotionPlan &plan, const ExecutableMotionPlanComputationFn &motion_planner, unsigned int max_look_attempts, double max_safe_path_cost); 00064 00065 double getMaxSafePathCost() const 00066 { 00067 return default_max_safe_path_cost_; 00068 } 00069 00070 void setMaxSafePathCost(double max_safe_path_cost) 00071 { 00072 default_max_safe_path_cost_ = max_safe_path_cost; 00073 } 00074 00075 void setMaxLookAttempts(unsigned int attempts) 00076 { 00077 default_max_look_attempts_ = attempts; 00078 } 00079 00080 unsigned int getMaxLookAttempts() const 00081 { 00082 return default_max_look_attempts_; 00083 } 00084 00085 unsigned int getMaxCostSources() const 00086 { 00087 return max_cost_sources_; 00088 } 00089 00090 void setMaxCostSources(unsigned int value) 00091 { 00092 max_cost_sources_ = value; 00093 } 00094 00095 double getDiscardOverlappingCostSources() const 00096 { 00097 return discard_overlapping_cost_sources_; 00098 } 00099 00100 void setDiscardOverlappingCostSources(double value) 00101 { 00102 discard_overlapping_cost_sources_ = value; 00103 } 00104 00105 void setBeforeLookCallback(const boost::function<void()> &callback) 00106 { 00107 before_look_callback_ = callback; 00108 } 00109 00110 void displayCostSources(bool flag); 00111 00112 private: 00113 00114 bool lookAt(const std::set<collision_detection::CostSource> &cost_sources, const std::string &frame_id); 00115 00116 ros::NodeHandle node_handle_; 00117 trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_; 00118 00119 boost::scoped_ptr<pluginlib::ClassLoader<moveit_sensor_manager::MoveItSensorManager> > sensor_manager_loader_; 00120 moveit_sensor_manager::MoveItSensorManagerPtr sensor_manager_; 00121 unsigned int default_max_look_attempts_; 00122 double default_max_safe_path_cost_; 00123 00124 double discard_overlapping_cost_sources_; 00125 unsigned int max_cost_sources_; 00126 00127 bool display_cost_sources_; 00128 ros::Publisher cost_sources_publisher_; 00129 00130 boost::function<void()> before_look_callback_; 00131 00132 class DynamicReconfigureImpl; 00133 DynamicReconfigureImpl *reconfigure_impl_; 00134 }; 00135 00136 typedef boost::shared_ptr<PlanWithSensing> PlanWithSensingPtr; 00137 typedef boost::shared_ptr<const PlanWithSensing> PlanWithSensingConstPtr; 00138 00139 } 00140 #endif