joint_model_group.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2013, Ioan A. Sucan
00005 *  Copyright (c) 2013, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00036 /* Author: Ioan Sucan, Dave Coleman */
00037 
00038 #include <moveit/robot_model/robot_model.h>
00039 #include <moveit/robot_model/joint_model_group.h>
00040 #include <moveit/robot_model/revolute_joint_model.h>
00041 #include <moveit/exceptions/exceptions.h>
00042 #include <console_bridge/console.h>
00043 #include <boost/lexical_cast.hpp>
00044 #include <algorithm>
00045 #include "order_robot_model_items.inc"
00046 
00047 namespace moveit
00048 {
00049 namespace core
00050 {
00051 namespace
00052 {
00053   
00054 // check if a parent or ancestor of joint is included in this group
00055 bool includesParent(const JointModel *joint, const JointModelGroup *group)
00056 {
00057   bool found = false;
00058   // if we find that an ancestor is also in the group, then the joint is not a root
00059   while (joint->getParentLinkModel() != NULL)
00060   {
00061     joint = joint->getParentLinkModel()->getParentJointModel();
00062     if (group->hasJointModel(joint->getName()) && joint->getVariableCount() > 0 && joint->getMimic() == NULL)
00063     {
00064       found = true;
00065       break;
00066     }
00067     else
00068       if (joint->getMimic() != NULL)
00069       {
00070         const JointModel *mjoint = joint->getMimic();
00071         if (group->hasJointModel(mjoint->getName()) && mjoint->getVariableCount() > 0 && mjoint->getMimic() == NULL)
00072           found = true;
00073         else
00074           if (includesParent(mjoint, group))
00075             found = true;
00076         if (found)
00077           break;
00078       }
00079   }
00080   return found;
00081 }
00082 
00083 // check if joint a is right below b, in the kinematic chain, with no active DOF missing
00084 bool jointPrecedes(const JointModel *a, const JointModel *b)
00085 {
00086   if (!a->getParentLinkModel())
00087     return false;
00088   const JointModel *p = a->getParentLinkModel()->getParentJointModel();
00089   while (p)
00090   {
00091     if (p == b)
00092       return true;
00093     if (p->getType() == JointModel::FIXED)
00094       p = p->getParentLinkModel() ? p->getParentLinkModel()->getParentJointModel() : NULL;
00095     else
00096       break;
00097   }
00098   
00099   return false;
00100 }
00101 
00102 }
00103 }
00104 }
00105 
00106 moveit::core::JointModelGroup::JointModelGroup(const std::string& group_name,
00107                                                const srdf::Model::Group &config,
00108                                                const std::vector<const JointModel*> &unsorted_group_joints,
00109                                                const RobotModel* parent_model)
00110   : parent_model_(parent_model)
00111   , name_(group_name)
00112   , common_root_(NULL)
00113   , variable_count_(0)
00114   , is_contiguous_index_list_(true)
00115   , is_chain_(false)
00116   , is_single_dof_(true)
00117   , config_(config)
00118 {
00119   // sort joints in Depth-First order
00120   joint_model_vector_ = unsorted_group_joints;
00121   std::sort(joint_model_vector_.begin(), joint_model_vector_.end(), OrderJointsByIndex());
00122   joint_model_name_vector_.reserve(joint_model_vector_.size());
00123   
00124   // figure out active joints, mimic joints, fixed joints
00125   // construct index maps, list of variables
00126   for (std::size_t i = 0 ; i < joint_model_vector_.size() ; ++i)
00127   {
00128     joint_model_name_vector_.push_back(joint_model_vector_[i]->getName());
00129     joint_model_map_[joint_model_vector_[i]->getName()] = joint_model_vector_[i];
00130     unsigned int vc = joint_model_vector_[i]->getVariableCount();
00131     if (vc > 0)
00132     {
00133       if (vc > 1)
00134         is_single_dof_ = false;
00135       const std::vector<std::string>& name_order = joint_model_vector_[i]->getVariableNames();
00136       if (joint_model_vector_[i]->getMimic() == NULL)
00137       {
00138         active_joint_model_vector_.push_back(joint_model_vector_[i]);
00139         active_joint_model_name_vector_.push_back(joint_model_vector_[i]->getName());
00140         active_joint_model_start_index_.push_back(variable_count_);
00141         active_joint_models_bounds_.push_back(&joint_model_vector_[i]->getVariableBounds());
00142       }
00143       else
00144         mimic_joints_.push_back(joint_model_vector_[i]);
00145       for (std::size_t j = 0; j < name_order.size(); ++j)
00146       {
00147         variable_names_.push_back(name_order[j]);
00148         variable_names_set_.insert(name_order[j]);
00149       }
00150       
00151       int first_index = joint_model_vector_[i]->getFirstVariableIndex();
00152       for (std::size_t j = 0; j < name_order.size(); ++j)
00153       {
00154         variable_index_list_.push_back(first_index + j);
00155         joint_variables_index_map_[name_order[j]] = variable_count_ + j;
00156       }
00157       joint_variables_index_map_[joint_model_vector_[i]->getName()] = variable_count_;
00158       
00159       if (joint_model_vector_[i]->getType() == JointModel::REVOLUTE && 
00160           static_cast<const RevoluteJointModel*>(joint_model_vector_[i])->isContinuous())
00161         continuous_joint_model_vector_.push_back(joint_model_vector_[i]);
00162 
00163       variable_count_ += vc;
00164     }
00165     else
00166       fixed_joints_.push_back(joint_model_vector_[i]);
00167   }
00168   
00169   // now we need to find all the set of joints within this group
00170   // that root distinct subtrees
00171   for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
00172   {
00173     // if we find that an ancestor is also in the group, then the joint is not a root
00174     if (!includesParent(active_joint_model_vector_[i], this))
00175       joint_roots_.push_back(active_joint_model_vector_[i]);
00176   }
00177   
00178   // when updating this group within a state, it is useful to know
00179   // if the full state of a group is contiguous within the full state of the robot
00180   if (variable_index_list_.empty())
00181     is_contiguous_index_list_ = false;
00182   else
00183     for (std::size_t i = 1 ; i < variable_index_list_.size() ; ++i)
00184       if (variable_index_list_[i] != variable_index_list_[i - 1] + 1)
00185       {
00186         is_contiguous_index_list_ = false;
00187         break;
00188       }
00189 
00190   // when updating/sampling a group state only, only mimic joints that have their parent within the group get updated.
00191   for (std::size_t i = 0 ; i < mimic_joints_.size() ; ++i)
00192     // if the joint we mimic is also in this group, we will need to do updates when sampling
00193     if (hasJointModel(mimic_joints_[i]->getMimic()->getName()))
00194     {
00195       int src = joint_variables_index_map_[mimic_joints_[i]->getMimic()->getName()];
00196       int dest = joint_variables_index_map_[mimic_joints_[i]->getName()];
00197       GroupMimicUpdate mu(src, dest, mimic_joints_[i]->getMimicFactor(), mimic_joints_[i]->getMimicOffset());
00198       group_mimic_update_.push_back(mu);
00199     }
00200   
00201   // now we need to make another pass for group links (we include the fixed joints here)
00202   std::set<const LinkModel*> group_links_set;
00203   for (std::size_t i = 0 ; i < joint_model_vector_.size() ; ++i)
00204     group_links_set.insert(joint_model_vector_[i]->getChildLinkModel());
00205   for (std::set<const LinkModel*>::iterator it = group_links_set.begin(); it != group_links_set.end(); ++it)
00206     link_model_vector_.push_back(*it);
00207   std::sort(link_model_vector_.begin(), link_model_vector_.end(), OrderLinksByIndex());
00208 
00209   for (std::size_t i = 0 ; i < link_model_vector_.size() ; ++i)
00210   {
00211     link_model_map_[link_model_vector_[i]->getName()] = link_model_vector_[i];
00212     link_model_name_vector_.push_back(link_model_vector_[i]->getName());
00213     if (!link_model_vector_[i]->getShapes().empty())
00214     {
00215       link_model_with_geometry_vector_.push_back(link_model_vector_[i]);
00216       link_model_with_geometry_name_vector_.push_back(link_model_vector_[i]->getName());
00217     }
00218   }
00219   
00220   // compute the common root of this group
00221   if (!joint_roots_.empty())
00222   {
00223     common_root_ = joint_roots_[0];
00224     for (std::size_t i = 1 ; i < joint_roots_.size() ; ++i)
00225       common_root_ = parent_model->getCommonRoot(joint_roots_[i], common_root_);
00226   }
00227   
00228   // compute updated links
00229   for (std::size_t i = 0 ; i < joint_roots_.size() ; ++i)
00230   {
00231     const std::vector<const LinkModel*> &links = joint_roots_[i]->getDescendantLinkModels();
00232     updated_link_model_set_.insert(links.begin(), links.end());
00233   }
00234   for (std::set<const LinkModel*>::iterator it = updated_link_model_set_.begin(); it != updated_link_model_set_.end(); ++it)
00235   {
00236     updated_link_model_name_set_.insert((*it)->getName());
00237     updated_link_model_vector_.push_back(*it);
00238     if (!(*it)->getShapes().empty())
00239     {
00240       updated_link_model_with_geometry_vector_.push_back(*it);
00241       updated_link_model_with_geometry_set_.insert(*it);
00242       updated_link_model_with_geometry_name_set_.insert((*it)->getName());
00243     }
00244   }
00245   std::sort(updated_link_model_vector_.begin(), updated_link_model_vector_.end(), OrderLinksByIndex());
00246   std::sort(updated_link_model_with_geometry_vector_.begin(), updated_link_model_with_geometry_vector_.end(), OrderLinksByIndex());
00247   for (std::size_t i = 0; i < updated_link_model_vector_.size(); ++i)
00248     updated_link_model_name_vector_.push_back(updated_link_model_vector_[i]->getName());
00249   for (std::size_t i = 0; i < updated_link_model_with_geometry_vector_.size(); ++i)
00250     updated_link_model_with_geometry_name_vector_.push_back(updated_link_model_with_geometry_vector_[i]->getName());
00251   
00252   // check if this group should actually be a chain
00253   if (joint_roots_.size() == 1 && active_joint_model_vector_.size() > 1)
00254   {
00255     bool chain = true;
00256     // due to our sorting, the joints are sorted in a DF fashion, so looking at them in reverse, 
00257     // we should always get to the parent.    
00258     for (std::size_t k = joint_model_vector_.size() - 1 ; k > 0 ; --k)
00259       if (!jointPrecedes(joint_model_vector_[k], joint_model_vector_[k - 1]))
00260       {
00261         chain = false;
00262         break;
00263       }
00264     if (chain)
00265       is_chain_ = true;
00266   }
00267 }
00268 
00269 moveit::core::JointModelGroup::~JointModelGroup()
00270 {
00271 }
00272 
00273 void moveit::core::JointModelGroup::setSubgroupNames(const std::vector<std::string> &subgroups)
00274 {
00275   subgroup_names_ = subgroups;
00276   subgroup_names_set_.clear();
00277   for (std::size_t i = 0 ; i < subgroup_names_.size() ; ++i)
00278     subgroup_names_set_.insert(subgroup_names_[i]);
00279 }
00280 
00281 void moveit::core::JointModelGroup::getSubgroups(std::vector<const JointModelGroup*>& sub_groups) const
00282 {
00283   sub_groups.resize(subgroup_names_.size());
00284   for (std::size_t i = 0 ; i < subgroup_names_.size() ; ++i)
00285     sub_groups[i] = parent_model_->getJointModelGroup(subgroup_names_[i]);
00286 }
00287 
00288 bool moveit::core::JointModelGroup::hasJointModel(const std::string &joint) const
00289 {
00290   return joint_model_map_.find(joint) != joint_model_map_.end();
00291 }
00292 
00293 bool moveit::core::JointModelGroup::hasLinkModel(const std::string &link) const
00294 {
00295   return link_model_map_.find(link) != link_model_map_.end();
00296 }
00297 
00298 const moveit::core::LinkModel* moveit::core::JointModelGroup::getLinkModel(const std::string &name) const
00299 {
00300   LinkModelMapConst::const_iterator it = link_model_map_.find(name);
00301   if (it == link_model_map_.end())
00302   {
00303     logError("Link '%s' not found in group '%s'", name.c_str(), name_.c_str());
00304     return NULL;
00305   }
00306   return it->second;
00307 }
00308 
00309 const moveit::core::JointModel* moveit::core::JointModelGroup::getJointModel(const std::string &name) const
00310 {
00311   JointModelMapConst::const_iterator it = joint_model_map_.find(name);
00312   if (it == joint_model_map_.end())
00313   {
00314     logError("Joint '%s' not found in group '%s'", name.c_str(), name_.c_str());
00315     return NULL;
00316   }
00317   return it->second;
00318 }
00319 
00320 void moveit::core::JointModelGroup::getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values,
00321                                                                const JointBoundsVector &active_joint_bounds) const
00322 {
00323   assert(active_joint_bounds.size() == active_joint_model_vector_.size());
00324   for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
00325     active_joint_model_vector_[i]->getVariableRandomPositions(rng, values + active_joint_model_start_index_[i], *active_joint_bounds[i]);
00326   
00327   updateMimicJoints(values);
00328 }
00329 
00330 void moveit::core::JointModelGroup::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values,
00331                                                                      const JointBoundsVector &active_joint_bounds,
00332                                                                      const double *near, double distance) const
00333 {
00334   assert(active_joint_bounds.size() == active_joint_model_vector_.size());
00335   for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
00336     active_joint_model_vector_[i]->getVariableRandomPositionsNearBy(rng, values + active_joint_model_start_index_[i], *active_joint_bounds[i],
00337                                                                     near + active_joint_model_start_index_[i], distance);
00338   updateMimicJoints(values);
00339 }
00340 
00341 void moveit::core::JointModelGroup::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values,
00342                                                                      const JointBoundsVector &active_joint_bounds,
00343                                                                      const double *near, const std::map<JointModel::JointType, double> &distance_map) const
00344 {
00345   assert(active_joint_bounds.size() == active_joint_model_vector_.size());
00346   for (std::size_t i = 0  ; i < active_joint_model_vector_.size() ; ++i)
00347   {
00348     double distance = 0.0;
00349     std::map<moveit::core::JointModel::JointType, double>::const_iterator iter = distance_map.find(active_joint_model_vector_[i]->getType());
00350     if (iter != distance_map.end())
00351       distance = iter->second;
00352     else
00353       logWarn("Did not pass in distance for '%s'", active_joint_model_vector_[i]->getName().c_str());
00354     active_joint_model_vector_[i]->getVariableRandomPositionsNearBy(rng, values + active_joint_model_start_index_[i], *active_joint_bounds[i],
00355                                                                     near + active_joint_model_start_index_[i], distance);
00356   }
00357   updateMimicJoints(values);
00358 }
00359 
00360 void moveit::core::JointModelGroup::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values,
00361                                                                      const JointBoundsVector &active_joint_bounds,
00362                                                                      const double *near, const std::vector<double> &distances) const
00363 {
00364   assert(active_joint_bounds.size() == active_joint_model_vector_.size());
00365   if (distances.size() != active_joint_model_vector_.size())
00366     throw Exception("When sampling random values nearby for group '" + name_ + "', distances vector should be of size " + 
00367                     boost::lexical_cast<std::string>(active_joint_model_vector_.size()) + ", but it is of size " + 
00368                     boost::lexical_cast<std::string>(distances.size()));  
00369   for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
00370     active_joint_model_vector_[i]->getVariableRandomPositionsNearBy(rng, values + active_joint_model_start_index_[i], *active_joint_bounds[i],
00371                                                                     near + active_joint_model_start_index_[i], distances[i]);
00372   updateMimicJoints(values);
00373 }
00374 
00375 bool moveit::core::JointModelGroup::satisfiesPositionBounds(const double *state, const JointBoundsVector &active_joint_bounds, double margin) const
00376 {
00377   assert(active_joint_bounds.size() == active_joint_model_vector_.size());
00378   for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
00379     if (!active_joint_model_vector_[i]->satisfiesPositionBounds(state + active_joint_model_start_index_[i], *active_joint_bounds[i], margin))
00380       return false;
00381   return true;
00382 }
00383 
00384 bool moveit::core::JointModelGroup::enforcePositionBounds(double *state, const JointBoundsVector &active_joint_bounds) const
00385 {
00386   assert(active_joint_bounds.size() == active_joint_model_vector_.size());
00387   bool change = false;
00388   for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
00389     if (active_joint_model_vector_[i]->enforcePositionBounds(state + active_joint_model_start_index_[i], *active_joint_bounds[i]))
00390       change = true;
00391   if (change)
00392     updateMimicJoints(state);
00393   return change;  
00394 }
00395 
00396 double moveit::core::JointModelGroup::getMaximumExtent(const JointBoundsVector &active_joint_bounds) const
00397 {
00398   double max_distance = 0.0;
00399   for (std::size_t j = 0 ; j < active_joint_model_vector_.size() ; ++j)
00400     max_distance += active_joint_model_vector_[j]->getMaximumExtent(*active_joint_bounds[j]) * active_joint_model_vector_[j]->getDistanceFactor();
00401   return max_distance;
00402 }
00403 
00404 double moveit::core::JointModelGroup::distance(const double *state1, const double *state2) const
00405 {
00406   double d = 0.0;
00407   for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
00408     d += active_joint_model_vector_[i]->getDistanceFactor() * 
00409       active_joint_model_vector_[i]->distance(state1 + active_joint_model_start_index_[i], state2 + active_joint_model_start_index_[i]);
00410   return d;
00411 }
00412 
00413 void moveit::core::JointModelGroup::interpolate(const double *from, const double *to, double t, double *state) const
00414 {
00415   // we interpolate values only for active joint models (non-mimic)
00416   for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
00417     active_joint_model_vector_[i]->interpolate(from + active_joint_model_start_index_[i], to + active_joint_model_start_index_[i],
00418                                                t, state + active_joint_model_start_index_[i]);
00419   
00420   // now we update mimic as needed
00421   updateMimicJoints(state);
00422 }
00423 
00424 void moveit::core::JointModelGroup::updateMimicJoints(double *values) const
00425 {
00426   // update mimic (only local joints as we are dealing with a local group state)
00427   for (std::size_t i = 0 ; i < group_mimic_update_.size() ; ++i)
00428     values[group_mimic_update_[i].dest] = values[group_mimic_update_[i].src] * group_mimic_update_[i].factor + group_mimic_update_[i].offset;
00429 }
00430 
00431 void moveit::core::JointModelGroup::addDefaultState(const std::string &name, const std::map<std::string, double> &default_state)
00432 {
00433   default_states_[name] = default_state;
00434   default_states_names_.push_back(name);
00435 }
00436 
00437 bool moveit::core::JointModelGroup::getVariableDefaultPositions(const std::string &name, std::map<std::string, double> &values) const
00438 {
00439   std::map<std::string, std::map<std::string, double> >::const_iterator it = default_states_.find(name);
00440   if (it == default_states_.end())
00441     return false;
00442   values = it->second;
00443   return true;
00444 }
00445 
00446 void moveit::core::JointModelGroup::getVariableDefaultPositions(double *values) const
00447 {
00448   for (std::size_t i = 0 ; i < active_joint_model_vector_.size() ; ++i)
00449     active_joint_model_vector_[i]->getVariableDefaultPositions(values + active_joint_model_start_index_[i]);
00450   updateMimicJoints(values);
00451 }
00452 
00453 void moveit::core::JointModelGroup::getVariableDefaultPositions(std::map<std::string, double> &values) const
00454 {
00455   std::vector<double> tmp(variable_count_);
00456   getVariableDefaultPositions(&tmp[0]);
00457   for (std::size_t i = 0 ; i < variable_names_.size() ; ++i)
00458     values[variable_names_[i]] = tmp[i];
00459 }
00460 
00461 void moveit::core::JointModelGroup::setEndEffectorName(const std::string &name)
00462 {
00463   end_effector_name_ = name;
00464 }
00465 
00466 void moveit::core::JointModelGroup::setEndEffectorParent(const std::string &group, const std::string &link)
00467 {
00468   end_effector_parent_.first = group;
00469   end_effector_parent_.second = link;
00470 }
00471 
00472 void moveit::core::JointModelGroup::attachEndEffector(const std::string &eef_name)
00473 {
00474   attached_end_effector_names_.push_back(eef_name);
00475 }
00476 
00477 bool moveit::core::JointModelGroup::getEndEffectorTips(std::vector<std::string> &tips) const
00478 {
00479   // Get a vector of tip links
00480   std::vector<const LinkModel*> tip_links;
00481   if (!getEndEffectorTips(tip_links))
00482     return false;
00483 
00484   // Convert to string names
00485   tips.clear();
00486   for (std::size_t i = 0; i < tip_links.size(); ++i)
00487   {
00488     tips.push_back(tip_links[i]->getName());
00489   }
00490   return true;
00491 }
00492 
00493 bool moveit::core::JointModelGroup::getEndEffectorTips(std::vector<const LinkModel*> &tips) const
00494 {
00495   for (std::size_t i = 0; i < getAttachedEndEffectorNames().size(); ++i)
00496   {
00497     const JointModelGroup *eef = parent_model_->getEndEffector(getAttachedEndEffectorNames()[i]);
00498     if (!eef)
00499     {
00500       logError("Unable to find joint model group for eef");
00501       return false;
00502     }
00503     const std::string &eef_parent = eef->getEndEffectorParentGroup().second;
00504 
00505     const LinkModel* eef_link = parent_model_->getLinkModel(eef_parent);
00506     if (!eef_link)
00507     {
00508       logError("Unable to find end effector link for eef");
00509       return false;
00510     }
00511 
00512     tips.push_back(eef_link);
00513   }
00514   return true;
00515 }
00516 
00517 int moveit::core::JointModelGroup::getVariableGroupIndex(const std::string &variable) const
00518 {
00519   VariableIndexMap::const_iterator it = joint_variables_index_map_.find(variable);
00520   if (it == joint_variables_index_map_.end())
00521   {
00522     logError("Variable '%s' is not part of group '%s'", variable.c_str(), name_.c_str());
00523     return -1;
00524   }
00525   return it->second;
00526 }
00527 
00528 void moveit::core::JointModelGroup::setDefaultIKTimeout(double ik_timeout)
00529 {
00530   group_kinematics_.first.default_ik_timeout_ = ik_timeout;
00531   if (group_kinematics_.first.solver_instance_)
00532     group_kinematics_.first.solver_instance_->setDefaultTimeout(ik_timeout);
00533   for (KinematicsSolverMap::iterator it = group_kinematics_.second.begin() ; it != group_kinematics_.second.end() ; ++it)
00534     it->second.default_ik_timeout_ = ik_timeout;
00535 }
00536 
00537 void moveit::core::JointModelGroup::setDefaultIKAttempts(unsigned int ik_attempts)
00538 {
00539   group_kinematics_.first.default_ik_attempts_ = ik_attempts;
00540   for (KinematicsSolverMap::iterator it = group_kinematics_.second.begin() ; it != group_kinematics_.second.end() ; ++it)
00541     it->second.default_ik_attempts_ = ik_attempts;
00542 }
00543 
00544 bool moveit::core::JointModelGroup::computeIKIndexBijection(const std::vector<std::string> &ik_jnames, std::vector<unsigned int> &joint_bijection) const
00545 {
00546   joint_bijection.clear();
00547   for (std::size_t i = 0 ; i < ik_jnames.size() ; ++i)
00548   {
00549     VariableIndexMap::const_iterator it = joint_variables_index_map_.find(ik_jnames[i]);
00550     if (it == joint_variables_index_map_.end())
00551     {
00552       // skip reported fixed joints
00553       if (hasJointModel(ik_jnames[i]) && getJointModel(ik_jnames[i])->getType() == JointModel::FIXED)
00554         continue;
00555       logError("IK solver computes joint values for joint '%s' but group '%s' does not contain such a joint.", ik_jnames[i].c_str(), getName().c_str());
00556       return false;
00557     }
00558     const JointModel *jm = getJointModel(ik_jnames[i]);
00559     for (unsigned int k = 0 ; k < jm->getVariableCount() ; ++k)
00560       joint_bijection.push_back(it->second + k);
00561   }
00562   return true;
00563 }
00564 
00565 void moveit::core::JointModelGroup::setSolverAllocators(const std::pair<SolverAllocatorFn, SolverAllocatorMapFn> &solvers)
00566 {
00567   if (solvers.first)
00568   {
00569     group_kinematics_.first.allocator_ = solvers.first;
00570     group_kinematics_.first.solver_instance_ = solvers.first(this);
00571     if (group_kinematics_.first.solver_instance_)
00572     {
00573       group_kinematics_.first.solver_instance_->setDefaultTimeout(group_kinematics_.first.default_ik_timeout_);
00574       group_kinematics_.first.solver_instance_const_ = group_kinematics_.first.solver_instance_;
00575       if (!computeIKIndexBijection(group_kinematics_.first.solver_instance_->getJointNames(),
00576                                    group_kinematics_.first.bijection_))
00577         group_kinematics_.first.reset();
00578     }
00579   }
00580   else
00581     // we now compute a joint bijection only if we have a solver map
00582     for (SolverAllocatorMapFn::const_iterator it = solvers.second.begin() ; it != solvers.second.end() ; ++it)
00583       if (it->first->getSolverInstance())
00584       {
00585         KinematicsSolver &ks = group_kinematics_.second[it->first];
00586         ks.allocator_ = it->second;
00587         ks.solver_instance_ = const_cast<JointModelGroup*>(it->first)->getSolverInstance();
00588         ks.solver_instance_const_ = ks.solver_instance_;
00589         ks.default_ik_timeout_ = group_kinematics_.first.default_ik_timeout_;
00590         ks.default_ik_attempts_ = group_kinematics_.first.default_ik_attempts_;
00591         if (!computeIKIndexBijection(ks.solver_instance_->getJointNames(), ks.bijection_))
00592         {
00593           group_kinematics_.second.clear();
00594           break;
00595         }
00596       }
00597 }
00598 
00599 bool moveit::core::JointModelGroup::canSetStateFromIK(const std::string &tip) const
00600 {
00601   const kinematics::KinematicsBaseConstPtr& solver = getSolverInstance();
00602   if (!solver || tip.empty())
00603     return false;
00604 
00605   const std::vector<std::string> &tip_frames = solver->getTipFrames();
00606 
00607   if (tip_frames.empty())
00608   {
00609     logDebug("Group %s has no tip frame(s)", name_.c_str());
00610     return false;
00611   }
00612 
00613   // loop through all tip frames supported by the JMG
00614   for (std::size_t i = 0; i < tip_frames.size(); ++i)
00615   {
00616     // remove frame reference, if specified
00617     const std::string &tip_local = tip[0] == '/' ? tip.substr(1) : tip;
00618     const std::string &tip_frame_local = tip_frames[i][0] == '/' ? tip_frames[i].substr(1) : tip_frames[i];
00619     logDebug("joint_model_group.canSetStateFromIK: comparing input tip: %s to this groups tip: %s ", tip_local.c_str(), tip_frame_local.c_str());
00620 
00621     // Check if the IK solver's tip is the same as the frame of inquiry
00622     if (tip_local != tip_frame_local)
00623     {
00624       // If not the same, check if this planning group includes the frame of inquiry
00625       if (hasLinkModel(tip_frame_local))
00626       {
00627         const LinkModel *lm = getLinkModel(tip_frame_local);
00628         const LinkTransformMap &fixed_links = lm->getAssociatedFixedTransforms();
00629         // Check if our frame of inquiry is located anywhere further down the chain (towards the tip of the arm)
00630         for (LinkTransformMap::const_iterator it = fixed_links.begin() ; it != fixed_links.end() ; ++it)
00631         {
00632           if (it->first->getName() == tip_local)
00633             return true;
00634         }
00635       }
00636     }
00637     else
00638       return true;
00639   }
00640 
00641   // Did not find any valid tip frame links to use
00642   return false;
00643 }
00644 
00645 void moveit::core::JointModelGroup::printGroupInfo(std::ostream &out) const
00646 {
00647   out << "Group '" << name_ << "' using " << variable_count_ <<  " variables" << std::endl;
00648   out << "  * Joints:" << std::endl;
00649   for (std::size_t i = 0 ; i < joint_model_vector_.size() ; ++i)
00650     out << "    '" << joint_model_vector_[i]->getName() << "' (" << joint_model_vector_[i]->getTypeName() << ")" << std::endl;
00651   out << "  * Variables:" << std::endl;
00652   for (std::size_t i = 0 ; i < variable_names_.size() ; ++i)
00653   {
00654     int local_idx = joint_variables_index_map_.find(variable_names_[i])->second;
00655     const JointModel *jm = parent_model_->getJointOfVariable(variable_names_[i]);
00656     out << "    '" << variable_names_[i] << "', index " << (jm->getFirstVariableIndex() + jm->getLocalVariableIndex(variable_names_[i]))
00657         << " in full state, index " << local_idx << " in group state";
00658     if (jm->getMimic())
00659       out << ", mimic '" << jm->getMimic()->getName() << "'";
00660     out << std::endl;
00661     out << "        " << parent_model_->getVariableBounds(variable_names_[i]) << std::endl;
00662   }
00663   out << "  * Variables Index List:" << std::endl;
00664   out << "    ";
00665   for (std::size_t i = 0 ; i < variable_index_list_.size() ; ++i)
00666     out << variable_index_list_[i] << " ";
00667   if (is_contiguous_index_list_)
00668     out << "(contiguous)";
00669   else
00670     out << "(non-contiguous)";
00671   out << std::endl;
00672   if (group_kinematics_.first)
00673   {
00674     out << "  * Kinematics solver bijection:" << std::endl;
00675     out << "    ";
00676     for (std::size_t i = 0 ; i < group_kinematics_.first.bijection_.size() ; ++i)
00677       out << group_kinematics_.first.bijection_[i] << " ";
00678     out << std::endl;
00679   }
00680   if (!group_kinematics_.second.empty())
00681   {
00682     out << "  * Compound kinematics solver:" << std::endl;
00683     for (KinematicsSolverMap::const_iterator it = group_kinematics_.second.begin() ; it != group_kinematics_.second.end() ; ++it)
00684     {
00685       out << "    " << it->first->getName() << ":";
00686       for (std::size_t i = 0 ; i < it->second.bijection_.size() ; ++i)
00687         out << " " << it->second.bijection_[i];
00688       out << std::endl;
00689     }
00690   }
00691   
00692   if (!group_mimic_update_.empty())
00693   {
00694     out << "  * Local Mimic Updates:" << std::endl;
00695     for (std::size_t i = 0 ; i < group_mimic_update_.size() ; ++i)
00696       out << "    [" << group_mimic_update_[i].dest << "] = " << group_mimic_update_[i].factor << " * [" << group_mimic_update_[i].src << "] + " << group_mimic_update_[i].offset << std::endl;
00697   }
00698   out << std::endl;
00699 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:52