CombinatorialOptimizer.cpp
Go to the documentation of this file.
1 
19 
21 
22 
24  std::vector<std::string> pObjectTypes, std::vector<boost::shared_ptr<ISM::ObjectSet>> pExamplesList):
25  mMinFalsePositives(0), // No false positives found, like in fully meshed.
26  mMinFalseNegatives(0), // No false negatives found, like in fully meshed.
27  mMinAverageRecognitionRuntime(0.0), // minimum recognition runtime is not really limited
28  mMinFPInitialized(true), mMinFNInitialized(true), mMinTimeInitialized(true),
29  mMaxFPInitialized(false), mMaxFNInitialized(false), mMaxTimeInitialized(false),
30  mRandomRestartProbability(0.0), // no random restart by default.
31  mPrintHelper('=')
32  {
34 
35  std::string startingTopologiesType;
36  // Try to get the type of starting topology selection.
37  if(!mNodeHandle.getParam("starting_topologies_type", startingTopologiesType))
38  throw std::runtime_error("Please specify parameter starting_topologies_type when starting this node.");
39 
40  int numberOfStartingTopologies;
41  // Try to get the number of starting topologies.
42  if(!mNodeHandle.getParam("number_of_starting_topologies", 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).");
46 
47  bool removeRelations;
48  // Try to get whether to allow the neighbourhood function to remove relations.
49  if(!mNodeHandle.getParam("remove_relations", removeRelations))
50  throw std::runtime_error("Please specify parameter remove_relations when starting this node.");
51 
52  bool swapRelations;
53  // Try to get whether to allow the neighbourhood function to swap relations.
54  if(!mNodeHandle.getParam("swap_relations", swapRelations))
55  throw std::runtime_error("Please specify parameter swap_relations when starting this node.");
56 
57  int maximumNeighbourCount;
58  // Try to get the maximum neighbour count.
59  if(!mNodeHandle.getParam("maximum_neighbour_count", 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).");
63 
64  // Try to get whether to use a flexible threshold:
65  if(!mNodeHandle.getParam("flexible_recognition_threshold", mUseFlexibleRecognitionThreshold))
66  throw std::runtime_error("Please specify parameter flexible_recognition_threshold when starting this node.");
67 
68  double baseRecognitionThreshold;
69  // Try to get the probability threshold over which (>) a scene is considered as recognized.
70  if(!mNodeHandle.getParam("recognition_threshold", baseRecognitionThreshold))
71  throw std::runtime_error("Please specify parameter recognition_threshold when starting this node.");
72  mRecognitionThreshold = std::pow(baseRecognitionThreshold, pObjectTypes.size() - 1);
73 
74 
75  bool quitAfterTestSetEvaluation;
76  // Try to get whether to quit after test set evaluation (helps with testing):
77  if(!mNodeHandle.getParam("quit_after_test_set_evaluation", quitAfterTestSetEvaluation))
78  throw std::runtime_error("Please specify parameter quit_after_test_set_evaluation when starting this node.");
79 
80  // Do not change order of functions below!
81 
82  // Create evaluator
83  mEvaluator.reset(new TopologyEvaluator(pExamplesList, pLearners, mRecognitionThreshold));
84 
85  boost::shared_ptr<SceneModel::AbstractTopologyCreator> topgen(new SceneModel::TopologyCreator(pObjectTypes, maximumNeighbourCount, removeRelations, swapRelations));
86  mTopologyManager.reset(new TopologyManager(pExamplesList, pObjectTypes, topgen , mEvaluator));
87 
88  initTestSets(pObjectTypes, pExamplesList);
89  // evaluator complete
90 
92 
93  if (quitAfterTestSetEvaluation)
94  {
95  ROS_INFO_STREAM("TEST SET EVALUATION COMPLETE: QUITTING EARLY.");
96  exit (EXIT_SUCCESS);
97  }
98 
100 
101  // Initialize components of combinatorial optimization:
102 
103  std::string costFunctionType;
104  // Try to get the type of the cost function.
105  if(!mNodeHandle.getParam("cost_function", costFunctionType))
106  throw std::runtime_error("Please specify parameter cost_function when starting this node.");
107  initCostFunction(costFunctionType);
108 
109  // calculate cost for fully meshed and star topologies and set mBestOptimizedTopology to best.
110  // Has to be done after initialization since the cost function could not be initialised before:
111  if (!mCostFunction) throw std::runtime_error("In CombinatorialTrainer: cost function not initialised.");
112  mBestOptimizedTopology = mTopologyManager->getFullyMeshedTopology();
113  mCostFunction->calculateCost(mBestOptimizedTopology);
114 
115  std::vector<boost::shared_ptr<SceneModel::Topology>> starTopologies = mTopologyManager->getStarTopologies();
116  boost::shared_ptr<SceneModel::Topology> bestStar = starTopologies[0];
117  boost::shared_ptr<SceneModel::Topology> worstStar = starTopologies[0];
118  mCostFunction->calculateCost(bestStar);
119  mCostFunction->calculateCost(worstStar);
120  for (unsigned int i = 1; i < starTopologies.size(); i++)
121  {
122  boost::shared_ptr<SceneModel::Topology> star = starTopologies[i];
123  mCostFunction->calculateCost(star);
124  if (star->getCost() < bestStar->getCost())
125  bestStar = star;
126  if (star->getCost() > worstStar->getCost())
127  worstStar = star;
128  }
129  if (bestStar->getCost() < mBestOptimizedTopology->getCost())
130  mBestOptimizedTopology = bestStar;
131 
132  ROS_INFO_STREAM("Found best topology from fully meshed and stars. Was " << mBestOptimizedTopology->mIdentifier << " with cost " << mBestOptimizedTopology->getCost());
133 
134  bool getWorstStarTopology;
135  // Try to get whether to get the worst of the star topologies.
136  if(!mNodeHandle.getParam("get_worst_star_topology", getWorstStarTopology))
137  throw std::runtime_error("Please specify parameter get_worst_star_topology when starting this node.");
138 
139  if (getWorstStarTopology)
140  {
141  ROS_INFO_STREAM("Worst star is " << worstStar->mIdentifier << " with cost " << worstStar->getCost());
142  mWorstStarIfRequested = worstStar;
143  }
144 
145  initStartingTopologies(numberOfStartingTopologies, startingTopologiesType);
146 
147  std::string neighbourhoodFunctionType;
148  // Try to get the type of the neighbourhood function.
149  if(!mNodeHandle.getParam("neighbourhood_function", neighbourhoodFunctionType))
150  throw std::runtime_error("Please specify parameter neighbourhood_function when starting this node.");
151  initNeighbourhoodFunction(neighbourhoodFunctionType);
152 
153  std::string optimizationAlgorithmType;
154  // Try to get the type of the optimization algorithm.
155  if(!mNodeHandle.getParam("optimization_algorithm", optimizationAlgorithmType))
156  throw std::runtime_error("Please specify parameter optimization_algorithm when starting this node.");
157  initOptimizationAlgorithm(optimizationAlgorithmType);
158  }
159 
161  { }
162 
164  {
166  return mWorstStarIfRequested;
167 
168  mPrintHelper.printAsHeader("Starting optimization.");
169  std::chrono::high_resolution_clock::time_point start = std::chrono::high_resolution_clock::now(); // Get the start time.
170  if (mStartingTopologies.empty()) throw std::runtime_error("No starting topologies found.");
171 
172  unsigned int i = 0;
174  {
175  optimize(startingTopology, i);
176  i++;
177 
178  // check whether to perform a random restart:
179  if (mRandomRestartProbability > 0.0)
180  {
181  std::default_random_engine generator;
182  std::uniform_real_distribution<double> distribution = std::uniform_real_distribution<double>(0.0, 1.0);
183  while (distribution(generator) < mRandomRestartProbability)
184  {
185  mPrintHelper.printAsHeader("PERFORMING RANDOM RESTART.");
186  boost::shared_ptr<SceneModel::Topology> randomStartingTopology = mTopologyManager->getRandomTopology();
187  mEvaluator->evaluate(randomStartingTopology);
188  optimize(randomStartingTopology, i);
189  i++;
190  }
191  }
192  }
193 
194  std::chrono::duration<float> diff = std::chrono::high_resolution_clock::now() - start; // Get the stop time.
195  double optimizationTime = std::chrono::duration_cast<std::chrono::milliseconds>(diff).count();
196 
197  if (!mBestOptimizedTopology) // if no best optimized topology was found:
198  throw std::runtime_error("In CombinatorialTrainer::runOptimization(): No best optimized topology found.");
199 
200  mPrintHelper.addLine("Combinatorial optimization complete.");
201  mPrintHelper.addLine("Optimal topology is " + mBestOptimizedTopology->mIdentifier + " with a cost of " + boost::lexical_cast<std::string>(mBestOptimizedTopology->getCost()));
202  mPrintHelper.addLine("Optimization took " + boost::lexical_cast<std::string>(optimizationTime) + " milliseconds.");
204 
205  return mBestOptimizedTopology;
206  }
207 
208  void CombinatorialOptimizer::initTestSets(const std::vector<std::string>& pObjectTypes, const std::vector<boost::shared_ptr<ISM::ObjectSet>>& pExamplesList)
209  {
210  // Try to get the number of test sets to use.
211  if(!mNodeHandle.getParam("test_set_count", mTestSetCount))
212  throw std::runtime_error("Please specify parameter test_set_count when starting this node.");
213  if (mTestSetCount < 0)
214  throw std::runtime_error("Parameter test_set_count should be larger than 0 (cannot use a negative amount of tets sets).");
215 
216  // Try to get the number of test sets to load.
217  if(!mNodeHandle.getParam("loaded_test_set_count", mLoadedTestSetCount))
218  throw std::runtime_error("Please specify parameter loaded_test_set_count when starting this node.");
219  if (mLoadedTestSetCount < 0)
220  throw std::runtime_error("Parameter loaded_test_set_count should be larger than 0 (cannot load a negative amount of tets sets).");
222  {
224  ROS_INFO_STREAM("Warning: loaded_test_set_count was smaller than test_set_count. Was changed to be equal.");
225  }
226 
227  boost::shared_ptr<SceneModel::Topology> fullyMeshedTopology = mTopologyManager->getFullyMeshedTopology();
228  if (!fullyMeshedTopology) throw std::runtime_error("In CombinatorialTrainer(): failed to get fully meshed topology from TopologyManager");
229 
230  // Create test set generator
231  // Try to get the test set generator type.
232  std::string testSetGeneratorType;
233  if(!mNodeHandle.getParam("test_set_generator_type", testSetGeneratorType))
234  throw std::runtime_error("Please specify parameter test_set_generator_type when starting this node.");
235 
236  boost::shared_ptr<TestSetGenerator> testSetGenerator;
237  if (testSetGeneratorType == "absolute")
238  testSetGenerator.reset(new AbsoluteTestSetGenerator(mEvaluator, fullyMeshedTopology, pObjectTypes));
239  else if (testSetGeneratorType == "relative")
240  testSetGenerator.reset(new RelativeTestSetGenerator(mEvaluator, fullyMeshedTopology, pObjectTypes));
241  else if (testSetGeneratorType == "reference")
242  testSetGenerator.reset(new ReferenceTestSetGenerator(mEvaluator, fullyMeshedTopology, pObjectTypes));
243  else
244  throw std::runtime_error("In CombinatorialOptimizer(): " + testSetGeneratorType + " is not a valid test_set_generator_type. "
245  + "Valid types are absolute, relative, reference.");
246 
247  testSetGenerator->generateTestSets(pExamplesList, mTestSetCount); // completes the evaluator
248  }
249 
251  {
252  boost::shared_ptr<SceneModel::Topology> fm = mTopologyManager->getFullyMeshedTopology();
253 
254  TestSetSelection testSetSelection(mEvaluator);
255 
256  // Take more sets than the test set count to restrict runtime while at the same time accounting for test set removal:
257  testSetSelection.takeXTestSets(mLoadedTestSetCount);
258 
259  // should already have been evaluated if test sets were not loaded from file; if topology was already evaluated, Evaluator returns immediately:
260  // if evaluate() did not return immediately, which indicates that the test sets were loaded from file instead of created, look at probabilities to determine a better recognition threshold:
261  if (mEvaluator->evaluate(fm, true))
262  {
264  {
265  double minValidProbability, maxInvalidProbability;
266  testSetSelection.removeUnusableTestSets(minValidProbability, maxInvalidProbability);
267 
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));
271  }
272  else // remove test sets that would be misclassified with this recognition threshold
273  {
275  }
276 
277  // if there is still more test sets left than asked for, take only X = mTestSetCount of them.
278  // if test sets were not loaded but created, there are exactly testSetCount of them in the first place.
279  testSetSelection.takeXTestSets(mTestSetCount);
280 
281  // since the fully meshed topology was possibly run on different test sets, average recognition runtime needs to be recalculated:
282  double recognitionRuntimeSum = 0;
283  for (boost::shared_ptr<TestSet> valid: mEvaluator->getValidTestSets())
284  recognitionRuntimeSum += valid->getFullyMeshedRecognitionRuntime();
285  for (boost::shared_ptr<TestSet> invalid: mEvaluator->getInvalidTestSets())
286  recognitionRuntimeSum += invalid->getFullyMeshedRecognitionRuntime();
287  fm->setEvaluationResult(recognitionRuntimeSum / (mEvaluator->getValidTestSets().size() + mEvaluator->getInvalidTestSets().size()), // new average recognition runtime
288  0, 0); // since the test sets which would lead to false positives or negatives were specifically removed, there are none such.
289  }
290 
291  mMaxAverageRecognitionRuntime = fm->getAverageRecognitionRuntime();
292 
293  mPrintHelper.addLine("Evaluation of fully meshed topology:");
294  mPrintHelper.addLine("Average recognition runtime (maximum of all topologies) is " + boost::lexical_cast<std::string>(mMaxAverageRecognitionRuntime));
296 
297  mMaxTimeInitialized = true;
298  }
299 
301  {
302  mPrintHelper.printAsHeader("Evaluation of star topologies:");
303 
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.");
306 
307  unsigned int maxFalsePositives = 0;
308  unsigned int maxFalseNegatives = 0;
309  double minAverageRecognitionRuntime = mMaxAverageRecognitionRuntime; // set to maximum for the beginning so it can only get lower
311  {
312  if (!star) throw std::runtime_error("In CombinatorialTrainer::initStarTopologies(): invalid star topology.");
313 
314  mEvaluator->evaluate(star);
315  double starFalsePositives = star->getFalsePositives();
316  double starAverageRecognitionRuntime = star->getAverageRecognitionRuntime();
317  double starFalseNegatives = star->getFalseNegatives();
318  if (starFalsePositives > maxFalsePositives)
319  maxFalsePositives = starFalsePositives; // find maximum
320  if (starFalseNegatives > maxFalseNegatives)
321  maxFalseNegatives = starFalseNegatives;
322  if (starAverageRecognitionRuntime <= minAverageRecognitionRuntime)
323  minAverageRecognitionRuntime = starAverageRecognitionRuntime; // find mimumum
324  }
325  mPrintHelper.addLine("Star topology evaluation complete.");
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));
330 
331  mMaxFalsePositives = maxFalsePositives;
332  mMaxFPInitialized = true;
333  mMaxFalseNegatives = maxFalseNegatives;
334  mMaxFNInitialized = true;
335  }
336 
337  void CombinatorialOptimizer::initStartingTopologies(unsigned int pNumberOfStartingTopologies, const std::string& pStartingTopologiesType)
338  {
339  mPrintHelper.printAsHeader("Initializing " + boost::lexical_cast<std::string>(pNumberOfStartingTopologies) + " starting topologies of type " + pStartingTopologiesType);
340 
341  if (pStartingTopologiesType == "BestStarOrFullyMeshed")
342  {
343  ROS_INFO_STREAM("Using best star or fully meshed as starting topology.");
344  if (pNumberOfStartingTopologies > 1)
345  {
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)");
348  }
350  throw std::runtime_error("In CombinatorialOptimizer::initStartingTopologies(): no valid topology found.");
351  // use the best topology found in setting up the optimization:
353  }
354  else if (pStartingTopologiesType == "Random")
355  {
356  for (unsigned int i = 0; i < pNumberOfStartingTopologies; i++)
357  {
358  mPrintHelper.addLine("Generating random topology");
359  boost::shared_ptr<SceneModel::Topology> randomTopology = mTopologyManager->getRandomTopology();
360  mPrintHelper.addLine("Evaluating random topology " + randomTopology->mIdentifier);
362  mEvaluator->evaluate(randomTopology);
363  mPrintHelper.printAsHeader("Random topology " + randomTopology->mIdentifier + " evaluation complete.");
364 
365  mStartingTopologies.push_back(randomTopology);
366  }
367  }
368  else throw std::runtime_error("Parameter starting_topologies_type has invalid value " + pStartingTopologiesType);
369  }
370 
371  void CombinatorialOptimizer::initCostFunction(const std::string& pType)
372  {
373  if (pType == "WeightedSum")
374  {
375  ROS_INFO_STREAM("Creating WeightedSum as cost function.");
376 
377  double falsePositivesFactor, avgRecognitionTimeFactor, falseNegativesFactor;
378 
379  // Try to get the false positives weight for the cost function.
380  if(!mNodeHandle.getParam("false_positives_weight", falsePositivesFactor))
381  throw std::runtime_error("Please specify parameter false_positives_weight when starting this node.");
382 
383  // Try to get the average recognition runtime weight for the cost function.
384  if(!mNodeHandle.getParam("avg_recognition_time_weight", avgRecognitionTimeFactor))
385  throw std::runtime_error("Please specify parameter avg_recognition_time_weight when starting this node.");
386 
387  // Try to get the false negatives weight for the cost function.
388  if(!mNodeHandle.getParam("false_negatives_weight", falseNegativesFactor))
389  throw std::runtime_error("Please specify parameter false_negatives_weight when starting this node.");
390 
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));
396  }
397  else throw std::runtime_error("Invalid cost function type " + pType);
398  }
399 
401  {
402  if (pType == "TopologyManager")
403  {
404  ROS_INFO_STREAM("Using TopologyManager as neighbourhood function.");
406  }
407  else throw std::runtime_error("Invalid neighbourhood function type " + pType);
408  }
409 
411  {
412  if (pType == "HillClimbing")
413  {
414  ROS_INFO_STREAM("Creating ISM::HillClimbingAlgorithm as optimization algorithm.");
415 
416  double hillClimbingRandomWalkProbability;
417  // Try to get the probability that hill climbing performs a random walk.
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.");
420 
421  // Try to get the probability that hill climbing performs a random restart (for all other algorithms, the default value of 0, no random restart, is used).
422  if(!mNodeHandle.getParam("hill_climbing_random_restart_probability", mRandomRestartProbability))
423  throw std::runtime_error("Please specify parameter hill_climbing_random_restart_probability when starting this node.");
424 
425  mOptimizationAlgorithm.reset(new ISM::HillClimbingAlogrithm<boost::shared_ptr<SceneModel::Topology>>(mNeighbourhoodFunction, mCostFunction, hillClimbingRandomWalkProbability));
426  // class name misspelled as alOGrithm
427  }
428  else if (pType == "RecordHunt")
429  {
430  ROS_INFO_STREAM("Creating ISM::RecordHuntAlgorithm as optimization algorithm.");
431 
432  double initialAcceptableCostDelta, costDeltaDecreaseFactor;
433  // Try to get the initial acceptable cost delta.
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.");
436 
437  // Try to get the probability that hill climbing performs a random walk.
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.");
440 
441 
442  boost::shared_ptr<ISM::AcceptanceFunction> acceptanceFunction(new ISM::CostDeltaAcceptanceFunction(initialAcceptableCostDelta, costDeltaDecreaseFactor));
443  mOptimizationAlgorithm.reset(new ISM::RecordHuntAlgorithm<boost::shared_ptr<SceneModel::Topology>>(mNeighbourhoodFunction, mCostFunction, acceptanceFunction));
444  }
445  else if (pType == "SimulatedAnnealing")
446  {
447  ROS_INFO_STREAM("Creating ISM::SimulatedAnnealingAlgorithm as optimization algorithm.");
448 
449  double startTemperature, endTemperature, temperatureFactor;
450  // Try to get the start temperature.
451  if(!mNodeHandle.getParam("simulated_annealing_start_temperature", startTemperature))
452  throw std::runtime_error("Please specify parameter simulated_annealing_start_temperature when starting this node.");
453 
454  // Try to get the end temperature.
455  if(!mNodeHandle.getParam("simulated_annealing_end_temperature", endTemperature))
456  throw std::runtime_error("Please specify parameter simulated_annealing_end_temperature when starting this node.");
457 
458  int repetitionsBeforeUpdate;
459  // Try to get the number of repetitions before temperature update.
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).");
464 
465  // Try to get the factor by which the temperature changes.
466  if(!mNodeHandle.getParam("simulated_annealing_temperature_factor", temperatureFactor))
467  throw std::runtime_error("Please specify parameter simulated_annealing_temperature_factor when starting this node.");
468 
469  boost::shared_ptr<ISM::CoolingSchedule> coolingSchedule(new ISM::ExponentialCoolingSchedule(startTemperature, endTemperature, repetitionsBeforeUpdate, temperatureFactor));
470  mOptimizationAlgorithm.reset(new ISM::SimulatedAnnealingAlgorithm<boost::shared_ptr<SceneModel::Topology>>(mNeighbourhoodFunction, mCostFunction, coolingSchedule));
471  }
472  else throw std::runtime_error("Invalid optimization algorithm type " + pType);
473  }
474 
475  void CombinatorialOptimizer::optimize(boost::shared_ptr<SceneModel::Topology> pStartingTopology, unsigned int pStartingTopologyNumber)
476  {
477  mPrintHelper.printAsHeader("Optimizing from starting topology " + boost::lexical_cast<std::string>(pStartingTopologyNumber) + " (" + pStartingTopology->mIdentifier + ")");
478 
479  boost::shared_ptr<SceneModel::Topology> optimizedTopology = mOptimizationAlgorithm->optimize(pStartingTopology);
480 
482  throw std::runtime_error("In CombinatorialTrainer::runOptimization(): no valid older best topology.");
483  if (optimizedTopology->getCost() <= mBestOptimizedTopology->getCost())
484  mBestOptimizedTopology = optimizedTopology;
485 
486  mTopologyManager->printHistory(pStartingTopologyNumber);
487  mTopologyManager->resetTopologies(); // set all cached topologies to "unvisited"
488 
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()));
492  }
493 }
boost::shared_ptr< ISM::CostFunction< boost::shared_ptr< SceneModel::Topology > > > mCostFunction
void takeXTestSets(unsigned int pTestSetCount)
void initStartingTopologies(unsigned int pNumberOfStartingTopologies, const std::string &pStartingTopologiesType)
boost::shared_ptr< ISM::NeighbourhoodFunction< boost::shared_ptr< SceneModel::Topology > > > mNeighbourhoodFunction
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< SceneModel::Topology > runOptimization()
boost::shared_ptr< SceneModel::Topology > mBestOptimizedTopology
void addLine(const std::string &pLine)
Definition: PrintHelper.h:48
void removeMisclassifiedTestSets(double pRecognitionThreshold)
boost::shared_ptr< AbstractTopologyEvaluator > mEvaluator
boost::shared_ptr< SceneModel::Topology > mWorstStarIfRequested
void optimize(boost::shared_ptr< SceneModel::Topology > pStartingTopology, unsigned int pStartingTopologyNumber)
std::vector< boost::shared_ptr< SceneModel::Topology > > mStartingTopologies
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
boost::shared_ptr< ISM::OptimizationAlgorithm< boost::shared_ptr< SceneModel::Topology > > > mOptimizationAlgorithm


asr_psm
Author(s): Braun Kai, Gehrung Joachim, Heizmann Heinrich, Meißner Pascal
autogenerated on Fri Nov 15 2019 03:57:54