Go to the documentation of this file.00001
00004 #ifndef JOINTGTSPSOLVER_H_
00005 #define JOINTGTSPSOLVER_H_
00006
00007 #include<surfacelet/SurfacePatch.h>
00008 #include<coverage_3d_arm_navigation/TrajectoryPlanner.h>
00009 #include<coverage_3d_planning/SolverInterface.h>
00010 #include<tf/tf.h>
00011
00012 class JointGTSPSolver : public SolverInterface{
00013 public:
00014 JointGTSPSolver();
00015 JointGTSPSolver(double max_adjacency, std::string tsp_type);
00016
00017 void getSolution(std::vector<std::vector<double> >& joint_path, std::vector<tf::Pose>& pose_path, std::vector<
00018 unsigned int>& action, std::vector<unsigned int>& res_traj);
00019 void getActions(const std::vector<unsigned int>& traj, std::vector<unsigned int>& actions);
00020
00021 private:
00022
00023 void transformGraphToGTSP(const Eigen::MatrixXi& adj_bool, const std::vector<SurfacePatch>& patches,
00024 const std::vector<std::vector<std::vector<std::vector<double> > > >& coll_free_ik, Eigen::VectorXi& mapping,
00025 Eigen::MatrixXi& new_adj_bool, Eigen::MatrixXf& new_adj_float);
00026 void transformGTSPToTSP(const Eigen::VectorXi& multinode_mapping, Eigen::MatrixXi& adj_bool,
00027 Eigen::MatrixXf& adj_float);
00028 void mapGTSPIndexToMultinode(const Eigen::VectorXi& multinode_mapping, const std::vector<unsigned int>& traj,
00029 std::vector<unsigned int>& multinode_traj);
00030 unsigned int mapGTSPIndexToMultinode(const Eigen::VectorXi& multinode_mapping, unsigned int node);
00031 void insertStartIntoWeights(const Eigen::MatrixXf& weights, const Eigen::VectorXi& multinode_mapping,
00032 Eigen::MatrixXf& new_weights);
00033 void getJointPoses(const Eigen::VectorXi& multinode_mapping,
00034 const std::vector<unsigned int>& traj, std::vector<std::vector<double> >& joint_path);
00035 };
00036
00037 #endif