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