Fawkes API Fawkes Development Version
filter_thread.cpp
1
2/***************************************************************************
3 * filter_thread.cpp - Thread that filters data in blackboard
4 *
5 * Created: Sun Mar 13 01:12:53 2011
6 * Copyright 2006-2014 Tim Niemueller [www.niemueller.de]
7 ****************************************************************************/
8
9/* This program is free software; you can redistribute it and/or modify
10 * it under the terms of the GNU General Public License as published by
11 * the Free Software Foundation; either version 2 of the License, or
12 * (at your option) any later version.
13 *
14 * This program is distributed in the hope that it will be useful,
15 * but WITHOUT ANY WARRANTY; without even the implied warranty of
16 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17 * GNU Library General Public License for more details.
18 *
19 * Read the full text in the LICENSE.GPL file in the doc directory.
20 */
21
22#include "filter_thread.h"
23
24#include "filters/1080to360.h"
25#include "filters/720to360.h"
26#include "filters/cascade.h"
27#include "filters/circle_sector.h"
28#include "filters/copy.h"
29#include "filters/deadspots.h"
30#include "filters/max_circle.h"
31#include "filters/min_circle.h"
32#include "filters/min_merge.h"
33#include "filters/reverse_angle.h"
34#ifdef HAVE_TF
35# include "filters/box_filter.h"
36# include "filters/map_filter.h"
37# include "filters/projection.h"
38#endif
39
40#include <core/threading/barrier.h>
41#include <core/threading/mutex.h>
42#include <core/threading/wait_condition.h>
43#include <interfaces/Laser1080Interface.h>
44#include <interfaces/Laser360Interface.h>
45#include <interfaces/Laser720Interface.h>
46#include <utils/time/time.h>
47
48#include <cstdio>
49#include <cstring>
50#include <memory>
51
52using namespace fawkes;
53
54/** @class LaserFilterThread "filter_thread.h"
55 * Laser filter thread.
56 * This thread integrates into the Fawkes main loop at the sensor processing
57 * hook, reads data from specified interfaces, filters it with a given
58 * cascade, and then writes it back to an interface.
59 * @author Tim Niemueller
60 */
61
62/** Constructor.
63 * @param cfg_name short name of configuration group
64 * @param cfg_prefix configuration path prefix
65 */
66LaserFilterThread::LaserFilterThread(std::string &cfg_name, std::string &cfg_prefix)
67: Thread("LaserFilterThread", Thread::OPMODE_WAITFORWAKEUP),
68 BlockedTimingAspect(BlockedTimingAspect::WAKEUP_HOOK_SENSOR_PROCESS)
69{
70 set_name("LaserFilterThread(%s)", cfg_name.c_str());
71 cfg_name_ = cfg_name;
72 cfg_prefix_ = cfg_prefix;
73 wait_barrier_ = NULL;
74}
75
76void
78{
79 try {
80 open_interfaces(cfg_prefix_ + "in/", in_, in_bufs_, false);
81 open_interfaces(cfg_prefix_ + "out/", out_, out_bufs_, true);
82
83 if (in_.empty()) {
84 throw Exception("No input interfaces defined for %s", cfg_name_.c_str());
85 }
86 if (out_.empty()) {
87 throw Exception("No output interfaces defined for %s", cfg_name_.c_str());
88 }
89
90 std::map<std::string, std::string> filters;
91
92 std::string fpfx = cfg_prefix_ + "filters/";
93#if __cplusplus >= 201103L
94 std::unique_ptr<Configuration::ValueIterator> i(config->search(fpfx.c_str()));
95#else
96 std::auto_ptr<Configuration::ValueIterator> i(config->search(fpfx.c_str()));
97#endif
98
99 while (i->next()) {
100 std::string suffix = std::string(i->path()).substr(fpfx.length());
101 std::string filter_name = std::string(suffix.substr(0, suffix.find("/")));
102 std::string conf_key = std::string(suffix.substr(suffix.find("/") + 1, suffix.length()));
103
104 if (conf_key != "type")
105 continue;
106
107 if (!i->is_string()) {
108 throw Exception("Filter value %s is not a string", i->path());
109 }
110
111 filters[filter_name] = i->get_string();
112 }
113 if (filters.empty()) {
114 throw Exception("No filters defined for %s", cfg_name_.c_str());
115 }
116
117 if (filters.size() == 1) {
118 std::string filter_name = filters.begin()->first;
120 "Adding filter %s (%s)",
121 filter_name.c_str(),
122 filters[filter_name].c_str());
123 filter_ = create_filter(cfg_name_ + "/" + filter_name,
124 filters[filter_name],
125 fpfx + filter_name + "/",
126 in_[0].size,
127 in_bufs_);
128 } else {
129 LaserDataFilterCascade *cascade =
130 new LaserDataFilterCascade(cfg_name_, in_[0].size, in_bufs_);
131
132 try {
133 std::map<std::string, std::string>::iterator f;
134 for (f = filters.begin(); f != filters.end(); ++f) {
136 "Adding filter %s (%s) %zu %zu",
137 f->first.c_str(),
138 f->second.c_str(),
139 in_bufs_.size(),
140 cascade->get_out_vector().size());
141 cascade->add_filter(create_filter(cfg_name_ + "/" + f->first,
142 f->second,
143 fpfx + f->first + "/",
144 cascade->get_out_data_size(),
145 cascade->get_out_vector()));
146 }
147 } catch (Exception &e) {
148 delete cascade;
149 throw;
150 }
151
152 filter_ = cascade;
153 }
154
155 if (out_[0].size != filter_->get_out_data_size()) {
156 Exception e("Output interface and filter data size for %s do not match (%u != %u)",
157 cfg_name_.c_str(),
158 out_[0].size,
159 filter_->get_out_data_size());
160 delete filter_;
161 throw e;
162 }
163
164 filter_->set_out_vector(out_bufs_);
165
166 } catch (Exception &e) {
167 for (unsigned int i = 0; i < in_.size(); ++i) {
168 blackboard->close(in_[i].interface);
169 }
170 for (unsigned int i = 0; i < out_.size(); ++i) {
171 blackboard->close(out_[i].interface);
172 }
173 throw;
174 }
175
176 std::list<LaserFilterThread *>::iterator wt;
177 for (wt = wait_threads_.begin(); wt != wait_threads_.end(); ++wt) {
178 logger->log_debug(name(), "Depending on %s", (*wt)->name());
179 }
180
181 wait_done_ = true;
182 wait_mutex_ = new Mutex();
183 wait_cond_ = new WaitCondition(wait_mutex_);
184}
185
186void
188{
189 delete filter_;
190 delete wait_cond_;
191 delete wait_mutex_;
192
193 for (unsigned int i = 0; i < in_.size(); ++i) {
194 blackboard->close(in_[i].interface);
195 }
196 in_.clear();
197 for (unsigned int i = 0; i < out_.size(); ++i) {
198 blackboard->close(out_[i].interface);
199 }
200 out_.clear();
201}
202
203void
205{
206 // Wait for dependencies
207 if (wait_barrier_) {
208 std::list<LaserFilterThread *>::iterator wt;
209 for (wt = wait_threads_.begin(); wt != wait_threads_.end(); ++wt) {
210 (*wt)->wait_done();
211 }
212 }
213
214 // Read input interfaces
215 const size_t in_num = in_.size();
216 for (size_t i = 0; i != in_num; ++i) {
217 in_[i].interface->read();
218 if (in_[i].size == 360) {
219 in_bufs_[i]->frame = in_[i].interface_typed.as360->frame();
220 *in_bufs_[i]->timestamp = in_[i].interface_typed.as360->timestamp();
221 } else if (in_[i].size == 720) {
222 in_bufs_[i]->frame = in_[i].interface_typed.as720->frame();
223 *in_bufs_[i]->timestamp = in_[i].interface_typed.as720->timestamp();
224 } else if (in_[i].size == 1080) {
225 in_bufs_[i]->frame = in_[i].interface_typed.as1080->frame();
226 *in_bufs_[i]->timestamp = in_[i].interface_typed.as1080->timestamp();
227 }
228 }
229
230 // Filter!
231 try {
232 filter_->filter();
233 } catch (Exception &e) {
234 logger->log_warn(name(), "Filtering failed, exception follows");
235 logger->log_warn(name(), e);
236 }
237
238 // Write output interfaces
239 const size_t num = out_.size();
240 for (size_t i = 0; i < num; ++i) {
241 if (out_[i].size == 360) {
242 out_[i].interface_typed.as360->set_timestamp(out_bufs_[i]->timestamp);
243 out_[i].interface_typed.as360->set_frame(out_bufs_[i]->frame.c_str());
244 } else if (out_[i].size == 720) {
245 out_[i].interface_typed.as720->set_timestamp(out_bufs_[i]->timestamp);
246 out_[i].interface_typed.as720->set_frame(out_bufs_[i]->frame.c_str());
247 } else if (out_[i].size == 1080) {
248 out_[i].interface_typed.as1080->set_timestamp(out_bufs_[i]->timestamp);
249 out_[i].interface_typed.as1080->set_frame(out_bufs_[i]->frame.c_str());
250 }
251 out_[i].interface->write();
252 }
253
254 if (wait_barrier_) {
255 wait_mutex_->lock();
256 wait_done_ = false;
257 wait_cond_->wake_all();
258 wait_mutex_->unlock();
259 wait_barrier_->wait();
260 wait_mutex_->lock();
261 wait_done_ = true;
262 wait_mutex_->unlock();
263 }
264}
265
266/** Wait until thread is done.
267 * This method blocks the calling thread until this instance's thread has
268 * finished filtering.
269 */
270void
272{
273 wait_mutex_->lock();
274 while (wait_done_) {
275 //logger->log_debug(name(), "%s is waiting", Thread::current_thread()->name());
276 wait_cond_->wait();
277 }
278 wait_mutex_->unlock();
279}
280
281void
282LaserFilterThread::open_interfaces(std::string prefix,
283 std::vector<LaserInterface> & ifs,
284 std::vector<LaserDataFilter::Buffer *> &bufs,
285 bool writing)
286{
287#if __cplusplus >= 201103L
288 std::unique_ptr<Configuration::ValueIterator> in(config->search(prefix.c_str()));
289#else
290 std::auto_ptr<Configuration::ValueIterator> in(config->search(prefix.c_str()));
291#endif
292 while (in->next()) {
293 if (!in->is_string()) {
294 throw Exception("Config value %s is not of type string", in->path());
295 } else {
296 std::string uid = in->get_string();
297 size_t sf;
298
299 if ((sf = uid.find("::")) == std::string::npos) {
300 throw Exception("Interface '%s' is not a UID", uid.c_str());
301 }
302 std::string type = uid.substr(0, sf);
303 std::string id = uid.substr(sf + 2);
304
305 LaserInterface lif;
306 lif.interface = NULL;
307
308 if (type == "Laser360Interface") {
309 lif.size = 360;
310 } else if (type == "Laser720Interface") {
311 lif.size = 720;
312 } else if (type == "Laser1080Interface") {
313 lif.size = 1080;
314 } else {
315 throw Exception("Interfaces must be of type Laser360Interface, "
316 "Laser720Interface, or Laser1080Interface, "
317 "but it is '%s'",
318 type.c_str());
319 }
320
321 lif.id = id;
322 ifs.push_back(lif);
323 }
324 }
325
326 if (ifs.empty()) {
327 throw Exception("No interfaces defined at %s", prefix.c_str());
328 }
329
330 bufs.resize(ifs.size());
331
332 unsigned int req_size = ifs[0].size;
333
334 try {
335 if (writing) {
336 for (unsigned int i = 0; i < ifs.size(); ++i) {
337 if (req_size != ifs[i].size) {
338 throw Exception("Interfaces of mixed sizes for %s", cfg_name_.c_str());
339 }
340
341 if (ifs[i].size == 360) {
342 logger->log_debug(name(), "Opening writing Laser360Interface::%s", ifs[i].id.c_str());
343 Laser360Interface *laser360 =
344 blackboard->open_for_writing<Laser360Interface>(ifs[i].id.c_str());
345
346 laser360->set_auto_timestamping(false);
347
348 ifs[i].interface_typed.as360 = laser360;
349 ifs[i].interface = laser360;
350 bufs[i] = new LaserDataFilter::Buffer();
351 bufs[i]->name = laser360->uid();
352 bufs[i]->values = laser360->distances();
353
354 } else if (ifs[i].size == 720) {
355 logger->log_debug(name(), "Opening writing Laser720Interface::%s", ifs[i].id.c_str());
356 Laser720Interface *laser720 =
357 blackboard->open_for_writing<Laser720Interface>(ifs[i].id.c_str());
358
359 laser720->set_auto_timestamping(false);
360
361 ifs[i].interface_typed.as720 = laser720;
362 ifs[i].interface = laser720;
363 bufs[i] = new LaserDataFilter::Buffer();
364 bufs[i]->name = laser720->uid();
365 bufs[i]->values = laser720->distances();
366
367 } else if (ifs[i].size == 1080) {
368 logger->log_debug(name(), "Opening writing Laser1080Interface::%s", ifs[i].id.c_str());
369 Laser1080Interface *laser1080 =
371
372 laser1080->set_auto_timestamping(false);
373
374 ifs[i].interface_typed.as1080 = laser1080;
375 ifs[i].interface = laser1080;
376 bufs[i] = new LaserDataFilter::Buffer();
377 bufs[i]->name = laser1080->uid();
378 bufs[i]->values = laser1080->distances();
379 }
380 }
381 } else {
382 for (unsigned int i = 0; i < ifs.size(); ++i) {
383 if (ifs[i].size == 360) {
384 logger->log_debug(name(), "Opening reading Laser360Interface::%s", ifs[i].id.c_str());
385 Laser360Interface *laser360 =
386 blackboard->open_for_reading<Laser360Interface>(ifs[i].id.c_str());
387
388 ifs[i].interface_typed.as360 = laser360;
389 ifs[i].interface = laser360;
390 bufs[i] = new LaserDataFilter::Buffer();
391 bufs[i]->name = laser360->uid();
392 bufs[i]->frame = laser360->frame();
393 bufs[i]->values = laser360->distances();
394
395 } else if (ifs[i].size == 720) {
396 logger->log_debug(name(), "Opening reading Laser720Interface::%s", ifs[i].id.c_str());
397 Laser720Interface *laser720 =
398 blackboard->open_for_reading<Laser720Interface>(ifs[i].id.c_str());
399
400 ifs[i].interface_typed.as720 = laser720;
401 ifs[i].interface = laser720;
402 bufs[i] = new LaserDataFilter::Buffer();
403 bufs[i]->name = laser720->uid();
404 bufs[i]->frame = laser720->frame();
405 bufs[i]->values = laser720->distances();
406
407 } else if (ifs[i].size == 1080) {
408 logger->log_debug(name(), "Opening reading Laser1080Interface::%s", ifs[i].id.c_str());
409 Laser1080Interface *laser1080 =
411
412 ifs[i].interface_typed.as1080 = laser1080;
413 ifs[i].interface = laser1080;
414 bufs[i] = new LaserDataFilter::Buffer();
415 bufs[i]->name = laser1080->uid();
416 bufs[i]->frame = laser1080->frame();
417 bufs[i]->values = laser1080->distances();
418 }
419 }
420 }
421 } catch (Exception &e) {
422 for (unsigned int i = 0; i < ifs.size(); ++i) {
423 blackboard->close(ifs[i].interface);
424 }
425 ifs.clear();
426 bufs.clear();
427 throw;
428 }
429}
430
432LaserFilterThread::create_filter(std::string filter_name,
433 std::string filter_type,
434 std::string prefix,
435 unsigned int in_data_size,
436 std::vector<LaserDataFilter::Buffer *> &inbufs)
437{
438 if (filter_type == "copy") {
439 return new LaserCopyDataFilter(filter_name, in_data_size, inbufs);
440 } else if (filter_type == "720to360") {
441 bool average = false;
442 try {
443 average = config->get_bool((prefix + "average").c_str());
444 } catch (Exception &e) {
445 } // ignore
446 return new Laser720to360DataFilter(filter_name, average, in_data_size, inbufs);
447 } else if (filter_type == "1080to360") {
448 bool average = false;
449 try {
450 average = config->get_bool((prefix + "average").c_str());
451 } catch (Exception &e) {
452 } // ignore
453 return new Laser1080to360DataFilter(filter_name, average, in_data_size, inbufs);
454 } else if (filter_type == "reverse") {
455 return new LaserReverseAngleDataFilter(filter_name, in_data_size, inbufs);
456 } else if (filter_type == "max_circle") {
457 float radius = config->get_float((prefix + "radius").c_str());
458 return new LaserMaxCircleDataFilter(filter_name, radius, in_data_size, inbufs);
459 } else if (filter_type == "min_circle") {
460 float radius = config->get_float((prefix + "radius").c_str());
461 return new LaserMinCircleDataFilter(filter_name, radius, in_data_size, inbufs);
462 } else if (filter_type == "circle_sector") {
463 unsigned int from = config->get_uint((prefix + "from").c_str());
464 unsigned int to = config->get_uint((prefix + "to").c_str());
465 return new LaserCircleSectorDataFilter(filter_name, from, to, in_data_size, inbufs);
466 } else if (filter_type == "deadspots") {
467 return new LaserDeadSpotsDataFilter(filter_name, config, logger, prefix, in_data_size, inbufs);
468 } else if (filter_type == "min_merge") {
469 std::string timestamp_selection;
470 try {
471 timestamp_selection = config->get_string((prefix + "timestamp_selection").c_str());
472 } catch (Exception &e) {
473 } // ignored, use default
474
475 if (timestamp_selection == "latest") {
476 return new LaserMinMergeDataFilter(
477 filter_name, logger, in_data_size, inbufs, LaserMinMergeDataFilter::TIMESTAMP_LATEST);
478 } else if (timestamp_selection == "first") {
479 return new LaserMinMergeDataFilter(
480 filter_name, logger, in_data_size, inbufs, LaserMinMergeDataFilter::TIMESTAMP_FIRST);
481 } else if (timestamp_selection == "index") {
482 unsigned int timestamp_if_index = config->get_uint((prefix + "timestamp_index").c_str());
483 return new LaserMinMergeDataFilter(filter_name,
484 logger,
485 in_data_size,
486 inbufs,
488 timestamp_if_index);
489 } else if (timestamp_selection != "") {
490 throw Exception("Laser filter: unknown timestamp selection method '%s'",
491 timestamp_selection.c_str());
492 } else {
493 return new LaserMinMergeDataFilter(
494 filter_name, logger, in_data_size, inbufs, LaserMinMergeDataFilter::TIMESTAMP_LATEST);
495 }
496 } else if (filter_type == "projection") {
497#ifdef HAVE_TF
498 const float not_from_x = config->get_float((prefix + "not_from_x").c_str());
499 const float not_to_x = config->get_float((prefix + "not_to_x").c_str());
500 const float not_from_y = config->get_float((prefix + "not_from_y").c_str());
501 const float not_to_y = config->get_float((prefix + "not_to_y").c_str());
502 const float only_from_z = config->get_float((prefix + "only_from_z").c_str());
503 const float only_to_z = config->get_float((prefix + "only_to_z").c_str());
504 const std::string frame = config->get_string((prefix + "target_frame").c_str());
505 return new LaserProjectionDataFilter(filter_name,
506 tf_listener,
507 frame,
508 not_from_x,
509 not_to_x,
510 not_from_y,
511 not_to_y,
512 only_from_z,
513 only_to_z,
514 in_data_size,
515 inbufs);
516#else
517 throw Exception("Projection filter unavailable, tf missing");
518#endif
519 } else if (filter_type == "map_filter") {
520#ifdef HAVE_TF
521 return new LaserMapFilterDataFilter(
522 filter_name, in_data_size, inbufs, tf_listener, config, prefix, logger);
523#else
524 throw Exception("Projection filter unavailable, tf missing");
525#endif
526 } else if (filter_type == "box_filter") {
527#ifdef HAVE_TF
528 return new LaserBoxFilterDataFilter(
529 filter_name, in_data_size, inbufs, tf_listener, config, logger, blackboard);
530#else
531 throw Exception("Projection filter unavailable, tf missing");
532#endif
533 } else {
534 throw Exception("Unknown filter type %s", filter_type.c_str());
535 }
536}
537
538/** Set threads to wait for in loop.
539 * The threads produce data this thread depends on as input, therefore this
540 * instance has to wait for these threads to get up to date data in each
541 * loop.
542 * @param threads threads this instance depends on
543 */
544void
545LaserFilterThread::set_wait_threads(std::list<LaserFilterThread *> &threads)
546{
547 wait_threads_ = threads;
548}
549
550/** Set wait barrier.
551 * If there are any dependencies between laser filter threads a common
552 * barrier is used to signal the end of filtering to reset internal
553 * variables for the next loop.
554 * @param barrier common "end of filtering" barrier
555 */
556void
558{
559 wait_barrier_ = barrier;
560}
Downsample filter from 1080 to 360 values.
Definition: 1080to360.h:29
Downsample filter from 720 to 360 values.
Definition: 720to360.h:29
Removes laser data which is represented by a set of boxes.
Definition: box_filter.h:40
Erase beams outside specified circle sector.
Definition: circle_sector.h:29
Copy laser data without modification to a new name.
Definition: copy.h:27
Cascade of several laser filters to one.
Definition: cascade.h:31
void add_filter(LaserDataFilter *filter)
Add a filter to the cascade.
Definition: cascade.cpp:69
Laser data buffer.
Definition: filter.h:36
Laser data filter.
Definition: filter.h:33
virtual std::vector< Buffer * > & get_out_vector()
Get filtered data array.
Definition: filter.cpp:117
virtual unsigned int get_out_data_size()
Get size of filtered data array.
Definition: filter.cpp:173
virtual void filter()=0
Filter the incoming data.
virtual void set_out_vector(std::vector< Buffer * > &out)
Set filtered data array.
Definition: filter.cpp:129
Erase dead spots (i.e.
Definition: deadspots.h:38
virtual void init()
Initialize the thread.
void set_wait_barrier(fawkes::Barrier *barrier)
Set wait barrier.
void set_wait_threads(std::list< LaserFilterThread * > &threads)
Set threads to wait for in loop.
virtual void loop()
Code to execute in the thread.
virtual void finalize()
Finalize the thread.
void wait_done()
Wait until thread is done.
LaserFilterThread(std::string &cfg_name, std::string &cfg_prefix)
Constructor.
Removes static laser data (laser beams near occupied map cells)
Definition: map_filter.h:36
Cut of laser data at max distance.
Definition: max_circle.h:29
Erase beams below a certain minimum distance distance.
Definition: min_circle.h:29
Merge multiple laser data arrays into one.
Definition: min_merge.h:35
@ TIMESTAMP_LATEST
use the latest of all timestamps
Definition: min_merge.h:39
@ TIMESTAMP_FIRST
use the first (oldest) of all timestamps
Definition: min_merge.h:40
@ TIMESTAMP_INDEX
use a specific index in the input buffer list
Definition: min_merge.h:41
Projects one laser into another laser's plane.
Definition: projection.h:42
Reverse the angle of beams.
Definition: reverse_angle.h:29
A barrier is a synchronization tool which blocks until a given number of threads have reached the bar...
Definition: barrier.h:32
virtual void wait()
Wait for other threads.
Definition: barrier.cpp:153
BlackBoard * blackboard
This is the BlackBoard instance you can use to interact with the BlackBoard.
Definition: blackboard.h:44
virtual Interface * open_for_reading(const char *interface_type, const char *identifier, const char *owner=NULL)=0
Open interface for reading.
virtual Interface * open_for_writing(const char *interface_type, const char *identifier, const char *owner=NULL)=0
Open interface for writing.
virtual void close(Interface *interface)=0
Close interface.
Thread aspect to use blocked timing.
Configuration * config
This is the Configuration member used to access the configuration.
Definition: configurable.h:41
virtual unsigned int get_uint(const char *path)=0
Get value from configuration which is of type unsigned int.
virtual bool get_bool(const char *path)=0
Get value from configuration which is of type bool.
virtual float get_float(const char *path)=0
Get value from configuration which is of type float.
virtual ValueIterator * search(const char *path)=0
Iterator with search results.
virtual std::string get_string(const char *path)=0
Get value from configuration which is of type string.
Base class for exceptions in Fawkes.
Definition: exception.h:36
void set_auto_timestamping(bool enabled)
Enable or disable automated timestamping.
Definition: interface.cpp:755
const char * id() const
Get identifier of interface.
Definition: interface.cpp:661
const char * uid() const
Get unique identifier of interface.
Definition: interface.cpp:686
Laser1080Interface Fawkes BlackBoard Interface.
char * frame() const
Get frame value.
float * distances() const
Get distances value.
Laser360Interface Fawkes BlackBoard Interface.
float * distances() const
Get distances value.
char * frame() const
Get frame value.
Laser720Interface Fawkes BlackBoard Interface.
char * frame() const
Get frame value.
float * distances() const
Get distances value.
virtual void log_debug(const char *component, const char *format,...)=0
Log debug message.
virtual void log_warn(const char *component, const char *format,...)=0
Log warning message.
Logger * logger
This is the Logger member used to access the logger.
Definition: logging.h:41
Mutex mutual exclusion lock.
Definition: mutex.h:33
void lock()
Lock this mutex.
Definition: mutex.cpp:87
void unlock()
Unlock the mutex.
Definition: mutex.cpp:131
Thread class encapsulation of pthreads.
Definition: thread.h:46
const char * name() const
Get name of thread.
Definition: thread.h:100
void set_name(const char *format,...)
Set name of thread.
Definition: thread.cpp:748
Wait until a given condition holds.
void wait()
Wait for the condition forever.
void wake_all()
Wake up all waiting threads.
Fawkes library namespace.