Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/ompl_interface/ompl_interface.h>
00038 #include <moveit/planning_interface/planning_interface.h>
00039 #include <moveit/planning_scene/planning_scene.h>
00040 #include <moveit/robot_state/conversions.h>
00041 #include <moveit/profiler/profiler.h>
00042 #include <class_loader/class_loader.h>
00043
00044 #include <dynamic_reconfigure/server.h>
00045 #include "moveit_planners_ompl/OMPLDynamicReconfigureConfig.h"
00046
00047 #include <moveit_msgs/DisplayRobotState.h>
00048 #include <moveit_msgs/DisplayTrajectory.h>
00049
00050 namespace ompl_interface
00051 {
00052 using namespace moveit_planners_ompl;
00053
00054 class OMPLPlannerManager : public planning_interface::PlannerManager
00055 {
00056 public:
00057
00058 OMPLPlannerManager() : planning_interface::PlannerManager(),
00059 nh_("~"),
00060 display_random_valid_states_(false)
00061 {
00062 }
00063
00064 virtual bool initialize(const robot_model::RobotModelConstPtr& model, const std::string &ns)
00065 {
00066 if (!ns.empty())
00067 nh_ = ros::NodeHandle(ns);
00068 ompl_interface_.reset(new OMPLInterface(model, nh_));
00069 std::string ompl_ns = ns.empty() ? "ompl" : ns + "/ompl";
00070 dynamic_reconfigure_server_.reset(new dynamic_reconfigure::Server<OMPLDynamicReconfigureConfig>(ros::NodeHandle(nh_, ompl_ns)));
00071 dynamic_reconfigure_server_->setCallback(boost::bind(&OMPLPlannerManager::dynamicReconfigureCallback, this, _1, _2));
00072 return true;
00073 }
00074
00075 virtual bool canServiceRequest(const moveit_msgs::MotionPlanRequest &req) const
00076 {
00077 return req.trajectory_constraints.constraints.empty();
00078 }
00079
00080 virtual std::string getDescription() const
00081 {
00082 return "OMPL";
00083 }
00084
00085 virtual void getPlanningAlgorithms(std::vector<std::string> &algs) const
00086 {
00087 const planning_interface::PlannerConfigurationMap &pconfig = ompl_interface_->getPlannerConfigurations();
00088 algs.clear();
00089 algs.reserve(pconfig.size());
00090 for (planning_interface::PlannerConfigurationMap::const_iterator it = pconfig.begin() ; it != pconfig.end() ; ++it)
00091 algs.push_back(it->first);
00092 }
00093
00094 virtual void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
00095 {
00096
00097 ompl_interface_->setPlannerConfigurations(pconfig);
00098
00099 PlannerManager::setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
00100 }
00101
00102 virtual planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
00103 const planning_interface::MotionPlanRequest &req,
00104 moveit_msgs::MoveItErrorCodes &error_code) const
00105 {
00106 return ompl_interface_->getPlanningContext(planning_scene, req, error_code);
00107 }
00108
00109 private:
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152
00153
00154
00155
00156
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219 void dynamicReconfigureCallback(OMPLDynamicReconfigureConfig &config, uint32_t level)
00220 {
00221 if (config.link_for_exploration_tree.empty() && !planner_data_link_name_.empty())
00222 {
00223 pub_markers_.shutdown();
00224 planner_data_link_name_.clear();
00225 ROS_INFO("Not displaying OMPL exploration data structures.");
00226 }
00227 else
00228 if (!config.link_for_exploration_tree.empty() && planner_data_link_name_.empty())
00229 {
00230 pub_markers_ = nh_.advertise<visualization_msgs::MarkerArray>("ompl_planner_data_marker_array", 5);
00231 planner_data_link_name_ = config.link_for_exploration_tree;
00232 ROS_INFO("Displaying OMPL exploration data structures for %s", planner_data_link_name_.c_str());
00233 }
00234
00235 ompl_interface_->simplifySolutions(config.simplify_solutions);
00236 ompl_interface_->getPlanningContextManager().setMaximumSolutionSegmentLength(config.maximum_waypoint_distance);
00237 ompl_interface_->getPlanningContextManager().setMinimumWaypointCount(config.minimum_waypoint_count);
00238 if (display_random_valid_states_ && !config.display_random_valid_states)
00239 {
00240 display_random_valid_states_ = false;
00241 if (pub_valid_states_thread_)
00242 {
00243 pub_valid_states_thread_->join();
00244 pub_valid_states_thread_.reset();
00245 }
00246 pub_valid_states_.shutdown();
00247 pub_valid_traj_.shutdown();
00248 }
00249 else
00250 if (!display_random_valid_states_ && config.display_random_valid_states)
00251 {
00252 pub_valid_states_ = nh_.advertise<moveit_msgs::DisplayRobotState>("ompl_planner_valid_states", 5);
00253 pub_valid_traj_ = nh_.advertise<moveit_msgs::DisplayTrajectory>("ompl_planner_valid_trajectories", 5);
00254 display_random_valid_states_ = true;
00255
00256 }
00257 }
00258
00259 ros::NodeHandle nh_;
00260 boost::scoped_ptr<dynamic_reconfigure::Server<OMPLDynamicReconfigureConfig> > dynamic_reconfigure_server_;
00261 boost::scoped_ptr<OMPLInterface> ompl_interface_;
00262 boost::scoped_ptr<boost::thread> pub_valid_states_thread_;
00263 bool display_random_valid_states_;
00264 ros::Publisher pub_markers_;
00265 ros::Publisher pub_valid_states_;
00266 ros::Publisher pub_valid_traj_;
00267 std::string planner_data_link_name_;
00268 };
00269
00270 }
00271
00272 CLASS_LOADER_REGISTER_CLASS(ompl_interface::OMPLPlannerManager, planning_interface::PlannerManager);