Fawkes API  Fawkes Development Version
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
shm_image.cpp
1 
2 /***************************************************************************
3  * shm_image.cpp - shared memory image buffer
4  *
5  * Created: Thu Jan 12 14:10:43 2006
6  * Copyright 2005-2009 Tim Niemueller [www.niemueller.de]
7  *
8  ****************************************************************************/
9 
10 /* This program is free software; you can redistribute it and/or modify
11  * it under the terms of the GNU General Public License as published by
12  * the Free Software Foundation; either version 2 of the License, or
13  * (at your option) any later version. A runtime exception applies to
14  * this software (see LICENSE.GPL_WRE file mentioned below for details).
15  *
16  * This program is distributed in the hope that it will be useful,
17  * but WITHOUT ANY WARRANTY; without even the implied warranty of
18  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
19  * GNU Library General Public License for more details.
20  *
21  * Read the full text in the LICENSE.GPL_WRE file in the doc directory.
22  */
23 
24 #include <core/exception.h>
25 #include <fvutils/ipc/shm_image.h>
26 #include <fvutils/ipc/shm_exceptions.h>
27 #include <utils/system/console_colors.h>
28 #include <utils/ipc/shm_exceptions.h>
29 #include <utils/misc/strndup.h>
30 
31 #include <iostream>
32 #include <cstring>
33 #include <cstdlib>
34 #include <cstdio>
35 
36 using namespace std;
37 using namespace fawkes;
38 
39 namespace firevision {
40 #if 0 /* just to make Emacs auto-indent happy */
41 }
42 #endif
43 
44 /** @class SharedMemoryImageBuffer <fvutils/ipc/shm_image.h>
45  * Shared memory image buffer.
46  * Write images to or retrieve images from a shared memory segment.
47  * @author Tim Niemueller
48  */
49 
50 /** Write Constructor.
51  * Create a new shared memory segment. Will open a shared memory segment that
52  * exactly fits the given information. Will throw an error if image with id
53  * image_id exists.
54  * I will create a new segment if no matching segment was found.
55  * The segment is accessed in read-write mode.
56  *
57  * Use this constructor to open a shared memory image buffer for writing.
58  * @param image_id image ID to open
59  * @param cspace colorspace
60  * @param width image width
61  * @param height image height
62  */
63 SharedMemoryImageBuffer::SharedMemoryImageBuffer(const char *image_id,
64  colorspace_t cspace,
65  unsigned int width,
66  unsigned int height)
67  : SharedMemory(FIREVISION_SHM_IMAGE_MAGIC_TOKEN,
68  /* read-only */ false,
69  /* create */ true,
70  /* destroy on delete */ true)
71 {
72  constructor(image_id, cspace, width, height, false);
73  add_semaphore();
74 }
75 
76 
77 /** Read Constructor.
78  * This constructor is used to search for an existing shared memory segment.
79  * It will throw an error if it cannot find a segment with the specified data.
80  * The segment is opened read-only by default, but this can be overridden with
81  * the is_read_only argument if needed.
82  *
83  * Use this constructor to open an image for reading.
84  * @param image_id Image ID to open
85  * @param is_read_only true to open image read-only
86  */
87 SharedMemoryImageBuffer::SharedMemoryImageBuffer(const char *image_id, bool is_read_only)
88  : SharedMemory(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, is_read_only, /* create */ false, /* destroy */ false)
89 {
90  constructor(image_id, CS_UNKNOWN, 0, 0, is_read_only);
91 }
92 
93 
94 void
95 SharedMemoryImageBuffer::constructor(const char *image_id, colorspace_t cspace,
96  unsigned int width, unsigned int height,
97  bool is_read_only)
98 {
99  _image_id = strdup(image_id);
101 
102  _colorspace = cspace;
103  _width = width;
104  _height = height;
105 
106  priv_header = new SharedMemoryImageBufferHeader(_image_id, _colorspace, width, height);
107  _header = priv_header;
108  try {
109  attach();
110  raw_header = priv_header->raw_header();
111  } catch (Exception &e) {
112  e.append("SharedMemoryImageBuffer: could not attach to '%s'\n", image_id);
113  ::free(_image_id);
114  _image_id = NULL;
115  delete priv_header;
116  throw;
117  }
118 }
119 
120 
121 /** Destructor. */
123 {
124  ::free(_image_id);
125  delete priv_header;
126 }
127 
128 
129 /** Set image number.
130  * This will close the currently opened image and will try to open the new
131  * image. This operation should be avoided.
132  * @param image_id new image ID
133  * @return true on success
134  */
135 bool
137 {
138  free();
139  ::free(_image_id);
140  _image_id = strdup(image_id);
141  priv_header->set_image_id(_image_id);
142  attach();
143  raw_header = priv_header->raw_header();
144  return (_memptr != NULL);
145 }
146 
147 
148 /** Set frame ID.
149  * @param frame_id new frame ID
150  */
151 void
153 {
154  priv_header->set_frame_id(frame_id);
155  strncpy(raw_header->frame_id, frame_id, FRAME_ID_MAX_LENGTH);
156 }
157 
158 
159 /** Get Image ID.
160  * @return image id
161  */
162 const char *
164 {
165  return _image_id;
166 }
167 
168 
169 /** Get frame ID.
170  * @return frame id
171  */
172 const char *
174 {
175  return priv_header->frame_id();
176 }
177 
178 
179 /** Get the time when the image was captured.
180  * @param sec upon return contains the seconds part of the time
181  * @param usec upon return contains the micro seconds part of the time
182  */
183 void
184 SharedMemoryImageBuffer::capture_time(long int *sec, long int *usec) const
185 {
186  *sec = raw_header->capture_time_sec;
187  *usec = raw_header->capture_time_usec;
188 }
189 
190 /** Get the time when the image was captured.
191  * @return capture time
192  */
193 Time
195 {
196  return Time(raw_header->capture_time_sec, raw_header->capture_time_usec);
197 }
198 
199 
200 /** Set the capture time.
201  * @param time capture time
202  */
203 void
205 {
206  if (_is_read_only) {
207  throw Exception("Buffer is read-only. Not setting capture time.");
208  }
209 
210  const timeval *t = time->get_timeval();
211  raw_header->capture_time_sec = t->tv_sec;
212  raw_header->capture_time_usec = t->tv_usec;
213 }
214 
215 /** Set the capture time.
216  * @param sec seconds part of capture time
217  * @param usec microseconds part of capture time
218  */
219 void
220 SharedMemoryImageBuffer::set_capture_time(long int sec, long int usec)
221 {
222  if (_is_read_only) {
223  throw Exception("Buffer is read-only. Not setting capture time.");
224  }
225 
226  raw_header->capture_time_sec = sec;
227  raw_header->capture_time_usec = usec;
228 }
229 
230 /** Get image buffer.
231  * @return image buffer.
232  */
233 unsigned char *
235 {
236  return (unsigned char *)_memptr;
237 }
238 
239 
240 /** Get color space.
241  * @return colorspace
242  */
243 colorspace_t
245 {
246  return (colorspace_t)raw_header->colorspace;
247 }
248 
249 
250 /** Get image width.
251  * @return width
252  */
253 unsigned int
255 {
256  return raw_header->width;
257 }
258 
259 
260 /** Get image height.
261  * @return image height
262  */
263 unsigned int
265 {
266  return raw_header->height;
267 }
268 
269 
270 /** Get ROI X.
271  * @return ROI X
272  */
273 unsigned int
275 {
276  return raw_header->roi_x;
277 }
278 
279 
280 /** Get ROI Y.
281  * @return ROI Y
282  */
283 unsigned int
285 {
286  return raw_header->roi_y;
287 }
288 
289 
290 /** Get ROI width.
291  * @return ROI width
292  */
293 unsigned int
295 {
296  return raw_header->roi_width;
297 }
298 
299 
300 /** Get ROI height.
301  * @return ROI height
302  */
303 unsigned int
305 {
306  return raw_header->roi_height;
307 }
308 
309 
310 /** Get circle X.
311  * @return circle X
312  */
313 int
315 {
316  return raw_header->circle_x;
317 }
318 
319 
320 /** Get circle Y.
321  * @return circle Y
322  */
323 int
325 {
326  return raw_header->circle_y;
327 }
328 
329 
330 /** Get circle radius.
331  * @return circle radius
332  */
333 unsigned int
335 {
336  return raw_header->circle_radius;
337 }
338 
339 
340 /** Set ROI X.
341  * @param roi_x new ROI X
342  */
343 void
345 {
346  if (_is_read_only) {
347  throw Exception("Buffer is read-only. Not setting ROI X.");
348  }
349  raw_header->roi_x = roi_x;
350 }
351 
352 
353 /** Set ROI Y.
354  * @param roi_y new ROI Y
355  */
356 void
358 {
359  if (_is_read_only) {
360  throw Exception("Buffer is read-only. Not setting ROI Y.");
361  }
362  raw_header->roi_y = roi_y;
363 }
364 
365 
366 /** Set ROI width.
367  * @param roi_w new ROI width
368  */
369 void
371 {
372  if (_is_read_only) {
373  throw Exception("Buffer is read-only. Not setting ROI width.");
374  }
375  raw_header->roi_width = roi_w;
376 }
377 
378 
379 /** Set ROI height.
380  * @param roi_h new ROI height
381  */
382 void
384 {
385  if (_is_read_only) {
386  throw Exception("Buffer is read-only. Not setting ROI height.");
387  }
388  raw_header->roi_height = roi_h;
389 }
390 
391 
392 /** Set ROI data.
393  * @param roi_x new ROI X
394  * @param roi_y new ROI Y
395  * @param roi_w new ROI width
396  * @param roi_h new ROI height
397  */
398 void
399 SharedMemoryImageBuffer::set_roi(unsigned int roi_x, unsigned int roi_y,
400  unsigned int roi_w, unsigned int roi_h)
401 {
402  if (_is_read_only) {
403  throw Exception("Buffer is read-only. Not setting ROI X/Y.");
404  }
405  raw_header->roi_x = roi_x;
406  raw_header->roi_y = roi_y;
407  raw_header->roi_width = roi_w;
408  raw_header->roi_height = roi_h;
409 }
410 
411 
412 /** Set circle X.
413  * @param circle_x new circle X
414  */
415 void
417 {
418  if (_is_read_only) {
419  throw Exception("Buffer is read-only. Not setting circle X.");
420  }
421  raw_header->circle_x = circle_x;
422 }
423 
424 
425 /** Set circle Y.
426  * @param circle_y new circle Y
427  */
428 void
430 {
431  if (_is_read_only) {
432  throw Exception("Buffer is read-only. Not setting circle Y.");
433  }
434  raw_header->circle_y = circle_y;
435 }
436 
437 
438 /** Set circle radius.
439  * @param circle_radius new circle radius
440  */
441 void
443 {
444  if (_is_read_only) {
445  throw Exception("Buffer is read-only. Not setting circle radius.");
446  }
447  raw_header->circle_radius = circle_radius;
448 }
449 
450 
451 /** Set circle data.
452  * @param x circle X
453  * @param y circle Y
454  * @param r circle radius
455  */
456 void
457 SharedMemoryImageBuffer::set_circle(int x, int y, unsigned int r)
458 {
459  if (_is_read_only) {
460  throw Exception("Buffer is read-only. Not setting circle X/Y/radius.");
461  }
462  raw_header->circle_x = x;
463  raw_header->circle_y = y;
464  raw_header->circle_radius = r;
465 }
466 
467 
468 /** Set circle found.
469  * @param found true if circle found
470  */
471 void
473 {
474  raw_header->flag_circle_found = (found ? 1 : 0);
475 }
476 
477 
478 /** Check if circle was found .
479  * @return true if circle was found, false otherwise
480  */
481 bool
483 {
484  return (raw_header->flag_circle_found == 1);
485 }
486 
487 
488 /** List all shared memory segments that contain a FireVision image. */
489 void
491 {
494 
495  SharedMemory::list(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, h, lister);
496 
497  delete lister;
498  delete h;
499 }
500 
501 
502 /** Erase all shared memory segments that contain FireVision images.
503  * @param use_lister if true a lister is used to print the shared memory segments
504  * to stdout while cleaning up.
505  */
506 void
508 {
509  SharedMemoryImageBufferLister *lister = NULL;
511 
512  if (use_lister) {
513  lister = new SharedMemoryImageBufferLister();
514  }
515 
516  SharedMemory::erase_orphaned(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, h, lister);
517 
518  delete lister;
519  delete h;
520 }
521 
522 
523 /** Check image availability.
524  * @param image_id image ID to check
525  * @return true if shared memory segment with requested image exists
526  */
527 bool
528 SharedMemoryImageBuffer::exists(const char *image_id)
529 {
530  SharedMemoryImageBufferHeader *h = new SharedMemoryImageBufferHeader(image_id, CS_UNKNOWN, 0, 0);
531 
532  bool ex = SharedMemory::exists(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, h);
533 
534  delete h;
535  return ex;
536 }
537 
538 
539 /** Erase a specific shared memory segment that contains an image.
540  * @param image_id ID of image to wipe
541  */
542 void
543 SharedMemoryImageBuffer::wipe(const char *image_id)
544 {
545  SharedMemoryImageBufferHeader *h = new SharedMemoryImageBufferHeader(image_id, CS_UNKNOWN, 0, 0);
546 
547  SharedMemory::erase(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, h, NULL);
548 
549  delete h;
550 }
551 
552 
553 /** @class SharedMemoryImageBufferHeader <fvutils/ipc/shm_image.h>
554  * Shared memory image buffer header.
555  */
556 
557 /** Constructor. */
559 {
560  _colorspace = CS_UNKNOWN;
561  _image_id = NULL;
562  _frame_id = NULL;
563  _width = 0;
564  _height = 0;
565  _header = NULL;
566  _orig_image_id = NULL;
567  _orig_frame_id = NULL;
568 }
569 
570 
571 /** Constructor.
572  * @param image_id image id
573  * @param colorspace colorspace
574  * @param width width
575  * @param height height
576  */
578  colorspace_t colorspace,
579  unsigned int width,
580  unsigned int height)
581 {
582  _image_id = strdup(image_id);
583  _colorspace = colorspace;
584  _width = width;
585  _height = height;
586  _header = NULL;
587  _frame_id = NULL;
588 
589  _orig_image_id = NULL;
590  _orig_frame_id = NULL;
591  _orig_width = 0;
592  _orig_height = 0;
593  _orig_colorspace = CS_UNKNOWN;
594 }
595 
596 
597 /** Copy constructor.
598  * @param h shared memory image header to copy
599  */
601 {
602  if ( h->_image_id != NULL ) {
603  _image_id = strdup(h->_image_id);
604  } else {
605  _image_id = NULL;
606  }
607  if ( h->_frame_id != NULL ) {
608  _frame_id = strdup(h->_frame_id);
609  } else {
610  _frame_id = NULL;
611  }
612  _colorspace = h->_colorspace;
613  _width = h->_width;
614  _height = h->_height;
615  _header = h->_header;
616 
617  _orig_image_id = NULL;
618  _orig_frame_id = NULL;
619  _orig_width = 0;
620  _orig_height = 0;
621  _orig_colorspace = CS_UNKNOWN;
622 }
623 
624 
625 /** Destructor. */
627 {
628  if ( _image_id != NULL) free(_image_id);
629  if ( _frame_id != NULL) free(_frame_id);
630  if ( _orig_image_id != NULL) free(_orig_image_id);
631  if ( _orig_frame_id != NULL) free(_orig_frame_id);
632 }
633 
634 
635 size_t
637 {
638  return sizeof(SharedMemoryImageBuffer_header_t);
639 }
640 
641 
644 {
645  return new SharedMemoryImageBufferHeader(this);
646 }
647 
648 
649 size_t
651 {
652  if (_header == NULL) {
653  return colorspace_buffer_size(_colorspace, _width, _height);
654  } else {
655  return colorspace_buffer_size((colorspace_t)_header->colorspace, _header->width, _header->height);
656  }
657 }
658 
659 
660 bool
662 {
664 
665  if (_image_id == NULL) {
666  return true;
667 
668  } else if (strncmp(h->image_id, _image_id, IMAGE_ID_MAX_LENGTH) == 0) {
669  if ( (_colorspace == CS_UNKNOWN) ||
670  (((colorspace_t)h->colorspace == _colorspace) &&
671  (h->width == _width) &&
672  (h->height == _height) &&
673  (! _frame_id || (strncmp(h->frame_id, _frame_id, FRAME_ID_MAX_LENGTH) == 0))
674  )
675  )
676  {
677  return true;
678  } else {
679  throw InconsistentImageException("Inconsistent image found in memory (meta)");
680  }
681  } else {
682  return false;
683  }
684 }
685 
686 /** Check for equality of headers.
687  * First checks if passed SharedMemoryHeader is an instance of
688  * SharedMemoryImageBufferHeader. If not returns false, otherwise it compares
689  * image ID, colorspace, width, and height. If all match returns true, false
690  * if any of them differs.
691  * @param s shared memory header to compare to
692  * @return true if the two instances identify the very same shared memory segments,
693  * false otherwise
694  */
695 bool
697 {
698  const SharedMemoryImageBufferHeader *h = dynamic_cast<const SharedMemoryImageBufferHeader *>(&s);
699  if ( ! h ) {
700  return false;
701  } else {
702  return ( (strncmp(_image_id, h->_image_id, IMAGE_ID_MAX_LENGTH) == 0) &&
703  (! _frame_id || (strncmp(_frame_id, h->_frame_id, FRAME_ID_MAX_LENGTH) == 0)) &&
704  (_colorspace == h->_colorspace) &&
705  (_width == h->_width) &&
706  (_height == h->_height) );
707  }
708 }
709 
710 /** Print some info. */
711 void
713 {
714  if (_image_id == NULL) {
715  cout << "No image set" << endl;
716  return;
717  }
718  cout << "SharedMemory Image Info: " << endl;
719  printf(" address: %p\n", _header);
720  cout << " image id: " << _image_id << endl
721  << " frame id: " << (_frame_id ? _frame_id : "NOT SET") << endl
722  << " colorspace: " << _colorspace << endl
723  << " dimensions: " << _width << "x" << _height << endl;
724  /*
725  << " ROI: at (" << header->roi_x << "," << header->roi_y
726  << ") dim " << header->roi_width << "x" << header->roi_height << endl
727  << " circle: " << (header->flag_circle_found ? "" : "not ")
728  << "found at (" << header->circle_x << "," << header->circle_y
729  << ") radius " << header->circle_radius << endl
730  << " img ready: " << (header->flag_image_ready ? "yes" : "no") << endl;
731  */
732 }
733 
734 
735 /** Create if colorspace, width and height have been supplied.
736  * @return true if colorspace has been set, width and height are greater than zero.
737  */
738 bool
740 {
741  return ( (_colorspace != CS_UNKNOWN) &&
742  (_width > 0) &&
743  (_height > 0) );
744 }
745 
746 
747 void
749 {
751  memset(memptr, 0, sizeof(SharedMemoryImageBuffer_header_t));
752 
753  strncpy(header->image_id, _image_id, IMAGE_ID_MAX_LENGTH);
754  if (_frame_id) {
755  strncpy(header->frame_id, _frame_id, FRAME_ID_MAX_LENGTH);
756  }
757  header->colorspace = _colorspace;
758  header->width = _width;
759  header->height = _height;
760 
761  _header = header;
762 }
763 
764 
765 void
767 {
769  if ( NULL != _orig_image_id ) free(_orig_image_id);
770  if ( NULL != _image_id ) {
771  _orig_image_id = strdup(_image_id);
772  free(_image_id);
773  } else {
774  _orig_image_id = NULL;
775  }
776  if ( NULL != _orig_frame_id ) free(_orig_frame_id);
777  if ( NULL != _frame_id ) {
778  _orig_frame_id = strdup(_frame_id);
779  free(_frame_id);
780  } else {
781  _orig_frame_id = NULL;
782  }
783  _orig_width = _width;
784  _orig_height = _height;
785  _orig_colorspace = _colorspace;
786  _header = header;
787 
788  _image_id = strndup(header->image_id, IMAGE_ID_MAX_LENGTH);
789  _frame_id = strndup(header->frame_id, FRAME_ID_MAX_LENGTH);
790  _width = header->width;
791  _height = header->height;
792  _colorspace = (colorspace_t)header->colorspace;
793 }
794 
795 
796 void
798 {
799  if ( NULL != _image_id ) {
800  free(_image_id);
801  _image_id = NULL;
802  }
803  if ( _orig_image_id != NULL ) {
804  _image_id = strdup(_orig_image_id);
805  }
806  if ( NULL != _frame_id ) {
807  free(_frame_id);
808  _frame_id = NULL;
809  }
810  if ( _orig_frame_id != NULL ) {
811  _frame_id = strdup(_orig_frame_id);
812  }
813  _width =_orig_width;
814  _height =_orig_height;
815  _colorspace =_orig_colorspace;
816  _header = NULL;
817 }
818 
819 
820 /** Get colorspace.
821  * @return colorspace
822  */
823 colorspace_t
825 {
826  if ( _header) return (colorspace_t)_header->colorspace;
827  else return _colorspace;
828 }
829 
830 
831 /** Get width.
832  * @return image width
833  */
834 unsigned int
836 {
837  if ( _header) return _header->width;
838  else return _width;
839 }
840 
841 
842 /** Get height.
843  * @return image height
844  */
845 unsigned int
847 {
848  if ( _header) return _header->height;
849  else return _height;
850 }
851 
852 
853 /** Get image number
854  * @return image number
855  */
856 const char *
858 {
859  return _image_id;
860 }
861 
862 
863 /** Get frame ID.
864  * @return reference coordinate frame ID.
865  */
866 const char *
868 {
869  return _frame_id;
870 }
871 
872 
873 /** Set image id
874  * @param image_id image ID
875  */
876 void
878 {
879  if ( _image_id != NULL) ::free(_image_id);
880  _image_id = strdup(image_id);
881 }
882 
883 
884 /** Set frame ID.
885  * @param frame_id frame ID
886  */
887 void
889 {
890  if ( _frame_id != NULL) ::free(_frame_id);
891  _frame_id = strdup(frame_id);
892 }
893 
894 
895 /** Get raw header.
896  * @return raw header.
897  */
900 {
901  return _header;
902 }
903 
904 
905 /** @class SharedMemoryImageBufferLister <fvutils/ipc/shm_image.h>
906  * Shared memory image buffer lister.
907  */
908 
909 /** Constructor. */
911 {
912 }
913 
914 
915 /** Destructor. */
917 {
918 }
919 
920 
921 void
923 {
924  cout << endl << cgreen << "FireVision Shared Memory Segments - Images" << cnormal << endl
925  << "========================================================================================" << endl
926  << cdarkgray;
927  printf ("%-20s %-20s %-10s %-10s %-9s %-16s %-5s %-5s %s\n",
928  "Image ID", "Frame ID", "ShmID", "Semaphore", "Bytes", "Color Space", "Width", "Height",
929  "State");
930  cout << cnormal
931  << "----------------------------------------------------------------------------------------" << endl;
932 }
933 
934 
935 void
937 {
938 }
939 
940 
941 void
943 {
944  cout << "No FireVision shared memory segments found" << endl;
945 }
946 
947 
948 void
950 {
951  cout << "No orphaned FireVision shared memory segments found" << endl;
952 }
953 
954 
955 void
957  int shm_id, int semaphore,
958  unsigned int mem_size,
959  const void *memptr)
960 {
961 
963 
964  const char *colorspace = colorspace_to_string(h->colorspace());
965 
966  printf("%-20s %-20s %-10d %-10d %-9u %-16s %-5u %-5u %s%s\n",
967  h->image_id(), h->frame_id(), shm_id, semaphore, mem_size, colorspace,
968  h->width(), h->height(),
969  (SharedMemory::is_swapable(shm_id) ? "S" : ""),
970  (SharedMemory::is_destroyed(shm_id) ? "D" : "")
971  );
972 }
973 
974 } // end namespace firevision
void set_frame_id(const char *frame_id)
Set frame ID.
Definition: shm_image.cpp:888
unsigned int height() const
Get height.
Definition: shm_image.cpp:846
virtual bool create()
Create if colorspace, width and height have been supplied.
Definition: shm_image.cpp:739
long int capture_time_sec
Time in seconds since the epoch when the image was captured.
Definition: shm_image.h:59
void set_circle_found(bool found)
Set circle found.
Definition: shm_image.cpp:472
Shared memory image buffer header.
Definition: shm_image.h:68
virtual void print_no_orphaned_segments()
Print this if no matching orphaned segment was found.
Definition: shm_image.cpp:949
virtual void initialize(void *memptr)
Initialize the header.
Definition: shm_image.cpp:748
int circle_x() const
Get circle X.
Definition: shm_image.cpp:314
const timeval * get_timeval() const
Obtain the timeval where the time is stored.
Definition: time.h:109
const char * frame_id() const
Get frame ID.
Definition: shm_image.cpp:173
virtual ~SharedMemoryImageBufferLister()
Destructor.
Definition: shm_image.cpp:916
unsigned int circle_radius
ROI circle radius.
Definition: shm_image.h:58
virtual void reset()
Reset information previously set with set().
Definition: shm_image.cpp:797
bool set_image_id(const char *image_id)
Set image number.
Definition: shm_image.cpp:136
unsigned int height() const
Get image height.
Definition: shm_image.cpp:264
void set_roi_height(unsigned int roi_h)
Set ROI height.
Definition: shm_image.cpp:383
virtual ~SharedMemoryImageBufferHeader()
Destructor.
Definition: shm_image.cpp:626
void set_roi_x(unsigned int roi_x)
Set ROI X.
Definition: shm_image.cpp:344
long int capture_time_usec
Addendum to capture_time_sec in micro seconds.
Definition: shm_image.h:61
virtual void print_no_segments()
Print this if no matching segment was found.
Definition: shm_image.cpp:942
virtual bool matches(void *memptr)
Method to check if the given memptr matches this header.
Definition: shm_image.cpp:661
static void cleanup(bool use_lister=true)
Erase all shared memory segments that contain FireVision images.
Definition: shm_image.cpp:507
A class for handling time.
Definition: time.h:91
void set_roi_y(unsigned int roi_y)
Set ROI Y.
Definition: shm_image.cpp:357
Throw if an inconsistent image was found.
SharedMemoryImageBuffer(const char *image_id, colorspace_t cspace, unsigned int width, unsigned int height)
Write Constructor.
Definition: shm_image.cpp:63
const char * image_id() const
Get image number.
Definition: shm_image.cpp:857
unsigned int roi_height
ROI height.
Definition: shm_image.h:54
const char * frame_id() const
Get frame ID.
Definition: shm_image.cpp:867
char image_id[IMAGE_ID_MAX_LENGTH]
image ID
Definition: shm_image.h:46
colorspace_t colorspace() const
Get colorspace.
Definition: shm_image.cpp:824
virtual void print_footer()
Print footer of the table.
Definition: shm_image.cpp:936
Shared memory header struct for FireVision images.
Definition: shm_image.h:45
unsigned int colorspace
color space
Definition: shm_image.h:48
bool is_read_only() const
Check for read-only mode.
Definition: shm.cpp:653
void free()
Detach from and maybe destroy the shared memory segment.
Definition: shm.cpp:423
virtual fawkes::SharedMemoryHeader * clone() const
Clone this shared memory header.
Definition: shm_image.cpp:643
Base class for exceptions in Fawkes.
Definition: exception.h:36
void set_roi(unsigned int roi_x, unsigned int roi_y, unsigned int roi_w, unsigned int roi_h)
Set ROI data.
Definition: shm_image.cpp:399
unsigned int circle_radius() const
Get circle radius.
Definition: shm_image.cpp:334
void attach()
Attach to the shared memory segment.
Definition: shm.cpp:450
void set_circle_radius(unsigned int circle_radius)
Set circle radius.
Definition: shm_image.cpp:442
unsigned int flag_circle_found
1 if circle found
Definition: shm_image.h:63
unsigned int roi_height() const
Get ROI height.
Definition: shm_image.cpp:304
virtual void print_info()
Print some info.
Definition: shm_image.cpp:712
void set_frame_id(const char *frame_id)
Set frame ID.
Definition: shm_image.cpp:152
virtual void set(void *memptr)
Set information from memptr.
Definition: shm_image.cpp:766
unsigned int width() const
Get width.
Definition: shm_image.cpp:835
unsigned char * buffer() const
Get image buffer.
Definition: shm_image.cpp:234
bool circle_found() const
Check if circle was found .
Definition: shm_image.cpp:482
unsigned int roi_x() const
Get ROI X.
Definition: shm_image.cpp:274
void * _memptr
Pointer to the data segment.
Definition: shm.h:178
void set_circle(int x, int y, unsigned int r)
Set circle data.
Definition: shm_image.cpp:457
virtual bool operator==(const fawkes::SharedMemoryHeader &s) const
Check for equality of headers.
Definition: shm_image.cpp:696
char frame_id[FRAME_ID_MAX_LENGTH]
coordinate frame ID
Definition: shm_image.h:47
void set_circle_x(int circle_x)
Set circle X.
Definition: shm_image.cpp:416
void add_semaphore()
Add semaphore to shared memory segment.
Definition: shm.cpp:810
Shared memory segment.
Definition: shm.h:49
unsigned int width() const
Get image width.
Definition: shm_image.cpp:254
Shared memory image buffer lister.
Definition: shm_image.h:117
bool _is_read_only
Read-only.
Definition: shm.h:182
SharedMemoryHeader * _header
Data-specific header.
Definition: shm.h:181
const char * image_id() const
Get Image ID.
Definition: shm_image.cpp:163
virtual size_t data_size()
Return the size of the data.
Definition: shm_image.cpp:650
static void list()
List all shared memory segments that contain a FireVision image.
Definition: shm_image.cpp:490
void set_roi_width(unsigned int roi_w)
Set ROI width.
Definition: shm_image.cpp:370
virtual size_t size()
Size of the header.
Definition: shm_image.cpp:636
void set_circle_y(int circle_y)
Set circle Y.
Definition: shm_image.cpp:429
void set_image_id(const char *image_id)
Set image id.
Definition: shm_image.cpp:877
int circle_y() const
Get circle Y.
Definition: shm_image.cpp:324
virtual void print_header()
Print header of the table.
Definition: shm_image.cpp:922
static bool exists(const char *image_id)
Check image availability.
Definition: shm_image.cpp:528
unsigned int roi_y() const
Get ROI Y.
Definition: shm_image.cpp:284
void set_capture_time(fawkes::Time *time)
Set the capture time.
Definition: shm_image.cpp:204
colorspace_t colorspace() const
Get color space.
Definition: shm_image.cpp:244
static void wipe(const char *image_id)
Erase a specific shared memory segment that contains an image.
Definition: shm_image.cpp:543
unsigned int roi_width() const
Get ROI width.
Definition: shm_image.cpp:294
Interface for shared memory header.
Definition: shm.h:33
SharedMemoryImageBuffer_header_t * raw_header()
Get raw header.
Definition: shm_image.cpp:899
void append(const char *format,...)
Append messages to the message list.
Definition: exception.cpp:341
virtual void print_info(const fawkes::SharedMemoryHeader *header, int shm_id, int semaphore, unsigned int mem_size, const void *memptr)
Print info about segment.
Definition: shm_image.cpp:956
fawkes::Time capture_time() const
Get the time when the image was captured.
Definition: shm_image.cpp:194