shared_recognition_results_manager.cpp
Go to the documentation of this file.
1 
18 //Local includes
20 #include <ros/ros.h>
21 
22 using namespace std;
23 using namespace ISM;
24 
26 {
27 
28 bool SharedRecognitionResultsManager::addResults(std::vector<ISM::RecognitionResultPtr> &result_ptrs)
29 {
30  mutex_.lock();
31  shared_memory_vector_.insert(shared_memory_vector_.end(), result_ptrs.begin(), result_ptrs.end());
32  ROS_DEBUG_STREAM_NAMED("SharedMemory", "Added: " << result_ptrs.size() << " recognitionresults to shared memory, now containing " << shared_memory_vector_.size() << " recognitionresults");
33  mutex_.unlock();
34  return true;
35 }
36 
37 RecognitionResult SharedRecognitionResultsManager::getLastResult()
38 {
39  ROS_DEBUG_STREAM_NAMED("SharedMemory", "Returning last recognitionresults");
40  return *shared_memory_vector_.back();
41 }
42 
43 std::vector<RecognitionResultPtr> SharedRecognitionResultsManager::getResults()
44 {
45 
46  std::vector<RecognitionResultPtr> results;
47 
48  mutex_.lock();
49  //This should may copy all Recognition Results!!!
50  for (std::vector<RecognitionResultPtr>::iterator it = shared_memory_vector_.begin(); it != shared_memory_vector_.end(); it++)
51  results.push_back(*it);
52 
53  ROS_DEBUG_STREAM_NAMED("SharedMemory", "Returning all (" << shared_memory_vector_.size() << ") recognitionresults");
54 
55  mutex_.unlock();
56 
57  return results;
58 
59 }
60 
61 unsigned int SharedRecognitionResultsManager::getResultsNumber()
62 {
63  ROS_DEBUG_STREAM_NAMED("SharedMemory", "Returning size of shared memory");
64  return shared_memory_vector_.size();
65 }
66 
67 void SharedRecognitionResultsManager::clearResults()
68 {
69  mutex_.lock();
70  shared_memory_vector_.clear();
71  ROS_DEBUG_STREAM_NAMED("SharedMemory", "Cleared shared memory, now containing " << shared_memory_vector_.size() << " recognitionresults");
72  mutex_.unlock();
73 }
74 
75 bool SharedRecognitionResultsManager::recognitionResultsAvailable()
76 {
77  return !shared_memory_vector_.empty();
78 }
79 
80 bool SharedRecognitionResultsManager::popLastResult()
81 {
82  mutex_.lock();
83 
84  if (!shared_memory_vector_.empty())
85  shared_memory_vector_.pop_back();
86  else
87  return false;
88  mutex_.unlock();
89 
90  ROS_DEBUG_STREAM_NAMED("SharedMemory", "Popped last recognitionresult, now containing " << shared_memory_vector_.size() << " recognitionresults");
91  return true;
92 }
93 std::ostream& operator<<(std::ostream &strm, SharedRecognitionResultsManager &p){
94  stringstream s;
95  std::vector<RecognitionResultPtr> rr_vec = p.getResults();
96  s << "[SharedMemory:size=" << rr_vec.size() <<";vector:[";
97  for(RecognitionResultPtr r : rr_vec){
98  s << r << ",";
99  }
100  s << "]]";
101  return strm << s.str();
102 }
103 
104 std::ostream& operator<<(std::ostream &strm, const SharedRecognitionResultsManagerPtr &pPtr){
105  return strm << (*pPtr);
106 }
107 }
#define ROS_DEBUG_STREAM_NAMED(name, args)
XmlRpcServer s
std::ostream & operator<<(std::ostream &strm, SharedRecognitionResultsManager &p)


asr_recognizer_prediction_ism
Author(s): Aumann Florian, Heller Florian, Hutmacher Robin, Meißner Pascal, Stöckle Patrick, Stroh Daniel
autogenerated on Wed Jan 8 2020 03:18:32