Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00035 #ifndef SEED_SEARCH_H
00036 #define SEED_SEARCH_H
00037
00038 #include <moveit/robot_state/robot_state.h>
00039
00040 namespace descartes_moveit
00041 {
00042 namespace seed
00043 {
00055 std::vector<std::vector<double> > findSeedStatesByPairs(moveit::core::RobotState& state, const std::string& group_name,
00056 const std::string& tool_frame,
00057 const std::vector<std::pair<unsigned, unsigned> >& pairs);
00058
00064 inline std::vector<std::vector<double> > findIndustrialSixDOFSeeds(moveit::core::RobotState& state,
00065 const std::string& group_name,
00066 const std::string& tool_frame)
00067 {
00068 return findSeedStatesByPairs(state, group_name, tool_frame, { { 1, 2 }, { 3, 5 } });
00069 }
00070
00079 std::vector<std::vector<double> > findRandomSeeds(moveit::core::RobotState& state, const std::string& group_name,
00080 unsigned n);
00081
00082 }
00083 }
00084
00085 #endif // SEED_SEARCH_H