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