JeVois  1.12
JeVois Smart Embedded Machine Vision Toolkit
Share this page:
Component.C
Go to the documentation of this file.
1 // ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
2 //
3 // JeVois Smart Embedded Machine Vision Toolkit - Copyright (C) 2016 by Laurent Itti, the University of Southern
4 // California (USC), and iLab at USC. See http://iLab.usc.edu and http://jevois.org for information about this project.
5 //
6 // This file is part of the JeVois Smart Embedded Machine Vision Toolkit. This program is free software; you can
7 // redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software
8 // Foundation, version 2. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY;
9 // without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
10 // License for more details. You should have received a copy of the GNU General Public License along with this program;
11 // if not, write to the Free Software Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
12 //
13 // Contact information: Laurent Itti - 3641 Watt Way, HNB-07A - Los Angeles, CA 90089-2520 - USA.
14 // Tel: +1 213 740 3527 - itti@pollux.usc.edu - http://iLab.usc.edu - http://jevois.org
15 // ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
16 /*! \file */
17 
18 // This code is inspired by the Neuromorphic Robotics Toolkit (http://nrtkit.org)
19 
20 #include <jevois/Debug/Log.H>
24 #include <jevois/Core/Engine.H>
25 #include <jevois/Util/Utils.H>
27 
28 #include <fstream>
29 #include <algorithm> // for std::all_of
30 
31 // ######################################################################
32 jevois::Component::Component(std::string const & instanceName) :
33  itsInstanceName(instanceName), itsInitialized(false), itsParent(nullptr), itsPath()
34 {
35  JEVOIS_TRACE(5);
36 }
37 
38 // ######################################################################
39 std::string const & jevois::Component::className() const
40 {
41  boost::shared_lock<boost::shared_mutex> lck(itsMetaMtx);
42 
43  // We need the (derived!) component to be fully constructed for demangle to work, hence the const_cast here:
44  if (itsClassName.empty()) *(const_cast<std::string *>(&itsClassName)) = jevois::demangle(typeid(*this).name());
45 
46  return itsClassName;
47 }
48 
49 // ######################################################################
50 std::string const & jevois::Component::instanceName() const
51 { return itsInstanceName; }
52 
53 // ######################################################################
55 {
56  JEVOIS_TRACE(5);
57 
58  LDEBUG("Deleting Component");
59 
60  // Recursively un-init us and our subs; call base class version as derived classes are destroyed:
61  if (itsInitialized) jevois::Component::uninit();
62 
63  // All right, we need to nuke our subs BEFORE we get destroyed, since they will backflow to us (for param
64  // notices, recursive descriptor access, etc):
65  boost::upgrade_lock<boost::shared_mutex> uplck(itsSubMtx);
66 
67  while (itsSubComponents.empty() == false)
68  {
69  auto itr = itsSubComponents.begin();
70  doRemoveSubComponent(itr, uplck, "SubComponent");
71  }
72 }
73 
74 // ######################################################################
75 void jevois::Component::removeSubComponent(std::string const & instanceName, bool warnIfNotFound)
76 {
77  JEVOIS_TRACE(5);
78 
79  boost::upgrade_lock<boost::shared_mutex> uplck(itsSubMtx);
80 
81  for (auto itr = itsSubComponents.begin(); itr != itsSubComponents.end(); ++itr)
82  if ((*itr)->instanceName() == instanceName)
83  {
84  // All checks out, get doRemoveSubComponent() to do the work:
85  doRemoveSubComponent(itr, uplck, "SubComponent");
86  return;
87  }
88 
89  if (warnIfNotFound) LERROR("SubComponent [" << instanceName << "] not found. Ignored.");
90 }
91 
92 // ######################################################################
93 void jevois::Component::doRemoveSubComponent(std::vector<std::shared_ptr<jevois::Component> >::iterator & itr,
94  boost::upgrade_lock<boost::shared_mutex> & uplck,
95  std::string const & displayname)
96 {
97  JEVOIS_TRACE(5);
98 
99  // Try to delete and let's check that it will actually be deleted:
100  std::shared_ptr<jevois::Component> component = *itr;
101 
102  LDEBUG("Removing " << displayname << " [" << component->descriptor() << ']');
103 
104  // Un-init the component:
105  if (component->initialized()) component->uninit();
106 
107  // Remove it from our list of subs:
108  boost::upgrade_to_unique_lock<boost::shared_mutex> ulck(uplck);
109  itsSubComponents.erase(itr);
110 
111  if (component.use_count() > 1)
112  LERROR(component.use_count() - 1 << " additional external shared_ptr reference(s) exist to "
113  << displayname << " [" << component->descriptor() << "]. It was removed but NOT deleted.");
114 
115  component.reset(); // nuke the shared_ptr, this should yield a delete unless use_count was > 1
116 }
117 
118 // ######################################################################
120 {
121  JEVOIS_TRACE(6);
122 
123  boost::shared_lock<boost::shared_mutex> lck(itsMtx);
124  if (dynamic_cast<jevois::Manager *>(itsParent) != nullptr) return true;
125  return false;
126 }
127 
128 // ######################################################################
130 {
131  JEVOIS_TRACE(6);
132 
133  boost::shared_lock<boost::shared_mutex> lck(itsMtx);
134  jevois::Engine * eng = dynamic_cast<jevois::Engine *>(itsParent);
135  if (eng) return eng;
136  if (itsParent) return itsParent->engine();
137  LFATAL("Reached root of hierarchy but could not find an Engine");
138 }
139 
140 // ######################################################################
141 void jevois::Component::init()
142 {
143  JEVOIS_TRACE(5);
144 
145  if (itsInitialized) { LERROR("Already initialized. Ignored."); return; }
146 
147  LDEBUG("Initializing...");
148 
149  runPreInit();
150  setInitialized();
151  runPostInit();
152 
153  LDEBUG("Initialized.");
154 }
155 
156 // ######################################################################
157 void jevois::Component::runPreInit()
158 {
159  JEVOIS_TRACE(6);
160 
161  // Pre-init all subComponents:
162  {
163  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
164  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->runPreInit();
165  }
166 
167  // Then us. So the last one here will be the manager, and its preInit() will parse the command line:
168  preInit();
169 
170  // If we have some parameters with callbacks that have not been set expicitly by the command-line, call the callback a
171  // first time here. This may add some new parameters
173 }
174 
175 // ######################################################################
176 void jevois::Component::setInitialized()
177 {
178  JEVOIS_TRACE(6);
179 
180  // First all subComponents
181  {
182  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
183  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->setInitialized();
184  }
185 
186  // Then us:
187  itsInitialized = true;
188 }
189 
190 // ######################################################################
191 void jevois::Component::runPostInit()
192 {
193  JEVOIS_TRACE(6);
194 
195  // First all subComponents:
196  {
197  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
198  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->runPostInit();
199  }
200 
201  // Then us:
202  postInit();
203 }
204 
205 // ######################################################################
207 {
208  JEVOIS_TRACE(6);
209 
210  return itsInitialized;
211 }
212 
213 // ######################################################################
214 void jevois::Component::uninit()
215 {
216  JEVOIS_TRACE(5);
217 
218  if (itsInitialized)
219  {
220  LDEBUG("Uninitializing...");
221 
222  runPreUninit();
223  setUninitialized();
224  runPostUninit();
225 
226  LDEBUG("Uninitialized.");
227  }
228 }
229 
230 // ######################################################################
231 void jevois::Component::runPreUninit()
232 {
233  JEVOIS_TRACE(6);
234 
235  // First all subComponents:
236  {
237  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
238  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->runPreUninit();
239  }
240 
241  // Then us:
242  preUninit();
243 }
244 
245 // ######################################################################
246 void jevois::Component::setUninitialized()
247 {
248  JEVOIS_TRACE(6);
249 
250  // First us:
251  itsInitialized = false;
252 
253  // Then all subComponents
254  {
255  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
256  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->setUninitialized();
257  }
258 }
259 
260 // ######################################################################
261 void jevois::Component::runPostUninit()
262 {
263  JEVOIS_TRACE(6);
264 
265  // First us:
266  postUninit();
267 
268  // Then all subComponents:
269  {
270  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
271  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->runPostUninit();
272  }
273 }
274 
275 // ######################################################################
276 std::string jevois::Component::descriptor() const
277 {
278  JEVOIS_TRACE(8);
279 
280  // Top-level components or those with no parent just return their instance name. Sub-components return a chain of
281  // component instance names up to the top level:
282 
283  boost::shared_lock<boost::shared_mutex> lck(itsMtx);
284 
285  if (itsParent && dynamic_cast<jevois::Manager *>(itsParent) == nullptr)
286  return itsParent->descriptor() + ':' + itsInstanceName;
287 
288  return itsInstanceName;
289 }
290 
291 // ######################################################################
292 void jevois::Component::findParamAndActOnIt(std::string const & descrip,
293  std::function<void(jevois::ParameterBase *, std::string const &)> doit,
294  std::function<bool()> empty) const
295 {
296  JEVOIS_TRACE(9);
297 
298  // Split this parameter descriptor by single ":" (skipping over all "::")
299  std::vector<std::string> desc = jevois::split(descrip, ":" /*"FIXME "(?<!:):(?!:)" */);
300 
301  if (desc.empty()) std::range_error(descriptor() + ": Cannot parse empty parameter name");
302 
303  // Recursive call with the vector of tokens:
304  findParamAndActOnIt(desc, true, 0, "", doit);
305 
306  if (empty()) throw std::range_error(descriptor() + ": No Parameter named [" + descrip + ']');
307 }
308 
309 // ######################################################################
310 void jevois::Component::findParamAndActOnIt(std::vector<std::string> const & descrip,
311  bool recur, size_t idx, std::string const & unrolled,
312  std::function<void(jevois::ParameterBase *, std::string const &)> doit) const
313 {
314  JEVOIS_TRACE(9);
315 
316  // Have we not yet reached the bottom (still have some component names before the param)?
317  if (descrip.size() > idx + 1)
318  {
319  // We have some token before the param, is it a '*', in which case we turn on recursion?
320  if (descrip[idx] == "*") { recur = true; ++idx; }
321  else {
322  // We have some Instance specification(s) of component(s) before the param. Let's see if we match against the
323  // first one. If it's a match, eat up the first token and send the rest of the tokens to our subcomponents,
324  // otherwise keep the token and recurse the entire list to the subs:
325  if (itsInstanceName == descrip[idx]) { recur = false; ++idx; }
326  }
327  }
328 
329  // Have we reached the end of the list (the param name)?
330  if (descrip.size() == idx + 1)
331  {
332  // We have just a paramname, let's see if we have that param:
333  boost::shared_lock<boost::shared_mutex> lck(itsParamMtx);
334 
335  for (auto const & p : itsParameterList)
336  if (p.second->name() == descrip[idx])
337  {
338  // param name is a match, act on it:
339  std::string ur = itsInstanceName + ':' + p.second->name();
340  if (unrolled.empty() == false) ur = unrolled + ':' + ur;
341  doit(p.second, ur);
342  }
343  }
344 
345  // Recurse through our subcomponents if recur is on or we have not yet reached the bottom:
346  if (recur || descrip.size() > idx + 1)
347  {
348  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
349 
350  std::string ur;
351  if (unrolled.empty()) ur = itsInstanceName; else ur = unrolled + ':' + itsInstanceName;
352 
353  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->findParamAndActOnIt(descrip, recur, idx, ur, doit);
354  }
355 }
356 
357 // ######################################################################
358 std::vector<std::string> jevois::Component::setParamString(std::string const & descriptor, std::string const & val)
359 {
360  JEVOIS_TRACE(7);
361 
362  std::vector<std::string> ret;
363  findParamAndActOnIt(descriptor,
364 
365  [&ret,&val](jevois::ParameterBase * param, std::string const & unrolled)
366  { param->strset(val); ret.push_back(unrolled); },
367 
368  [&ret]() { return ret.empty(); }
369  );
370  return ret;
371 }
372 
373 // ######################################################################
374 void jevois::Component::setParamStringUnique(std::string const & descriptor, std::string const & val)
375 {
376  JEVOIS_TRACE(7);
377 
378  std::vector<std::string> ret = setParamString(descriptor, val);
379  if (ret.size() > 1)
380  throw std::range_error("Multiple matches for descriptor [" + descriptor + "] while only one is allowed");
381 }
382 
383 // ######################################################################
384 std::vector<std::pair<std::string, std::string> >
386 {
387  JEVOIS_TRACE(8);
388 
389  std::vector<std::pair<std::string, std::string> > ret;
390  findParamAndActOnIt(descriptor,
391 
392  [&ret](jevois::ParameterBase * param, std::string const & unrolled)
393  { ret.push_back(std::make_pair(unrolled, param->strget())); },
394 
395  [&ret]() { return ret.empty(); }
396  );
397  return ret;
398 }
399 
400 // ######################################################################
401 std::string jevois::Component::getParamStringUnique(std::string const & descriptor) const
402 {
403  JEVOIS_TRACE(8);
404 
405  std::vector<std::pair<std::string, std::string> > ret = getParamString(descriptor);
406  if (ret.size() > 1)
407  throw std::range_error("Multiple matches for descriptor [" + descriptor + "] while only one is allowed");
408 
409  // We know that ret is not empty because getParamString() throws if the param is not found:
410  return ret[0].second;
411 }
412 
413 // ######################################################################
414 void jevois::Component::freezeParam(std::string const & paramdescriptor)
415 {
416  int n = 0;
417  findParamAndActOnIt(paramdescriptor,
418  [&n](jevois::ParameterBase * param, std::string const & JEVOIS_UNUSED_PARAM(unrolled))
419  { param->freeze(); ++n; },
420 
421  [&n]() { return (n == 0); }
422  );
423 }
424 
425 // ######################################################################
426 void jevois::Component::unFreezeParam(std::string const & paramdescriptor)
427 {
428  int n = 0;
429  findParamAndActOnIt(paramdescriptor,
430  [&n](jevois::ParameterBase * param, std::string const & JEVOIS_UNUSED_PARAM(unrolled))
431  { param->unFreeze(); ++n; },
432 
433  [&n]() { return (n == 0); }
434  );
435 }
436 
437 // ######################################################################
439 {
440  boost::shared_lock<boost::shared_mutex> lck(itsParamMtx);
441 
442  for (auto const & p : itsParameterList) p.second->freeze();
443 }
444 
445 // ######################################################################
447 {
448  boost::shared_lock<boost::shared_mutex> lck(itsParamMtx);
449 
450  for (auto const & p : itsParameterList) p.second->unFreeze();
451 }
452 
453 // ######################################################################
454 void jevois::Component::setParamsFromFile(std::string const & filename)
455 {
456  std::string const absfile = absolutePath(filename);
457  std::ifstream ifs(absfile);
458  if (!ifs) LFATAL("Could not open file " << absfile);
459  setParamsFromStream(ifs, absfile);
460 }
461 
462 // ######################################################################
463 std::istream & jevois::Component::setParamsFromStream(std::istream & is,std::string const & absfile)
464 {
465  size_t linenum = 1;
466  for (std::string line; std::getline(is, line); /* */)
467  {
468  // Skip over comments:
469  if (line.length() && line[0] == '#') { ++linenum; continue; }
470 
471  // Skip over empty lines:
472  if (std::all_of(line.begin(), line.end(), [](unsigned char c) { return std::isspace(c); })) { ++linenum; continue; }
473 
474  // Parse descriptor=value:
475  size_t idx = line.find('=');
476  if (idx == line.npos) LFATAL("No '=' symbol found at line " << linenum << " in " << absfile);
477  if (idx == 0) LFATAL("No parameter descriptor found at line " << linenum << " in " << absfile);
478  if (idx == line.length() - 1) LFATAL("No parameter value found at line " << linenum << " in " << absfile);
479 
480  std::string desc = line.substr(0, idx);
481  std::string val = line.substr(idx + 1);
482 
483  // Be nice and clean whitespace at start and end (not in the middle):
484  while (desc.length() > 0 && std::isspace(desc[0])) desc.erase(0, 1);
485  while (desc.length() > 0 && std::isspace(desc[desc.length()-1])) desc.erase(desc.length()-1, 1);
486  if (desc.empty()) LFATAL("Invalid blank parameter descriptor at line " << linenum << " in " << absfile);
487 
488  while (val.length() > 0 && std::isspace(val[0])) val.erase(0, 1);
489  while (val.length() > 0 && std::isspace(val[val.length()-1])) val.erase(val.length()-1, 1);
490  if (val.empty()) LFATAL("Invalid blank parameter value at line " << linenum << " in " << absfile);
491 
492  // Ok, set that param:
493  setParamString(desc, val);
494 
495  ++linenum;
496  }
497  return is;
498 }
499 
500 // ######################################################################
501 void jevois::Component::setPath(std::string const & path)
502 {
503  JEVOIS_TRACE(5);
504 
505  // First all subComponents:
506  {
507  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
508  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->setPath(path);
509  }
510 
511  itsPath = path;
512 }
513 
514 // ######################################################################
515 std::string jevois::Component::absolutePath(std::string const & path)
516 {
517  JEVOIS_TRACE(6);
518 
519  // If path is empty, return itsPath (be it empty of not):
520  if (path.empty()) return itsPath;
521 
522  // no-op if the given path is already absolute:
523  if (path[0] == '/') return path;
524 
525  // no-op if itsPath is empty:
526  if (itsPath.empty()) return path;
527 
528  // We know itsPath is not empty and path does not start with a / and is not empty; concatenate both:
529  return itsPath + '/' + path;
530 }
531 
532 // ######################################################################
533 void jevois::Component::paramInfo(std::shared_ptr<UserInterface> s, std::map<std::string, std::string> & categs,
534  bool skipFrozen, std::string const & cname, std::string const & pfx)
535 {
536  JEVOIS_TRACE(9);
537 
538  std::string const compname = cname.empty() ? itsInstanceName : cname + ':' + itsInstanceName;
539 
540  // First add our own params:
541  {
542  boost::shared_lock<boost::shared_mutex> lck(itsParamMtx);
543  for (auto const & p : itsParameterList)
544  {
545  jevois::ParameterSummary const ps = p.second->summary();
546 
547  if (skipFrozen && ps.frozen) continue;
548 
549  categs[ps.category] = ps.categorydescription;
550 
551  if (ps.frozen) s->writeString(pfx, "F"); else s->writeString(pfx, "N");
552  s->writeString(pfx, compname);
553  s->writeString(pfx, ps.category);
554  s->writeString(pfx, ps.name);
555  s->writeString(pfx, ps.valuetype);
556  s->writeString(pfx, ps.value);
557  s->writeString(pfx, ps.defaultvalue);
558  s->writeString(pfx, ps.validvalues);
559  s->writeString(pfx, ps.description);
560  }
561  }
562 
563  // Then recurse through our subcomponents:
564  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
565  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->paramInfo(s, categs, skipFrozen, compname, pfx);
566 
567  // At the root only, dump the list of categories:
568  if (cname.empty())
569  {
570  s->writeString(pfx, "C");
571  for (auto const & c : categs)
572  {
573  s->writeString(pfx, c.first);
574  s->writeString(pfx, c.second);
575  }
576  }
577 }
578 
579 // ######################################################################
580 void jevois::Component::populateHelpMessage(std::string const & cname,
581  std::unordered_map<std::string,
582  std::unordered_map<std::string,
583  std::vector<std::pair<std::string, std::string> > > > & helplist,
584  bool recurse) const
585 {
586  JEVOIS_TRACE(9);
587 
588  std::string const compname = cname.empty() ? itsInstanceName : cname + ':' + itsInstanceName;
589 
590  // First add our own params:
591  {
592  boost::shared_lock<boost::shared_mutex> lck(itsParamMtx);
593  for (auto const & p : itsParameterList)
594  {
595  jevois::ParameterSummary const ps = p.second->summary();
596 
597  if (ps.frozen) continue; // skip frozen parameters
598 
599  std::string const key1 = ps.category + ": "+ ps.categorydescription;
600  std::string const key2 = " --" + ps.name + " (" + ps.valuetype + ") default=[" + ps.defaultvalue + "]" +
601  (ps.validvalues == "None:[]" ? "\n" : " " + ps.validvalues + "\n") + " " + ps.description;
602  std::string val = "";
603  if (ps.value != ps.defaultvalue) val = ps.value;
604  helplist[key1][key2].push_back(std::make_pair(compname, val));
605  }
606  }
607 
608  // Then recurse through our subcomponents:
609  if (recurse)
610  {
611  boost::shared_lock<boost::shared_mutex> lck(itsSubMtx);
612  for (std::shared_ptr<jevois::Component> c : itsSubComponents) c->populateHelpMessage(compname, helplist);
613  }
614 }
615 
616 // ######################################################################
617 std::string jevois::Component::computeInstanceName(std::string const & instance, std::string const & classname) const
618 {
619  JEVOIS_TRACE(9);
620 
621  std::string inst = instance;
622 
623  // If empty instance, replace it by the classname:
624  if (inst.empty())
625  {
626  // Use the class name:
627  inst = classname + '#';
628 
629  // Remove any namespace:: prefix:
630  size_t const idxx = inst.rfind(':'); if (idxx != inst.npos) inst = inst.substr(idxx + 1);
631  }
632 
633  // Replace all # characters by some number, if necessary:
634  std::vector<std::string> vec = jevois::split(inst, "#");
635  if (vec.size() > 1)
636  {
637  // First try to have no numbers in there:
638  inst = jevois::join(vec, ""); bool found = false;
639  for (std::shared_ptr<Component> const & c : itsSubComponents)
640  if (c->instanceName() == inst) { found = true; break; }
641 
642  if (found)
643  {
644  // Ok, we have some conflict, so let's add some numbers where the # signs were:
645  inst = "";
646  for (std::string const & v : vec)
647  {
648  if (v.empty()) continue;
649 
650  inst += v;
651  size_t largestId = 1;
652 
653  while (true)
654  {
655  std::string stem = inst + std::to_string(largestId);
656  bool gotit = false;
657 
658  for (std::shared_ptr<Component> const & c : itsSubComponents)
659  if (c->instanceName() == stem) { gotit = true; break; }
660 
661  if (gotit == false) { inst = stem; break; }
662 
663  ++largestId;
664  }
665  }
666  }
667 
668  LDEBUG("Using automatic instance name [" << inst << ']');
669  return inst;
670  }
671 
672  // If we have not returned yet, no # was given. Throw if there is a conflict:
673  for (std::shared_ptr<Component> const & c : itsSubComponents)
674  if (c->instanceName() == inst)
675  throw std::runtime_error("Provided instance name [" + instance + "] clashes with existing sub-components.");
676 
677  return inst;
678 }
679 
#define LDEBUG(msg)
Convenience macro for users to print out console or syslog messages, DEBUG level. ...
Definition: Log.H:155
std::string name
Plain name of the parameter.
Definition: Parameter.H:90
std::string validvalues
Description of the parameter&#39;s valid values specification, as a string.
Definition: Parameter.H:105
std::string description
Description of the parameter.
Definition: Parameter.H:93
virtual void preInit()
Called before all sub-Components are init()ed.
Definition: Component.H:464
std::vector< std::string > setParamString(std::string const &paramdescriptor, std::string const &val)
Set a parameter value, by string.
Definition: Component.C:358
void unFreeze()
Unfreeze this parameter, it becomes read-write and will show up in the help message.
Definition: ParameterImpl.H:41
ParameterSummary provides a summary about a parameter.
Definition: Parameter.H:83
std::string value
Current value of the parameter, as a string.
Definition: Parameter.H:102
std::string const & className() const
The class name of this component.
Definition: Component.C:39
std::string defaultvalue
Default value of the parameter, as a string.
Definition: Parameter.H:99
void setPath(std::string const &path)
Assign a filesystem path to this component.
Definition: Component.C:501
void setParamStringUnique(std::string const &paramdescriptor, std::string const &val)
Set a parameter value by string, simple version assuming only one parameter match.
Definition: Component.C:374
void setParamsFromFile(std::string const &filename)
Set some parameters from a file.
Definition: Component.C:454
#define JEVOIS_TRACE(level)
Trace object.
Definition: Log.H:267
bool isTopLevel() const
Returns true if this component is top-level, i.e., its parent is jevois::Manager. ...
Definition: Component.C:119
void freezeParam(std::string const &paramdescriptor)
Freeze a parameter, by name, see ParameterBase::freeze()
Definition: Component.C:414
bool initialized() const
Has this component been initialized yet?
Definition: Component.C:206
#define LERROR(msg)
Convenience macro for users to print out console or syslog messages, ERROR level. ...
Definition: Log.H:193
std::string join(std::vector< std::string > const &strings, std::string const &delimiter)
Concatenate a vector of tokens into a string.
Definition: Utils.C:152
std::string getParamStringUnique(std::string const &paramdescriptor) const
Get a parameter value by string, simple version assuming only one parameter match.
Definition: Component.C:401
std::string demangle(std::string const &mangledName)
Demangle a mangled name.
Definition: DemangleImpl.H:54
virtual void preUninit()
Called before all sub-Components are uninit()ed.
Definition: Component.H:470
Engine * engine() const
Get a handle to our Engine, or throw if we do not have an Engine as root ancestor.
Definition: Component.C:129
std::string valuetype
Parameter value type, as a string.
Definition: Parameter.H:96
virtual ~Component()
Virtual destructor for safe inheritance.
Definition: Component.C:54
std::string descriptor() const
Get our full descriptor (including all parents) as [Instancename]:[...]:[...].
Definition: Component.C:276
bool frozen
Flag that indicates whether parameter is frozen.
Definition: Parameter.H:114
void removeSubComponent(std::shared_ptr< Comp > &component)
Remove a sub-Component from this Component, by shared_ptr.
void freeze()
Freeze this parameter, it becomes read-only and will not show up in the help message.
Definition: ParameterImpl.H:37
Base class for Parameter.
Definition: Parameter.H:121
Component(std::string const &instance)
Constructor.
Definition: Component.C:32
virtual void strset(std::string const &valstring)=0
Set the value from a string representation of it.
#define LFATAL(msg)
Convenience macro for users to print out console or syslog messages, FATAL level. ...
Definition: Log.H:212
std::istream & setParamsFromStream(std::istream &is, std::string const &absfile)
Set some parameters from an open stream.
Definition: Component.C:463
virtual void paramInfo(std::shared_ptr< UserInterface > s, std::map< std::string, std::string > &categs, bool skipFrozen, std::string const &cname="", std::string const &pfx="")
Get machine-oriented descriptions of all parameters.
Definition: Component.C:533
virtual std::string const strget() const =0
Get the value as a string.
std::string category
Category of the parameter, as a string.
Definition: Parameter.H:108
virtual void postInit()
Called after all sub-Components are init()ed.
Definition: Component.H:467
std::vector< std::pair< std::string, std::string > > getParamString(std::string const &paramdescriptor) const
Get a parameter value, by string.
Definition: Component.C:385
void unFreezeParam(std::string const &paramdescriptor)
Unfreeze a parameter, by name, see ParameterBase::unFreeze()
Definition: Component.C:426
JeVois processing engine - gets images from camera sensor, processes them, and sends results over USB...
Definition: Engine.H:265
std::string to_string(T const &val)
Convert from type to string.
Definition: UtilsImpl.H:58
void callbackInitCall()
For all parameters that have a callback which has never been called, call it with the default param v...
void freezeAllParams()
Freeze all parameters.
Definition: Component.C:438
void unFreezeAllParams()
Unfreeze all parameters.
Definition: Component.C:446
std::string const & instanceName() const
The instance name of this component.
Definition: Component.C:50
std::string categorydescription
Category description.
Definition: Parameter.H:111
virtual void postUninit()
Called after all sub-Components are uninit()ed.
Definition: Component.H:473
std::string absolutePath(std::string const &path="")
If given path is relative (not starting with /), prepend the Component path to it.
Definition: Component.C:515
std::vector< std::string > split(std::string const &input, std::string const &regex="\+")
Split string into vector of tokens using a regex to specify what to split on; default regex splits by...
Definition: Utils.C:142