seed_search.cpp
Go to the documentation of this file.
00001 #include <descartes_moveit/seed_search.h>
00002 
00003 #include <ros/ros.h>
00004 
00005 using namespace descartes_moveit;
00006 
00007 typedef std::vector<unsigned> BijectionVec;
00008 typedef std::pair<unsigned, unsigned> JointPair;
00009 typedef std::vector<JointPair> JointPairVec;
00010 typedef std::vector<double> JointConfig;
00011 typedef std::vector<JointConfig> JointConfigVec;
00012 
00016 bool doFK(moveit::core::RobotState& state, const moveit::core::JointModelGroup* group, const std::string& tool,
00017           const JointConfig& joint_pose, Eigen::Affine3d& result)
00018 {
00019   state.setJointGroupPositions(group, joint_pose);
00020   if (!state.knowsFrameTransform(tool))
00021   {
00022     ROS_WARN("No transform to this tool frame");
00023     return false;
00024   }
00025 
00026   if (!state.satisfiesBounds())
00027   {
00028     ROS_WARN("Joint angles do not satisfy robot bounds");
00029     return false;
00030   }
00031 
00032   result = state.getFrameTransform(tool);
00033   return true;
00034 }
00035 
00040 bool doIK(moveit::core::RobotState& state, const moveit::core::JointModelGroup* group, const std::string& group_name,
00041           const std::string& tool, const Eigen::Affine3d& pose, const JointConfig& seed, JointConfig& result)
00042 {
00043   const static int N_ATTEMPTS = 1;
00044   const static double IK_TIMEOUT = 0.01;
00045 
00046   state.setJointGroupPositions(group_name, seed);
00047   if (!state.setFromIK(group, pose, tool, N_ATTEMPTS, IK_TIMEOUT))
00048   {
00049     return false;
00050   }
00051   state.copyJointGroupPositions(group, result);
00052   return true;
00053 }
00054 
00058 bool isSingularity(moveit::core::RobotState& state, const moveit::core::JointModelGroup* group)
00059 {
00060   const static double MIN_DETERMINANT_VALUE = 0.0001;
00061   Eigen::Vector3d reference_point_position(0.0, 0.0, 0.0);
00062   Eigen::MatrixXd jacobian;
00063   state.getJacobian(group, state.getLinkModel(group->getLinkModelNames().back()), reference_point_position, jacobian);
00064 
00065   return std::abs(jacobian.determinant()) < MIN_DETERMINANT_VALUE;
00066 }
00067 
00068 // Compares the first n_compare bijection joint values from a and b and tests
00069 // whether they are within 45 degrees of one another
00070 inline bool isSameJointConfig(const JointConfig& a, const JointConfig& b, const JointPair& pair)
00071 {
00072   const static double MIN_DIFF = M_PI_4;
00073   return std::abs(a[pair.first] - b[pair.first]) < MIN_DIFF && std::abs(a[pair.second] - b[pair.second]) < MIN_DIFF;
00074 }
00075 
00076 // Tests whether a given joint configuration, c, is similar to any joint set already
00077 // in set using the given bijection values and number of joints.
00078 inline bool isInJointSet(const JointConfig& c, const JointConfigVec& set, const JointPair& pair)
00079 {
00080   for (std::size_t i = 0; i < set.size(); ++i)
00081   {
00082     if (isSameJointConfig(c, set[i], pair))
00083       return true;
00084   }
00085   return false;
00086 }
00087 
00088 std::vector<double> createValidJointPositions(const moveit::core::JointModel& model, double increment)
00089 {
00090   // Should never be called with fixed joint
00091   const moveit::core::JointModel::Bounds& bounds = model.getVariableBounds();
00092   double min = bounds[0].min_position_;
00093   double max = bounds[0].max_position_;
00094 
00095   std::vector<double> result;
00096   while (min <= max)
00097   {
00098     result.push_back(min);
00099     min += increment;
00100   }
00101 
00102   return result;
00103 }
00104 
00105 std::vector<double> createSeedFromPerms(const std::vector<double>& initial, const std::vector<double>& a_perms,
00106                                         unsigned a_joint_idx, const std::vector<double>& b_perms, unsigned b_joint_idx,
00107                                         unsigned n)
00108 {
00109   std::vector<double> seed = initial;
00110   double a_value = a_perms[n / b_perms.size()];
00111   double b_value = b_perms[n % b_perms.size()];
00112   seed[a_joint_idx] = a_value;
00113   seed[b_joint_idx] = b_value;
00114   return seed;
00115 }
00116 
00117 JointConfigVec findSeedStatesForPair(moveit::core::RobotState& state, const std::string& group_name,
00118                                      const std::string& tool_frame, const JointPair& pair)
00119 {
00120   using namespace moveit::core;
00121 
00122   const JointModelGroup* group = state.getJointModelGroup(group_name);
00123   const std::vector<const JointModel*> active_joints = group->getActiveJointModels();
00124 
00125   // check each joint to see if it is revolute
00126   for (const JointModel* model : active_joints)
00127   {
00128     if (model->getType() != JointModel::REVOLUTE)
00129       ROS_WARN_STREAM("Joint '" << model->getName() << "' does not appear to be revolute");
00130   }
00131 
00132   // compute random starting values for all joints
00133   state.setToRandomPositions();
00134   JointConfig init_state;
00135   state.copyJointGroupPositions(group, init_state);
00136 
00137   // Precompute the valid positions for the two joints we'll iterate over
00138   std::vector<double> joint1_perms = createValidJointPositions(*active_joints[pair.first], M_PI_2);
00139   std::vector<double> joint2_perms = createValidJointPositions(*active_joints[pair.second], M_PI_2);
00140 
00141   std::set<size_t> final_seed_states;
00142 
00143   // Walk the valid combos
00144   const size_t iterations = joint1_perms.size() * joint2_perms.size();
00145   for (std::size_t i = 0; i < iterations; ++i)
00146   {
00147     // Make the seed state for this index from permutations
00148     JointConfig round_ik = createSeedFromPerms(init_state, joint1_perms, pair.first, joint2_perms, pair.second, i);
00149     // Containers for the valid seeds and ik solutions for THIS round
00150     std::vector<size_t> this_round_seeds;
00151     JointConfigVec this_round_iks;
00152 
00153     // Forward kinematics
00154     Eigen::Affine3d target_pose;
00155     if (!doFK(state, group, tool_frame, round_ik, target_pose))
00156     {
00157       ROS_DEBUG_STREAM("No FK for pose " << i);
00158       continue;
00159     }
00160 
00161     // Check to make sure we're not in a singularity
00162     if (isSingularity(state, group))
00163     {
00164       ROS_DEBUG_STREAM("Pose " << i << " at singularity.");
00165       continue;
00166     }
00167 
00168     // Add initial states to the iks/seeds for this point
00169     this_round_seeds.push_back(i);
00170     this_round_iks.push_back(round_ik);
00171 
00172     // Now we'll walk through all of the other seeds, starting with the ones that have worked so far
00173     for (size_t idx : final_seed_states)
00174     {
00175       // create joint config fom handle
00176       JointConfig seed = createSeedFromPerms(init_state, joint1_perms, pair.first, joint2_perms, pair.second, idx);
00177       JointConfig ik;
00178       // perform ik
00179       if (!doIK(state, group, group_name, tool_frame, target_pose, seed, ik))
00180       {
00181         continue;
00182       }
00183       // If we have a unique IK solution, then add to the iks seen this round
00184       if (!isInJointSet(ik, this_round_iks, pair))
00185       {
00186         this_round_iks.push_back(ik);
00187         this_round_seeds.push_back(idx);
00188       }
00189     }
00190 
00191     // Now try the rest of the joint possible seed states if they haven't been tried
00192     for (std::size_t j = 0; j < iterations; ++j)
00193     {
00194       // skip the situation where pose is generated from current seed we already have that ik
00195       if (i == j)
00196         continue;
00197 
00198       unsigned count = final_seed_states.count(j);
00199       if (count != 0)
00200         continue;
00201 
00202       JointConfig seed = createSeedFromPerms(init_state, joint1_perms, pair.first, joint2_perms, pair.second, j);
00203       JointConfig ik;
00204       if (!doIK(state, group, group_name, tool_frame, target_pose, seed, ik))
00205       {
00206         continue;
00207       }
00208 
00209       // If we have a new IK solution here, then it was generated
00210       // by a seed that has not yet been added to the overall seed
00211       // states to be returned
00212       if (!isInJointSet(ik, this_round_iks, pair))
00213       {
00214         this_round_iks.push_back(ik);
00215         this_round_seeds.push_back(j);
00216         final_seed_states.insert(j);
00217       }
00218     }
00219 
00220     ROS_DEBUG_STREAM("Calculated " << this_round_iks.size() << " unique IK states this round");
00221   }  // outer loop end
00222 
00223   // Consolidate set into vector for the result
00224   JointConfigVec result;
00225   result.reserve(final_seed_states.size());
00226   for (size_t idx : final_seed_states)
00227   {
00228     result.push_back(createSeedFromPerms(init_state, joint1_perms, pair.first, joint2_perms, pair.second, idx));
00229   }
00230   return result;
00231 }
00232 
00233 JointConfigVec seed::findSeedStatesByPairs(moveit::core::RobotState& state, const std::string& group_name,
00234                                            const std::string& tool_frame, const JointPairVec& pairs)
00235 {
00236   JointConfigVec result;
00237   for (const auto& pair : pairs)
00238   {
00239     JointConfigVec partial_answer = findSeedStatesForPair(state, group_name, tool_frame, pair);
00240     result.insert(result.end(), partial_answer.begin(), partial_answer.end());
00241   }
00242   return result;
00243 }
00244 
00245 JointConfigVec seed::findRandomSeeds(moveit::core::RobotState& state, const std::string& group_name, unsigned n)
00246 {
00247   auto group = state.getJointModelGroup(group_name);
00248 
00249   JointConfigVec result;
00250 
00251   for (unsigned i = 0; i < n; ++i)
00252   {
00253     state.setToRandomPositions();
00254 
00255     JointConfig c;
00256     state.copyJointGroupPositions(group, c);
00257 
00258     result.push_back(c);
00259   }
00260   return result;
00261 }


descartes_moveit
Author(s): Shaun Edwards
autogenerated on Thu Jun 6 2019 21:36:08