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/robot_state/conversions.h>
00039 #include <moveit/kinematic_constraints/utils.h>
00040 #include <moveit/ompl_interface/detail/constrained_valid_state_sampler.h>
00041 #include <moveit/profiler/profiler.h>
00042 #include <fstream>
00043
00044 ompl_interface::OMPLInterface::OMPLInterface(const robot_model::RobotModelConstPtr &kmodel, const ros::NodeHandle &nh) :
00045 nh_(nh),
00046 kmodel_(kmodel),
00047 constraint_sampler_manager_(new constraint_samplers::ConstraintSamplerManager()),
00048 context_manager_(kmodel, constraint_sampler_manager_),
00049 constraints_library_(new ConstraintsLibrary(context_manager_)),
00050 use_constraints_approximations_(true),
00051 simplify_solutions_(true)
00052 {
00053 ROS_INFO("Initializing OMPL interface using ROS parameters");
00054 loadPlannerConfigurations();
00055 loadConstraintApproximations();
00056 loadConstraintSamplers();
00057 }
00058
00059 ompl_interface::OMPLInterface::OMPLInterface(const robot_model::RobotModelConstPtr &kmodel, const planning_interface::PlannerConfigurationMap &pconfig, const ros::NodeHandle &nh) :
00060 nh_(nh),
00061 kmodel_(kmodel),
00062 constraint_sampler_manager_(new constraint_samplers::ConstraintSamplerManager()),
00063 context_manager_(kmodel, constraint_sampler_manager_),
00064 constraints_library_(new ConstraintsLibrary(context_manager_)),
00065 use_constraints_approximations_(true),
00066 simplify_solutions_(true)
00067 {
00068 ROS_INFO("Initializing OMPL interface using specified configuration");
00069 setPlannerConfigurations(pconfig);
00070 loadConstraintApproximations();
00071 loadConstraintSamplers();
00072 }
00073
00074 ompl_interface::OMPLInterface::~OMPLInterface()
00075 {
00076 }
00077
00078 void ompl_interface::OMPLInterface::setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
00079 {
00080 planning_interface::PlannerConfigurationMap pconfig2 = pconfig;
00081
00082
00083 const std::vector<const robot_model::JointModelGroup*>& groups = kmodel_->getJointModelGroups();
00084 for (std::size_t i = 0 ; i < groups.size() ; ++i)
00085 {
00086 if (pconfig.find(groups[i]->getName()) == pconfig.end())
00087 {
00088 planning_interface::PlannerConfigurationSettings empty;
00089 empty.name = empty.group = groups[i]->getName();
00090 pconfig2[empty.name] = empty;
00091 }
00092 }
00093
00094 context_manager_.setPlannerConfigurations(pconfig2);
00095 }
00096
00097 ompl_interface::ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
00098 const planning_interface::MotionPlanRequest &req) const
00099 {
00100 moveit_msgs::MoveItErrorCodes dummy;
00101 return getPlanningContext(planning_scene, req, dummy);
00102 }
00103
00104 ompl_interface::ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
00105 const planning_interface::MotionPlanRequest &req,
00106 moveit_msgs::MoveItErrorCodes &error_code) const
00107 {
00108 ModelBasedPlanningContextPtr ctx = context_manager_.getPlanningContext(planning_scene, req, error_code);
00109 if (ctx)
00110 configureContext(ctx);
00111 return ctx;
00112 }
00113
00114 ompl_interface::ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext(const std::string &config, const std::string &factory_type) const
00115 {
00116 ModelBasedPlanningContextPtr ctx = context_manager_.getPlanningContext(config, factory_type);
00117 if (ctx)
00118 configureContext(ctx);
00119 return ctx;
00120 }
00121
00122 void ompl_interface::OMPLInterface::configureContext(const ModelBasedPlanningContextPtr &context) const
00123 {
00124 if (use_constraints_approximations_)
00125 context->setConstraintsApproximations(constraints_library_);
00126 else
00127 context->setConstraintsApproximations(ConstraintsLibraryPtr());
00128 context->simplifySolutions(simplify_solutions_);
00129 }
00130
00131 void ompl_interface::OMPLInterface::loadConstraintApproximations(const std::string &path)
00132 {
00133 constraints_library_->loadConstraintApproximations(path);
00134 std::stringstream ss;
00135 constraints_library_->printConstraintApproximations(ss);
00136 ROS_INFO_STREAM(ss.str());
00137 }
00138
00139 void ompl_interface::OMPLInterface::saveConstraintApproximations(const std::string &path)
00140 {
00141 constraints_library_->saveConstraintApproximations(path);
00142 }
00143
00144 bool ompl_interface::OMPLInterface::saveConstraintApproximations()
00145 {
00146 std::string cpath;
00147 if (nh_.getParam("constraint_approximations_path", cpath))
00148 {
00149 saveConstraintApproximations(cpath);
00150 return true;
00151 }
00152 ROS_WARN("ROS param 'constraint_approximations' not found. Unable to save constraint approximations");
00153 return false;
00154 }
00155
00156 bool ompl_interface::OMPLInterface::loadConstraintApproximations()
00157 {
00158 std::string cpath;
00159 if (nh_.getParam("constraint_approximations_path", cpath))
00160 {
00161 loadConstraintApproximations(cpath);
00162 return true;
00163 }
00164 return false;
00165 }
00166
00167 void ompl_interface::OMPLInterface::loadConstraintSamplers()
00168 {
00169 constraint_sampler_manager_loader_.reset(new constraint_sampler_manager_loader::ConstraintSamplerManagerLoader(constraint_sampler_manager_));
00170 }
00171
00172 void ompl_interface::OMPLInterface::loadPlannerConfigurations()
00173 {
00174 const std::vector<std::string> &group_names = kmodel_->getJointModelGroupNames();
00175 planning_interface::PlannerConfigurationMap pconfig;
00176
00177
00178 pconfig.clear();
00179 for (std::size_t i = 0 ; i < group_names.size() ; ++i)
00180 {
00181
00182 static const std::string KNOWN_GROUP_PARAMS[] = {
00183 "projection_evaluator", "longest_valid_segment_fraction"
00184 };
00185
00186
00187 std::map<std::string, std::string> specific_group_params;
00188 for (std::size_t k = 0 ; k < sizeof(KNOWN_GROUP_PARAMS) / sizeof(std::string) ; ++k)
00189 {
00190 if (nh_.hasParam(group_names[i] + "/" + KNOWN_GROUP_PARAMS[k]))
00191 {
00192 std::string value;
00193 if (nh_.getParam(group_names[i] + "/" + KNOWN_GROUP_PARAMS[k], value))
00194 {
00195 if (!value.empty())
00196 specific_group_params[KNOWN_GROUP_PARAMS[k]] = value;
00197 }
00198 else
00199 {
00200 double value_d;
00201 if (nh_.getParam(group_names[i] + "/" + KNOWN_GROUP_PARAMS[k], value_d))
00202 specific_group_params[KNOWN_GROUP_PARAMS[k]] = boost::lexical_cast<std::string>(value_d);
00203 else
00204 {
00205 int value_i;
00206 if (nh_.getParam(group_names[i] + "/" + KNOWN_GROUP_PARAMS[k], value_d))
00207 specific_group_params[KNOWN_GROUP_PARAMS[k]] = boost::lexical_cast<std::string>(value_i);
00208 else
00209 {
00210 bool value_b;
00211 if (nh_.getParam(group_names[i] + "/" + KNOWN_GROUP_PARAMS[k], value_b))
00212 specific_group_params[KNOWN_GROUP_PARAMS[k]] = boost::lexical_cast<std::string>(value_b);
00213 }
00214 }
00215 }
00216 }
00217 }
00218
00219
00220 if (!specific_group_params.empty())
00221 {
00222 planning_interface::PlannerConfigurationSettings pc;
00223 pc.name = group_names[i];
00224 pc.group = group_names[i];
00225 pc.config = specific_group_params;
00226 pconfig[pc.name] = pc;
00227 }
00228
00229
00230 XmlRpc::XmlRpcValue config_names;
00231 if (nh_.getParam(group_names[i] + "/planner_configs", config_names))
00232 {
00233 if (config_names.getType() == XmlRpc::XmlRpcValue::TypeArray)
00234 {
00235 for (int32_t j = 0; j < config_names.size() ; ++j)
00236 if (config_names[j].getType() == XmlRpc::XmlRpcValue::TypeString)
00237 {
00238 std::string planner_config = static_cast<std::string>(config_names[j]);
00239 XmlRpc::XmlRpcValue xml_config;
00240 if (nh_.getParam("planner_configs/" + planner_config, xml_config))
00241 {
00242 if (xml_config.getType() == XmlRpc::XmlRpcValue::TypeStruct)
00243 {
00244 planning_interface::PlannerConfigurationSettings pc;
00245 pc.name = group_names[i] + "[" + planner_config + "]";
00246 pc.group = group_names[i];
00247
00248 pc.config = specific_group_params;
00249
00250
00251 for (XmlRpc::XmlRpcValue::iterator it = xml_config.begin() ; it != xml_config.end() ; ++it)
00252 if (it->second.getType() == XmlRpc::XmlRpcValue::TypeString)
00253 pc.config[it->first] = static_cast<std::string>(it->second);
00254 else
00255 if (it->second.getType() == XmlRpc::XmlRpcValue::TypeDouble)
00256 pc.config[it->first] = boost::lexical_cast<std::string>(static_cast<double>(it->second));
00257 else
00258 if (it->second.getType() == XmlRpc::XmlRpcValue::TypeInt)
00259 pc.config[it->first] = boost::lexical_cast<std::string>(static_cast<int>(it->second));
00260 else
00261 if (it->second.getType() == XmlRpc::XmlRpcValue::TypeBoolean)
00262 pc.config[it->first] = boost::lexical_cast<std::string>(static_cast<bool>(it->second));
00263 pconfig[pc.name] = pc;
00264 }
00265 else
00266 ROS_ERROR("A planning configuration should be of type XmlRpc Struct type (for configuration '%s')", planner_config.c_str());
00267 }
00268 else
00269 ROS_ERROR("Could not find the planner configuration '%s' on the param server", planner_config.c_str());
00270 }
00271 else
00272 ROS_ERROR("Planner configuration names must be of type string (for group '%s')", group_names[i].c_str());
00273 }
00274 else
00275 ROS_ERROR("The planner_configs argument of a group configuration should be an array of strings (for group '%s')", group_names[i].c_str());
00276 }
00277 }
00278
00279 for(planning_interface::PlannerConfigurationMap::iterator it = pconfig.begin();
00280 it != pconfig.end(); ++it)
00281 {
00282 ROS_DEBUG_STREAM_NAMED("parameters","Parameters for configuration '"<< it->first << "'");
00283 for (std::map<std::string, std::string>::const_iterator config_it = it->second.config.begin() ;
00284 config_it != it->second.config.end() ; ++config_it)
00285 ROS_DEBUG_STREAM_NAMED("parameters"," - " << config_it->first << " = " << config_it->second);
00286 }
00287 setPlannerConfigurations(pconfig);
00288 }
00289
00290 void ompl_interface::OMPLInterface::printStatus()
00291 {
00292 ROS_INFO("OMPL ROS interface is running.");
00293 }