shm_image.cpp

00001
00002 /***************************************************************************
00003  *  shm_image.cpp - shared memory image buffer
00004  *
00005  *  Created: Thu Jan 12 14:10:43 2006
00006  *  Copyright  2005-2009  Tim Niemueller [www.niemueller.de]
00007  *
00008  ****************************************************************************/
00009
00010 /*  This program is free software; you can redistribute it and/or modify
00011  *  it under the terms of the GNU General Public License as published by
00012  *  the Free Software Foundation; either version 2 of the License, or
00013  *  (at your option) any later version. A runtime exception applies to
00014  *  this software (see LICENSE.GPL_WRE file mentioned below for details).
00015  *
00016  *  This program is distributed in the hope that it will be useful,
00017  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00018  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00019  *  GNU Library General Public License for more details.
00020  *
00021  *  Read the full text in the LICENSE.GPL_WRE file in the doc directory.
00022  */
00023
00024 #include <core/exception.h>
00025 #include <fvutils/ipc/shm_image.h>
00026 #include <fvutils/ipc/shm_exceptions.h>
00027 #include <utils/system/console_colors.h>
00028 #include <utils/ipc/shm_exceptions.h>
00029
00030 #include <iostream>
00031 #include <cstring>
00032 #include <cstdlib>
00033 #include <cstdio>
00034 #ifdef __FreeBSD__
00035 #  include <strfunc.h>
00036 #endif
00037 
00038 using namespace std;
00039 using namespace fawkes;
00040 
00041 /** @class SharedMemoryImageBuffer <fvutils/ipc/shm_image.h>
00042  * Shared memory image buffer.
00043  * Write images to or retrieve images from a shared memory segment.
00044  * @author Tim Niemueller
00045  */
00046 
00047 /** Write Constructor.
00048  * Create a new shared memory segment. Will open a shared memory segment that
00049  * exactly fits the given information. Will throw an error if image with id
00050  * image_id exists.
00051  * I will create a new segment if no matching segment was found.
00052  * The segment is accessed in read-write mode.
00053  *
00054  * Use this constructor to open a shared memory image buffer for writing.
00055  * @param image_id image ID to open
00056  * @param cspace colorspace
00057  * @param width image width
00058  * @param height image height
00059  */
00060 SharedMemoryImageBuffer::SharedMemoryImageBuffer(const char *image_id,
00061                                                  colorspace_t cspace,
00062                                                  unsigned int width,
00063                                                  unsigned int height)
00064   : SharedMemory(FIREVISION_SHM_IMAGE_MAGIC_TOKEN,
00065                  /* read-only */ false,
00066                  /* create */ true,
00067                  /* destroy on delete */ true)
00068 {
00069   constructor(image_id, cspace, width, height, false);
00070   add_semaphore();
00071 }
00072
00073 
00074 /** Read Constructor.
00075  * This constructor is used to search for an existing shared memory segment.
00076  * It will throw an error if it cannot find a segment with the specified data.
00077  * The segment is opened read-only by default, but this can be overridden with
00078  * the is_read_only argument if needed.
00079  *
00080  * Use this constructor to open an image for reading.
00081  * @param image_id Image ID to open
00082  * @param is_read_only true to open image read-only
00083  */
00084 SharedMemoryImageBuffer::SharedMemoryImageBuffer(const char *image_id, bool is_read_only)
00085   : SharedMemory(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, is_read_only, /* create */ false, /* destroy */ false)
00086 {
00087   constructor(image_id, CS_UNKNOWN, 0, 0, is_read_only);
00088 }
00089
00090
00091 void
00092 SharedMemoryImageBuffer::constructor(const char *image_id, colorspace_t cspace,
00093                                      unsigned int width, unsigned int height,
00094                                      bool is_read_only)
00095 {
00096   _image_id     = strdup(image_id);
00097   _is_read_only = is_read_only;
00098
00099   _colorspace = cspace;
00100   _width      = width;
00101   _height     = height;
00102
00103   priv_header = new SharedMemoryImageBufferHeader(_image_id, _colorspace, width, height);
00104   _header = priv_header;
00105   try {
00106     attach();
00107     raw_header = priv_header->raw_header();
00108   } catch (Exception &e) {
00109     e.append("SharedMemoryImageBuffer: could not attach to '%s'\n", image_id);
00110     ::free(_image_id);
00111     _image_id = NULL;
00112     delete priv_header;
00113     throw;
00114   }
00115 }
00116
00117 
00118 /** Destructor. */
00119 SharedMemoryImageBuffer::~SharedMemoryImageBuffer()
00120 {
00121   ::free(_image_id);
00122   delete priv_header;
00123 }
00124
00125 
00126 /** Set image number.
00127  * This will close the currently opened image and will try to open the new
00128  * image. This operation should be avoided.
00129  * @param image_id new image ID
00130  * @return true on success
00131  */
00132 bool
00133 SharedMemoryImageBuffer::set_image_id(const char *image_id)
00134 {
00135   free();
00136   ::free(_image_id);
00137   _image_id = strdup(image_id);
00138   priv_header->set_image_id(_image_id);
00139   attach();
00140   raw_header = priv_header->raw_header();
00141   return (_memptr != NULL);
00142 }
00143
00144 
00145 /** Get Image ID.
00146  * @return image id
00147  */
00148 const char *
00149 SharedMemoryImageBuffer::image_id() const
00150 {
00151   return _image_id;
00152 }
00153
00154 
00155 /** Get the time when the image was captured.
00156  * @param sec upon return contains the seconds part of the time
00157  * @param usec upon return contains the micro seconds part of the time
00158  */
00159 void
00160 SharedMemoryImageBuffer::capture_time(long int *sec, long int *usec) const
00161 {
00162   *sec  = raw_header->capture_time_sec;
00163   *usec = raw_header->capture_time_usec;
00164 }
00165 
00166 /** Get the time when the image was captured.
00167  * @return capture time
00168  */
00169 Time
00170 SharedMemoryImageBuffer::capture_time() const
00171 {
00172   return Time(raw_header->capture_time_sec, raw_header->capture_time_usec);
00173 }
00174
00175 
00176 /** Set the capture time.
00177  * @param time capture time
00178  */
00179 void
00180 SharedMemoryImageBuffer::set_capture_time(Time *time)
00181 {
00182   if (_is_read_only) {
00183     throw Exception("Buffer is read-only. Not setting capture time.");
00184   }
00185
00186   const timeval *t = time->get_timeval();
00187   raw_header->capture_time_sec  = t->tv_sec;
00188   raw_header->capture_time_usec = t->tv_usec;
00189 }
00190 
00191 /** Set the capture time.
00192  * @param sec seconds part of capture time
00193  * @param usec microseconds part of capture time
00194  */
00195 void
00196 SharedMemoryImageBuffer::set_capture_time(long int sec, long int usec)
00197 {
00198   if (_is_read_only) {
00199     throw Exception("Buffer is read-only. Not setting capture time.");
00200   }
00201
00202   raw_header->capture_time_sec  = sec;
00203   raw_header->capture_time_usec = usec;
00204 }
00205 
00206 /** Get image buffer.
00207  * @return image buffer.
00208  */
00209 unsigned char *
00210 SharedMemoryImageBuffer::buffer() const
00211 {
00212   return (unsigned char *)_memptr;
00213 }
00214
00215 
00216 /** Get color space.
00217  * @return colorspace
00218  */
00219 colorspace_t
00220 SharedMemoryImageBuffer::colorspace() const
00221 {
00222   return (colorspace_t)raw_header->colorspace;
00223 }
00224
00225 
00226 /** Get image width.
00227  * @return width
00228  */
00229 unsigned int
00230 SharedMemoryImageBuffer::width() const
00231 {
00232   return raw_header->width;
00233 }
00234
00235 
00236 /** Get image height.
00237  * @return image height
00238  */
00239 unsigned int
00240 SharedMemoryImageBuffer::height() const
00241 {
00242   return raw_header->height;
00243 }
00244
00245 
00246 /** Get ROI X.
00247  * @return ROI X
00248  */
00249 unsigned int
00250 SharedMemoryImageBuffer::roi_x() const
00251 {
00252   return raw_header->roi_x;
00253 }
00254
00255 
00256 /** Get ROI Y.
00257  * @return ROI Y
00258  */
00259 unsigned int
00260 SharedMemoryImageBuffer::roi_y() const
00261 {
00262   return raw_header->roi_y;
00263 }
00264
00265 
00266 /** Get ROI width.
00267  * @return ROI width
00268  */
00269 unsigned int
00270 SharedMemoryImageBuffer::roi_width() const
00271 {
00272   return raw_header->roi_width;
00273 }
00274
00275 
00276 /** Get ROI height.
00277  * @return ROI height
00278  */
00279 unsigned int
00280 SharedMemoryImageBuffer::roi_height() const
00281 {
00282   return raw_header->roi_height;
00283 }
00284
00285 
00286 /** Get circle X.
00287  * @return circle X
00288  */
00289 int
00290 SharedMemoryImageBuffer::circle_x() const
00291 {
00292   return raw_header->circle_x;
00293 }
00294
00295 
00296 /** Get circle Y.
00297  * @return circle Y
00298  */
00299 int
00300 SharedMemoryImageBuffer::circle_y() const
00301 {
00302   return raw_header->circle_y;
00303 }
00304
00305 
00306 /** Get circle radius.
00307  * @return circle radius
00308  */
00309 unsigned int
00310 SharedMemoryImageBuffer::circle_radius() const
00311 {
00312   return raw_header->circle_radius;
00313 }
00314
00315 
00316 /** Set ROI X.
00317  * @param roi_x new ROI X
00318  */
00319 void
00320 SharedMemoryImageBuffer::set_roi_x(unsigned int roi_x)
00321 {
00322   if (_is_read_only) {
00323     throw Exception("Buffer is read-only. Not setting ROI X.");
00324   }
00325   raw_header->roi_x = roi_x;
00326 }
00327
00328 
00329 /** Set ROI Y.
00330  * @param roi_y new ROI Y
00331  */
00332 void
00333 SharedMemoryImageBuffer::set_roi_y(unsigned int roi_y)
00334 {
00335   if (_is_read_only) {
00336     throw Exception("Buffer is read-only. Not setting ROI Y.");
00337   }
00338   raw_header->roi_y = roi_y;
00339 }
00340
00341 
00342 /** Set ROI width.
00343  * @param roi_w new ROI width
00344  */
00345 void
00346 SharedMemoryImageBuffer::set_roi_width(unsigned int roi_w)
00347 {
00348   if (_is_read_only) {
00349     throw Exception("Buffer is read-only. Not setting ROI width.");
00350   }
00351   raw_header->roi_width = roi_w;
00352 }
00353
00354 
00355 /** Set ROI height.
00356  * @param roi_h new ROI height
00357  */
00358 void
00359 SharedMemoryImageBuffer::set_roi_height(unsigned int roi_h)
00360 {
00361   if (_is_read_only) {
00362     throw Exception("Buffer is read-only. Not setting ROI height.");
00363   }
00364   raw_header->roi_height = roi_h;
00365 }
00366
00367 
00368 /** Set ROI data.
00369  * @param roi_x new ROI X
00370  * @param roi_y new ROI Y
00371  * @param roi_w new ROI width
00372  * @param roi_h new ROI height
00373  */
00374 void
00375 SharedMemoryImageBuffer::set_roi(unsigned int roi_x, unsigned int roi_y,
00376                                  unsigned int roi_w, unsigned int roi_h)
00377 {
00378   if (_is_read_only) {
00379     throw Exception("Buffer is read-only. Not setting ROI X/Y.");
00380   }
00381   raw_header->roi_x = roi_x;
00382   raw_header->roi_y = roi_y;
00383   raw_header->roi_width  = roi_w;
00384   raw_header->roi_height = roi_h;
00385 }
00386
00387 
00388 /** Set circle X.
00389  * @param circle_x new circle X
00390  */
00391 void
00392 SharedMemoryImageBuffer::set_circle_x(int circle_x)
00393 {
00394   if (_is_read_only) {
00395     throw Exception("Buffer is read-only. Not setting circle X.");
00396   }
00397   raw_header->circle_x = circle_x;
00398 }
00399
00400 
00401 /** Set circle Y.
00402  * @param circle_y new circle Y
00403  */
00404 void
00405 SharedMemoryImageBuffer::set_circle_y(int circle_y)
00406 {
00407   if (_is_read_only) {
00408     throw Exception("Buffer is read-only. Not setting circle Y.");
00409   }
00410   raw_header->circle_y = circle_y;
00411 }
00412
00413 
00414 /** Set circle radius.
00415  * @param circle_radius new circle radius
00416  */
00417 void
00418 SharedMemoryImageBuffer::set_circle_radius(unsigned int circle_radius)
00419 {
00420   if (_is_read_only) {
00421     throw Exception("Buffer is read-only. Not setting circle radius.");
00422   }
00423   raw_header->circle_radius = circle_radius;
00424 }
00425
00426 
00427 /** Set circle data.
00428  * @param x circle X
00429  * @param y circle Y
00430  * @param r circle radius
00431  */
00432 void
00433 SharedMemoryImageBuffer::set_circle(int x, int y, unsigned int r)
00434 {
00435   if (_is_read_only) {
00436     throw Exception("Buffer is read-only. Not setting circle X/Y/radius.");
00437   }
00438   raw_header->circle_x      = x;
00439   raw_header->circle_y      = y;
00440   raw_header->circle_radius = r;
00441 }
00442
00443 
00444 /** Set circle found.
00445  * @param found true if circle found
00446  */
00447 void
00448 SharedMemoryImageBuffer::set_circle_found(bool found)
00449 {
00450   raw_header->flag_circle_found = (found ? 1 : 0);
00451 }
00452
00453 
00454 /** Check if circle was found .
00455  * @return true if circle was found, false otherwise
00456  */
00457 bool
00458 SharedMemoryImageBuffer::circle_found() const
00459 {
00460   return (raw_header->flag_circle_found == 1);
00461 }
00462
00463 
00464 /** List all shared memory segments that contain a FireVision image. */
00465 void
00466 SharedMemoryImageBuffer::list()
00467 {
00468   SharedMemoryImageBufferLister *lister = new SharedMemoryImageBufferLister();
00469   SharedMemoryImageBufferHeader *h      = new SharedMemoryImageBufferHeader();
00470
00471   SharedMemory::list(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, h, lister);
00472
00473   delete lister;
00474   delete h;
00475 }
00476
00477 
00478 /** Erase all shared memory segments that contain FireVision images.
00479  * @param use_lister if true a lister is used to print the shared memory segments
00480  * to stdout while cleaning up.
00481  */
00482 void
00483 SharedMemoryImageBuffer::cleanup(bool use_lister)
00484 {
00485   SharedMemoryImageBufferLister *lister = NULL;
00486   SharedMemoryImageBufferHeader *h      = new SharedMemoryImageBufferHeader();
00487
00488   if (use_lister) {
00489     lister = new SharedMemoryImageBufferLister();
00490   }
00491
00492   SharedMemory::erase_orphaned(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, h, lister);
00493
00494   delete lister;
00495   delete h;
00496 }
00497
00498 
00499 /** Check image availability.
00500  * @param image_id image ID to check
00501  * @return true if shared memory segment with requested image exists
00502  */
00503 bool
00504 SharedMemoryImageBuffer::exists(const char *image_id)
00505 {
00506   SharedMemoryImageBufferHeader *h      = new SharedMemoryImageBufferHeader(image_id, CS_UNKNOWN, 0, 0);
00507
00508   bool ex = SharedMemory::exists(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, h);
00509
00510   delete h;
00511   return ex;
00512 }
00513
00514 
00515 /** Erase a specific shared memory segment that contains an image.
00516  * @param image_id ID of image to wipe
00517  */
00518 void
00519 SharedMemoryImageBuffer::wipe(const char *image_id)
00520 {
00521   SharedMemoryImageBufferHeader *h      = new SharedMemoryImageBufferHeader(image_id, CS_UNKNOWN, 0, 0);
00522
00523   SharedMemory::erase(FIREVISION_SHM_IMAGE_MAGIC_TOKEN, h, NULL);
00524
00525   delete h;
00526 }
00527
00528 
00529 /** @class SharedMemoryImageBufferHeader <fvutils/ipc/shm_image.h>
00530  * Shared memory image buffer header.
00531  */
00532 
00533 /** Constructor. */
00534 SharedMemoryImageBufferHeader::SharedMemoryImageBufferHeader()
00535 {
00536   _colorspace = CS_UNKNOWN;
00537   _image_id = NULL;
00538   _width = 0;
00539   _height = 0;
00540   _header = NULL;
00541   _orig_image_id = NULL;
00542 }
00543
00544 
00545 /** Constructor.
00546  * @param image_id image id
00547  * @param colorspace colorspace
00548  * @param width width
00549  * @param height height
00550  */
00551 SharedMemoryImageBufferHeader::SharedMemoryImageBufferHeader(const char *image_id,
00552                                                              colorspace_t colorspace,
00553                                                              unsigned int width,
00554                                                              unsigned int height)
00555 {
00556   _image_id   = strdup(image_id);
00557   _colorspace = colorspace;
00558   _width      = width;
00559   _height     = height;
00560   _header     = NULL;
00561
00562   _orig_image_id   = NULL;
00563   _orig_width      = 0;
00564   _orig_height     = 0;
00565   _orig_colorspace = CS_UNKNOWN;
00566 }
00567
00568 
00569 /** Copy constructor.
00570  * @param h shared memory image header to copy
00571  */
00572 SharedMemoryImageBufferHeader::SharedMemoryImageBufferHeader(const SharedMemoryImageBufferHeader *h)
00573 {
00574   if ( h->_image_id != NULL ) {
00575     _image_id   = strdup(h->_image_id);
00576   } else {
00577     _image_id = NULL;
00578   }
00579   _colorspace = h->_colorspace;
00580   _width      = h->_width;
00581   _height     = h->_height;
00582   _header     = h->_header;
00583
00584   _orig_image_id   = NULL;
00585   _orig_width      = 0;
00586   _orig_height     = 0;
00587   _orig_colorspace = CS_UNKNOWN;
00588 }
00589
00590 
00591 /** Destructor. */
00592 SharedMemoryImageBufferHeader::~SharedMemoryImageBufferHeader()
00593 {
00594   if ( _image_id != NULL)  free(_image_id);
00595   if ( _orig_image_id != NULL)  free(_orig_image_id);
00596 }
00597
00598
00599 size_t
00600 SharedMemoryImageBufferHeader::size()
00601 {
00602   return sizeof(SharedMemoryImageBuffer_header_t);
00603 }
00604
00605
00606 SharedMemoryHeader *
00607 SharedMemoryImageBufferHeader::clone() const
00608 {
00609   return new SharedMemoryImageBufferHeader(this);
00610 }
00611
00612
00613 size_t
00614 SharedMemoryImageBufferHeader::data_size()
00615 {
00616   if (_header == NULL) {
00617     return colorspace_buffer_size(_colorspace, _width, _height);
00618   } else {
00619     return colorspace_buffer_size((colorspace_t)_header->colorspace, _header->width, _header->height);
00620   }
00621 }
00622
00623
00624 bool
00625 SharedMemoryImageBufferHeader::matches(void *memptr)
00626 {
00627   SharedMemoryImageBuffer_header_t *h = (SharedMemoryImageBuffer_header_t *)memptr;
00628
00629   if (_image_id == NULL) {
00630     return true;
00631
00632   } else if (strncmp(h->image_id, _image_id, IMAGE_ID_MAX_LENGTH) == 0) {
00633
00634     if ( (_colorspace == CS_UNKNOWN) ||
00635          (((colorspace_t)h->colorspace == _colorspace) &&
00636           (h->width == _width) &&
00637           (h->height == _height)
00638           )
00639          ) {
00640       return true;
00641     } else {
00642       throw InconsistentImageException("Inconsistent image found in memory (meta)");
00643     }
00644   } else {
00645     return false;
00646   }
00647 }
00648
00649
00650 bool
00651 SharedMemoryImageBufferHeader::operator==(const SharedMemoryHeader & s) const
00652 {
00653   const SharedMemoryImageBufferHeader *h = dynamic_cast<const SharedMemoryImageBufferHeader *>(&s);
00654   if ( ! h ) {
00655     return false;
00656   } else {
00657     return ( (strncmp(_image_id, h->_image_id, IMAGE_ID_MAX_LENGTH) == 0) &&
00658              (_colorspace == h->_colorspace) &&
00659              (_width == h->_width) &&
00660              (_height == h->_height) );
00661   }
00662 }
00663 
00664 /** Print some info. */
00665 void
00666 SharedMemoryImageBufferHeader::print_info()
00667 {
00668   if (_image_id == NULL) {
00669     cout << "No image set" << endl;
00670     return;
00671   }
00672   cout << "SharedMemory Image Info: " << endl;
00673   printf("    address:  %p\n", _header);
00674   cout << "    image id:  " << _image_id << endl
00675        << "    colorspace: " << _colorspace << endl
00676        << "    dimensions: " << _width << "x" << _height << endl;
00677   /*
00678      << "    ROI:        at (" << header->roi_x << "," << header->roi_y
00679        << ")  dim " << header->roi_width << "x" << header->roi_height << endl
00680        << "    circle:     " << (header->flag_circle_found ? "" : "not ")
00681        << "found at (" << header->circle_x << "," << header->circle_y
00682        << ")  radius " << header->circle_radius << endl
00683        << "    img ready:  " << (header->flag_image_ready ? "yes" : "no") << endl;
00684   */
00685 }
00686
00687 
00688 /** Create if colorspace, width and height have been supplied.
00689  * @return true if colorspace has been set, width and height are greater than zero.
00690  */
00691 bool
00692 SharedMemoryImageBufferHeader::create()
00693 {
00694   return ( (_colorspace != CS_UNKNOWN) &&
00695            (_width > 0) &&
00696            (_height > 0) );
00697 }
00698
00699
00700 void
00701 SharedMemoryImageBufferHeader::initialize(void *memptr)
00702 {
00703   SharedMemoryImageBuffer_header_t *header = (SharedMemoryImageBuffer_header_t *)memptr;
00704   memset(memptr, 0, sizeof(SharedMemoryImageBuffer_header_t));
00705
00706   strncpy(header->image_id, _image_id, IMAGE_ID_MAX_LENGTH);
00707   header->colorspace = _colorspace;
00708   header->width      = _width;
00709   header->height     = _height;
00710
00711   _header = header;
00712 }
00713
00714
00715 void
00716 SharedMemoryImageBufferHeader::set(void *memptr)
00717 {
00718   SharedMemoryImageBuffer_header_t *header = (SharedMemoryImageBuffer_header_t *)memptr;
00719   if ( NULL != _orig_image_id )  free(_orig_image_id);
00720   if ( NULL != _image_id ) {
00721     _orig_image_id = strdup(_image_id);
00722     free(_image_id);
00723   } else {
00724     _orig_image_id = NULL;
00725   }
00726   _orig_width = _width;
00727   _orig_height = _height;
00728   _orig_colorspace = _colorspace;
00729   _header = header;
00730
00731   _image_id = strndup(header->image_id, IMAGE_ID_MAX_LENGTH);
00732   _width = header->width;
00733   _height = header->height;
00734   _colorspace = (colorspace_t)header->colorspace;
00735 }
00736
00737
00738 void
00739 SharedMemoryImageBufferHeader::reset()
00740 {
00741   if ( NULL != _image_id ) {
00742     free(_image_id);
00743     _image_id = NULL;
00744   }
00745   if ( _orig_image_id != NULL ) {
00746     _image_id = strdup(_orig_image_id);
00747   }
00748   _width =_orig_width;
00749   _height =_orig_height;
00750   _colorspace =_orig_colorspace;
00751   _header = NULL;
00752 }
00753
00754 
00755 /** Get colorspace.
00756  * @return colorspace
00757  */
00758 colorspace_t
00759 SharedMemoryImageBufferHeader::colorspace() const
00760 {
00761   if ( _header)  return (colorspace_t)_header->colorspace;
00762   else           return _colorspace;
00763 }
00764
00765 
00766 /** Get width.
00767  * @return image width
00768  */
00769 unsigned int
00770 SharedMemoryImageBufferHeader::width() const
00771 {
00772   if ( _header)  return _header->width;
00773   else           return _width;
00774 }
00775
00776 
00777 /** Get height.
00778  * @return image height
00779  */
00780 unsigned int
00781 SharedMemoryImageBufferHeader::height() const
00782 {
00783   if ( _header)  return _header->height;
00784   else           return _height;
00785 }
00786
00787 
00788 /** Get image number
00789  * @return image number
00790  */
00791 const char *
00792 SharedMemoryImageBufferHeader::image_id() const
00793 {
00794   return _image_id;
00795 }
00796
00797 
00798 /** Set image id
00799  * @param image_id image ID
00800  */
00801 void
00802 SharedMemoryImageBufferHeader::set_image_id(const char *image_id)
00803 {
00804   if ( _image_id != NULL)  ::free(_image_id);
00805   _image_id = strdup(image_id);
00806 }
00807
00808 
00809 /** Get raw header.
00810  * @return raw header.
00811  */
00812 SharedMemoryImageBuffer_header_t *
00813 SharedMemoryImageBufferHeader::raw_header()
00814 {
00815   return _header;
00816 }
00817
00818 
00819 /** @class SharedMemoryImageBufferLister <fvutils/ipc/shm_image.h>
00820  * Shared memory image buffer lister.
00821  */
00822 
00823 /** Constructor. */
00824 SharedMemoryImageBufferLister::SharedMemoryImageBufferLister()
00825 {
00826 }
00827
00828 
00829 /** Destructor. */
00830 SharedMemoryImageBufferLister::~SharedMemoryImageBufferLister()
00831 {
00832 }
00833
00834
00835 void
00836 SharedMemoryImageBufferLister::print_header()
00837 {
00838   cout << endl << cgreen << "FireVision Shared Memory Segments - Images" << cnormal << endl
00839        << "========================================================================================" << endl
00840        << cdarkgray;
00841   printf ("%-20s %-10s %-10s %-9s %-16s %-5s %-5s %s\n",
00842           "Image ID", "ShmID", "Semaphore", "Bytes", "Color Space", "Width", "Height",
00843           "State");
00844   cout << cnormal
00845        << "----------------------------------------------------------------------------------------" << endl;
00846 }
00847
00848
00849 void
00850 SharedMemoryImageBufferLister::print_footer()
00851 {
00852 }
00853
00854
00855 void
00856 SharedMemoryImageBufferLister::print_no_segments()
00857 {
00858   cout << "No FireVision shared memory segments found" << endl;
00859 }
00860
00861
00862 void
00863 SharedMemoryImageBufferLister::print_no_orphaned_segments()
00864 {
00865   cout << "No orphaned FireVision shared memory segments found" << endl;
00866 }
00867
00868
00869 void
00870 SharedMemoryImageBufferLister::print_info(const SharedMemoryHeader *header,
00871                                           int shm_id, int semaphore,
00872                                           unsigned int mem_size,
00873                                           const void *memptr)
00874 {
00875
00876   SharedMemoryImageBufferHeader *h = (SharedMemoryImageBufferHeader *)header;
00877
00878   const char *colorspace = colorspace_to_string(h->colorspace());
00879
00880   printf("%-20s %-10d %-10d %-9u %-16s %-5u %-5u %s%s\n",
00881          h->image_id(), shm_id, semaphore, mem_size, colorspace,
00882          h->width(), h->height(),
00883          (SharedMemory::is_swapable(shm_id) ? "S" : ""),
00884          (SharedMemory::is_destroyed(shm_id) ? "D" : "")
00885          );
00886 }