25 mMinFalsePositives(0),
26 mMinFalseNegatives(0),
27 mMinAverageRecognitionRuntime(0.0),
28 mMinFPInitialized(true), mMinFNInitialized(true), mMinTimeInitialized(true),
29 mMaxFPInitialized(false), mMaxFNInitialized(false), mMaxTimeInitialized(false),
30 mRandomRestartProbability(0.0),
35 std::string startingTopologiesType;
38 throw std::runtime_error(
"Please specify parameter starting_topologies_type when starting this node.");
40 int numberOfStartingTopologies;
43 throw std::runtime_error(
"Please specify parameter number_of_starting_topologies when starting this node.");
44 if (numberOfStartingTopologies < 1)
45 throw std::runtime_error(
"Parameter number_of_starting_topologies should be larger than 0 (cannot use a negative amount of starting topologies).");
50 throw std::runtime_error(
"Please specify parameter remove_relations when starting this node.");
55 throw std::runtime_error(
"Please specify parameter swap_relations when starting this node.");
57 int maximumNeighbourCount;
60 throw std::runtime_error(
"Please specify parameter maximum_neighbour_count when starting this node.");
61 if (maximumNeighbourCount < 1)
62 throw std::runtime_error(
"Parameter maximum_neighbour_count should be larger than 0 (cannot use a negative amount of neighbours).");
66 throw std::runtime_error(
"Please specify parameter flexible_recognition_threshold when starting this node.");
68 double baseRecognitionThreshold;
71 throw std::runtime_error(
"Please specify parameter recognition_threshold when starting this node.");
75 bool quitAfterTestSetEvaluation;
78 throw std::runtime_error(
"Please specify parameter quit_after_test_set_evaluation when starting this node.");
93 if (quitAfterTestSetEvaluation)
103 std::string costFunctionType;
106 throw std::runtime_error(
"Please specify parameter cost_function when starting this node.");
111 if (!
mCostFunction)
throw std::runtime_error(
"In CombinatorialTrainer: cost function not initialised.");
115 std::vector<boost::shared_ptr<SceneModel::Topology>> starTopologies =
mTopologyManager->getStarTopologies();
120 for (
unsigned int i = 1; i < starTopologies.size(); i++)
124 if (star->getCost() < bestStar->getCost())
126 if (star->getCost() > worstStar->getCost())
134 bool getWorstStarTopology;
137 throw std::runtime_error(
"Please specify parameter get_worst_star_topology when starting this node.");
139 if (getWorstStarTopology)
141 ROS_INFO_STREAM(
"Worst star is " << worstStar->mIdentifier <<
" with cost " << worstStar->getCost());
147 std::string neighbourhoodFunctionType;
150 throw std::runtime_error(
"Please specify parameter neighbourhood_function when starting this node.");
153 std::string optimizationAlgorithmType;
156 throw std::runtime_error(
"Please specify parameter optimization_algorithm when starting this node.");
169 std::chrono::high_resolution_clock::time_point start = std::chrono::high_resolution_clock::now();
170 if (
mStartingTopologies.empty())
throw std::runtime_error(
"No starting topologies found.");
181 std::default_random_engine generator;
182 std::uniform_real_distribution<double> distribution = std::uniform_real_distribution<double>(0.0, 1.0);
188 optimize(randomStartingTopology, i);
194 std::chrono::duration<float> diff = std::chrono::high_resolution_clock::now() - start;
195 double optimizationTime = std::chrono::duration_cast<std::chrono::milliseconds>(diff).count();
198 throw std::runtime_error(
"In CombinatorialTrainer::runOptimization(): No best optimized topology found.");
202 mPrintHelper.
addLine(
"Optimization took " + boost::lexical_cast<std::string>(optimizationTime) +
" milliseconds.");
212 throw std::runtime_error(
"Please specify parameter test_set_count when starting this node.");
214 throw std::runtime_error(
"Parameter test_set_count should be larger than 0 (cannot use a negative amount of tets sets).");
218 throw std::runtime_error(
"Please specify parameter loaded_test_set_count when starting this node.");
220 throw std::runtime_error(
"Parameter loaded_test_set_count should be larger than 0 (cannot load a negative amount of tets sets).");
224 ROS_INFO_STREAM(
"Warning: loaded_test_set_count was smaller than test_set_count. Was changed to be equal.");
228 if (!fullyMeshedTopology)
throw std::runtime_error(
"In CombinatorialTrainer(): failed to get fully meshed topology from TopologyManager");
232 std::string testSetGeneratorType;
234 throw std::runtime_error(
"Please specify parameter test_set_generator_type when starting this node.");
237 if (testSetGeneratorType ==
"absolute")
239 else if (testSetGeneratorType ==
"relative")
241 else if (testSetGeneratorType ==
"reference")
244 throw std::runtime_error(
"In CombinatorialOptimizer(): " + testSetGeneratorType +
" is not a valid test_set_generator_type. " 245 +
"Valid types are absolute, relative, reference.");
247 testSetGenerator->generateTestSets(pExamplesList,
mTestSetCount);
265 double minValidProbability, maxInvalidProbability;
268 double flexibleRecognitionThreshold = ((minValidProbability - maxInvalidProbability) / 2) + maxInvalidProbability;
269 mEvaluator->setRecognitionThreshold(flexibleRecognitionThreshold);
270 mPrintHelper.
printAsHeader(
"Recognition threshold set to flexible " + boost::lexical_cast<std::string>(flexibleRecognitionThreshold));
282 double recognitionRuntimeSum = 0;
284 recognitionRuntimeSum += valid->getFullyMeshedRecognitionRuntime();
286 recognitionRuntimeSum += invalid->getFullyMeshedRecognitionRuntime();
287 fm->setEvaluationResult(recognitionRuntimeSum / (
mEvaluator->getValidTestSets().size() +
mEvaluator->getInvalidTestSets().size()),
304 std::vector<boost::shared_ptr<SceneModel::Topology>> stars =
mTopologyManager->getStarTopologies();
305 if (stars.empty())
throw std::runtime_error(
"In CombinatorialTrainer::initStarTopologies(): no star topologies found.");
307 unsigned int maxFalsePositives = 0;
308 unsigned int maxFalseNegatives = 0;
312 if (!star)
throw std::runtime_error(
"In CombinatorialTrainer::initStarTopologies(): invalid star topology.");
315 double starFalsePositives = star->getFalsePositives();
316 double starAverageRecognitionRuntime = star->getAverageRecognitionRuntime();
317 double starFalseNegatives = star->getFalseNegatives();
318 if (starFalsePositives > maxFalsePositives)
319 maxFalsePositives = starFalsePositives;
320 if (starFalseNegatives > maxFalseNegatives)
321 maxFalseNegatives = starFalseNegatives;
322 if (starAverageRecognitionRuntime <= minAverageRecognitionRuntime)
323 minAverageRecognitionRuntime = starAverageRecognitionRuntime;
326 mPrintHelper.
addLine(
"Maximum number of false positives is " + boost::lexical_cast<std::string>(maxFalsePositives));
327 mPrintHelper.
addLine(
"Maximum number of false negatives is " + boost::lexical_cast<std::string>(maxFalseNegatives));
328 mPrintHelper.
addLine(
"Minimum average runtime is " + boost::lexical_cast<std::string>(minAverageRecognitionRuntime));
339 mPrintHelper.
printAsHeader(
"Initializing " + boost::lexical_cast<std::string>(pNumberOfStartingTopologies) +
" starting topologies of type " + pStartingTopologiesType);
341 if (pStartingTopologiesType ==
"BestStarOrFullyMeshed")
343 ROS_INFO_STREAM(
"Using best star or fully meshed as starting topology.");
344 if (pNumberOfStartingTopologies > 1)
346 ROS_INFO_STREAM(
"There is only one best topology from stars and fully meshed, which will be used as the single starting topology ");
347 ROS_INFO_STREAM(
"(change number_of_starting_topologies to 1 or start_topologies to something other than BestStarOrFullyMeshed)");
350 throw std::runtime_error(
"In CombinatorialOptimizer::initStartingTopologies(): no valid topology found.");
354 else if (pStartingTopologiesType ==
"Random")
356 for (
unsigned int i = 0; i < pNumberOfStartingTopologies; i++)
368 else throw std::runtime_error(
"Parameter starting_topologies_type has invalid value " + pStartingTopologiesType);
373 if (pType ==
"WeightedSum")
377 double falsePositivesFactor, avgRecognitionTimeFactor, falseNegativesFactor;
381 throw std::runtime_error(
"Please specify parameter false_positives_weight when starting this node.");
385 throw std::runtime_error(
"Please specify parameter avg_recognition_time_weight when starting this node.");
389 throw std::runtime_error(
"Please specify parameter false_negatives_weight when starting this node.");
392 throw std::runtime_error(
"In CombinatorialTrainer::initCostFunction: some of the minima and maxima for false positives and runtime are not initialized.");
395 falsePositivesFactor, avgRecognitionTimeFactor, falseNegativesFactor));
397 else throw std::runtime_error(
"Invalid cost function type " + pType);
402 if (pType ==
"TopologyManager")
407 else throw std::runtime_error(
"Invalid neighbourhood function type " + pType);
412 if (pType ==
"HillClimbing")
414 ROS_INFO_STREAM(
"Creating ISM::HillClimbingAlgorithm as optimization algorithm.");
416 double hillClimbingRandomWalkProbability;
418 if(!
mNodeHandle.
getParam(
"hill_climbing_random_walk_probability", hillClimbingRandomWalkProbability))
419 throw std::runtime_error(
"Please specify parameter hill_climbing_random_walk_probability when starting this node.");
423 throw std::runtime_error(
"Please specify parameter hill_climbing_random_restart_probability when starting this node.");
428 else if (pType ==
"RecordHunt")
430 ROS_INFO_STREAM(
"Creating ISM::RecordHuntAlgorithm as optimization algorithm.");
432 double initialAcceptableCostDelta, costDeltaDecreaseFactor;
434 if(!
mNodeHandle.
getParam(
"record_hunt_initial_acceptable_cost_delta", initialAcceptableCostDelta))
435 throw std::runtime_error(
"Please specify parameter record_hunt_initial_acceptable_cost_delta when starting this node.");
438 if(!
mNodeHandle.
getParam(
"record_hunt_cost_delta_decrease_factor", costDeltaDecreaseFactor))
439 throw std::runtime_error(
"Please specify parameter record_hunt_cost_delta_decrease_factor when starting this node.");
445 else if (pType ==
"SimulatedAnnealing")
447 ROS_INFO_STREAM(
"Creating ISM::SimulatedAnnealingAlgorithm as optimization algorithm.");
449 double startTemperature, endTemperature, temperatureFactor;
452 throw std::runtime_error(
"Please specify parameter simulated_annealing_start_temperature when starting this node.");
456 throw std::runtime_error(
"Please specify parameter simulated_annealing_end_temperature when starting this node.");
458 int repetitionsBeforeUpdate;
460 if(!
mNodeHandle.
getParam(
"simulated_annealing_repetitions_before_update", repetitionsBeforeUpdate))
461 throw std::runtime_error(
"Please specify parameter simulated_annealing_repetitions_before_update when starting this node.");
462 if (repetitionsBeforeUpdate < 0)
463 throw std::runtime_error(
"Parameter simulated_annealing_repetitions_before_update should be larger than 0 (cannot repeat steps a negative amount of times).");
467 throw std::runtime_error(
"Please specify parameter simulated_annealing_temperature_factor when starting this node.");
472 else throw std::runtime_error(
"Invalid optimization algorithm type " + pType);
477 mPrintHelper.
printAsHeader(
"Optimizing from starting topology " + boost::lexical_cast<std::string>(pStartingTopologyNumber) +
" (" + pStartingTopology->mIdentifier +
")");
482 throw std::runtime_error(
"In CombinatorialTrainer::runOptimization(): no valid older best topology.");
489 mPrintHelper.
addLine(
"Optimization from starting topology " + boost::lexical_cast<std::string>(pStartingTopologyNumber) +
" (" + pStartingTopology->mIdentifier +
") complete.");
490 mPrintHelper.
addLine(
"Best topology is " + optimizedTopology->mIdentifier +
" with cost " + boost::lexical_cast<std::string>(optimizedTopology->getCost()));
boost::shared_ptr< ISM::CostFunction< boost::shared_ptr< SceneModel::Topology > > > mCostFunction
void takeXTestSets(unsigned int pTestSetCount)
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)
void removeUnusableTestSets(double &pMinValidProbability, double &pMaxInvalidProbability)
boost::shared_ptr< TopologyManager > mTopologyManager
boost::shared_ptr< SceneModel::Topology > runOptimization()
boost::shared_ptr< SceneModel::Topology > mBestOptimizedTopology
unsigned int mMinFalseNegatives
void addLine(const std::string &pLine)
void initCostFunction(const std::string &pType)
unsigned int mMinFalsePositives
void removeMisclassifiedTestSets(double pRecognitionThreshold)
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 > > mStartingTopologies
#define ROS_INFO_STREAM(args)
double mRecognitionThreshold
bool getParam(const std::string &key, std::string &s) const
boost::shared_ptr< ISM::OptimizationAlgorithm< boost::shared_ptr< SceneModel::Topology > > > mOptimizationAlgorithm
bool mUseFlexibleRecognitionThreshold
double mMinAverageRecognitionRuntime
double mRandomRestartProbability