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/macros/class_forward.h> 00041 #include <moveit/plan_execution/plan_representation.h> 00042 #include <moveit/trajectory_execution_manager/trajectory_execution_manager.h> 00043 00044 #include <moveit/planning_scene_monitor/trajectory_monitor.h> 00045 #include <moveit/sensor_manager/sensor_manager.h> 00046 #include <pluginlib/class_loader.h> 00047 #include <boost/scoped_ptr.hpp> 00048 00049 namespace plan_execution 00050 { 00051 MOVEIT_CLASS_FORWARD(PlanWithSensing); 00052 00053 class PlanWithSensing 00054 { 00055 public: 00056 PlanWithSensing(const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution); 00057 ~PlanWithSensing(); 00058 00059 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& getTrajectoryExecutionManager() const 00060 { 00061 return trajectory_execution_manager_; 00062 } 00063 00064 bool computePlan(ExecutableMotionPlan& plan, const ExecutableMotionPlanComputationFn& motion_planner, 00065 unsigned int max_look_attempts, double max_safe_path_cost); 00066 00067 double getMaxSafePathCost() const 00068 { 00069 return default_max_safe_path_cost_; 00070 } 00071 00072 void setMaxSafePathCost(double max_safe_path_cost) 00073 { 00074 default_max_safe_path_cost_ = max_safe_path_cost; 00075 } 00076 00077 void setMaxLookAttempts(unsigned int attempts) 00078 { 00079 default_max_look_attempts_ = attempts; 00080 } 00081 00082 unsigned int getMaxLookAttempts() const 00083 { 00084 return default_max_look_attempts_; 00085 } 00086 00087 unsigned int getMaxCostSources() const 00088 { 00089 return max_cost_sources_; 00090 } 00091 00092 void setMaxCostSources(unsigned int value) 00093 { 00094 max_cost_sources_ = value; 00095 } 00096 00097 double getDiscardOverlappingCostSources() const 00098 { 00099 return discard_overlapping_cost_sources_; 00100 } 00101 00102 void setDiscardOverlappingCostSources(double value) 00103 { 00104 discard_overlapping_cost_sources_ = value; 00105 } 00106 00107 void setBeforeLookCallback(const boost::function<void()>& callback) 00108 { 00109 before_look_callback_ = callback; 00110 } 00111 00112 void displayCostSources(bool flag); 00113 00114 private: 00115 bool lookAt(const std::set<collision_detection::CostSource>& cost_sources, const std::string& frame_id); 00116 00117 ros::NodeHandle node_handle_; 00118 trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_; 00119 00120 boost::scoped_ptr<pluginlib::ClassLoader<moveit_sensor_manager::MoveItSensorManager> > sensor_manager_loader_; 00121 moveit_sensor_manager::MoveItSensorManagerPtr sensor_manager_; 00122 unsigned int default_max_look_attempts_; 00123 double default_max_safe_path_cost_; 00124 00125 double discard_overlapping_cost_sources_; 00126 unsigned int max_cost_sources_; 00127 00128 bool display_cost_sources_; 00129 ros::Publisher cost_sources_publisher_; 00130 00131 boost::function<void()> before_look_callback_; 00132 00133 class DynamicReconfigureImpl; 00134 DynamicReconfigureImpl* reconfigure_impl_; 00135 }; 00136 } 00137 #endif