JeVois  1.10
JeVois Smart Embedded Machine Vision Toolkit
Share this page:
Module.H
Go to the documentation of this file.
1 // ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
2 //
3 // JeVois Smart Embedded Machine Vision Toolkit - Copyright (C) 2016 by Laurent Itti, the University of Southern
4 // California (USC), and iLab at USC. See http://iLab.usc.edu and http://jevois.org for information about this project.
5 //
6 // This file is part of the JeVois Smart Embedded Machine Vision Toolkit. This program is free software; you can
7 // redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software
8 // Foundation, version 2. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY;
9 // without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public
10 // License for more details. You should have received a copy of the GNU General Public License along with this program;
11 // if not, write to the Free Software Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
12 //
13 // Contact information: Laurent Itti - 3641 Watt Way, HNB-07A - Los Angeles, CA 90089-2520 - USA.
14 // Tel: +1 213 740 3527 - itti@pollux.usc.edu - http://iLab.usc.edu - http://jevois.org
15 // ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
16 /*! \file */
17 
18 #pragma once
19 
20 #include <memory>
21 #include <jevois/Image/RawImage.H>
22 #include <jevois/Core/VideoBuf.H>
23 #include <jevois/Core/UserInterface.H> // not strictly needed but derived classes will want to use it
25 #include <jevois/Types/ObjReco.H>
26 #include <jevois/Types/Enum.H>
27 #include <opencv2/core/core.hpp>
28 #include <ostream>
29 
30 namespace jevois
31 {
32  class VideoInput;
33  class VideoOutput;
34  class Engine;
35 
36  //! Exception-safe wrapper around a raw camera input frame
37  /*! This wrapper operates much like std:future in standard C++11. Users can get the next image captured by the camera
38  by calling get(), which may block if the capture is not complete yet, or may throw if the capture fails for some
39  reason (e.g., the camera is not streaming). The image size and pixel type are as defined by the current
40  VideoMapping, camera section. In addition, a done() function is provided which users may use as soon as they are
41  finished with the pixel data in the image obtained via get(), to allow the camera driver to setup the underlying
42  memory buffer again for capture. If done() has not been called by the time the InputFrame is destroyed, it will be
43  called automatically, if get() had been called. It may in some cases improve your frame rate to call done()
44  manually as early as possible instead of letting the InputFrame destructor do it.
45 
46  InputFrame implements a zero-copy, zero-wait access to input video frames, that is:
47 
48  1. the pixel data of the image you obtain via get() is directly the memory-mapped pixel buffer that the silicon
49  hardware on the JeVois chip uses via direct-memory-access (DMA) to stream the pixel data from the camera chip
50  to processor memory;
51  2. as soon as an image is captured by the camera hardware, get() unblocks and returns it (as opposed to having a
52  fixed, regular interval at which images may be available). Camera has several image buffers, allowing one to be
53  captured while another is being handed over for processing via get(). These buffers are recycled, i.e., once
54  done() is called, the underlying buffer is sent back to the camera hardware for future capture.
55 
56  \ingroup core */
57  class InputFrame
58  {
59  public:
60  //! Move constructor
61  InputFrame(InputFrame && other) = default;
62 
63  //! Get the next captured camera image
64  /*! Throws if we the camera is not streaming or blocks until an image is available (has been captured). */
65  RawImage const & get(bool casync = false) const;
66 
67  //! Indicate that user processing is done with the image previously obtained via get()
68  /*! You should call this as soon after get() as possible, once you are finished with the RawImage data so that it
69  can be recycled and sent back to the camera driver for video capture. */
70  void done() const;
71 
72  //! Shorthand to get the input image as a GRAY cv::Mat and release the raw buffer
73  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
74  processing. C++ module writers should stick to the get()/done() pair as this provides better fine-grained
75  control. Note that the raw image from the camera will always be copied or converted to cv::Mat and will then
76  be released by calling done(), so users should not call done() after using this function. This function is
77  basically equivalent to calling get(), converting to cv::Mat, and calling done(). */
78  cv::Mat getCvGRAY(bool casync = false) const;
79 
80  //! Shorthand to get the input image as a BGR cv::Mat and release the raw buffer
81  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
82  processing. C++ module writers should stick to the get()/done() pair as this provides better fine-grained
83  control. Note that the raw image from the camera will always be copied or converted to cv::Mat and will then
84  be released by calling done(), so users should not call done() after using this function. This function is
85  basically equivalent to calling get(), converting to cv::Mat, and calling done(). */
86  cv::Mat getCvBGR(bool casync = false) const;
87 
88  //! Shorthand to get the input image as a RGB cv::Mat and release the raw buffer
89  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
90  processing. C++ module writers should stick to the get()/done() pair as this provides better fine-grained
91  control. Note that the raw image from the camera will always be copied or converted to cv::Mat and will then
92  be released by calling done(), so users should not call done() after using this function. This function is
93  basically equivalent to calling get(), converting to cv::Mat, and calling done(). */
94  cv::Mat getCvRGB(bool casync = false) const;
95 
96  //! Shorthand to get the input image as a RGBA cv::Mat and release the raw buffer
97  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
98  processing. C++ module writers should stick to the get()/done() pair as this provides better fine-grained
99  control. Note that the raw image from the camera will always be copied or converted to cv::Mat and will then
100  be released by calling done(), so users should not call done() after using this function. This function is
101  basically equivalent to calling get(), converting to cv::Mat, and calling done(). */
102  cv::Mat getCvRGBA(bool casync = false) const;
103 
104  //! Destructor, returns the buffers to the driver as needed
105  ~InputFrame();
106 
107  private:
108  InputFrame() = delete;
109  InputFrame(InputFrame const & other) = delete;
110  InputFrame & operator=(InputFrame const & other) = delete;
111 
112  friend class Engine;
113  InputFrame(std::shared_ptr<VideoInput> const & cam, bool turbo); // Only our friends can construct us
114 
115  std::shared_ptr<VideoInput> itsCamera;
116  mutable bool itsDidGet;
117  mutable bool itsDidDone;
118  mutable RawImage itsImage;
119  bool const itsTurbo;
120  };
121 
122  //! Exception-safe wrapper around a raw image to be sent over USB
123  /*! This wrapper operates much like std:future in standard C++11. Users can get the next memory-allocated but blank
124  image to be sent over USB by calling get(), which may block if all buffers are still being sent over USB by Gadget
125  and no blank one is available, or may throw if getting that buffer fails for some reason (e.g., usb disconnect,
126  user just changed video mode in their webcam software or closed it). The allocated image size and pixel type is as
127  defined by the current VideoMapping, USB section, i.e., it is the USB video mode currently selected by the
128  user. To save time, image buffers are not zeroed out, so you should not assume that the image is filled with black
129  pixels, it could contain random pixels, or previous output frames. In addition, a send() function is provided
130  which users may use as soon as they are finished with writing the pixel data into the image obtained via get(), to
131  allow the USB driver to send that image to the connected host computer. If send() has not been called by the time
132  the OutputFrame is destroyed, it will be called automatically, if get() had been called.
133 
134  OutputFrame implements a zero-copy, zero-wait access to output video frames, that is:
135 
136  1. the pixel data of the image you obtain via get() is directly the memory-mapped pixel buffer that the silicon
137  hardware on the JeVois chip will use via direct-memory-access (DMA) to stream the data out over the USB link;
138  2. as soon as you call send() that buffer will be queued for sending over USB (as opposed to having a fixed,
139  regular interval at which images may be streamed out). Gadget has several image buffers, allowing one to be
140  streamed out over USB while another is being handed over for filling by your application via get(). These
141  buffers are recycled, i.e., once send() is called, the underlying buffer is streamed over USB and then sent
142  back to the Gadget for future access by your code.
143 
144  \ingroup core */
146  {
147  public:
148  //! Move constructor
149  OutputFrame(OutputFrame && other) = default;
150 
151  //! Get a pre-allocated image so that we can fill the pixel data and later send out over USB using send()
152  /*! May throw if not buffer is available, i.e., all have been queued to send to the host but have not yet been
153  sent. Application code must balance exactly one send() for each get(). */
154  RawImage const & get() const;
155 
156  //! Send an image out over USB to the host computer
157  /*! May throw if the format is incorrect or std::overflow_error if we have not yet consumed the previous image. */
158  void send() const;
159 
160  //! Shorthand to send a cv::Mat after converting / scaling it to the current output format
161  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
162  processing. The cv::Mat will be rescaled to the same dims as the output frame.
163 
164  The pixel format of the given cv::Mat is guessed as follows:
165  - if img.type() == CV_8UC3, assume BGR pixels
166  - if img.type() == CV_8UC1, assume GRAY pixels
167  - if img.type() == CV_8UC4, assume RGBA pixels
168 
169  C++ module writers should stick to the get()/send() pair as this provides better fine-grained control. Note
170  that the cv::Mat image will always be copied or converted to the destination RawImage and will then be sent
171  out immediately by calling send(), so users should not call send() after using this function. This function is
172  basically equivalent to calling get(), converting the given cv::Mat to the proper output format, and calling
173  send(). quality is used only if the output format is MJPEG and should be between 1 and 100.*/
174  void sendCv(cv::Mat const & img, int quality = 75) const;
175 
176  //! Shorthand to send a GRAY cv::Mat after converting it to the current output format
177  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
178  processing. The cv::Mat must have same dims as the output frame. C++ module writers should stick to the
179  get()/send() pair as this provides better fine-grained control. Note that the cv::Mat image will always be
180  copied or converted to the destination RawImage and will then be sent out immediately by calling send(), so
181  users should not call send() after using this function. This function is basically equivalent to calling
182  get(), converting the given cv::Mat to the proper output format, and calling send(). quality is used only if
183  the output format is MJPEG and should be between 1 and 100. */
184  void sendCvGRAY(cv::Mat const & img, int quality = 75) const;
185 
186  //! Shorthand to send a BGR cv::Mat after converting it to the current output format
187  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
188  processing. The cv::Mat must have same dims as the output frame. C++ module writers should stick to the
189  get()/send() pair as this provides better fine-grained control. Note that the cv::Mat image will always be
190  copied or converted to the destination RawImage and will then be sent out immediately by calling send(), so
191  users should not call send() after using this function. This function is basically equivalent to calling
192  get(), converting the given cv::Mat to the proper output format, and calling send(). quality is used only if
193  the output format is MJPEG and should be between 1 and 100.*/
194  void sendCvBGR(cv::Mat const & img, int quality = 75) const;
195 
196  //! Shorthand to send a RGB cv::Mat after converting it to the current output format
197  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
198  processing. The cv::Mat must have same dims as the output frame. C++ module writers should stick to the
199  get()/send() pair as this provides better fine-grained control. Note that the cv::Mat image will always be
200  copied or converted to the destination RawImage and will then be sent out immediately by calling send(), so
201  users should not call send() after using this function. This function is basically equivalent to calling
202  get(), converting the given cv::Mat to the proper output format, and calling send(). quality is used only if
203  the output format is MJPEG and should be between 1 and 100.*/
204  void sendCvRGB(cv::Mat const & img, int quality = 75) const;
205 
206  //! Shorthand to send a RGBA cv::Mat after converting it to the current output format
207  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
208  processing. The cv::Mat must have same dims as the output frame. C++ module writers should stick to the
209  get()/send() pair as this provides better fine-grained control. Note that the cv::Mat image will always be
210  copied or converted to the destination RawImage and will then be sent out immediately by calling send(), so
211  users should not call send() after using this function. This function is basically equivalent to calling
212  get(), converting the given cv::Mat to the proper output format, and calling send(). quality is used only if
213  the output format is MJPEG and should be between 1 and 100.*/
214  void sendCvRGBA(cv::Mat const & img, int quality = 75) const;
215 
216  //! Shorthand to send a GRAY cv::Mat after converting it to the current output format
217  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
218  processing. The cv::Mat will be rescaled to the same dims as the output frame. C++ module writers should stick
219  to the get()/send() pair as this provides better fine-grained control. Note that the cv::Mat image will always
220  be copied or converted to the destination RawImage and will then be sent out immediately by calling send(), so
221  users should not call send() after using this function. This function is basically equivalent to calling
222  get(), converting the given cv::Mat to the proper output format, and calling send(). quality is used only if
223  the output format is MJPEG and should be between 1 and 100. */
224  void sendScaledCvGRAY(cv::Mat const & img, int quality = 75) const;
225 
226  //! Shorthand to send a BGR cv::Mat after converting it to the current output format
227  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
228  processing. The cv::Mat will be rescaled to the same dims as the output frame. C++ module writers should stick
229  to the get()/send() pair as this provides better fine-grained control. Note that the cv::Mat image will always
230  be copied or converted to the destination RawImage and will then be sent out immediately by calling send(), so
231  users should not call send() after using this function. This function is basically equivalent to calling
232  get(), converting the given cv::Mat to the proper output format, and calling send(). quality is used only if
233  the output format is MJPEG and should be between 1 and 100.*/
234  void sendScaledCvBGR(cv::Mat const & img, int quality = 75) const;
235 
236  //! Shorthand to send a RGB cv::Mat after converting it to the current output format
237  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
238  processing. The cv::Mat will be rescaled to the same dims as the output frame. C++ module writers should stick
239  to the get()/send() pair as this provides better fine-grained control. Note that the cv::Mat image will always
240  be copied or converted to the destination RawImage and will then be sent out immediately by calling send(), so
241  users should not call send() after using this function. This function is basically equivalent to calling
242  get(), converting the given cv::Mat to the proper output format, and calling send(). quality is used only if
243  the output format is MJPEG and should be between 1 and 100.*/
244  void sendScaledCvRGB(cv::Mat const & img, int quality = 75) const;
245 
246  //! Shorthand to send a RGBA cv::Mat after converting it to the current output format
247  /*! This is mostly intended for Python module writers, as they will likely use OpenCV for all their image
248  processing. The cv::Mat will be rescaled to the same dims as the output frame. C++ module writers should stick
249  to the get()/send() pair as this provides better fine-grained control. Note that the cv::Mat image will always
250  be copied or converted to the destination RawImage and will then be sent out immediately by calling send(), so
251  users should not call send() after using this function. This function is basically equivalent to calling
252  get(), converting the given cv::Mat to the proper output format, and calling send(). quality is used only if
253  the output format is MJPEG and should be between 1 and 100.*/
254  void sendScaledCvRGBA(cv::Mat const & img, int quality = 75) const;
255 
256  //! Destructor, returns the buffers to the driver as needed
257  ~OutputFrame();
258 
259  private:
260  OutputFrame() = delete;
261  OutputFrame(OutputFrame const & other) = delete;
262  OutputFrame & operator=(OutputFrame const & other) = delete;
263 
264  // Only our friends can construct us:
265  friend class Engine;
266  OutputFrame(std::shared_ptr<VideoOutput> const & gad, RawImage * excimg = nullptr);
267 
268  std::shared_ptr<VideoOutput> itsGadget;
269  mutable bool itsDidGet;
270  mutable bool itsDidSend;
271  mutable RawImage itsImage;
272  jevois::RawImage * itsImagePtrForException;
273  };
274 
275  //! Virtual base class for a vision processing module
276  /*! Module is the base class to implement camera-to-USB frame-by-frame video processing. The Engine instantiates one
277  class derived from Module, according to the current VideoMapping selected by the end user (e.g., current image
278  resolution, format, and frame rate setected by a webcam viewing program on a host computer). The Module is loaded
279  as shared object (.so) file according to the VideoMapping definitions in videomappings.cfg and the current
280  VideoMapping selected by the user.
281 
282  Module derives from Component and as such can contain:
283 
284  - any number of Parameter settings
285 
286  - any arbitrarily complex sub-hierarchy of Component objects to implement various functionality. Parameter
287  settings from all the sub-components are available to the Module and to users connected over Serial ports of the
288  Engine.
289 
290  This allows one to implement complex vision processing pipelines efficiently and with substantial code re-use. For
291  example, one may first want to implement an EdgeDetector or Saliency component, with Parameter settings for
292  various thresholds, features, etc. One can then create any number of top-level objects that derive from Module and
293  that may contain one or more EdgeDetector, Saliency, etc components in their hierarchy of sub-components, with the
294  implementation in the module simply routing images from one Component to another to create a processing pipeline.
295 
296  Classes that derive from Module should implement up to four functions:
297 
298  - process(InputFrame && inframe, OutputFrame && outframe) is called once per iteration of the Engine main loop
299  when the current VideoMapping specifies both a particular Camera resolution and format, and a USB resolution and
300  format. This function should process the received input frame and fill the pixel buffer of the output frame with
301  results. Memory has already been allocated for both the input and output images before process() is
302  called. Because the output image is actually allocated by the USB Gadget driver (and, ultimately, by the Linux
303  kernel), its pixel memory location cannot be moved (hence, do not attempt to copy the output image or replace it
304  by another image, etc; just write pixel data into the output image's pixel array). There is no restriction on
305  video modes or frame rates, except as suported by the Camera hardware, and as limited by USB bandwidth. For most
306  implementations, matching the input and output frame rate is easiest, and means that each invocation of
307  process() would access and use both of the provided InputFrame and OutputFrame (one-input-to-one-output
308  processing pipeline). But this is not mandatory. For example, a motion flow computation Module for use in a
309  flying drone may have 320x240 YUYV 53.0fps inputs and 100x142 GREY 10.6fps output (since output frame rate is 5x
310  lower than input in this example, the process() function would here get, fill, and send the OutputFrame only
311  once every 5 times it is called; implementation of the process() function should keep track of that, e.g.,
312  through a member variable that gets incremented each time process() is called). In addition to filling the pixel
313  data of the OutputFrame, process() may also send results over the serial ports (e.g., for use by an Arduino
314  connected to the JeVois platform hardware) using sendSerial().
315 
316  - process(InputFrame && inframe) is called once per Camera frame when the current VideoMapping specifies a
317  particular Camera resolution and format, and NONE as USB output format. This function should process the
318  received input frame and would typicaly then send results to serial ports (e.g., for use by an Arduino connected
319  to the JeVois platform hardware) using sendSerial(). There is no restriction on video modes or frame rates,
320  except as suported by the Camera hardware.
321 
322  - parseSerial(std::string const & str, std::shared_ptr<UserInterface> s) allows the Module to support custom user
323  commands. Engine will forward to this function any command received over Serial or other UserInterface that it
324  does not understand. You should use this for things that go beyond Parameter settings (which is already natively
325  supported by Engine) or built-in commands of Engine (see \ref UserCli). For example, one could implement here a
326  command called "start" to allow users to start some specific thing.
327 
328  - supportedCommands(std::ostream & os) should stream out a human-readable description of any custom commands
329  supported by parseSerial(). These will be shown to users when they type "help" over a Serial port.
330 
331  \note Every module implementation file should contain a call to #JEVOIS_REGISTER_MODULE(MODULENAME) for the
332  module's class. This creates some plain-C entry points that will be used when the module is loaded from a dynamic
333  library (.so) file to instantiate the module. See \ref ModuleTutorial for examples.
334 
335  \ingroup core */
336  class Module : public Component
337  {
338  public:
339  //! Constructor
340  /*! the instance is a user-defined string that may be used to differentiate between several instances of the
341  same module. */
342  Module(std::string const & instance);
343 
344  //! Virtual destructor for safe inheritance
345  virtual ~Module();
346 
347  //! Processing function, version that receives a frame from camera and sends a frame out over USB
348  /*! This function is called once for each grabbed video frame from the camera, and it should complete within the
349  camera's frame period in order to avoid dropping frames. The InputFrame and OutputFrame objects are simple
350  wrappers to ensure that the low-level video buffers will always be returned to the low-level camera and USB
351  drivers even if the process function throws at any point during the processing. If any error occurs, it is
352  hence ok to throw from within process() at any time, just make sure your locally allocated resources will be
353  freed, which is usually best achieved by using shared_ptr and similar wrappers around them. The Engine (which
354  calls process() on your module for every frame) will catch any exception an proceed to the next frame.
355 
356  Default implementation in the base class just throws. Derived classes should override it. */
357  virtual void process(InputFrame && inframe, OutputFrame && outframe);
358 
359  //! Processing function, version that receives a frame from camera and does not use USB
360  /*! This function is called once for each grabbed video frame from the camera, and it should complete within the
361  camera's frame period in order to avoid dropping frames. The InputFrame object is a simple wrapper to ensure
362  that the low-level video buffers will always be returned to the low-level camera driver even if the process
363  function throws at any point during the processing. If any error occurs, it is hence ok to throw from within
364  process() at any time, just make sure your locally allocated resources will be freed, which is usually best
365  achieved by using shared_ptr and similar wrappers around them. The Engine (which calls process() on your
366  module for every frame) will catch any exception an proceed to the next frame.
367 
368  Default implementation in the base class just throws. Derived classes should override it. */
369  virtual void process(InputFrame && inframe);
370 
371  //! Send a string over the 'serout' serial port
372  /*! The default implementation just sends the string to the serial port specified by the 'serout' Parameter in
373  Engine (which could be the hardware serial port, the serial-over-USB port, both, or none; see \ref UserCli for
374  information about \c serout). No need to override in most cases. Typically, you would use this function from
375  within process() to send out some results of your processing.
376 
377  Note that the default 'serout' Parameter setting in Engine is None. This is to allow users to configure
378  parameters, get parameter values, possibly read the help message, etc before the flow of serial outputs from
379  vision processing starts. Once ready to receive serial outputs, one would typically issue a command 'setpar
380  serout Hard' over the JeVois command line to enable serial outputs to the hardware serial port. An Arduino
381  would issue that setpar commands when it is ready to work. See ArduinoTutorial for an example. */
382  virtual void sendSerial(std::string const & str);
383 
384  //! Receive a string from a serial port which contains a user command
385  /*! This function may be called in between calls to process() with any received string from any of the serial
386  ports. Some commands are parsed upstream already (like "help", set param value, set camera control, etc; see
387  the Engine class) and will not be received here. Only the ones not recognized by the Engine will be received
388  (i.e., custom commands specific to your module).
389 
390  The default implementation just throws std::runtime_error("Unsupported command"), but some modules may want to
391  override this function to handle custom commands. If you successfully process the command, just return;
392  otherwise, throw, and if your exception derives from std::exception, the Engine will append its what() to the
393  error message issued to the user. When you support commands here, you should update the implementation of
394  supportedCommands() to provide some description of those commands to the users.
395 
396  The \c s parameter is the serial port that received the command. You can send any results back to that port
397  using writeString() on it. Note that the Engine will automatically add the 'OK' message upon success, so you
398  do not have to send that here. */
399  virtual void parseSerial(std::string const & str, std::shared_ptr<UserInterface> s);
400 
401  //! Human-readable description of this Module's supported custom commands
402  /*! The format here is free. Just use std::endl to demarcate lines, these will be converted to the appropriate
403  line endings by the serial ports. Default implementation writes "None" to os. */
404  virtual void supportedCommands(std::ostream & os);
405 
406  //! Get frame number from the Engine
407  /*! The Engine maintains a master frame counter that is incremented on each call to process(), whether or not the
408  call succeeds. The counter is not incremented when a module has not been loaded (e.g., failed to load). The
409  counter is reset to zero each time a new module is loaded. */
410  size_t frameNum() const;
411 
412  //! Write a value of one of the camera's registers
413  /*! This very low-level access is for development of optimal camera settings only and should not be used in normal
414  operation, it can crash your system. */
415  void writeCamRegister(unsigned short reg, unsigned short val);
416 
417  //! Read a value from one of the camera's registers
418  /*! This very low-level access is for development of optimal camera settings only and should not be used in normal
419  operation, it can crash your system. */
420  unsigned short readCamRegister(unsigned short reg);
421 
422  //! Write a value to one of the camera's IMU registers
423  /*! This very low-level access is for development of optimal IMU settings only and should not be used in normal
424  operation, it can crash your system. */
425  void writeIMUregister(unsigned short reg, unsigned short val);
426 
427  //! Read a value from one of the camera's IMU registers
428  /*! This very low-level access is for development of optimal IMU settings only and should not be used in normal
429  operation, it can crash your system. */
430  unsigned short readIMUregister(unsigned short reg);
431  };
432 
433  namespace module
434  {
435  static ParameterCategory const ParamCateg("Module Serial Message Options");
436 
437  //! Enum for Parameter \relates jevois::StdModule
438  JEVOIS_DEFINE_ENUM_CLASS(SerStyle, (Terse) (Normal) (Detail) (Fine) )
439 
440  //! Parameter \relates jevois::StdModule
441  JEVOIS_DECLARE_PARAMETER(serstyle, SerStyle, "Style for standardized serial messages as defined in "
442  "http://jevois.org/doc/UserSerialStyle.html",
443  SerStyle::Terse, SerStyle_Values, ParamCateg);
444 
445  //! Parameter \relates jevois::StdModule
446  JEVOIS_DECLARE_PARAMETER(serprec, unsigned int, "Number of decimal points in standardized serial messages as "
447  "defined in http://jevois.org/doc/UserSerialStyle.html",
448  0U, jevois::Range<unsigned int>(0U, 10U), ParamCateg);
449 
450  //! Enum for Parameter \relates jevois::StdModule
451  JEVOIS_DEFINE_ENUM_CLASS(SerStamp, (None) (Frame) (Time) (FrameTime) (FrameDateTime) )
452 
453  //! Parameter \relates jevois::StdModule
454  JEVOIS_DECLARE_PARAMETER(serstamp, SerStamp, "Prepend standardized serial messages with a frame number, "
455  "time, frame+time, or frame+date+time. See details in "
456  "http://jevois.org/doc/UserSerialStyle.html",
457  SerStamp::None, SerStamp_Values, ParamCateg);
458 
459  //! Enum for Parameter \relates jevois::StdModule
460  JEVOIS_DEFINE_ENUM_CLASS(SerMark, (None) (Start) (Stop) (Both) )
461 
462  //! Parameter \relates jevois::StdModule
463  JEVOIS_DECLARE_PARAMETER(sermark, SerMark, "Send serial message to mark the beginning (MARK START) of the "
464  "processing of a video frame from the camera sensor, the end (MARK STOP), or both. "
465  "Useful, among others, if one needs to know when no results were sent over serial "
466  "on a given frame. Combine with parameter serstamp if you need to know the frame number.",
467  SerMark::None, SerMark_Values, ParamCateg);
468  }
469 
470  //! Base class for a module that supports standardized serial messages
471  /*! Modules that can output standardized serial messages should derive from StdModule instead of Module. StdModule
472  brings in extra parameters to set serial message style and precision, and extra member functions to assemble,
473  format, and send standardized serial messages. The process(), sendSerial(), parseSerial(), supportedCommands(),
474  etc of StdModule functions are directly inherited from Module. See \ref UserSerialStyle for standardized serial
475  messages. \ingroup core */
476  class StdModule : public Module,
477  public Parameter<module::serprec, module::serstyle, module::serstamp, module::sermark>
478  {
479  public:
480  //! Constructor
481  /*! the instance is a user-defined string that may be used to differentiate between several instances of the
482  same module. */
483  StdModule(std::string const & instance);
484 
485  //! Virtual destructor for safe inheritance
486  virtual ~StdModule();
487 
488  //! Send standardized 1D message for an X image coordinate
489  /*! See \ref UserSerialStyle for more info. Coordinates should be in camera image pixels, this function will
490  convert them to standardized coordinates as per \ref coordhelpers. */
491  void sendSerialImg1Dx(unsigned int camw, float x, float size = 0.0F, std::string const & id = "",
492  std::string const & extra = "");
493 
494  //! Send standardized 1D message for a standardized X coordinate
495  /*! See \ref UserSerialStyle for more info. Coordinates should be in camera image pixels, this function will
496  convert them to standardized coordinates as per \ref coordhelpers. */
497  void sendSerialStd1Dx(float x, float size = 0.0F, std::string const & id = "", std::string const & extra = "");
498 
499  //! Send standardized 1D message for an Y image coordinate
500  /*! See \ref UserSerialStyle for more info. Coordinates should be in camera image pixels, this function will
501  convert them to standardized coordinates as per \ref coordhelpers. */
502  void sendSerialImg1Dy(unsigned int camh, float y, float size = 0.0F, std::string const & id = "",
503  std::string const & extra = "");
504 
505  //! Send standardized 1D message for a standardized Y coordinate
506  /*! See \ref UserSerialStyle for more info. Coordinates should be in camera image pixels, this function will
507  convert them to standardized coordinates as per \ref coordhelpers. */
508  void sendSerialStd1Dy(float y, float size = 0.0F, std::string const & id = "", std::string const & extra = "");
509 
510  //! Send standardized 2D message for image coordinates
511  /*! Use this function if you only know location and optionally size. Use the other variants if you have the
512  corners. An upright rectangular shape will be assumed here. See \ref UserSerialStyle for more
513  info. Coordinates should be in camera image pixels, this function will convert them to standardized
514  coordinates as per \ref coordhelpers. */
515  void sendSerialImg2D(unsigned int camw, unsigned int camh, float x, float y, float w = 0.0F, float h = 0.0F,
516  std::string const & id = "", std::string const & extra = "");
517 
518  //! Send standardized 2D message for standardized coordinates
519  /*! Use this function if you only know location and optionally size. Use the other variants if you have the
520  corners. An upright rectangular shape will be assumed here. See \ref UserSerialStyle for more
521  info. Coordinates should be in camera image pixels, this function will convert them to standardized
522  coordinates as per \ref coordhelpers. */
523  void sendSerialStd2D(float x, float y, float w = 0.0F, float h = 0.0F,
524  std::string const & id = "", std::string const & extra = "");
525 
526  //! Send standardized 2D message for polygons in image coordinates
527  /*! Use this function if you have a polygon around your object, for example, one of the contours found with
528  cv::findContours(), or if you have the 4 corners of a rectangular object. See \ref UserSerialStyle for more
529  info. Coordinates should be in camera image pixels, this function will convert them to standardized
530  coordinates as per \ref coordhelpers. For \b Terse serial style, the center of gravity of the points will be
531  computed and output; for \b Normal, an upright bounding rectangle will be computed and output; for \b
532  Detailed, a rotated bounding rectangle will be computed and output; for \b Fine, all the given points will
533  be output. Make sure you try to reduce the number of points so the message is not too long; for example see
534  OpenCV approxPolyDP() or similar. */
535  template <typename T = int>
536  void sendSerialContour2D(unsigned int camw, unsigned int camh, std::vector<cv::Point_<T> > points,
537  std::string const & id = "", std::string const & extra = "");
538 
539  //! Send standardized 3D message
540  /*! Use this function if you only know location and optionally size and an orientation quaternion. Use the other
541  variants if you have a bunch of vertices. See \ref UserSerialStyle for more info. Coordinates should be in
542  millimeters. */
543  void sendSerialStd3D(float x, float y, float z, float w = 0.0F, float h = 0.0F, float d = 0.0F,
544  float q1 = 0.0F, float q2 = 0.0F, float q3 = 0.0f, float q4 = 0.0F,
545  std::string const & id = "", std::string const & extra = "");
546 
547  //! Send standardized 3D message
548  /*! Use this function if you only know location and optionally size and an orientation quaternion. Use the other
549  variants if you have a bunch of vertices. See \ref UserSerialStyle for more info. Coordinates should be in
550  millimeters. */
551  void sendSerialStd3D(std::vector<cv::Point3f> points, std::string const & id = "",
552  std::string const & extra = "");
553 
554  //! Send a standardized object recognition message
555  /*! \param res should be a list of scores and category names, in descending order of scores. Note that no message
556  is sent if the vector is empty. */
557  void sendSerialObjReco(std::vector<ObjReco> const & res);
558 
559  //! Send a standardized object detection + recognition message
560  /*! \param res should be a list of scores and category names, in descending order of scores. Note that no message
561  is sent if the vector is empty. See sendSerialImg2D() for info about the object box. */
562  void sendSerialObjDetImg2D(unsigned int camw, unsigned int camh, float x, float y, float w, float h,
563  std::vector<ObjReco> const & res);
564 
565  protected:
566  friend class jevois::Engine;
567 
568  //! Send a message <b>MARK START</b> to indicate the beginning of processing
569  /*! A stamp may be prepended depending on param \p serstamp. Engine calls this automatically so users would
570  normally not use this function. Note that this function may not send anything depending on the current
571  value of parameter \p sermark. */
572  void sendSerialMarkStart();
573 
574  //! Send a message <b>MARK STOP</b> to indicate the end of processing
575  /*! A stamp may be prepended depending on param \p serstamp. Engine calls this automatically so users would
576  normally not use this function. Note that this function may not send anything depending on the current
577  value of parameter \p sermark. */
578  void sendSerialMarkStop();
579 
580  //! Get a string with the frame/date/time stamp in it, depending on serstamp parameter
581  std::string getStamp() const;
582  };
583 }
584 
585 //! Register a module, allowing it to be dynamically loaded from a .so file
586 /* \def JEVOIS_REGISTER_MODULE(MODULENAME)
587  \hideinitializer
588 
589  Every module implementation file should contain a call to JEVOIS_REGISTER_MODULE for the module's class. This creates
590  some plain-C entry points that will be used when the module is loaded from a dynamic library (.so) file to
591  instantiate the module. \relates Module */
592 #define JEVOIS_REGISTER_MODULE(MODULENAME) \
593  extern "C" std::shared_ptr<jevois::Module> MODULENAME##_create(std::string const & instanceid) \
594  { return std::shared_ptr<jevois::Module>(new MODULENAME(instanceid)); } \
595  extern "C" int MODULENAME##_version_major() { return JEVOIS_VERSION_MAJOR; } \
596  extern "C" int MODULENAME##_version_minor() { return JEVOIS_VERSION_MINOR; } \
597 
598 
Style for standardized serial messages as defined in SerStyle_Values
Definition: Module.H:441
Send serial message to mark the the end(MARK STOP)
Exception-safe wrapper around a raw camera input frame.
Definition: Module.H:57
Generic variadic template class template definition for Component Parameters.
cv::Mat getCvRGBA(bool casync=false) const
Shorthand to get the input image as a RGBA cv::Mat and release the raw buffer.
Definition: Module.C:94
A category to which multiple ParameterDef definitions can belong.
Definition: ParameterDef.H:33
JEVOIS_DECLARE_PARAMETER(thresh1, double, "First threshold for hysteresis", 50.0, ParamCateg)
Send serial message to mark the beginning(MARK START) of the " "processing of a video frame from the camera sensor
A component of a model hierarchy.
Definition: Component.H:177
A raw image as coming from a V4L2 Camera and/or being sent out to a USB Gadget.
Definition: RawImage.H:110
Prepend standardized serial messages with a frame frame or frame date time See details in SerStamp_Values
Definition: Module.H:454
cv::Mat getCvRGB(bool casync=false) const
Shorthand to get the input image as a RGB cv::Mat and release the raw buffer.
Definition: Module.C:85
Send serial message to mark the the or both Useful
Definition: Module.H:465
Send serial message to mark the the or both among others
Definition: Module.H:465
Prepend standardized serial messages with a frame number
Definition: Module.H:454
Send serial message to mark the the or both among if one needs to know when no results were sent over serial on a given frame Combine with parameter serstamp if you need to know the frame SerMark_Values
Definition: Module.H:465
cv::Mat getCvGRAY(bool casync=false) const
Shorthand to get the input image as a GRAY cv::Mat and release the raw buffer.
Definition: Module.C:67
A generic range class.
Definition: Range.H:80
Prepend standardized serial messages with a frame time
Definition: Module.H:454
JeVois processing engine - gets images from camera sensor, processes them, and sends results over USB...
Definition: Engine.H:265
Base class for a module that supports standardized serial messages.
Definition: Module.H:476
Virtual base class for a vision processing module.
Definition: Module.H:336
Exception-safe wrapper around a raw image to be sent over USB.
Definition: Module.H:145
~InputFrame()
Destructor, returns the buffers to the driver as needed.
Definition: Module.C:38
Style for standardized serial messages as defined in http
Definition: Module.H:441
cv::Mat getCvBGR(bool casync=false) const
Shorthand to get the input image as a BGR cv::Mat and release the raw buffer.
Definition: Module.C:76
JEVOIS_DEFINE_ENUM_CLASS(CameraSensor,(any)(ov9650)(ov2640)(ov7725)(ar0135))
Enum for different sensor models.
void done() const
Indicate that user processing is done with the image previously obtained via get() ...
Definition: Module.C:60