Functions | |
| std::vector< std::vector < double > > | findIndustrialSixDOFSeeds (moveit::core::RobotState &state, const std::string &group_name, const std::string &tool_frame) |
| findIndustrialSixDOFSeeds() is a specialization of findSeedStatesByPairs() that searches for seed states over joints 2,3 and 4,6 (1 indexed). These joints often form elbow and wrist configurations. | |
| std::vector< std::vector < double > > | findRandomSeeds (moveit::core::RobotState &state, const std::string &group_name, unsigned n) |
| Uses moveit's underlying random function to find n random joint configurations that satisfy model bounds. | |
| std::vector< std::vector < double > > | findSeedStatesByPairs (moveit::core::RobotState &state, const std::string &group_name, const std::string &tool_frame, const std::vector< std::pair< unsigned, unsigned > > &pairs) |
| Returns a sequence of seed states for iterative inverse kinematic solvers to use when 'sampling' the solution space of a pose. These seeds are generated by iterating through all possible joint permutations of each pair of joints passed in by the user. | |
| std::vector<std::vector<double> > descartes_moveit::seed::findIndustrialSixDOFSeeds | ( | moveit::core::RobotState & | state, |
| const std::string & | group_name, | ||
| const std::string & | tool_frame | ||
| ) | [inline] |
findIndustrialSixDOFSeeds() is a specialization of findSeedStatesByPairs() that searches for seed states over joints 2,3 and 4,6 (1 indexed). These joints often form elbow and wrist configurations.
Definition at line 64 of file seed_search.h.
| JointConfigVec descartes_moveit::seed::findRandomSeeds | ( | moveit::core::RobotState & | state, |
| const std::string & | group_name, | ||
| unsigned | n | ||
| ) |
Uses moveit's underlying random function to find n random joint configurations that satisfy model bounds.
| state | Shared pointer to robot state used to perform FK/IK |
| group_name | Name of the move group for which to generate seeds |
| n | Number of random seeds to create |
Definition at line 245 of file seed_search.cpp.
| std::vector<std::vector<double> > descartes_moveit::seed::findSeedStatesByPairs | ( | moveit::core::RobotState & | state, |
| const std::string & | group_name, | ||
| const std::string & | tool_frame, | ||
| const std::vector< std::pair< unsigned, unsigned > > & | pairs | ||
| ) |
Returns a sequence of seed states for iterative inverse kinematic solvers to use when 'sampling' the solution space of a pose. These seeds are generated by iterating through all possible joint permutations of each pair of joints passed in by the user.
| state | Shared pointer to robot state used to perform FK/IK |
| group_name | Name of the move group for which to generate seeds |
| tool_frame | The name of the tool link in which to work with FK/IK |
| pairs | A sequence of joint pairs used to generate the seed states. |