constrained_ik.cpp
Go to the documentation of this file.
00001 
00026 #include <constrained_ik/constrained_ik.h>
00027 #include "constrained_ik/constraint_group.h"
00028 #include <boost/make_shared.hpp>
00029 #include <constrained_ik/constraint_results.h>
00030 #include <ros/ros.h>
00031 
00032 const std::vector<std::string> SUPPORTED_COLLISION_DETECTORS = {"IndustrialFCL", "CollisionDetectionOpenVDB"}; 
00034 namespace constrained_ik
00035 {
00036 using Eigen::MatrixXd;
00037 using Eigen::VectorXd;
00038 using Eigen::Affine3d;
00039 
00040 Constrained_IK::Constrained_IK():nh_("~")
00041 {
00042   initialized_ = false;
00043 
00044   loadDefaultSolverConfiguration();
00045 }
00046 
00047 void Constrained_IK::addConstraintsFromParamServer(const std::string &parameter_name)
00048 {
00049   XmlRpc::XmlRpcValue constraints_xml;
00050   boost::shared_ptr<pluginlib::ClassLoader<constrained_ik::Constraint> > constraint_loader;
00051 
00052   constraint_loader.reset(new pluginlib::ClassLoader<constrained_ik::Constraint>("constrained_ik", "constrained_ik::Constraint"));
00053 
00054   if (!nh_.getParam(parameter_name, constraints_xml))
00055   {
00056     ROS_ERROR("Unable to find ros parameter: %s", parameter_name.c_str());
00057     ROS_BREAK();
00058     return;
00059   }
00060 
00061   if(constraints_xml.getType() != XmlRpc::XmlRpcValue::TypeArray)
00062   {
00063     ROS_ERROR("ROS parameter %s must be an array", parameter_name.c_str());
00064     ROS_BREAK();
00065     return;
00066   }
00067 
00068   for (int i=0; i<constraints_xml.size(); ++i)
00069   {
00070     XmlRpc::XmlRpcValue constraint_xml = constraints_xml[i];
00071 
00072     if (constraint_xml.hasMember("class") &&
00073               constraint_xml["class"].getType() == XmlRpc::XmlRpcValue::TypeString &&
00074               constraint_xml.hasMember("primary") &&
00075               constraint_xml["primary"].getType() == XmlRpc::XmlRpcValue::TypeBoolean)
00076     {
00077       std::string class_name = constraint_xml["class"];
00078       bool is_primary = constraint_xml["primary"];
00079 
00080       Constraint *constraint;
00081       try
00082       {
00083         constraint = constraint_loader->createUnmanagedInstance(class_name);
00084 
00085         constraint->loadParameters(constraint_xml);
00086         if (is_primary)
00087           addConstraint(constraint, constraint_types::Primary);
00088         else
00089           addConstraint(constraint, constraint_types::Auxiliary);
00090 
00091       }
00092       catch (pluginlib::PluginlibException& ex)
00093       {
00094         ROS_ERROR("Couldn't load constraint named %s.\n Error: %s", class_name.c_str(), ex.what());
00095         ROS_BREAK();
00096       }
00097     }
00098     else
00099     {
00100       ROS_ERROR("Constraint must have class(string) and primary(boolean) members");
00101     }
00102   }
00103 }
00104 
00105 void Constrained_IK::loadDefaultSolverConfiguration()
00106 {
00107   ConstrainedIKConfiguration config;
00108   config.debug_mode = false;
00109   config.allow_joint_convergence = false;
00110   config.allow_primary_normalization = true;
00111   config.allow_auxiliary_nomalization = true;
00112   config.limit_primary_motion = false;
00113   config.limit_auxiliary_motion = false;
00114   config.limit_auxiliary_interations = false;
00115   config.solver_max_iterations = 500;
00116   config.solver_min_iterations = 0;
00117   config.auxiliary_max_iterations = 5;
00118   config.primary_max_motion = 2.0;
00119   config.auxiliary_max_motion = 0.2;
00120   config.primary_norm = 1.0;
00121   config.auxiliary_norm = 0.2;
00122   config.primary_gain = 1.0;
00123   config.auxiliary_gain = 1.0;
00124   config.joint_convergence_tol = 0.0001;
00125 
00126   setSolverConfiguration(config);
00127 }
00128 
00129 void Constrained_IK::setSolverConfiguration(const ConstrainedIKConfiguration &config)
00130 {
00131   config_ = config;
00132   validateConstrainedIKConfiguration<ConstrainedIKConfiguration>(config_);
00133 }
00134 
00135 constrained_ik::ConstraintResults Constrained_IK::evalConstraint(constraint_types::ConstraintTypes constraint_type, const constrained_ik::SolverState &state) const
00136 {
00137   switch(constraint_type)
00138   {
00139     case constraint_types::Primary:
00140       return primary_constraints_.evalConstraint(state);
00141     case constraint_types::Auxiliary:
00142       return auxiliary_constraints_.evalConstraint(state);
00143   }
00144 }
00145 
00146 Eigen::MatrixXd Constrained_IK::calcNullspaceProjection(const Eigen::MatrixXd &J) const
00147 {
00148   MatrixXd J_pinv = calcDampedPseudoinverse(J);
00149   MatrixXd JplusJ = J_pinv * J;
00150   int mn = JplusJ.rows();
00151   MatrixXd P = MatrixXd::Identity(mn,mn)-JplusJ;
00152   return (P);
00153 }
00154 
00155 Eigen::MatrixXd Constrained_IK::calcNullspaceProjectionTheRightWay(const Eigen::MatrixXd &A) const
00156 {
00157   Eigen::JacobiSVD<MatrixXd> svd(A, Eigen::ComputeFullV);
00158   MatrixXd V(svd.matrixV());
00159 
00160   // determine rank using same algorithym as latest Eigen
00161   // TODO replace next 10 lines of code with rnk = svd.rank(); once eigen3 is updated
00162   int rnk = 0;
00163   if(svd.singularValues().size()==0)
00164   {
00165     rnk = 0;
00166   }
00167   else
00168   {
00169     double threshold = std::min(A.rows(),A.cols())*Eigen::NumTraits<double>::epsilon();
00170     double premultiplied_threshold = svd.singularValues().coeff(0) * threshold;
00171     rnk = svd.nonzeroSingularValues()-1;
00172     while(rnk>=0 && svd.singularValues().coeff(rnk) < premultiplied_threshold) --rnk;
00173     rnk++;
00174   }
00175 
00176   // zero singular vectors in the range of A
00177   for(int i=0; i<rnk; ++i)
00178   {
00179     for(int j=0; j<A.cols(); j++) V(j,i) = 0;
00180   }
00181 
00182   MatrixXd P = V *  V.transpose();
00183   return(P);
00184 }
00185 
00186 Eigen::MatrixXd Constrained_IK::calcDampedPseudoinverse(const Eigen::MatrixXd &J) const
00187 {
00188   MatrixXd J_pinv;
00189 
00190   if (basic_kin::BasicKin::dampedPInv(J,J_pinv))
00191   {
00192     return J_pinv;
00193   }
00194   else
00195   {
00196     ROS_ERROR_STREAM("Not able to calculate damped pseudoinverse!");
00197     throw std::runtime_error("Not able to calculate damped pseudoinverse!  IK solution may be invalid.");
00198   }
00199 }
00200 
00201 bool Constrained_IK::calcInvKin(const Eigen::Affine3d &goal,
00202                                 const Eigen::VectorXd &joint_seed,
00203                                 Eigen::VectorXd &joint_angles) const
00204 {
00205   return calcInvKin(goal,joint_seed, planning_scene::PlanningSceneConstPtr(), joint_angles);
00206 }
00207 
00208 bool Constrained_IK::calcInvKin(const Eigen::Affine3d &goal,
00209                                 const Eigen::VectorXd &joint_seed,
00210                                 const planning_scene::PlanningSceneConstPtr planning_scene,
00211                                 Eigen::VectorXd &joint_angles) const
00212 {
00213   double dJoint_norm;
00214   SolverStatus status;
00215 
00216     // initialize state
00217   joint_angles = joint_seed;  // initialize result to seed value
00218   constrained_ik::SolverState state = getState(goal, joint_seed); // create state vars for this IK solve
00219   state.condition = checkInitialized();
00220   state.planning_scene = planning_scene;
00221   state.group_name = kin_.getJointModelGroup()->getName();
00222 
00223   //TODO: Does this still belong here?
00224   if(planning_scene)
00225   {
00226     state.robot_state = robot_state::RobotStatePtr(new moveit::core::RobotState(planning_scene->getCurrentState()));
00227 
00228     //Check and make sure the correct collision detector is loaded.
00229     auto pos = std::find(SUPPORTED_COLLISION_DETECTORS.begin(),SUPPORTED_COLLISION_DETECTORS.end(),
00230                          planning_scene->getActiveCollisionDetectorName());
00231     if (pos == SUPPORTED_COLLISION_DETECTORS.end())
00232     {
00233       std::stringstream error_message;
00234       error_message<<" Constrained IK requires the use of collision detectors: ";
00235       for(auto& d : SUPPORTED_COLLISION_DETECTORS)
00236       {
00237         error_message<<"'"<< d<<"' ";
00238       }
00239       error_message<<".\nSet or add the 'collision_detector' parameter to an allowed collision detector in the move_group.launch file"<<std::endl;
00240       throw std::runtime_error(error_message.str());
00241     }
00242 
00243     state.collision_robot = boost::dynamic_pointer_cast<const collision_detection::CollisionRobotIndustrial>(planning_scene->getCollisionRobot());
00244     state.collision_world = boost::dynamic_pointer_cast<const collision_detection::CollisionWorldIndustrial>(planning_scene->getCollisionWorld());
00245   }
00246 
00247   if (state.condition == initialization_state::NothingInitialized || state.condition == initialization_state::AuxiliaryOnly)
00248     throw std::runtime_error("Must call init() before using Constrained_IK and have a primary constraint.");
00249 
00250   //Cache the joint angles to return if max iteration is reached.
00251   Eigen::VectorXd cached_joint_angles = joint_seed;
00252 
00253   // iterate until solution converges (or aborted)
00254   while (true)
00255   {
00256     // re-update internal state variables
00257     updateState(state, joint_angles);
00258 
00259     // calculate a Jacobian (relating joint-space updates/deltas to cartesian-space errors/deltas)
00260     // and the associated cartesian-space error/delta vector
00261     // Primary Constraints
00262     constrained_ik::ConstraintResults primary = evalConstraint(constraint_types::Primary, state);
00263     // TODO since we already have J_p = USV, use that to get null-projection too.
00264     // otherwise, we are repeating the expensive calculation of the SVD
00265 
00266     VectorXd dJoint_p;
00267     dJoint_p.setZero(joint_seed.size());
00268     if (!primary.isEmpty()) // This is required because not all constraints always return data.
00269     {
00270       MatrixXd Ji_p = calcDampedPseudoinverse(primary.jacobian);
00271       dJoint_p = config_.primary_gain*(Ji_p*primary.error);
00272       dJoint_norm = dJoint_p.norm();
00273       if(config_.allow_primary_normalization && dJoint_norm > config_.primary_norm)// limit maximum update radian/meter
00274       {
00275         dJoint_p = config_.primary_norm * (dJoint_p/dJoint_norm);
00276         dJoint_norm = dJoint_p.norm();
00277       }
00278       state.primary_sum += dJoint_norm;
00279     }
00280 
00281     // Auxiliary Constraints
00282     VectorXd dJoint_a;
00283     constrained_ik::ConstraintResults auxiliary;
00284     dJoint_a.setZero(dJoint_p.size());
00285     if (state.condition == initialization_state::PrimaryAndAuxiliary)
00286     {
00287       if (!((config_.limit_auxiliary_motion && state.auxiliary_sum >= config_.auxiliary_max_motion) ||
00288           (config_.limit_auxiliary_interations && state.iter > config_.auxiliary_max_iterations)))
00289       {
00290         auxiliary = evalConstraint(constraint_types::Auxiliary, state);
00291         if (!auxiliary.isEmpty()) // This is required because not all constraints always return data.
00292         {
00293           MatrixXd N_p = calcNullspaceProjectionTheRightWay(primary.jacobian);
00294           MatrixXd Jnull_a = calcDampedPseudoinverse(auxiliary.jacobian*N_p);
00295           dJoint_a = config_.auxiliary_gain*Jnull_a*(auxiliary.error-auxiliary.jacobian*dJoint_p);
00296           dJoint_norm = dJoint_a.norm();
00297           if(config_.allow_auxiliary_nomalization && dJoint_norm > config_.auxiliary_norm)// limit maximum update radian/meter
00298           {
00299             dJoint_a = config_.auxiliary_norm * (dJoint_a/dJoint_norm);
00300             dJoint_norm = dJoint_a.norm();
00301           }
00302           state.auxiliary_sum += dJoint_norm;
00303         }
00304       }
00305       else
00306       {
00307         state.auxiliary_at_limit = true;
00308       }
00309     }
00310 
00311     status = checkStatus(state, primary, auxiliary);
00312     
00313     
00314     if (status == Converged)
00315     {
00316       ROS_DEBUG_STREAM("Found IK solution in " << state.iter << " iterations: " << joint_angles.transpose());
00317       return true;
00318     }
00319     else if (status == NotConverged)
00320     {
00321       // update joint solution by the calculated update (or a partial fraction)
00322       joint_angles += (dJoint_p + dJoint_a);
00323       clipToJointLimits(joint_angles);
00324     }
00325     else if (status == Failed)
00326     {
00327       joint_angles = cached_joint_angles;
00328       return false;
00329     }
00330   }
00331 }
00332 
00333 SolverStatus Constrained_IK::checkStatus(const constrained_ik::SolverState &state, const constrained_ik::ConstraintResults &primary, const constrained_ik::ConstraintResults &auxiliary) const
00334 {
00335   // Check the status of convergence
00336   if(state.condition == initialization_state::PrimaryAndAuxiliary)
00337   {
00338     bool status = (primary.status && auxiliary.status);
00339 
00340     if (state.iter > config_.solver_min_iterations)
00341     {
00342       if (!status && primary.status && state.auxiliary_at_limit)
00343       {
00344         ROS_DEBUG("Auxiliary motion or iteration limit reached!");
00345         return Converged;
00346       }
00347       else if(status)
00348       {
00349         return Converged;
00350       }
00351     }
00352   }
00353   
00354   if(state.condition == initialization_state::PrimaryOnly)
00355   {   
00356     if (primary.status && state.iter > config_.solver_min_iterations)
00357     {
00358       return Converged;
00359     }
00360   }
00361 
00362   // check for joint convergence
00363   //   - this is an error: joints stabilize, but goal pose not reached
00364   if (config_.allow_joint_convergence)
00365   {
00366     if (state.joints_delta.cwiseAbs().maxCoeff() < config_.joint_convergence_tol)
00367     {
00368       if (state.iter > config_.solver_min_iterations)
00369       {
00370         ROS_DEBUG_STREAM("Joint convergence reached " << state.iter << " / " << config_.solver_max_iterations << " iterations before convergence.");
00371         return Converged;
00372       }
00373     }
00374   }
00375   
00376   if (state.iter > config_.solver_max_iterations || (config_.limit_primary_motion && state.primary_sum >= config_.primary_max_motion))
00377   {
00378     if (!primary.status)
00379     {
00380       if (config_.limit_primary_motion && state.primary_sum >= config_.primary_max_motion)
00381       {
00382         ROS_WARN_STREAM("Primary reached max allowed motion, no solution returned.");
00383       }
00384       else
00385       {
00386         ROS_WARN_STREAM("Solver reached max allowed iteration, no solution returned.");
00387       }
00388       return Failed;
00389     }
00390     else if (state.condition == initialization_state::PrimaryAndAuxiliary)
00391     {
00392       ROS_WARN_STREAM("Maximum iterations reached but primary converged so returning solution.");
00393       return Converged;
00394     }
00395   }
00396 
00397   return NotConverged;
00398 }
00399 
00400 void Constrained_IK::clearConstraintList()
00401 {
00402   primary_constraints_.clear();
00403   auxiliary_constraints_.clear();
00404 }
00405 
00406 void Constrained_IK::clipToJointLimits(Eigen::VectorXd &joints) const
00407 {
00408   const MatrixXd limits = kin_.getLimits();
00409   const VectorXd orig_joints(joints);
00410 
00411   if (joints.size() != limits.rows())
00412     throw std::invalid_argument("clipToJointLimits: Unexpected number of joints");
00413 
00414   for (size_t i=0; i<limits.rows(); ++i)
00415   {
00416     joints[i] = std::max(limits(i,0), std::min(limits(i,1), joints[i]));
00417   }
00418   if (config_.debug_mode && !joints.isApprox(orig_joints))
00419       ROS_WARN("Joints have been clipped");
00420 }
00421 
00422 void Constrained_IK::init(const basic_kin::BasicKin &kin)
00423 {
00424   if (!kin.checkInitialized())
00425     throw std::invalid_argument("Input argument 'BasicKin' must be initialized");
00426 
00427   kin_ = kin;
00428   initialized_ = true;
00429   primary_constraints_.init(this);
00430   auxiliary_constraints_.init(this);
00431 
00432 }
00433 
00434 double Constrained_IK::rangedAngle(double angle)
00435 {
00436     angle = copysign(fmod(fabs(angle),2.0*M_PI), angle);
00437     if (angle < -M_PI) return angle+2.*M_PI;
00438     if (angle > M_PI)  return angle-2.*M_PI;
00439     return angle;
00440 }
00441 
00442 constrained_ik::SolverState Constrained_IK::getState(const Eigen::Affine3d &goal, const Eigen::VectorXd &joint_seed) const
00443 {
00444   if (!kin_.checkJoints(joint_seed))
00445     throw std::invalid_argument("Seed doesn't match kinematic model");
00446 
00447   if (!goal.matrix().block(0,0,3,3).isUnitary(1e-6))
00448         throw std::invalid_argument("Goal pose not proper affine");
00449 
00450   return constrained_ik::SolverState(goal, joint_seed);
00451 }
00452 
00453 void Constrained_IK::updateState(constrained_ik::SolverState &state, const Eigen::VectorXd &joints) const
00454 {
00455   // update maximum iterations
00456   state.iter++;
00457 
00458   // update joint convergence
00459   state.joints_delta = joints - state.joints;
00460   state.joints = joints;
00461   kin_.calcFwdKin(joints, state.pose_estimate);
00462 
00463   if(state.planning_scene && state.robot_state)
00464   {
00465     state.robot_state->setJointGroupPositions(kin_.getJointModelGroup()->getName(), joints);
00466     state.robot_state->update();
00467   }
00468 
00469   if (config_.debug_mode)
00470     state.iteration_path.push_back(joints);
00471 
00472 }
00473 
00474 } // namespace constrained_ik
00475 


constrained_ik
Author(s): Chris Lewis , Jeremy Zoss , Dan Solomon
autogenerated on Sat Jun 8 2019 19:23:45