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/kinematics_plugin_loader/kinematics_plugin_loader.h>
00038 #include <moveit/rdf_loader/rdf_loader.h>
00039 #include <pluginlib/class_loader.h>
00040 #include <boost/thread/mutex.hpp>
00041 #include <sstream>
00042 #include <vector>
00043 #include <map>
00044 #include <ros/ros.h>
00045 #include <moveit/profiler/profiler.h>
00046 
00047 namespace kinematics_plugin_loader
00048 {
00049 
00050 class KinematicsPluginLoader::KinematicsLoaderImpl
00051 {
00052 public:
00053   KinematicsLoaderImpl(const std::string &robot_description,
00054                        const std::map<std::string, std::vector<std::string> > &possible_kinematics_solvers,
00055                        const std::map<std::string, std::vector<double> > &search_res,
00056                        const std::map<std::string, std::string> &ik_links) :
00057     robot_description_(robot_description),
00058     possible_kinematics_solvers_(possible_kinematics_solvers),
00059     search_res_(search_res),
00060     ik_links_(ik_links)
00061   {
00062     try
00063     {
00064       kinematics_loader_.reset(new pluginlib::ClassLoader<kinematics::KinematicsBase>("moveit_core", "kinematics::KinematicsBase"));
00065     }
00066     catch(pluginlib::PluginlibException& e)
00067     {
00068       ROS_ERROR("Unable to construct kinematics loader. Error: %s", e.what());
00069     }
00070   }
00071 
00072   boost::shared_ptr<kinematics::KinematicsBase> allocKinematicsSolver(const robot_model::JointModelGroup *jmg)
00073   {
00074     boost::shared_ptr<kinematics::KinematicsBase> result;
00075     if (!jmg)
00076     {
00077       ROS_ERROR("Specified group is NULL. Cannot allocate kinematics solver.");
00078       return result;
00079     }
00080 
00081     ROS_DEBUG("Received request to allocate kinematics solver for group '%s'", jmg->getName().c_str());
00082 
00083     if (kinematics_loader_ && jmg)
00084     {
00085       std::map<std::string, std::vector<std::string> >::const_iterator it = possible_kinematics_solvers_.find(jmg->getName());
00086       if (it != possible_kinematics_solvers_.end())
00087       {
00088         
00089         boost::mutex::scoped_lock slock(lock_);
00090 
00091         for (std::size_t i = 0 ; !result && i < it->second.size() ; ++i)
00092         {
00093           try
00094           {
00095             result.reset(kinematics_loader_->createUnmanagedInstance(it->second[i]));
00096             if (result)
00097             {
00098               const std::vector<const robot_model::LinkModel*> &links = jmg->getLinkModels();
00099               if (!links.empty())
00100               {
00101                 const std::string &base = links.front()->getParentJointModel()->getParentLinkModel() ?
00102                   links.front()->getParentJointModel()->getParentLinkModel()->getName() : jmg->getParentModel()->getModelFrame();
00103                 std::map<std::string, std::string>::const_iterator ik_it = ik_links_.find(jmg->getName());
00104                 const std::string &tip = ik_it != ik_links_.end() ? ik_it->second : links.back()->getName();
00105                 double search_res = search_res_.find(jmg->getName())->second[i]; 
00106                 if (!result->initialize(robot_description_, jmg->getName(), base, tip, search_res))
00107                 {
00108                   ROS_ERROR("Kinematics solver of type '%s' could not be initialized for group '%s'", it->second[i].c_str(), jmg->getName().c_str());
00109                   result.reset();
00110                 }
00111                 else
00112         {
00113           result->setDefaultTimeout(jmg->getDefaultIKTimeout());
00114                   ROS_DEBUG("Successfully allocated and initialized a kinematics solver of type '%s' with search resolution %lf for group '%s' at address %p",
00115                             it->second[i].c_str(), search_res, jmg->getName().c_str(), result.get());
00116         }
00117               }
00118               else
00119                 ROS_ERROR("No links specified for group '%s'", jmg->getName().c_str());
00120             }
00121           }
00122           catch (pluginlib::PluginlibException& e)
00123           {
00124             ROS_ERROR("The kinematics plugin (%s) failed to load. Error: %s", it->first.c_str(), e.what());
00125           }
00126         }
00127       }
00128       else
00129         ROS_DEBUG("No kinematics solver available for this group");
00130     }
00131 
00132     if (!result)
00133     {
00134       ROS_DEBUG("No usable kinematics solver was found for this group.");
00135       ROS_DEBUG("Did you load kinematics.yaml into your node's namespace?");
00136     }
00137     return result;
00138   }
00139 
00140   boost::shared_ptr<kinematics::KinematicsBase> allocKinematicsSolverWithCache(const robot_model::JointModelGroup *jmg)
00141   {
00142     {
00143       boost::mutex::scoped_lock slock(lock_);
00144       const std::vector<boost::shared_ptr<kinematics::KinematicsBase> > &vi = instances_[jmg];
00145       for (std::size_t i = 0 ;  i < vi.size() ; ++i)
00146         if (vi[i].unique())
00147         {
00148           ROS_DEBUG("Reusing cached kinematics solver for group '%s'", jmg->getName().c_str());
00149           return vi[i]; 
00150         }
00151     }
00152 
00153     boost::shared_ptr<kinematics::KinematicsBase> res = allocKinematicsSolver(jmg);
00154 
00155     {
00156       boost::mutex::scoped_lock slock(lock_);
00157       instances_[jmg].push_back(res);
00158       return res;
00159     }
00160   }
00161 
00162   void status() const
00163   {
00164     for (std::map<std::string, std::vector<std::string> >::const_iterator it = possible_kinematics_solvers_.begin() ; it != possible_kinematics_solvers_.end() ; ++it)
00165       for (std::size_t i = 0 ; i < it->second.size() ; ++i)
00166         ROS_INFO("Solver for group '%s': '%s' (search resolution = %lf)", it->first.c_str(), it->second[i].c_str(), search_res_.at(it->first)[i]);
00167   }
00168 
00169 private:
00170 
00171   std::string                                                            robot_description_;
00172   std::map<std::string, std::vector<std::string> >                       possible_kinematics_solvers_;
00173   std::map<std::string, std::vector<double> >                            search_res_;
00174   std::map<std::string, std::string>                                     ik_links_;
00175   boost::shared_ptr<pluginlib::ClassLoader<kinematics::KinematicsBase> > kinematics_loader_;
00176   std::map<const robot_model::JointModelGroup*,
00177            std::vector<boost::shared_ptr<kinematics::KinematicsBase> > > instances_;
00178   boost::mutex                                                           lock_;
00179 };
00180 
00181 }
00182 
00183 void kinematics_plugin_loader::KinematicsPluginLoader::status() const
00184 {
00185   if (loader_)
00186     loader_->status();
00187   else
00188     ROS_INFO("Loader function was never required");
00189 }
00190 
00191 robot_model::SolverAllocatorFn kinematics_plugin_loader::KinematicsPluginLoader::getLoaderFunction()
00192 {
00193   moveit::Profiler::ScopedStart prof_start;
00194   moveit::Profiler::ScopedBlock prof_block("KinematicsPluginLoader::getLoaderFunction");
00195 
00196   if (loader_)
00197     return boost::bind(&KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolverWithCache, loader_.get(), _1);
00198 
00199   rdf_loader::RDFLoader rml(robot_description_);
00200   robot_description_ = rml.getRobotDescription();
00201   return getLoaderFunction(rml.getSRDF());
00202 }
00203 
00204 robot_model::SolverAllocatorFn kinematics_plugin_loader::KinematicsPluginLoader::getLoaderFunction(const boost::shared_ptr<srdf::Model> &srdf_model)
00205 {
00206   moveit::Profiler::ScopedStart prof_start;
00207   moveit::Profiler::ScopedBlock prof_block("KinematicsPluginLoader::getLoaderFunction(SRDF)");
00208 
00209   if (!loader_)
00210   {
00211     ROS_DEBUG("Configuring kinematics solvers");
00212     groups_.clear();
00213 
00214     std::map<std::string, std::vector<std::string> > possible_kinematics_solvers;
00215     std::map<std::string, std::vector<double> > search_res;
00216     std::map<std::string, std::string> ik_links;
00217 
00218     if (srdf_model)
00219     {
00220       const std::vector<srdf::Model::Group> &known_groups = srdf_model->getGroups();
00221       if (default_search_resolution_ <= std::numeric_limits<double>::epsilon())
00222         default_search_resolution_ = kinematics::KinematicsBase::DEFAULT_SEARCH_DISCRETIZATION;
00223 
00224       if (default_solver_plugin_.empty())
00225       {
00226         ROS_DEBUG("Loading settings for kinematics solvers from the ROS param server ...");
00227 
00228         
00229         ros::NodeHandle nh("~");
00230 
00231         
00232         for (std::size_t i = 0 ; i < known_groups.size() ; ++i)
00233         {
00234           ROS_DEBUG(" - Looking for param %s ", (known_groups[i].name_ + "/kinematics_solver").c_str());
00235           std::string ksolver_param_name;
00236           if (nh.searchParam(known_groups[i].name_ + "/kinematics_solver", ksolver_param_name))
00237           {
00238             ROS_DEBUG("Found param %s ", ksolver_param_name.c_str());
00239             std::string ksolver;
00240             if (nh.getParam(ksolver_param_name, ksolver))
00241             {
00242               std::stringstream ss(ksolver);
00243               bool first = true;
00244               while (ss.good() && !ss.eof())
00245               {
00246                 if (first)
00247                 {
00248                   first = false;
00249                   groups_.push_back(known_groups[i].name_);
00250                 }
00251                 std::string solver; ss >> solver >> std::ws;
00252                 possible_kinematics_solvers[known_groups[i].name_].push_back(solver);
00253                 ROS_DEBUG("Using kinematics solver '%s' for group '%s'.", solver.c_str(), known_groups[i].name_.c_str());
00254               }
00255             }
00256           }
00257 
00258           std::string ksolver_timeout_param_name;
00259           if (nh.searchParam(known_groups[i].name_ + "/kinematics_solver_timeout", ksolver_timeout_param_name))
00260           {
00261             double ksolver_timeout;
00262             if (nh.getParam(ksolver_timeout_param_name, ksolver_timeout))
00263               ik_timeout_[known_groups[i].name_] = ksolver_timeout;
00264             else
00265             {
00266               int ksolver_timeout_i;
00267               if (nh.getParam(ksolver_timeout_param_name, ksolver_timeout_i))
00268                 ik_timeout_[known_groups[i].name_] = ksolver_timeout_i;
00269             }
00270           }
00271 
00272           std::string ksolver_attempts_param_name;
00273           if (nh.searchParam(known_groups[i].name_ + "/kinematics_solver_attempts", ksolver_attempts_param_name))
00274           {
00275             int ksolver_attempts;
00276             if (nh.getParam(ksolver_attempts_param_name, ksolver_attempts))
00277               ik_attempts_[known_groups[i].name_] = ksolver_attempts;
00278           }
00279 
00280           std::string ksolver_res_param_name;
00281           if (nh.searchParam(known_groups[i].name_ + "/kinematics_solver_search_resolution", ksolver_res_param_name))
00282           {
00283             std::string ksolver_res;
00284             if (nh.getParam(ksolver_res_param_name, ksolver_res))
00285             {
00286               std::stringstream ss(ksolver_res);
00287               while (ss.good() && !ss.eof())
00288               {
00289                 double res; ss >> res >> std::ws;
00290                 search_res[known_groups[i].name_].push_back(res);
00291               }
00292             }
00293             else
00294             { 
00295               double res;
00296               if (nh.getParam(ksolver_res_param_name, res))
00297                 search_res[known_groups[i].name_].push_back(res);
00298               else
00299               {
00300                 int res_i;
00301                 if (nh.getParam(ksolver_res_param_name, res_i))
00302                   search_res[known_groups[i].name_].push_back(res_i);
00303               }
00304             }
00305           }
00306 
00307           std::string ksolver_ik_link_param_name;
00308           if (nh.searchParam(known_groups[i].name_ + "/kinematics_solver_ik_link", ksolver_ik_link_param_name))
00309           {
00310             std::string ksolver_ik_link;
00311             if (nh.getParam(ksolver_ik_link_param_name, ksolver_ik_link))
00312               ik_links[known_groups[i].name_] = ksolver_ik_link;
00313           }
00314 
00315           
00316           while (search_res[known_groups[i].name_].size() < possible_kinematics_solvers[known_groups[i].name_].size())
00317             search_res[known_groups[i].name_].push_back(default_search_resolution_);
00318         }
00319       }
00320       else
00321       {
00322         ROS_DEBUG("Using specified default settings for kinematics solvers ...");
00323         for (std::size_t i = 0 ; i < known_groups.size() ; ++i)
00324         {
00325           possible_kinematics_solvers[known_groups[i].name_].resize(1, default_solver_plugin_);
00326           search_res[known_groups[i].name_].resize(1, default_search_resolution_);
00327           ik_timeout_[known_groups[i].name_] = default_solver_timeout_;
00328           ik_attempts_[known_groups[i].name_] = default_ik_attempts_;
00329           groups_.push_back(known_groups[i].name_);
00330         }
00331       }
00332     }
00333 
00334     loader_.reset(new KinematicsLoaderImpl(robot_description_, possible_kinematics_solvers, search_res, ik_links));
00335   }
00336 
00337   return boost::bind(&KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolverWithCache, loader_.get(), _1);
00338 }