#include <SolverInterface.h>
Public Member Functions | |
virtual void | getActions (const std::vector< unsigned int > &traj, std::vector< unsigned int > &actions)=0 |
double | getMaxAdjacency () const |
virtual 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)=0 |
void | setDistMeasure (std::string measure) |
void | setGraph (const std::vector< SurfacePatch > &patches, const std::vector< pcl::PointXYZ > &surface_points, const Eigen::MatrixXi &adjacency, const std::vector< std::vector< tf::Pose > > &coll_free_poses, const std::vector< std::vector< std::vector< std::vector< double > > > > &coll_free_ik) |
void | setMaxAdjacency (double adjacency) |
void | setStartPose (std::vector< double > joint_pose, tf::Pose pose) |
SolverInterface () | |
SolverInterface (double max_adjacency) | |
Protected Attributes | |
Eigen::MatrixXi | adjacency_ |
std::vector< std::vector < std::vector< std::vector < double > > > > | coll_free_ik_ |
std::vector< std::vector < tf::Pose > > | coll_free_poses_ |
std::string | dist_measure_ |
double | max_adjacency_ |
std::vector< SurfacePatch > | patches_ |
std::vector< double > | start_joint_ |
tf::Pose | start_pose_ |
std::vector< pcl::PointXYZ > | surface_points_ |
TrajectoryPlanner | traj_planner_ |
Definition at line 9 of file SolverInterface.h.
Definition at line 5 of file SolverInterface.cpp.
SolverInterface::SolverInterface | ( | double | max_adjacency | ) |
Definition at line 9 of file SolverInterface.cpp.
virtual void SolverInterface::getActions | ( | const std::vector< unsigned int > & | traj, |
std::vector< unsigned int > & | actions | ||
) | [pure virtual] |
Implemented in JointGTSPSolver, GTSPSolver, and TSPSolver.
double SolverInterface::getMaxAdjacency | ( | ) | const |
Definition at line 36 of file SolverInterface.cpp.
virtual void SolverInterface::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 | ||
) | [pure virtual] |
Implemented in JointGTSPSolver, GTSPSolver, and TSPSolver.
void SolverInterface::setDistMeasure | ( | std::string | measure | ) |
Definition at line 14 of file SolverInterface.cpp.
void SolverInterface::setGraph | ( | const std::vector< SurfacePatch > & | patches, |
const std::vector< pcl::PointXYZ > & | surface_points, | ||
const Eigen::MatrixXi & | adjacency, | ||
const std::vector< std::vector< tf::Pose > > & | coll_free_poses, | ||
const std::vector< std::vector< std::vector< std::vector< double > > > > & | coll_free_ik | ||
) |
Definition at line 18 of file SolverInterface.cpp.
void SolverInterface::setMaxAdjacency | ( | double | adjacency | ) |
Definition at line 33 of file SolverInterface.cpp.
void SolverInterface::setStartPose | ( | std::vector< double > | joint_pose, |
tf::Pose | pose | ||
) |
Definition at line 28 of file SolverInterface.cpp.
Eigen::MatrixXi SolverInterface::adjacency_ [protected] |
Definition at line 36 of file SolverInterface.h.
std::vector<std::vector<std::vector<std::vector<double> > > > SolverInterface::coll_free_ik_ [protected] |
Definition at line 38 of file SolverInterface.h.
std::vector<std::vector<tf::Pose> > SolverInterface::coll_free_poses_ [protected] |
Definition at line 37 of file SolverInterface.h.
std::string SolverInterface::dist_measure_ [protected] |
Definition at line 29 of file SolverInterface.h.
double SolverInterface::max_adjacency_ [protected] |
Definition at line 30 of file SolverInterface.h.
std::vector<SurfacePatch> SolverInterface::patches_ [protected] |
Definition at line 34 of file SolverInterface.h.
std::vector<double> SolverInterface::start_joint_ [protected] |
Definition at line 32 of file SolverInterface.h.
tf::Pose SolverInterface::start_pose_ [protected] |
Definition at line 33 of file SolverInterface.h.
std::vector<pcl::PointXYZ> SolverInterface::surface_points_ [protected] |
Definition at line 35 of file SolverInterface.h.
TrajectoryPlanner SolverInterface::traj_planner_ [protected] |
Definition at line 39 of file SolverInterface.h.