robot_model_loader.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan, E. Gil Jones */
00036 
00037 #include <moveit/robot_model_loader/robot_model_loader.h>
00038 #include <moveit/profiler/profiler.h>
00039 #include <ros/ros.h>
00040 
00041 robot_model_loader::RobotModelLoader::RobotModelLoader(const std::string &robot_description, bool load_kinematics_solvers)
00042 {
00043   Options opt(robot_description);
00044   opt.load_kinematics_solvers_ = load_kinematics_solvers;
00045   configure(opt);
00046 }
00047 
00048 robot_model_loader::RobotModelLoader::RobotModelLoader(const Options &opt)
00049 {
00050   configure(opt);
00051 }
00052 
00053 robot_model_loader::RobotModelLoader::~RobotModelLoader()
00054 {
00055   model_.reset();
00056   rdf_loader_.reset();
00057   kinematics_loader_.reset();
00058 }
00059 
00060 namespace
00061 {
00062 
00063 bool canSpecifyPosition(const robot_model::JointModel *jmodel, const unsigned int index)
00064 {
00065   bool ok = false;
00066   if (jmodel->getType() == robot_model::JointModel::PLANAR && index == 2)
00067     ROS_ERROR("Cannot specify position limits for orientation of planar joint '%s'", jmodel->getName().c_str());
00068   else
00069   if (jmodel->getType() == robot_model::JointModel::FLOATING && index > 2)
00070     ROS_ERROR("Cannot specify position limits for orientation of floating joint '%s'", jmodel->getName().c_str());
00071   else
00072   if (jmodel->getType() == robot_model::JointModel::REVOLUTE &&
00073       static_cast<const robot_model::RevoluteJointModel*>(jmodel)->isContinuous())
00074     ROS_ERROR("Cannot specify position limits for continuous joint '%s'", jmodel->getName().c_str());
00075   else
00076     ok = true;
00077   return ok;
00078 }
00079 }
00080 
00081 void robot_model_loader::RobotModelLoader::configure(const Options &opt)
00082 {
00083   moveit::Profiler::ScopedStart prof_start;
00084   moveit::Profiler::ScopedBlock prof_block("RobotModelLoader::configure");
00085 
00086   ros::WallTime start = ros::WallTime::now();
00087   if (opt.urdf_doc_ && opt.srdf_doc_)
00088     rdf_loader_.reset(new rdf_loader::RDFLoader(opt.urdf_doc_, opt.srdf_doc_));
00089   else
00090     if (!opt.urdf_string_.empty() && !opt.srdf_string_.empty())
00091       rdf_loader_.reset(new rdf_loader::RDFLoader(opt.urdf_string_, opt.srdf_string_));
00092     else
00093       rdf_loader_.reset(new rdf_loader::RDFLoader(opt.robot_description_));
00094   if (rdf_loader_->getURDF())
00095   {
00096     const boost::shared_ptr<srdf::Model> &srdf = rdf_loader_->getSRDF() ? rdf_loader_->getSRDF() : boost::shared_ptr<srdf::Model>(new srdf::Model());
00097     model_.reset(new robot_model::RobotModel(rdf_loader_->getURDF(), srdf));
00098   }
00099 
00100   if (model_ && !rdf_loader_->getRobotDescription().empty())
00101   {
00102     moveit::Profiler::ScopedBlock prof_block2("RobotModelLoader::configure joint limits");
00103 
00104     // if there are additional joint limits specified in some .yaml file, read those in
00105     ros::NodeHandle nh("~");
00106     std::map<std::string, std::vector<moveit_msgs::JointLimits> > individual_joint_limits_map;
00107 
00108     for (unsigned int i = 0; i < model_->getJointModels().size() ; ++i)
00109     {
00110       robot_model::JointModel *jmodel = model_->getJointModels()[i];
00111       std::vector<moveit_msgs::JointLimits> jlim = jmodel->getVariableLimits();
00112       for(unsigned int j = 0; j < jlim.size(); ++j)
00113       {
00114         std::string prefix = rdf_loader_->getRobotDescription() + "_planning/joint_limits/" + jlim[j].joint_name + "/";
00115 
00116         double max_position;
00117         if (nh.getParam(prefix + "max_position", max_position))
00118         {
00119           if (canSpecifyPosition(jmodel, j))
00120           {
00121             jlim[j].has_position_limits = true;
00122             jlim[j].max_position = max_position;
00123 
00124             // also update the model
00125             std::pair<double, double> bounds;
00126             if (jmodel->getVariableBounds(jlim[j].joint_name, bounds))
00127             {
00128               bounds.second = max_position;
00129               jmodel->setVariableBounds(jlim[j].joint_name, bounds);
00130             }
00131           }
00132         }
00133         double min_position;
00134         if (nh.getParam(prefix + "min_position", min_position))
00135         {
00136           if (canSpecifyPosition(jmodel, j))
00137           {
00138             jlim[j].has_position_limits = true;
00139             jlim[j].min_position = min_position;
00140 
00141             // also update the model
00142             std::pair<double, double> bounds;
00143             if (jmodel->getVariableBounds(jlim[j].joint_name, bounds))
00144             {
00145               bounds.first = min_position;
00146               jmodel->setVariableBounds(jlim[j].joint_name, bounds);
00147             }
00148           }
00149         }
00150         double max_velocity;
00151         if (nh.getParam(prefix + "max_velocity", max_velocity))
00152         {
00153           jlim[j].has_velocity_limits = true;
00154           jlim[j].max_velocity = max_velocity;
00155         }
00156         bool has_vel_limits;
00157         if (nh.getParam(prefix + "has_velocity_limits", has_vel_limits))
00158           jlim[j].has_velocity_limits = has_vel_limits;
00159 
00160         double max_acc;
00161         if (nh.getParam(prefix + "max_acceleration", max_acc))
00162         {
00163           jlim[j].has_acceleration_limits = true;
00164           jlim[j].max_acceleration = max_acc;
00165         }
00166         bool has_acc_limits;
00167         if (nh.getParam(prefix + "has_acceleration_limits", has_acc_limits))
00168           jlim[j].has_acceleration_limits = has_acc_limits;
00169       }
00170       jmodel->setVariableLimits(jlim);
00171       individual_joint_limits_map[jmodel->getName()] = jlim;
00172     }
00173     const std::map<std::string, robot_model::JointModelGroup*> &jmgm = model_->getJointModelGroupMap();
00174     for (std::map<std::string, robot_model::JointModelGroup*>::const_iterator it = jmgm.begin() ; it != jmgm.end() ; ++it)
00175     {
00176       std::vector<moveit_msgs::JointLimits> group_joint_limits;
00177       for(unsigned int i = 0; i < it->second->getJointModelNames().size(); i++)
00178       {
00179         group_joint_limits.insert(group_joint_limits.end(),
00180                                   individual_joint_limits_map[it->second->getJointModelNames()[i]].begin(),
00181                                   individual_joint_limits_map[it->second->getJointModelNames()[i]].end());
00182       }
00183       it->second->setVariableLimits(group_joint_limits);
00184     }
00185   }
00186 
00187   if (model_ && opt.load_kinematics_solvers_)
00188     loadKinematicsSolvers();
00189 
00190   ROS_DEBUG_STREAM("Loaded kinematic model in " << (ros::WallTime::now() - start).toSec() << " seconds");
00191 }
00192 
00193 void robot_model_loader::RobotModelLoader::loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr &kloader)
00194 {
00195   moveit::Profiler::ScopedStart prof_start;
00196   moveit::Profiler::ScopedBlock prof_block("RobotModelLoader::loadKinematicsSolvers");
00197 
00198   if (rdf_loader_ && model_)
00199   {
00200     // load the kinematics solvers
00201     if (kloader)
00202       kinematics_loader_ = kloader;
00203     else
00204       kinematics_loader_.reset(new kinematics_plugin_loader::KinematicsPluginLoader(rdf_loader_->getRobotDescription()));
00205     robot_model::SolverAllocatorFn kinematics_allocator = kinematics_loader_->getLoaderFunction(rdf_loader_->getSRDF());
00206     const std::vector<std::string> &groups = kinematics_loader_->getKnownGroups();
00207     std::stringstream ss;
00208     std::copy(groups.begin(), groups.end(), std::ostream_iterator<std::string>(ss, " "));
00209     ROS_DEBUG_STREAM("Loaded information about the following groups: '" << ss.str() << "'");
00210 
00211     std::map<std::string, robot_model::SolverAllocatorFn> imap;
00212     for (std::size_t i = 0 ; i < groups.size() ; ++i)
00213     {
00214       if (!model_->hasJointModelGroup(groups[i]))
00215         continue;
00216       const robot_model::JointModelGroup *jmg = model_->getJointModelGroup(groups[i]);
00217       if (jmg->isChain())
00218         imap[groups[i]] = kinematics_allocator;
00219     }
00220     model_->setKinematicsAllocators(imap);
00221 
00222     // set the default IK timeouts
00223     const std::map<std::string, double> &timeout = kinematics_loader_->getIKTimeout();
00224     for (std::map<std::string, double>::const_iterator it = timeout.begin() ; it != timeout.end() ; ++it)
00225     {
00226       if (!model_->hasJointModelGroup(it->first))
00227         continue;
00228       robot_model::JointModelGroup *jmg = model_->getJointModelGroup(it->first);
00229       jmg->setDefaultIKTimeout(it->second);
00230     }
00231 
00232     // set the default IK attempts
00233     const std::map<std::string, unsigned int> &attempts = kinematics_loader_->getIKAttempts();
00234     for (std::map<std::string, unsigned int>::const_iterator it = attempts.begin() ; it != attempts.end() ; ++it)
00235     {
00236       if (!model_->hasJointModelGroup(it->first))
00237         continue;
00238       robot_model::JointModelGroup *jmg = model_->getJointModelGroup(it->first);
00239       jmg->setDefaultIKAttempts(it->second);
00240     }
00241   }
00242 }
00243 
00244 std::map<std::string, kinematics::KinematicsBasePtr> robot_model_loader::RobotModelLoader::generateKinematicsSolversMap() const
00245 {
00246   std::map<std::string, kinematics::KinematicsBasePtr> result;
00247   if (kinematics_loader_ && model_)
00248   {
00249     const std::vector<std::string> &groups = kinematics_loader_->getKnownGroups();
00250     for (std::size_t i = 0 ; i < groups.size() ; ++i)
00251     {
00252       if (!model_->hasJointModelGroup(groups[i]))
00253         continue;
00254       const robot_model::JointModelGroup *jmg = model_->getJointModelGroup(groups[i]);
00255       if (jmg)
00256       {
00257         robot_model::SolverAllocatorFn a = jmg->getSolverAllocators().first;
00258         if (a)
00259           result[jmg->getName()] = a(jmg);
00260       }
00261     }
00262   }
00263   else
00264     ROS_WARN("Kinematic solvers not yet loaded. Call loadKinematicSolvers() first.");
00265   return result;
00266 }


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:40