Main Page
Namespaces
Classes
Files
File List
File Members
src
learner.cpp
Go to the documentation of this file.
1
18
// Global includes
19
#include <cstdlib>
20
21
// Package includes
22
#include <
ros/ros.h
>
23
24
#include <
learner/pbd_computation_graph.hpp
>
25
26
// Local includes
27
#include "
learner/SceneLearningEngine.h
"
28
29
30
using namespace
ProbabilisticSceneRecognition
;
31
32
33
int
main
(
int
argc,
char
* argv[])
34
{
35
36
ros::init
(argc, argv,
"js_probabilistic_scene_learner"
);
37
38
// Declaration of the learner for the scene model.
39
SceneLearningEngine
* learner;
40
41
// Check for wrong configurations and similar.
42
try
{
43
learner =
new
SceneLearningEngine
();
44
45
}
catch
(std::exception& exception){
46
std::cerr << exception.what() << std::endl;
47
std::exit(1);
48
}
49
50
// Get all ISM::ObjectSets from database files passed as ros parameters.
51
learner->
readLearnerInput
();
52
53
// Check for errors with the resulting scene model
54
try
{
55
// Calculate parameters of scene model based on scene graphs from rosbag input.
56
learner->
generateSceneModel
();
57
58
// Dump model to file and plot its distributions.
59
learner->
saveSceneModel
();
60
}
catch
(std::exception& exception) {
61
std::cerr << exception.what() << std::endl;
62
}
63
64
// Specifies the updates per second.
65
ros::Rate
rate(30);
66
67
// Run main loop until termination.
68
while
(
ros::ok
())
69
{
70
// Visualize the model.
71
learner->
visualizeSceneModel
();
72
73
// Sleep for the given time in seconds.
74
rate.
sleep
();
75
}
76
77
// Get rid of learner object.
78
delete
learner;
79
80
// Stating that program has run correctly.
81
return
EXIT_SUCCESS;
82
}
83
ProbabilisticSceneRecognition::SceneLearningEngine::visualizeSceneModel
void visualizeSceneModel()
Definition:
SceneLearningEngine.cpp:174
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Rate
pbd_computation_graph.hpp
main
int main(int argc, char *argv[])
Definition:
learner.cpp:33
ros::ok
ROSCPP_DECL bool ok()
ProbabilisticSceneRecognition::SceneLearningEngine
Definition:
SceneLearningEngine.h:48
ProbabilisticSceneRecognition::SceneLearningEngine::generateSceneModel
void generateSceneModel()
Definition:
SceneLearningEngine.cpp:140
ProbabilisticSceneRecognition
Definition:
MappedProbabilityTable.h:33
ros::Rate::sleep
bool sleep()
ros.h
ProbabilisticSceneRecognition::SceneLearningEngine::readLearnerInput
void readLearnerInput()
Definition:
SceneLearningEngine.cpp:107
ProbabilisticSceneRecognition::SceneLearningEngine::saveSceneModel
void saveSceneModel()
Definition:
SceneLearningEngine.cpp:153
SceneLearningEngine.h
asr_psm
Author(s): Braun Kai, Gehrung Joachim, Heizmann Heinrich, Meißner Pascal
autogenerated on Fri Nov 15 2019 03:57:54