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
00036 #ifndef SEED_SEARCH_H
00037 #define SEED_SEARCH_H
00038
00039 #include <moveit/robot_state/robot_state.h>
00040
00041 namespace descartes_moveit
00042 {
00043 namespace seed
00044 {
00045
00057 std::vector<std::vector<double> >
00058 findSeedStatesByPairs(moveit::core::RobotState& state,
00059 const std::string& group_name,
00060 const std::string& tool_frame,
00061 const std::vector<std::pair<unsigned, unsigned> >& pairs);
00062
00068 inline std::vector<std::vector<double> >
00069 findIndustrialSixDOFSeeds(moveit::core::RobotState& state,
00070 const std::string& group_name,
00071 const std::string& tool_frame)
00072 {
00073 return findSeedStatesByPairs(state, group_name, tool_frame, {{1,2}, {3,5}});
00074 }
00075
00084 std::vector<std::vector<double> >
00085 findRandomSeeds(moveit::core::RobotState& state,
00086 const std::string& group_name,
00087 unsigned n);
00088
00089 }
00090 }
00091
00092 #endif // SEED_SEARCH_H
00093