20 #include <boost/filesystem.hpp> 22 #include <topology_creator/TopologyCreator.h> 24 #include <ISM/combinatorial_optimization/HillClimbingAlogrithm.hpp> 25 #include <ISM/combinatorial_optimization/RecordHuntAlgorithm.hpp> 26 #include <ISM/combinatorial_optimization/CostDeltaAcceptanceFunction.hpp> 27 #include <ISM/combinatorial_optimization/SimulatedAnnealingAlgorithm.hpp> 28 #include <ISM/combinatorial_optimization/ExponentialCoolingSchedule.hpp> 30 #include <ISM/common_type/ObjectSet.hpp> 98 void initStartingTopologies(
unsigned int pNumberOfStartingTopologies,
const std::string& pStartingTopologiesType);
boost::shared_ptr< ISM::CostFunction< boost::shared_ptr< SceneModel::Topology > > > mCostFunction
unsigned int mMaxFalsePositives
void initOptimizationAlgorithm(const std::string &pType)
void initStartingTopologies(unsigned int pNumberOfStartingTopologies, const std::string &pStartingTopologiesType)
void initFullyMeshedTopologyAndFilterLoadedTestSets()
boost::shared_ptr< ISM::NeighbourhoodFunction< boost::shared_ptr< SceneModel::Topology > > > mNeighbourhoodFunction
ros::NodeHandle mNodeHandle
unsigned int mMaxFalseNegatives
void initTestSets(const std::vector< std::string > &pObjectTypes, const std::vector< boost::shared_ptr< ISM::ObjectSet >> &pExamplesList)
CombinatorialOptimizer(std::vector< boost::shared_ptr< SceneObjectLearner >> pLearners, std::vector< std::string > pObjectTypes, std::vector< boost::shared_ptr< ISM::ObjectSet >> pExamplesList)
boost::shared_ptr< SceneModel::Topology > mFullyMeshedTopology
boost::shared_ptr< TopologyManager > mTopologyManager
boost::shared_ptr< SceneModel::Topology > runOptimization()
boost::shared_ptr< SceneModel::Topology > mBestOptimizedTopology
unsigned int mMinFalseNegatives
void initCostFunction(const std::string &pType)
unsigned int mMinFalsePositives
void initNeighbourhoodFunction(const std::string &pType)
~CombinatorialOptimizer()
double mMaxAverageRecognitionRuntime
boost::shared_ptr< AbstractTopologyEvaluator > mEvaluator
boost::shared_ptr< SceneModel::Topology > mWorstStarIfRequested
void initStarTopologies()
void optimize(boost::shared_ptr< SceneModel::Topology > pStartingTopology, unsigned int pStartingTopologyNumber)
std::vector< boost::shared_ptr< SceneModel::Topology > > mStarTopologies
std::vector< boost::shared_ptr< SceneModel::Topology > > mStartingTopologies
double mRecognitionThreshold
boost::shared_ptr< ISM::OptimizationAlgorithm< boost::shared_ptr< SceneModel::Topology > > > mOptimizationAlgorithm
bool mUseFlexibleRecognitionThreshold
double mMinAverageRecognitionRuntime
double mRandomRestartProbability