stomp_optimization_task.cpp
Go to the documentation of this file.
00001 
00026 #include <stdexcept>
00027 #include "stomp_moveit/stomp_optimization_task.h"
00028 
00029 using PluginConfigs = std::vector< std::pair<std::string,XmlRpc::XmlRpcValue> >;
00030 
00031 static const std::string COST_FUNCTIONS_FIELD = "cost_functions";
00032 static const std::string NOISY_FILTERS_FIELD = "noisy_filters";
00033 static const std::string UPDATE_FILTERS_FIELD = "update_filters";
00034 static const std::string NOISE_GENERATOR_FIELD = "noise_generator";
00035 
00043 bool parsePluginConfigs(XmlRpc::XmlRpcValue config,
00044                       std::string param_name,
00045                       PluginConfigs& plugins)
00046 {
00047   if(config.hasMember(param_name) && (config[param_name].getType() == XmlRpc::XmlRpcValue::TypeArray))
00048   {
00049     XmlRpc::XmlRpcValue& plugin_list = config[param_name];
00050     std::string class_name;
00051 
00052     // look for the 'class' entry
00053     for(auto i = 0u ; i < plugin_list.size(); i++)
00054     {
00055       XmlRpc::XmlRpcValue& plugin_config = plugin_list[i];
00056       if(plugin_config.hasMember("class") && (plugin_config["class"].getType() == XmlRpc::XmlRpcValue::TypeString))
00057       {
00058         class_name = static_cast<std::string>(plugin_config["class"]);
00059         plugins.push_back(std::make_pair(class_name,plugin_config));
00060       }
00061       else
00062       {
00063         ROS_ERROR("Element in the '%s' array parameter did not contain a 'class' entry",param_name.c_str());
00064         return false;
00065       }
00066     }
00067   }
00068   else
00069   {
00070     ROS_WARN("Plugin under entry '%s' was not found in ros parameter.",param_name.c_str());
00071     ROS_DEBUG("Failed to find plugin under entry '%s' in ros parameter %s",param_name.c_str(),config.toXml().c_str());
00072     return false;
00073   }
00074 
00075   return !plugins.empty();
00076 }
00077 
00089 struct PluginData
00090 {
00091   XmlRpc::XmlRpcValue config;
00092   std::string param_key;
00093   bool critical;
00094   bool single_instance;
00095   std::string plugin_desc;
00096   moveit::core::RobotModelConstPtr robot_model;
00097   std::string group_name;
00098 };
00099 
00100 template <typename PluginPtr,typename ClassLoaderPtr>
00101 bool loadPlugins(const PluginData plugin_data,
00102                  ClassLoaderPtr class_loader ,std::vector<PluginPtr>& plugin_array)
00103 {
00104   PluginConfigs plugins;
00105 
00106 
00107   if(parsePluginConfigs(plugin_data.config,plugin_data.param_key,plugins))
00108   {
00109     for(auto& entry: plugins)
00110     {
00111       // instantiating
00112       PluginPtr plugin;
00113       try
00114       {
00115         plugin = class_loader->createInstance(entry.first);
00116       }
00117       catch(pluginlib::PluginlibException& ex)
00118       {
00119         if(plugin_data.critical)
00120         {
00121           ROS_ERROR("%s plugin '%s' could not be created",plugin_data.plugin_desc.c_str() ,entry.first.c_str());
00122           return false;
00123         }
00124         else
00125         {
00126           ROS_WARN("%s plugin '%s' could not be created",plugin_data.plugin_desc.c_str() ,entry.first.c_str());
00127           continue;
00128         }
00129       }
00130 
00131       // initializing
00132       if(plugin->initialize(plugin_data.robot_model,plugin_data.group_name,entry.second))
00133       {
00134         plugin_array.push_back(plugin);
00135         ROS_INFO_STREAM("Stomp Optimization Task loaded "<< plugin_data.plugin_desc <<" '"<<plugin->getName()<<"' plugin");
00136       }
00137       else
00138       {
00139         if(plugin_data.critical)
00140         {
00141           ROS_ERROR("%s plugin '%s' failed to initialize",plugin_data.plugin_desc.c_str(), entry.first.c_str());
00142           return false;
00143         }
00144         else
00145         {
00146           ROS_WARN("%s plugin '%s' failed to initialize",plugin_data.plugin_desc.c_str(), entry.first.c_str());
00147           continue;
00148         }
00149       }
00150 
00151       if(plugin_data.single_instance)
00152       {
00153         break;
00154       }
00155     }
00156 
00157     std::stringstream ss;
00158     ss<<"[";
00159     auto arrayToString = [&ss](PluginConfigs::value_type& p)
00160     {
00161       ss<<p.first<<" ";
00162     };
00163 
00164     std::for_each(plugins.begin(),plugins.end(),arrayToString);
00165     ss<<"]";
00166 
00167     ROS_DEBUG("Loaded %s plugins: %s", plugin_data.plugin_desc.c_str(), ss.str().c_str());
00168   }
00169   else
00170   {
00171     return false;
00172   }
00173 
00174   return true;
00175 }
00176 
00177 namespace stomp_moveit
00178 {
00179 
00180 StompOptimizationTask::StompOptimizationTask(
00181     moveit::core::RobotModelConstPtr robot_model_ptr,
00182     std::string group_name,
00183     const XmlRpc::XmlRpcValue& config):
00184         robot_model_ptr_(robot_model_ptr),
00185         group_name_(group_name)
00186 {
00187   // initializing plugin loaders
00188   cost_function_loader_.reset(new CostFunctionLoader("stomp_moveit", "stomp_moveit::cost_functions::StompCostFunction"));
00189   noise_generator_loader_.reset(new NoiseGeneratorLoader("stomp_moveit","stomp_moveit::noise_generators::StompNoiseGenerator"));
00190   noisy_filter_loader_.reset(new NoisyFilterLoader("stomp_moveit", "stomp_moveit::noisy_filters::StompNoisyFilter"));
00191   update_filter_loader_.reset(new UpdateFilterLoader("stomp_moveit", "stomp_moveit::update_filters::StompUpdateFilter"));
00192 
00193   // preparing plugin init data
00194   PluginData plugin_data;
00195   plugin_data.config = config;
00196   plugin_data.group_name = group_name_;
00197   plugin_data.robot_model = robot_model_ptr_;
00198 
00199   // loading cost function plugins
00200   plugin_data.param_key = COST_FUNCTIONS_FIELD;
00201   plugin_data.plugin_desc = "CostFunction";
00202   plugin_data.critical = true;
00203   plugin_data.single_instance = false;
00204   if(!loadPlugins(plugin_data,cost_function_loader_,cost_functions_))
00205   {
00206     ROS_ERROR("StompOptimizationTask/%s failed to load '%s' plugins from yaml",group_name.c_str(),COST_FUNCTIONS_FIELD.c_str());
00207     throw std::logic_error("plugin not found");
00208   }
00209 
00210   // loading noise generators
00211   plugin_data.param_key = NOISE_GENERATOR_FIELD;
00212   plugin_data.plugin_desc = "NoiseGenerator";
00213   plugin_data.critical = true;
00214   plugin_data.single_instance = true;
00215   if(!loadPlugins(plugin_data, noise_generator_loader_,noise_generators_))
00216   {
00217     ROS_ERROR("StompOptimizationTask/%s failed to load '%s' plugins from yaml",group_name.c_str(),
00218              NOISE_GENERATOR_FIELD.c_str());
00219     throw std::logic_error("plugin not found");
00220   }
00221 
00222   // loading noisy filter plugins
00223   plugin_data.param_key = NOISY_FILTERS_FIELD;
00224   plugin_data.plugin_desc = "NoisyFilter";
00225   plugin_data.critical = false;
00226   plugin_data.single_instance = false;
00227   if(!loadPlugins(plugin_data,noisy_filter_loader_,noisy_filters_))
00228   {
00229     ROS_WARN("StompOptimizationTask/%s failed to load '%s' plugins from yaml",group_name.c_str(),NOISY_FILTERS_FIELD.c_str());
00230   }
00231 
00232   // loading filter plugins
00233   plugin_data.param_key = UPDATE_FILTERS_FIELD;
00234   plugin_data.plugin_desc = "UpdateFilter";
00235   plugin_data.critical = false;
00236   plugin_data.single_instance = false;
00237   if(!loadPlugins(plugin_data,update_filter_loader_,update_filters_))
00238   {
00239     ROS_WARN("StompOptimizationTask/%s failed to load '%s' plugins from yaml",group_name.c_str(),UPDATE_FILTERS_FIELD.c_str());
00240   }
00241 }
00242 
00243 StompOptimizationTask::~StompOptimizationTask()
00244 {
00245   // TODO Auto-generated destructor stub
00246 }
00247 
00248 bool StompOptimizationTask::generateNoisyParameters(const Eigen::MatrixXd& parameters,
00249                                      std::size_t start_timestep,
00250                                      std::size_t num_timesteps,
00251                                      int iteration_number,
00252                                      int rollout_number,
00253                                      Eigen::MatrixXd& parameters_noise,
00254                                      Eigen::MatrixXd& noise)
00255 {
00256   return noise_generators_.back()->generateNoise(parameters,start_timestep,num_timesteps,iteration_number,rollout_number,
00257                                                  parameters_noise,noise);
00258 }
00259 
00260 bool StompOptimizationTask::computeNoisyCosts(const Eigen::MatrixXd& parameters,
00261                                          std::size_t start_timestep,
00262                                          std::size_t num_timesteps,
00263                                          int iteration_number,
00264                                          int rollout_number,
00265                                          Eigen::VectorXd& costs,
00266                                          bool& validity)
00267 {
00268   Eigen::MatrixXd cost_matrix = Eigen::MatrixXd::Zero(num_timesteps,cost_functions_.size());
00269   Eigen::VectorXd state_costs = Eigen::VectorXd::Zero(num_timesteps);
00270   validity = true;
00271   for(auto i = 0u; i < cost_functions_.size(); i++ )
00272   {
00273     bool valid;
00274     auto cf = cost_functions_[i];
00275 
00276     if(!cf->computeCosts(parameters,start_timestep,num_timesteps,iteration_number,rollout_number,state_costs,valid))
00277     {
00278       return false;
00279     }
00280 
00281     validity &= valid;
00282 
00283     cost_matrix.col(i) = state_costs * cf->getWeight();
00284   }
00285   costs = cost_matrix.rowwise().sum();
00286   return true;
00287 }
00288 
00289 bool StompOptimizationTask::computeCosts(const Eigen::MatrixXd& parameters,
00290                                          std::size_t start_timestep,
00291                                          std::size_t num_timesteps,
00292                                          int iteration_number,
00293                                          Eigen::VectorXd& costs,
00294                                          bool& validity)
00295 {
00296   Eigen::MatrixXd cost_matrix = Eigen::MatrixXd::Zero(num_timesteps,cost_functions_.size());
00297   Eigen::VectorXd state_costs = Eigen::VectorXd::Zero(num_timesteps);
00298   validity = true;
00299   for(auto i = 0u; i < cost_functions_.size(); i++ )
00300   {
00301     bool valid;
00302     auto cf = cost_functions_[i];
00303 
00304     if(!cf->computeCosts(parameters,start_timestep,num_timesteps,iteration_number,cf->getOptimizedIndex(),state_costs,valid))
00305     {
00306       return false;
00307     }
00308 
00309     validity &= valid;
00310 
00311     cost_matrix.col(i) = state_costs * cf->getWeight();
00312   }
00313   costs = cost_matrix.rowwise().sum();
00314   return true;
00315 }
00316 
00317 bool StompOptimizationTask::setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00318                                         const moveit_msgs::MotionPlanRequest &req,
00319                                         const stomp_core::StompConfiguration &config,
00320                                         moveit_msgs::MoveItErrorCodes& error_code)
00321 {
00322   for(auto p: noise_generators_)
00323   {
00324     if(!p->setMotionPlanRequest(planning_scene,req,config,error_code))
00325     {
00326       ROS_ERROR("Failed to set Plan Request on noise generator %s",p->getName().c_str());
00327       return false;
00328     }
00329   }
00330 
00331   for(auto p : cost_functions_)
00332   {
00333     if(!p->setMotionPlanRequest(planning_scene,req,config,error_code))
00334     {
00335       ROS_ERROR("Failed to set Plan Request on cost function %s",p->getName().c_str());
00336       return false;
00337     }
00338   }
00339 
00340   for(auto p: noisy_filters_)
00341   {
00342     if(!p->setMotionPlanRequest(planning_scene,req,config,error_code))
00343     {
00344       ROS_ERROR("Failed to set Plan Request on noisy filter %s",p->getName().c_str());
00345       return false;
00346     }
00347   }
00348 
00349   for(auto p: update_filters_)
00350   {
00351     if(!p->setMotionPlanRequest(planning_scene,req,config,error_code))
00352     {
00353       ROS_ERROR("Failed to set Plan Request on update filter %s",p->getName().c_str());
00354       return false;
00355     }
00356   }
00357 
00358   return true;
00359 }
00360 
00361 bool StompOptimizationTask::filterNoisyParameters(std::size_t start_timestep,
00362                                                   std::size_t num_timesteps,
00363                                                   int iteration_number,
00364                                                   int rollout_number,
00365                                                   Eigen::MatrixXd& parameters,bool& filtered)
00366 {
00367   filtered = false;
00368   bool temp;
00369   for(auto& f: noisy_filters_)
00370   {
00371     if(f->filter(start_timestep,num_timesteps,iteration_number,rollout_number,parameters,temp))
00372     {
00373       filtered |= temp;
00374     }
00375     else
00376     {
00377       return false;
00378     }
00379   }
00380   return true;
00381 }
00382 
00383 bool StompOptimizationTask::filterParameterUpdates(std::size_t start_timestep,
00384                                              std::size_t num_timesteps,
00385                                              int iteration_number,
00386                                              const Eigen::MatrixXd& parameters,
00387                                              Eigen::MatrixXd& updates)
00388 {
00389   bool filtered = false;
00390   bool temp;
00391   for(auto& f: update_filters_)
00392   {
00393     if(f->filter(start_timestep,num_timesteps,iteration_number,parameters,updates,temp))
00394     {
00395       filtered |= temp;
00396     }
00397     else
00398     {
00399       return false;
00400     }
00401   }
00402   return true;
00403 }
00404 
00405 void StompOptimizationTask::postIteration(std::size_t start_timestep,
00406                                 std::size_t num_timesteps,int iteration_number,double cost,const Eigen::MatrixXd& parameters)
00407 {
00408   for(auto p : noise_generators_)
00409   {
00410     p->postIteration(start_timestep,num_timesteps,iteration_number,cost,parameters);
00411   }
00412 
00413   for(auto p : cost_functions_)
00414   {
00415     p->postIteration(start_timestep,num_timesteps,iteration_number,cost,parameters);
00416   }
00417 
00418   for(auto p: noisy_filters_)
00419   {
00420     p->postIteration(start_timestep,num_timesteps,iteration_number,cost,parameters);
00421   }
00422 
00423   for(auto p: update_filters_)
00424   {
00425     p->postIteration(start_timestep,num_timesteps,iteration_number,cost,parameters);
00426   }
00427 }
00428 
00429 void StompOptimizationTask::done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters)
00430 {
00431   for(auto p : noise_generators_)
00432   {
00433     p->done(success,total_iterations,final_cost,parameters);
00434   }
00435 
00436 
00437   for(auto p : cost_functions_)
00438   {
00439     p->done(success,total_iterations,final_cost,parameters);
00440   }
00441 
00442   for(auto p: noisy_filters_)
00443   {
00444     p->done(success,total_iterations,final_cost,parameters);
00445   }
00446 
00447   for(auto p: update_filters_)
00448   {
00449     p->done(success,total_iterations,final_cost,parameters);
00450   }
00451 }
00452 
00453 } /* namespace stomp_moveit */


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01