#include <GTSPSolver.h>

Public Member Functions | |
| void | getActions (const std::vector< unsigned int > &traj, std::vector< unsigned int > &actions) |
| void | getSolution (std::vector< std::vector< double > > &joint_path, std::vector< tf::Pose > &pose_path, std::vector< unsigned int > &action, std::vector< unsigned int > &res_traj) |
| GTSPSolver () | |
| GTSPSolver (double max_adjacency) | |
| void | setAlpha (double alpha) |
Private Member Functions | |
| void | insertStartIntoWeights (const Eigen::MatrixXf &weights, const Eigen::VectorXi &multinode_mapping, Eigen::MatrixXf &new_weights) |
| void | mapGTSPIndexToMultinode (const Eigen::VectorXi &multinode_mapping, const std::vector< unsigned int > &traj, std::vector< unsigned int > &multinode_traj) |
| unsigned int | mapGTSPIndexToMultinode (const Eigen::VectorXi &multinode_mapping, unsigned int node) |
| void | transformGraphToGTSP (const Eigen::MatrixXi &adj_bool, const std::vector< SurfacePatch > &patches, Eigen::VectorXi &mapping, Eigen::MatrixXi &new_adj_bool, Eigen::MatrixXf &new_adj_float) |
| void | transformGTSPToTSP (const Eigen::VectorXi &multinode_mapping, Eigen::MatrixXi &adj_bool, Eigen::MatrixXf &adj_float) |
Private Attributes | |
| double | alpha_ |
Definition at line 10 of file GTSPSolver.h.
Definition at line 13 of file GTSPSolver.cpp.
| GTSPSolver::GTSPSolver | ( | double | max_adjacency | ) |
Definition at line 18 of file GTSPSolver.cpp.
| void GTSPSolver::getActions | ( | const std::vector< unsigned int > & | traj, |
| std::vector< unsigned int > & | actions | ||
| ) | [virtual] |
Implements SolverInterface.
Definition at line 301 of file GTSPSolver.cpp.
| void GTSPSolver::getSolution | ( | std::vector< std::vector< double > > & | joint_path, |
| std::vector< tf::Pose > & | pose_path, | ||
| std::vector< unsigned int > & | action, | ||
| std::vector< unsigned int > & | res_traj | ||
| ) | [virtual] |
Implements SolverInterface.
Definition at line 27 of file GTSPSolver.cpp.
| void GTSPSolver::insertStartIntoWeights | ( | const Eigen::MatrixXf & | weights, |
| const Eigen::VectorXi & | multinode_mapping, | ||
| Eigen::MatrixXf & | new_weights | ||
| ) | [private] |
Definition at line 319 of file GTSPSolver.cpp.
| void GTSPSolver::mapGTSPIndexToMultinode | ( | const Eigen::VectorXi & | multinode_mapping, |
| const std::vector< unsigned int > & | traj, | ||
| std::vector< unsigned int > & | multinode_traj | ||
| ) | [private] |
Definition at line 272 of file GTSPSolver.cpp.
| unsigned int GTSPSolver::mapGTSPIndexToMultinode | ( | const Eigen::VectorXi & | multinode_mapping, |
| unsigned int | node | ||
| ) | [private] |
Definition at line 293 of file GTSPSolver.cpp.
| void GTSPSolver::setAlpha | ( | double | alpha | ) |
Definition at line 23 of file GTSPSolver.cpp.
| void GTSPSolver::transformGraphToGTSP | ( | const Eigen::MatrixXi & | adj_bool, |
| const std::vector< SurfacePatch > & | patches, | ||
| Eigen::VectorXi & | mapping, | ||
| Eigen::MatrixXi & | new_adj_bool, | ||
| Eigen::MatrixXf & | new_adj_float | ||
| ) | [private] |
Definition at line 128 of file GTSPSolver.cpp.
| void GTSPSolver::transformGTSPToTSP | ( | const Eigen::VectorXi & | multinode_mapping, |
| Eigen::MatrixXi & | adj_bool, | ||
| Eigen::MatrixXf & | adj_float | ||
| ) | [private] |
Definition at line 226 of file GTSPSolver.cpp.
double GTSPSolver::alpha_ [private] |
Definition at line 22 of file GTSPSolver.h.