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
00037 #include "ompl_ros_interface/ompl_ros_planner_config.h"
00038 #include <boost/algorithm/string.hpp>
00039 #include <sstream>
00040
00041 const std::string& ompl_ros_interface::PlannerConfig::getName(void)
00042 {
00043 return config_;
00044 }
00045
00046 bool ompl_ros_interface::PlannerConfig::hasParam(const std::string ¶m)
00047 {
00048 return nh_.hasParam(description_ + "/planner_configs/" + config_ + "/" + param);
00049 }
00050
00051 std::string ompl_ros_interface::PlannerConfig::getParamString(const std::string ¶m, const std::string& def)
00052 {
00053 std::string value;
00054 nh_.param(description_ + "/planner_configs/" + config_ + "/" + param, value, def);
00055 boost::trim(value);
00056 return value;
00057 }
00058
00059 double ompl_ros_interface::PlannerConfig::getParamDouble(const std::string ¶m, double def)
00060 {
00061 double value;
00062 nh_.param(description_ + "/planner_configs/" + config_ + "/" + param, value, def);
00063 return value;
00064 }
00065
00066 int ompl_ros_interface::PlannerConfig::getParamInt(const std::string ¶m, int def)
00067 {
00068 int value;
00069 nh_.param(description_ + "/planner_configs/" + config_ + "/" + param, value, def);
00070 return value;
00071 }
00072
00073 void ompl_ros_interface::PlannerConfigMap::loadPlannerConfigs() {
00074
00075 ros::NodeHandle nh("~");
00076
00077
00078 std::string group_list;
00079 nh.param(description_ + "/group_list", group_list, std::string(""));
00080 std::stringstream group_list_stream(group_list);
00081 std::map<std::string, bool> plan_group_map;
00082 while (group_list_stream.good() && !group_list_stream.eof())
00083 {
00084 std::string g;
00085 group_list_stream >> g;
00086 if(g.size() == 0) continue;
00087 planning_group_names_.push_back(g);
00088 }
00089
00090
00091 XmlRpc::XmlRpcValue all_groups;
00092
00093 if(!nh.hasParam(description_+"/groups")) {
00094 ROS_WARN("No groups for planning specified");
00095 return;
00096 }
00097
00098 nh.getParam(description_+"/groups", all_groups);
00099
00100 if(all_groups.getType() != XmlRpc::XmlRpcValue::TypeArray) {
00101 ROS_WARN("Groups is not an array");
00102 return;
00103 }
00104
00105 if(all_groups.size() == 0) {
00106 ROS_WARN("No groups in groups");
00107 return;
00108 }
00109
00110 for(int i = 0; i < all_groups.size(); i++) {
00111 if(!all_groups[i].hasMember("name")) {
00112 ROS_WARN("All groups must have a name");
00113 continue;
00114 }
00115 std::string gname = all_groups[i]["name"];
00116 std::vector<std::string> configs;
00117
00118 std::string plan_list = std::string(all_groups[i]["planner_configs"]);
00119 std::stringstream planner_name_stream(plan_list);
00120 while(planner_name_stream.good() && !planner_name_stream.eof()){
00121 std::string pname;
00122 planner_name_stream >> pname;
00123 if(pname.size() == 0) continue;
00124 configs.push_back(pname);
00125 }
00126 group_to_planner_string_config_map_[gname] = configs;
00127 }
00128 }
00129
00130 std::vector< boost::shared_ptr<ompl_ros_interface::PlannerConfig> > ompl_ros_interface::PlannerConfigMap::getGroupPlannersConfig(const std::string &group) const
00131 {
00132 std::vector< boost::shared_ptr<ompl_ros_interface::PlannerConfig> > ret;
00133 if(group_to_planner_string_config_map_.find(group) != group_to_planner_string_config_map_.end()) {
00134
00135 for(std::vector<std::string>::const_iterator it = group_to_planner_string_config_map_.find(group)->second.begin();
00136 it != group_to_planner_string_config_map_.find(group)->second.end();
00137 it++) {
00138 ret.push_back(boost::shared_ptr<PlannerConfig>(new ompl_ros_interface::PlannerConfig(description_, (*it))));
00139 }
00140 }
00141 return ret;
00142 }